Skip to content

Commit

Permalink
Add hardcoded QoS for /tf_static topic in parameter bridge
Browse files Browse the repository at this point in the history
Signed-off-by: lFatality <fynn-boyer@web.de>
  • Loading branch information
lFatality committed Dec 27, 2020
1 parent dc2de62 commit e9b2a50
Showing 1 changed file with 7 additions and 1 deletion.
8 changes: 7 additions & 1 deletion src/parameter_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -86,9 +86,15 @@ int main(int argc, char * argv[])
"with ROS 2 type '%s'\n",
topic_name.c_str(), type_name.c_str());

auto ros2_publisher_qos = rclcpp::QoS(rclcpp::KeepLast(queue_size));
if (topic_name == "/tf_static") {
ros2_publisher_qos.keep_all();
ros2_publisher_qos.transient_local();
}

try {
ros1_bridge::BridgeHandles handles = ros1_bridge::create_bidirectional_bridge(
ros1_node, ros2_node, "", type_name, topic_name, queue_size);
ros1_node, ros2_node, "", type_name, topic_name, queue_size, ros2_publisher_qos);
all_handles.push_back(handles);
} catch (std::runtime_error & e) {
fprintf(
Expand Down

0 comments on commit e9b2a50

Please sign in to comment.