From e9b2a503d399a53e19e12ea1b884c1c167a2d5d5 Mon Sep 17 00:00:00 2001 From: Fynn Boyer Date: Sun, 27 Dec 2020 23:27:22 +0100 Subject: [PATCH] Add hardcoded QoS for /tf_static topic in parameter bridge Signed-off-by: lFatality --- src/parameter_bridge.cpp | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/src/parameter_bridge.cpp b/src/parameter_bridge.cpp index f4f4bd76..eb7fc741 100644 --- a/src/parameter_bridge.cpp +++ b/src/parameter_bridge.cpp @@ -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(