Unable to do Gazebo sim Humble ROS 2 Integration Tutorials with gz-garden
Desktop Devel Station Machine: MAC M1 arm64/aarch64 with Ubuntu 22.04/ROS 2 Desktop Full installed. Removed ros-ign-*. Installed https://gazebosim.org/docs/garden Ubuntu Binary with this result:
~: gz sim shapes.sdf Works, showing Gazebo Window
Tutorial > ROS 2 Integration: Test scripts have errors.
ros2 run rosgzbridge parameterbridge /keyboard/keypress@stdmsgs/msg/Int32@gz.msgs.Int32
[INFO] [1680810238.611953783] [rosgzbridge]: Creating GZ->ROS Bridge: /keyboard/keypress (gz.msgs.Int32) -> /keyboard/keypress (std_msgs/msg/Int32)
[WARN] [1680810238.612481325] [rosgzbridge]: Failed to create a bridge for topic [/keyboard/keypress] with ROS2 type [/keyboard/keypress] to topic [stdmsgs/msg/Int32] with Gazebo Transport type [gz.msgs.Int32]
^C[INFO] [1680810242.344507380] [rclcpp]: signalhandler(signum=2)
The Next Tutorial - Spawn Urdf, gz sim empty.sdf displays Window gz service -s /world/empty/create --reqtype gz.msgs.EntityFactory --reptype gz.msgs.Boolean --timeout 1000 --req 'sdffilename: "/path/to/model.urdf", name: "urdfmodel"' Terminates to command line ~/ with no additional object in window.
As I understand that the default gz-sim install is Fortress, so possibly the problem as I intalled gz-garden. In a separate Gazebo.answer.org post, I asked an question on compiling ros_gz humble
Suggested diagnostic actions appreciated.
Asked by RobotRoss on 2023-04-06 15:46:21 UTC
Answers
The problem is not because of your gazebo version. I'm using ROS2 humble with garden. And it's working.
Did you install ros_gz through source ? Ros_gz
If not, you need to install it from source to use it with gazebo garden. Clone it, be sure to be on ROS2 or humble branch, install the dependencies through rosdep, and compile it. The procedure is written in the github page.
Asked by Mildred34 on 2023-04-11 08:30:32 UTC
Comments
April 25, 2023 Edit: Objective is to Install and Run "ros_gz_project_template" "diff_drive" ros_gz_project_template on the appropriate gz-garden or gz-fortress install on my Ubuntu 22.04/ROS2 Humble arm64/aarch64 machine.
See April 24, 2023 actions below, that resulted in a successful Ignition Fortress and rs_gz install, but failed ros_gz_project_template compile, that is now my outstanding Question.
April 22, 2023 Previous gz-garden install With a Gazebo Garden Binary install gz-garden, I was able to get the "Shapes.sdf display, but nothing else worked. Also unable to compile the ros_gz Garden from Source and the Package ros_gz_project_template
April 24, 2023 Actions to reinstall Ignition Fortress and compatible ros_gz from Binary: With Ubuntu Synaptic and command line $ sudo apt remove: Removed all previous Binary installed gz-garden and gz-fortress packages, and any dependancies referring to gz, gazebo, ign, ignition, etc.
Then I reinstalled $ sudo apt install ros-humble-Desktop-full , that installed ROS 2 with "Simulation Packages" (for Fortress) ros_ign_bridge, ros_ign_bridge, ros_ign_image, ros_ign_interfaxces.
Following Binary Installation Ubuntu , and ros_gz Fortress , successfully able to run $ ign gazebo shapes.sdf ($ gz fortress shapes .sdf is incorrect). This Docs/Gazebo Fortress page recommends the ROS 2 Humble GZ Fortress combination, NOT the GZ Garden labeled "Possible" (though as Recommended on [gz-garden]https://staging.gazebosim.org/docs/garden) .
The DOS/Gazebo Fortress " ROS Integration Tutorials and Advanced run OK.
Question: April 25, 2025 How to compile ros-gz_project_template on the Ignition Fortress & ros_gz ? After an initial colcon build compile errors, I realized that I had to install with Synaptic, libgz-cmake3-dev, libgz-plugin2, libgz-command5, and libgz-sim7, and configure "export CMAKE_PREFIX_PATH=/usr/share/cmake-gz-make3, which only enable this last package to clear.
I attempted the Known workaround to configure 4 links into a single environment file, which worked for gz-cmake3 as it has an explicit gz-cmake3-config.cmake file, but enable to identify the correct configuration file and location for the remaining links. gz-common5 and gz-plugin2 python3) are installed in /usr/lib/arch64-linux-gnu/ and gz-sim7 in /usr/share/gz .
Here's the error message:
ubuntu@macvm-ub22-r2:~/template_ws$ export GZ_CONFIG_PATH=$HOME/.gz/tools/configs
ubuntu@macvm-ub22-r2:~/template_ws$ env |grep CONFIG
GZ_CONFIG_PATH=/home/ubuntu/.gz/tools/configs
ubuntu@macvm-ub22-r2:~/template_ws$ colcon build --cmake-args -DBUILD_TESTING=ON
Starting >>> ros_z_example_application
Starting >>> ros_gz_example_bringup
Finished <<< ros_gz_example_bringup [0.12s]
Starting >>> ros_z_example_description
Finished <<< ros_gz_example_application [0.13s]
Starting >>> ros_gz_example_gazebo
Finished <<< ros_gz_example_description [0.10s]
--- stderr: ros_gz_example_gazebo
CMake Error at CMakeLists.txt:8 (find_package):
By not providing "Findgz-plugin2.cmake" in CMAKE_MODULE_PATH this project
has asked CMake to find a package configuration file provided by
"gz-plugin2", but CMake did not find one.
Could not find a package configuration file provided by "gz-plugin2" with any of the following names:
gz-plugin2Config.cmake
gz-plugin2-config.cmake
Add the installation prefix of "gz-plugin2" to CMAKE_PREFIX_PATH or set "gz-plugin2_DIR" to a directory containing one of the above files. If "gz-plugin2" provides a separate development package or SDK, be sure it has been installed.
So there is an unresolved problem to configure a CMAKE_MODULE PATH for the gz-plugin2, gz-common5 and gz-sim7 packages and appreciate suggested actions to enable compiling completion.
I should state that my objective to migrate existing Classic Gazebo examples that use "gazebo_ros_packages" by adapting the ros_gz_project_template "diff_drive" ros_gz_project_template "diff_drive" robot but obviously cannot until I get a clean Gazebo and ros_gz install , be it Garden or Fortress, though as ros_gz cannot compile on Garden, there appears better progress with Fortress. I note that the next LTS release of Harmonic is scheduled Sep/23 which I presume should result in a clean functional Sim & ros_gz Binary install and perhaps need to wait.
Asked by RobotRoss on 2023-04-22 18:57:26 UTC
Comments