How to debug: [ros_gz_bridge]: Failed to create a bridge for topic
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
For reference, a question about probably the same issue on robotics.stackexchange: https://robotics.stackexchange.com/qu...