Gazebo | Ignition | Community
Ask Your Question
1

How to debug: [ros_gz_bridge]: Failed to create a bridge for topic

asked 2022-12-18 13:56:55 -0500

azazdeaz gravatar image

updated 2022-12-19 05:14:29 -0500

Hi There,

ros_gz_bridge reports failure while the parameters seem to be correct:

$ ros2 run ros_gz_bridge parameter_bridge /cmd_vel@geometry_msgs/Twist@gz.msgs.Twist
[INFO] [1671392523.581891853] [ros_gz_bridge]: Creating GZ->ROS Bridge: [/cmd_vel (gz.msgs.Twist) -> /cmd_vel (geometry_msgs/Twist)] (Lazy 0)
[WARN] [1671392523.582115037] [ros_gz_bridge]: Failed to create a bridge for topic [/cmd_vel] with ROS2 type [/cmd_vel] to topic [geometry_msgs/Twist] with Gazebo Transport type [gz.msgs.Twist]

I'm using Gazebo Garden on the osrf/ros:humble-desktop Docker image. I have a robot in the simulation that i can control with the Teleop widget on the /cmd_vel topic. I installed the ros-humble-ros-gz-bridge with apt.

What else should i check to find the cause of the issue?

Update
Using ignition.msgs.Twist instead of gz.msgs.Twist removes the error, (even though i'm using Gazebo Garden). But the messages are still not transferred.

It seems like Gazebo is using the gz. version of the message. This could explain why ROS2 messages have no effect on the simulation:

gz topic -i -t  /cmd_vel 
Publishers [Address, Message Type]:
  tcp://172.17.0.1:39535, ignition.msgs.Twist
  tcp://172.17.0.1:42165, gz.msgs.Twist

Maybe i don't have some ROS message definitions installed? I installed gz-garden and ros-humble-gazebo-msgs from the official PPA.

For more info, ros2 topic info with the bridge, teleop_keyboard, and a ros2 echo running:

ros2 topic info -v /cmd_vel
Type: geometry_msgs/msg/Twist

Publisher count: 2

Node name: ros_gz_bridge
Node namespace: /
Topic type: geometry_msgs/msg/Twist
Endpoint type: PUBLISHER
GID: 01.0f.50.71.51.ab.45.39.01.00.00.00.00.00.12.03.00.00.00.00.00.00.00.00
QoS profile:
  Reliability: RELIABLE
  History (Depth): UNKNOWN
  Durability: VOLATILE
  Lifespan: Infinite
  Deadline: Infinite
  Liveliness: AUTOMATIC
  Liveliness lease duration: Infinite

Node name: teleop_twist_keyboard
Node namespace: /
Topic type: geometry_msgs/msg/Twist
Endpoint type: PUBLISHER
GID: 01.0f.50.71.da.d3.49.82.01.00.00.00.00.00.11.03.00.00.00.00.00.00.00.00
QoS profile:
  Reliability: RELIABLE
  History (Depth): UNKNOWN
  Durability: VOLATILE
  Lifespan: Infinite
  Deadline: Infinite
  Liveliness: AUTOMATIC
  Liveliness lease duration: Infinite

Subscription count: 2

Node name: ros_gz_bridge
Node namespace: /
Topic type: geometry_msgs/msg/Twist
Endpoint type: SUBSCRIPTION
GID: 01.0f.50.71.51.ab.45.39.01.00.00.00.00.00.13.04.00.00.00.00.00.00.00.00
QoS profile:
  Reliability: RELIABLE
  History (Depth): UNKNOWN
  Durability: VOLATILE
  Lifespan: Infinite
  Deadline: Infinite
  Liveliness: AUTOMATIC
  Liveliness lease duration: Infinite

Node name: _ros2cli_205184
Node namespace: /
Topic type: geometry_msgs/msg/Twist
Endpoint type: SUBSCRIPTION
GID: 01.0f.50.71.80.21.50.1f.01.00.00.00.00.00.05.04.00.00.00.00.00.00.00.00
QoS profile:
  Reliability: RELIABLE
  History (Depth): UNKNOWN
  Durability: VOLATILE
  Lifespan: Infinite
  Deadline: Infinite
  Liveliness: AUTOMATIC
  Liveliness lease duration: Infinite
edit retag flag offensive close merge delete

Comments

For reference, a question about probably the same issue on robotics.stackexchange: https://robotics.stackexchange.com/qu...

azazdeaz gravatar imageazazdeaz ( 2022-12-19 05:16:11 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
2

answered 2022-12-19 08:00:04 -0500

clydemcqueen gravatar image

Did you build from source? If not, this could be the problem. The pre-built bridge is looking for Fortress types on the gz topics, and failing to find them.

https://github.com/gazebosim/ros_gz

edit flag offensive delete link more

Comments

Thank you!

azazdeaz gravatar imageazazdeaz ( 2022-12-20 01:38:54 -0500 )edit
0

answered 2023-06-25 12:12:43 -0500

this post is marked as community wiki

This post is a wiki. Anyone with karma >75 is welcome to improve it.

For anyone struggling with this, my issue was that the command for Garden should be: ros2 run ros_gz_bridge parameter_bridge /cmd_vel@geometry_msgs/msg/Twist@gz.m... NOT ros2 run ros_gz_bridge parameter_bridge /cmd_vel@geometry_msgs/Twist@gz.msgs....

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2022-12-18 13:56:55 -0500

Seen: 1,316 times

Last updated: Dec 19 '22