gazebosim / ros_gz

Integration between ROS (1 and 2) and Gazebo simulation
https://gazebosim.org
Apache License 2.0
252 stars 138 forks source link

gz.msgs not working on humble - demos broken #339

Closed c-rizz closed 1 year ago

c-rizz commented 1 year ago

Hello, I'm just starting with ROS2 and the new gazebo, so I have been trying the demos, but they don't seem to work (which makes all quite a bit confusing for a new user of both things). I managed to make them work, the issue seems to be the use of gz.msgs on Humble/Fortress/IgnitionGazebo6.

Environment

Description

Steps to reproduce

Launch 'ros2 launch ros_gz_sim_demos tf_bridge.launch.py'

Output

ros2 launch ros_gz_sim_demos tf_bridge.launch.py 
[INFO] [launch]: All log files can be found below /home/april/.ros/log/2022-12-20-18-02-04-051812-alien17r3-2204-new-3537012
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [ign-1]: process started with pid [3537025]
[INFO] [parameter_bridge-2]: process started with pid [3537027]
[INFO] [rviz2-3]: process started with pid [3537029]
[parameter_bridge-2] [INFO] [1671555724.341193953] [ros_gz_bridge]: Creating GZ->ROS Bridge: [/world/default/model/double_pendulum_with_base0/joint_state (gz.msgs.Model) -> /world/default/model/double_pendulum_with_base0/joint_state (sensor_msgs/msg/JointState)] (Lazy 0)
[parameter_bridge-2] [WARN] [1671555724.341501747] [ros_gz_bridge]: Failed to create a bridge for topic [/world/default/model/double_pendulum_with_base0/joint_state] with ROS2 type [/world/default/model/double_pendulum_with_base0/joint_state] to topic [sensor_msgs/msg/JointState] with Gazebo Transport type [gz.msgs.Model]
[parameter_bridge-2] [INFO] [1671555724.341534787] [ros_gz_bridge]: Creating GZ->ROS Bridge: [/model/double_pendulum_with_base0/pose (gz.msgs.Pose_V) -> /model/double_pendulum_with_base0/pose (tf2_msgs/msg/TFMessage)] (Lazy 0)
[parameter_bridge-2] [WARN] [1671555724.341593543] [ros_gz_bridge]: Failed to create a bridge for topic [/model/double_pendulum_with_base0/pose] with ROS2 type [/model/double_pendulum_with_base0/pose] to topic [tf2_msgs/msg/TFMessage] with Gazebo Transport type [gz.msgs.Pose_V]
[rviz2-3] [INFO] [1671555724.717600684] [rviz2]: Stereo is NOT SUPPORTED
[rviz2-3] [INFO] [1671555724.717704446] [rviz2]: OpenGl version: 4.6 (GLSL 4.6)
[rviz2-3] [INFO] [1671555724.786843817] [rviz2]: Stereo is NOT SUPPORTED
[ign-1] libEGL warning: DRI2: failed to create dri screen
[ign-1] libEGL warning: DRI2: failed to create dri screen
^C[WARNING] [launch]: user interrupted with ctrl-c (SIGINT)
[rviz2-3] [INFO] [1671555753.971278015] [rclcpp]: signal_handler(signum=2)
[parameter_bridge-2] [INFO] [1671555753.971277617] [rclcpp]: signal_handler(signum=2)
[INFO] [rviz2-3]: process has finished cleanly [pid 3537029]
[ERROR] [parameter_bridge-2]: process[parameter_bridge-2] failed to terminate '5' seconds after receiving 'SIGINT', escalating to 'SIGTERM'
[ERROR] [ign-1]: process[ign-1] failed to terminate '5' seconds after receiving 'SIGINT', escalating to 'SIGTERM'
[INFO] [parameter_bridge-2]: sending signal 'SIGTERM' to process[parameter_bridge-2]
[INFO] [ign-1]: sending signal 'SIGTERM' to process[ign-1]
[INFO] [parameter_bridge-2]: process has finished cleanly [pid 3537027]
[ERROR] [ign-1]: process has died [pid 3537025, exit code -15, cmd 'ign gazebo -r /home/april/ros2_humble/install/ros_gz_sim_demos/share/ros_gz_sim_demos/models/double_pendulum_model.sdf'].

Solution:

Either roll back to use ignition.msgs (see fork) or somehow make gz.msgs work.

julled commented 1 year ago

Hi i am also new to ros2 + gazebo, so i am aswell maximum confused on how to get things started.

Env

Output

bash ros2 launch ros_gz_sim_demos camera.launch.py

returns

[INFO] [launch]: All log files can be found below /home/asfoe/.ros/log/2022-12-21-23-32-32-116961-asfoe-t14-946394                
[INFO] [launch]: Default logging verbosity is set to INFO                                                                           
[INFO] [ruby $(which gz) sim-1]: process started with pid [946395]                                                              
[INFO] [parameter_bridge-2]: process started with pid [946397]                                                  
[INFO] [rviz2-3]: process started with pid [946401]                                                                             
[rviz2-3] QStandardPaths: XDG_RUNTIME_DIR not set, defaulting to '/tmp/runtime-asfoe'                           
[parameter_bridge-2] [INFO] [1671665552.321776905] [ros_gz_bridge]: Creating GZ->ROS Bridge: [/camera (gz.msgs.Image) -> /camera (sensor_msgs/msg/Image)] (Lazy 0)
[parameter_bridge-2] [WARN] [1671665552.325729472] [ros_gz_bridge]: Failed to create a bridge for topic [/camera] with ROS2 type [/camera] to topic [sensor_msgs/msg/Image] with Gazebo Transport type [gz.msgs.Image]
[parameter_bridge-2] [INFO] [1671665552.325810129] [ros_gz_bridge]: Creating GZ->ROS Bridge: [/camera_info (gz.msgs.CameraInfo) -> /camera_info (sensor_msgs/msg/CameraInfo)] (Lazy 0)                                
[parameter_bridge-2] [WARN] [1671665552.325837714] [ros_gz_bridge]: Failed to create a bridge for topic [/camera_info] with ROS2 type [/camera_info] to topic [sensor_msgs/msg/CameraInfo] with Gazebo Transport type [gz.msgs.CameraInfo]
[ruby $(which gz) sim-1] QStandardPaths: XDG_RUNTIME_DIR not set, defaulting to '/tmp/runtime-asfoe'                                                                                                                                                                
[rviz2-3] [INFO] [1671665552.481120863] [rviz2]: Stereo is NOT SUPPORTED                                        
[rviz2-3] [INFO] [1671665552.481228825] [rviz2]: OpenGl version: 4.6 (GLSL 4.6)                                 
[rviz2-3] [INFO] [1671665552.501067288] [rviz2]: Stereo is NOT SUPPORTED                                                        
[rviz2-3] [INFO] [1671665552.619186883] [rviz2]: Stereo is NOT SUPPORTED                                                        
[rviz2-3] [INFO] [1671665552.628231068] [rviz2]: Stereo is NOT SUPPORTED    

So i think i see the same problem as you.

julled commented 1 year ago

Solution:

Either roll back to use ignition.msgs (see fork) or somehow make gz.msgs work.

i tried this by changing my launch file to use the other datatypes as above... there is no error at least, but the image viewer is still empty.


[INFO] [launch]: All log files can be found below /home/asfoe/.ros/log/2022-12-21-23-51-07-669495-asfoe-t14-968779                                                                                                                                                  
[INFO] [launch]: Default logging verbosity is set to INFO                                                                                                                                                                                                           
[INFO] [parameter_bridge-1]: process started with pid [969079]                                                                                                                                                                                                      
[INFO] [rviz2-2]: process started with pid [969081]                                                                                                                                                                                                                 
[rviz2-2] QStandardPaths: XDG_RUNTIME_DIR not set, defaulting to '/tmp/runtime-asfoe'                                                                                                                                                                               
[parameter_bridge-1] [INFO] [1671666667.894887696] [ros_gz_bridge]: Creating GZ->ROS Bridge: [/camera (ignition.msgs.Image) -> /camera (sensor_msgs/msg/Image)] (Lazy 0)                    
[parameter_bridge-1] [INFO] [1671666667.899576446] [ros_gz_bridge]: Creating ROS->GZ Bridge: [/camera (sensor_msgs/msg/Image) -> /camera (ignition.msgs.Image)] (Lazy 0)                    
[parameter_bridge-1] [INFO] [1671666667.902008043] [ros_gz_bridge]: Creating GZ->ROS Bridge: [/camera_info (ignition.msgs.CameraInfo) -> /camera_info (sensor_msgs/msg/CameraInfo)] (Lazy 0)
[parameter_bridge-1] [INFO] [1671666667.903179776] [ros_gz_bridge]: Creating ROS->GZ Bridge: [/camera_info (sensor_msgs/msg/CameraInfo) -> /camera_info (ignition.msgs.CameraInfo)] (Lazy 0)
[rviz2-2] [INFO] [1671666668.181093194] [rviz2]: Stereo is NOT SUPPORTED       
[rviz2-2] [INFO] [1671666668.181246339] [rviz2]: OpenGl version: 4.6 (GLSL 4.6)
[rviz2-2] [INFO] [1671666668.206359034] [rviz2]: Stereo is NOT SUPPORTED
[rviz2-2] [INFO] [1671666668.404316147] [rviz2]: Stereo is NOT SUPPORTED
[rviz2-2] [INFO] [1671666668.428308716] [rviz2]: Stereo is NOT SUPPORTED
AustinDeric commented 1 year ago

humble branch should support gz sim 6 (Fortress).

Where is this specified in the humble or ignition docs?

AustinDeric commented 1 year ago

effectively this means that ignition garden and ros2 humble are broken @tfoote.

tfoote commented 1 year ago

Based on timing of the report this looks like it is a regression since the latest release.

https://discourse.ros.org/t/new-packages-for-ros-2-humble-hawksbill-2022-12-16/28806

@audrow @azeey FYI

c-rizz commented 1 year ago

i tried this by changing my launch file to use the other datatypes as above... there is no error at least, but the image viewer is still empty.

I tried with my fork (https://github.com/c-rizz/ros_gz/tree/humble) in a clean workspace and it seems to work fine for me. Rqt correctly shows the image.

Where is this specified in the humble or ignition docs?

Not exactly sure how this is supposed to work, but the table at the beginning of the repo's README says the humble binaries at https://packages.ros.org/ support fortress. And the package.xml of ros_gz_sim by default depends on fortress on the humble branch ros_gz/ros_gz_sim/package.xml

PS: sorry for closing and reopening, I pressed by mistake...

mjcarroll commented 1 year ago

I have confirmed that this is broken. The humble branch should be compatible with fortress and garden, and that compatibility was broken. I'm opening a PR to fix.

mjcarroll commented 1 year ago

This was caused by the bridge only recognizing ignition. prefixed message definitions. I adjusted the bridge to also recognize gz. in #349 , which will make this branch compatible with more versions of gazebo without issue.

azeey commented 1 year ago

Closed by #349