Looking at the changelog of the ros1_bridge you can see that this problem was recently addressed for the dynamic bridge in this pull request.
They now use hardcoded QoS (keep all, transient local) for /tf_static topic in dynamic_bridge
.
The code in the bridge to accomplish this looks like this:
auto ros2_publisher_qos = rclcpp::QoS(rclcpp::KeepLast(10));
if (topic_name == "/tf_static") {
ros2_publisher_qos.keep_all();
ros2_publisher_qos.transient_local();
}
If you don't use the dynamic bridge but the parameter bridge, you have to add the following topics to your yaml-configuration file:
topics:
- {topic: "/tf", type: "tf2_msgs/msg/TFMessage"}
- {topic: "/tf_static", type: "tf2_msgs/msg/TFMessage"}
Additionally, you will have to make a change to the code of the bridge as the change in the QoS settings for the tf_static
topic was only made for the dynamic_bridge. I made it work by changing create_bidirectional_bridge
in bridge.cpp
to this:
BridgeHandles
create_bidirectional_bridge(
ros::NodeHandle ros1_node,
rclcpp::Node::SharedPtr ros2_node,
const std::string & ros1_type_name,
const std::string & ros2_type_name,
const std::string & topic_name,
size_t queue_size)
{
RCLCPP_INFO(ros2_node->get_logger(), "create bidirectional bridge for topic " + topic_name);
BridgeHandles handles;
auto ros2_publisher_qos = rclcpp::QoS(rclcpp::KeepLast(queue_size));
if (topic_name == "/tf_static") {
RCLCPP_INFO(ros2_node->get_logger(), "Setting QoS to keep_all msgs for topic /tf_static.");
ros2_publisher_qos.keep_all();
ros2_publisher_qos.transient_local();
}
handles.bridge1to2 = create_bridge_from_1_to_2(
ros1_node, ros2_node,
ros1_type_name, topic_name, queue_size, ros2_type_name, topic_name, ros2_publisher_qos);
handles.bridge2to1 = create_bridge_from_2_to_1(
ros2_node, ros1_node,
ros2_type_name, topic_name, queue_size, ros1_type_name, topic_name, queue_size,
handles.bridge1to2.ros2_publisher);
return handles;
}
Don't forget to recompile the bridge after the change was made.
Once these changes were made it was possible to look up both dynamic and static ROS1 transforms in ROS2 using:
ros2 run tf2_ros tf2_echo reference_frame target_frame
I'm having this same issue :/ Any possible workarounds?