ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

Problem passing /tf_static through ROS1_bridge to ROS2

asked 2020-04-12 12:16:16 -0500

mequi gravatar image

I am having a problem with /tf_static not being published on the ROS2 side of my setup through a ROS1 bridge. I am using ROS2 eloquent installed through apt on Ubuntu 18.04. My guess is that this is due to latching behavior and how it is translated to ROS2. I think the fix would be just running a robot state publisher on the ROS2 side but this definitely does not seem like the most optimum solution. Please advise on what is the best way to go about fixing this. Thanks

edit retag flag offensive close merge delete

Comments

I'm having this same issue :/ Any possible workarounds?

Caelin Sutch gravatar image Caelin Sutch  ( 2020-04-22 16:34:35 -0500 )edit

1 Answer

Sort by » oldest newest most voted
1

answered 2020-12-26 11:37:03 -0500

fb21 gravatar image

updated 2020-12-27 19:18:20 -0500

jayess gravatar image

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
edit flag offensive delete link more

Comments

Hey thanks for this! I had the issue where I got all my tf_tree using the dynamic_bridge, but not with the parameter_bridge. I'm using the parameter_bridge because it's waaaay quicker than the dynamic one, and I can select only the topics I want.

rodrigo55 gravatar image rodrigo55  ( 2021-09-10 11:14:36 -0500 )edit

Question Tools

5 followers

Stats

Asked: 2020-04-12 12:16:16 -0500

Seen: 848 times

Last updated: Dec 27 '20