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

ROS 1 bridge requires the topic to be published both sides

asked 2020-07-27 12:10:18 -0500

screen33 gravatar image

I'm following the ROS 1 / 2 communication steps from this ROS-I tuto trying to run a simple example : publish some Bool msg in ROS 1 and echo in ROS 2, and vice versa. As advised in the tuto, I have 3 workspaces: ros_ws for Noetic, ros2_ws for Foxy, ros1_bridge_ws for the bridge (foxy branch, compiled successfully with colcon). I'm running all terminals in localhost with default settings and DDS implementation.

Terminal 1: Bridge in ros1_bridge_ws workspace

source ros1_bridge_ws/install/setup.bash
ros2 run ros1_bridge dynamic_bridge

Terminal 2: roscore in ros_ws workspace source ros_ws/devel/setup.bash roscore

The bridge in terminal 1 then warns:

[ERROR] [1595868742.350252486]: Tried to advertise on topic [/rosout] with latch=0 but the topic is already advertised with latch=1
created 2to1 bridge for topic '/rosout' with ROS 2 type 'rcl_interfaces/msg/Log' and ROS 1 type 'rosgraph_msgs/Log'

Terminal 3: rostopic pub in ros_ws workspace

ROS 1 will publish False booleans every second:

source ros_ws/devel/setup.bash
rostopic pub /test std_msgs/Bool "data: false" -r1

The bridge does not display anything new.

Terminal 4: rostopic echo in ros2_ws workspace

ros2 topic echo /test
WARNING: topic [/test] does not appear to be published yet
Could not determine the type for the passed topic

Thus ROS 2 does not get any message from ROS 1. I keep the publisher and subscriber open.

Terminal 5: ros2 topic pub in ros2_ws workspace

ROS 2 will publish True booleans every second:

source ros2_ws/install/setup.bash
ros2 topic pub /test std_msgs/Bool "data: true"

The bridge does not display anything new.

Terminal 4: rostopic echo in ros2_ws workspace

Back to the temrinal 4 that was falling to retrieve False messages from ROS1 and retry the echo:

ros2 topic echo /test

Now the echo receives successfully both True and False messages from ROS 1 and ROS 2 but also the bridge has noticed a new conversion to be made:

created 1to2 bridge for topic '/test' with ROS 1 type 'std_msgs/Bool' and ROS 2 type 'std_msgs/msg/Bool'
[INFO] [1595869460.462758826] [ros_bridge]: Passing message from ROS 1 std_msgs/Bool to ROS 2 std_msgs/msg/Bool (showing msg only once per type)
[WARN] [1595869460.463629720] [ros_bridge]: Message from ROS 2 rcl_interfaces/msg/Log failed to be passed to ROS 1 rosgraph_msgs/Log because the ROS 1 publisher is invalid (showing msg only once per type)

Conclusion

Why do I need to publish both sides to get some messages? Note: this issue is identical if the initial publisher is from ROS 1 or ROS 2 side.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
2

answered 2020-07-27 12:32:10 -0500

Dirk Thomas gravatar image

The dynamic_bridge does not require a publisher on both sides. It requires a publisher on one side and a subscriber on the other.

The reason why rostopic / ros2 topic echoisn't sufficient as a subscriber is described in the first section of the README: https://github.com/ros2/ros1_bridge/b...

The dynamic bridge only bridges topic which are necessary to bridge for efficiency reasons. So it doesn't bridge the published topic until a subscriber is present. echo on the other hand tries to determine the type of the specified topic automatically when invoked without a type. Since the topic doesn't exist yet that fails with the error message:

Could not determine the type for the passed topic

You have multiple options to resolve this:

  • You pass the topic type explicitly: e.g. ros2 topic echo /test std_msgs/msg/Bool
  • You use the --bridge-all-1to2-topics option of the dynamic bridge (if the performance impact is acceptable)
  • You use a different bridge (e.g. the parameter_bridge) to configure the bridged topics explicitly
edit flag offensive delete link more

Comments

This is explained in the README but I hadn't really gotten it. Thank you!

screen33 gravatar image screen33  ( 2020-07-27 12:57:47 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2020-07-27 12:10:18 -0500

Seen: 1,441 times

Last updated: Jul 27 '20