From 8cdfc2e14909b134fcd1877e940a7986fc044a10 Mon Sep 17 00:00:00 2001 From: methylDragon Date: Tue, 21 Jun 2022 16:57:34 -0700 Subject: [PATCH] Support ros_ign migration and implement shims Clean up shared libraries, and tick-tock RosGzPointCloud Tick-tock launch args Hard-tock ign_ in sources Migrate ign, ign_, IGN_ for sources, launch, and test files Migrate IGN_XXX_VER, IGN_T, header guards Migrate launchfile, launchfile args, and test source references Migrate ros_ign_XXX and gz_gazebo -> gz_sim Migrate ros_ign_XXX project names Migrate Ign, ign-, IGN_DEPS, ign-gazebo Migrate ignitionrobotics, ignitionrobotics/ros_ign, osrf/ros_ign Migrate ignition-version, IGNITION_VERSION, Ignition , ros_ign_ci Signed-off-by: methylDragon --- .github/workflows/build-and-test.sh | 6 +- .github/workflows/ros2-ci.yml | 12 +- README.md | 20 +- RELEASING.md | 24 +- ros_gz/CHANGELOG.rst | 16 +- ros_gz/CMakeLists.txt | 2 +- ros_gz/README.md | 2 +- ros_gz/package.xml | 6 +- ros_gz_bridge/CHANGELOG.rst | 108 ++-- ros_gz_bridge/CMakeLists.txt | 72 +-- ros_gz_bridge/README.md | 38 +- .../include/ros_gz_bridge/convert.hpp | 22 +- .../convert/builtin_interfaces.hpp | 20 +- .../ros_gz_bridge/convert/geometry_msgs.hpp | 102 ++-- .../ros_gz_bridge/convert/nav_msgs.hpp | 30 +- .../convert/ros_gz_interfaces.hpp | 170 +++--- .../ros_gz_bridge/convert/rosgraph_msgs.hpp | 22 +- .../ros_gz_bridge/convert/sensor_msgs.hpp | 86 +-- .../ros_gz_bridge/convert/std_msgs.hpp | 86 +-- .../ros_gz_bridge/convert/tf2_msgs.hpp | 22 +- .../ros_gz_bridge/convert/trajectory_msgs.hpp | 30 +- .../include/ros_gz_bridge/convert_decl.hpp | 22 +- ros_gz_bridge/package.xml | 22 +- ros_gz_bridge/src/bridge.hpp | 68 +-- .../src/convert/builtin_interfaces.cpp | 22 +- ros_gz_bridge/src/convert/geometry_msgs.cpp | 218 ++++---- ros_gz_bridge/src/convert/nav_msgs.cpp | 62 +-- .../src/convert/ros_gz_interfaces.cpp | 510 +++++++++--------- ros_gz_bridge/src/convert/rosgraph_msgs.cpp | 20 +- ros_gz_bridge/src/convert/sensor_msgs.cpp | 388 ++++++------- ros_gz_bridge/src/convert/std_msgs.cpp | 128 ++--- ros_gz_bridge/src/convert/tf2_msgs.cpp | 28 +- ros_gz_bridge/src/convert/trajectory_msgs.cpp | 74 +-- ros_gz_bridge/src/convert/utils.cpp | 6 +- ros_gz_bridge/src/convert/utils.hpp | 6 +- ros_gz_bridge/src/factories.cpp | 46 +- ros_gz_bridge/src/factories.hpp | 10 +- .../src/factories/builtin_interfaces.cpp | 24 +- .../src/factories/builtin_interfaces.hpp | 6 +- ros_gz_bridge/src/factories/geometry_msgs.cpp | 184 +++---- ros_gz_bridge/src/factories/geometry_msgs.hpp | 6 +- ros_gz_bridge/src/factories/nav_msgs.cpp | 40 +- ros_gz_bridge/src/factories/nav_msgs.hpp | 6 +- .../src/factories/ros_gz_interfaces.cpp | 292 +++++----- .../src/factories/ros_gz_interfaces.hpp | 14 +- ros_gz_bridge/src/factories/rosgraph_msgs.cpp | 24 +- ros_gz_bridge/src/factories/rosgraph_msgs.hpp | 6 +- ros_gz_bridge/src/factories/sensor_msgs.cpp | 152 +++--- ros_gz_bridge/src/factories/sensor_msgs.hpp | 6 +- ros_gz_bridge/src/factories/std_msgs.cpp | 152 +++--- ros_gz_bridge/src/factories/std_msgs.hpp | 6 +- ros_gz_bridge/src/factories/tf2_msgs.cpp | 24 +- ros_gz_bridge/src/factories/tf2_msgs.hpp | 6 +- .../src/factories/trajectory_msgs.cpp | 36 +- .../src/factories/trajectory_msgs.hpp | 6 +- ros_gz_bridge/src/factory.hpp | 62 +-- ros_gz_bridge/src/factory_interface.cpp | 4 +- ros_gz_bridge/src/factory_interface.hpp | 14 +- ros_gz_bridge/src/parameter_bridge.cpp | 98 ++-- .../service_factories/ros_gz_interfaces.cpp | 42 +- .../service_factories/ros_gz_interfaces.hpp | 16 +- ros_gz_bridge/src/service_factory.hpp | 32 +- .../src/service_factory_interface.hpp | 6 +- ros_gz_bridge/src/static_bridge.cpp | 14 +- .../test/launch/test_gz_server.launch.py | 10 +- .../test/launch/test_gz_subscriber.launch.py | 26 +- .../test/launch/test_ros_subscriber.launch.py | 26 +- .../test/publishers/gz_publisher.cpp | 88 +-- .../test/publishers/ros_publisher.cpp | 140 ++--- ros_gz_bridge/test/serverclient/gz_server.cpp | 4 +- .../test/serverclient/ros_client.cpp | 10 +- .../test/subscribers/gz_subscriber.cpp | 94 ++-- .../builtin_interfaces_subscriber.cpp | 2 +- .../geometry_msgs_subscriber.cpp | 24 +- .../ros_subscriber/nav_msgs_subscriber.cpp | 4 +- .../ros_gz_interfaces_subscriber.cpp | 36 +- .../ros_subscriber/ros_subscriber.hpp | 2 +- .../rosgraph_msgs_subscriber.cpp | 2 +- .../ros_subscriber/sensor_msgs_subscriber.cpp | 18 +- .../ros_subscriber/std_msgs_subscriber.cpp | 16 +- .../trajectory_msgs_subscriber.cpp | 2 +- ros_gz_bridge/test/utils/gz_test_msg.cpp | 6 +- ros_gz_bridge/test/utils/gz_test_msg.hpp | 10 +- ros_gz_bridge/test/utils/ros_test_msg.cpp | 74 +-- ros_gz_bridge/test/utils/ros_test_msg.hpp | 60 +-- ros_gz_bridge/test/utils/test_utils.hpp | 4 +- ros_gz_image/CHANGELOG.rst | 46 +- ros_gz_image/CMakeLists.txt | 43 +- ros_gz_image/package.xml | 22 +- ros_gz_image/src/image_bridge.cpp | 28 +- .../test/launch/test_ros_subscriber.launch | 6 +- ros_gz_image/test/publishers/gz_publisher.cpp | 2 +- ros_gz_image/test/ros_subscriber.test | 4 +- .../test/subscribers/ros_subscriber.cpp | 4 +- ros_gz_image/test/test_utils.h | 10 +- ros_gz_interfaces/CHANGELOG.rst | 26 +- ros_gz_interfaces/CMakeLists.txt | 2 +- ros_gz_interfaces/msg/Contact.msg | 6 +- ros_gz_interfaces/msg/Contacts.msg | 2 +- ros_gz_interfaces/msg/WorldControl.msg | 2 +- ros_gz_interfaces/package.xml | 4 +- ros_gz_interfaces/srv/ControlWorld.srv | 2 +- ros_gz_interfaces/srv/DeleteEntity.srv | 2 +- ros_gz_interfaces/srv/SetEntityPose.srv | 2 +- ros_gz_interfaces/srv/SpawnEntity.srv | 2 +- ros_gz_point_cloud/CMakeLists.txt | 29 +- ros_gz_point_cloud/examples/depth_camera.sdf | 23 +- ros_gz_point_cloud/examples/gpu_lidar.sdf | 23 +- ros_gz_point_cloud/examples/rgbd_camera.sdf | 27 +- ros_gz_point_cloud/package.xml | 4 +- ros_gz_point_cloud/src/point_cloud.cc | 31 +- ros_gz_point_cloud/src/point_cloud.hh | 6 +- ros_gz_shims/README.md | 13 + ros_gz_shims/ros_ign/CMakeLists.txt | 10 + ros_gz_shims/ros_ign/README.md | 2 + ros_gz_shims/ros_ign/package.xml | 28 + ros_gz_shims/ros_ign_bridge/CMakeLists.txt | 29 + ros_gz_shims/ros_ign_bridge/README.md | 2 + ros_gz_shims/ros_ign_bridge/package.xml | 19 + .../src/parameter_bridge_shim.cpp | 30 ++ .../ros_ign_bridge/src/static_bridge_shim.cpp | 30 ++ ros_gz_shims/ros_ign_gazebo/CMakeLists.txt | 45 ++ .../launch/ign_gazebo.launch.py.in | 63 +++ ros_gz_shims/ros_ign_gazebo/package.xml | 19 + .../ros_ign_gazebo/src/create_shim.cpp | 30 ++ .../ros_ign_gazebo_demos/CMakeLists.txt | 29 + ros_gz_shims/ros_ign_gazebo_demos/README.md | 2 + .../launch/air_pressure.launch.py | 63 +++ .../launch/battery.launch.py | 69 +++ .../launch/camera.launch.py | 63 +++ .../launch/depth_camera.launch.py | 77 +++ .../launch/diff_drive.launch.py | 69 +++ .../launch/gpu_lidar.launch.py | 65 +++ .../launch/gpu_lidar_bridge.launch.py | 65 +++ .../launch/image_bridge.launch.py | 65 +++ .../ros_ign_gazebo_demos/launch/imu.launch.py | 78 +++ .../launch/joint_states.launch.py | 98 ++++ .../launch/magnetometer.launch.py | 63 +++ .../launch/rgbd_camera.launch.py | 63 +++ .../launch/rgbd_camera_bridge.launch.py | 70 +++ .../robot_description_publisher.launch.py | 93 ++++ .../launch/tf_bridge.launch.py | 59 ++ .../launch/triggered_camera.launch.py | 64 +++ .../models/double_pendulum_model.sdf | 266 +++++++++ .../ros_ign_gazebo_demos/models/rrbot.xacro | 165 ++++++ ros_gz_shims/ros_ign_gazebo_demos/package.xml | 17 + .../ros_ign_gazebo_demos/rviz/camera.rviz | 137 +++++ .../rviz/depth_camera.rviz | 147 +++++ .../ros_ign_gazebo_demos/rviz/diff_drive.rviz | 123 +++++ .../ros_ign_gazebo_demos/rviz/gpu_lidar.rviz | 181 +++++++ .../rviz/gpu_lidar_bridge.rviz | 167 ++++++ .../ros_ign_gazebo_demos/rviz/imu.rviz | 130 +++++ .../rviz/joint_states.rviz | 190 +++++++ .../rviz/rgbd_camera.rviz | 159 ++++++ .../rviz/rgbd_camera_bridge.rviz | 142 +++++ .../rviz/robot_description_publisher.rviz | 148 +++++ .../ros_ign_gazebo_demos/rviz/tf_bridge.rviz | 163 ++++++ ros_gz_shims/ros_ign_image/CMakeLists.txt | 26 + ros_gz_shims/ros_ign_image/README.md | 2 + ros_gz_shims/ros_ign_image/package.xml | 19 + .../ros_ign_image/src/image_bridge_shim.cpp | 30 ++ .../ros_ign_interfaces/CMakeLists.txt | 49 ++ ros_gz_shims/ros_ign_interfaces/README.md | 2 + .../ros_ign_interfaces/msg/Contact.msg | 6 + .../ros_ign_interfaces/msg/Contacts.msg | 2 + .../ros_ign_interfaces/msg/Entity.msg | 13 + .../ros_ign_interfaces/msg/EntityFactory.msg | 11 + .../ros_ign_interfaces/msg/GuiCamera.msg | 12 + .../ros_ign_interfaces/msg/JointWrench.msg | 8 + ros_gz_shims/ros_ign_interfaces/msg/Light.msg | 29 + .../ros_ign_interfaces/msg/StringVec.msg | 7 + .../ros_ign_interfaces/msg/TrackVisual.msg | 33 ++ .../ros_ign_interfaces/msg/VideoRecord.msg | 16 + .../ros_ign_interfaces/msg/WorldControl.msg | 7 + .../ros_ign_interfaces/msg/WorldReset.msg | 3 + ros_gz_shims/ros_ign_interfaces/package.xml | 27 + .../ros_ign_interfaces/srv/ControlWorld.srv | 3 + .../ros_ign_interfaces/srv/DeleteEntity.srv | 3 + .../ros_ign_interfaces/srv/SetEntityPose.srv | 4 + .../ros_ign_interfaces/srv/SpawnEntity.srv | 3 + ros_gz_sim/CHANGELOG.rst | 60 +-- ros_gz_sim/CMakeLists.txt | 56 +- ros_gz_sim/README.md | 8 +- ros_gz_sim/launch/gz_sim.launch.py.in | 37 +- ros_gz_sim/package.xml | 20 +- ros_gz_sim/src/create.cpp | 8 +- ros_gz_sim_demos/CHANGELOG.rst | 54 +- ros_gz_sim_demos/CMakeLists.txt | 2 +- ros_gz_sim_demos/README.md | 60 +-- .../launch/air_pressure.launch.py | 14 +- ros_gz_sim_demos/launch/battery.launch.py | 12 +- ros_gz_sim_demos/launch/camera.launch.py | 16 +- .../launch/depth_camera.launch.py | 16 +- ros_gz_sim_demos/launch/diff_drive.launch.py | 16 +- ros_gz_sim_demos/launch/gpu_lidar.launch.py | 16 +- .../launch/gpu_lidar_bridge.launch.py | 16 +- .../launch/image_bridge.launch.py | 12 +- ros_gz_sim_demos/launch/imu.launch.py | 16 +- .../launch/joint_states.launch.py | 20 +- .../launch/magnetometer.launch.py | 12 +- ros_gz_sim_demos/launch/rgbd_camera.launch.py | 16 +- .../launch/rgbd_camera_bridge.launch.py | 16 +- .../robot_description_publisher.launch.py | 14 +- ros_gz_sim_demos/launch/tf_bridge.launch.py | 8 +- .../launch/triggered_camera.launch.py | 16 +- ros_gz_sim_demos/models/rrbot.xacro | 2 +- ros_gz_sim_demos/package.xml | 20 +- 207 files changed, 6642 insertions(+), 2666 deletions(-) create mode 100644 ros_gz_shims/README.md create mode 100644 ros_gz_shims/ros_ign/CMakeLists.txt create mode 100644 ros_gz_shims/ros_ign/README.md create mode 100644 ros_gz_shims/ros_ign/package.xml create mode 100644 ros_gz_shims/ros_ign_bridge/CMakeLists.txt create mode 100644 ros_gz_shims/ros_ign_bridge/README.md create mode 100644 ros_gz_shims/ros_ign_bridge/package.xml create mode 100644 ros_gz_shims/ros_ign_bridge/src/parameter_bridge_shim.cpp create mode 100644 ros_gz_shims/ros_ign_bridge/src/static_bridge_shim.cpp create mode 100644 ros_gz_shims/ros_ign_gazebo/CMakeLists.txt create mode 100644 ros_gz_shims/ros_ign_gazebo/launch/ign_gazebo.launch.py.in create mode 100644 ros_gz_shims/ros_ign_gazebo/package.xml create mode 100644 ros_gz_shims/ros_ign_gazebo/src/create_shim.cpp create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/CMakeLists.txt create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/README.md create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/air_pressure.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/battery.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/camera.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/depth_camera.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/diff_drive.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/gpu_lidar.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/gpu_lidar_bridge.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/image_bridge.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/imu.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/joint_states.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/magnetometer.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/rgbd_camera.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/rgbd_camera_bridge.launch.py create mode 100755 ros_gz_shims/ros_ign_gazebo_demos/launch/robot_description_publisher.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/tf_bridge.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/launch/triggered_camera.launch.py create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/models/double_pendulum_model.sdf create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/models/rrbot.xacro create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/package.xml create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/camera.rviz create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/depth_camera.rviz create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/diff_drive.rviz create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/gpu_lidar.rviz create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/gpu_lidar_bridge.rviz create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/imu.rviz create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/joint_states.rviz create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/rgbd_camera.rviz create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/rgbd_camera_bridge.rviz create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/robot_description_publisher.rviz create mode 100644 ros_gz_shims/ros_ign_gazebo_demos/rviz/tf_bridge.rviz create mode 100644 ros_gz_shims/ros_ign_image/CMakeLists.txt create mode 100644 ros_gz_shims/ros_ign_image/README.md create mode 100644 ros_gz_shims/ros_ign_image/package.xml create mode 100644 ros_gz_shims/ros_ign_image/src/image_bridge_shim.cpp create mode 100644 ros_gz_shims/ros_ign_interfaces/CMakeLists.txt create mode 100644 ros_gz_shims/ros_ign_interfaces/README.md create mode 100644 ros_gz_shims/ros_ign_interfaces/msg/Contact.msg create mode 100644 ros_gz_shims/ros_ign_interfaces/msg/Contacts.msg create mode 100644 ros_gz_shims/ros_ign_interfaces/msg/Entity.msg create mode 100644 ros_gz_shims/ros_ign_interfaces/msg/EntityFactory.msg create mode 100644 ros_gz_shims/ros_ign_interfaces/msg/GuiCamera.msg create mode 100644 ros_gz_shims/ros_ign_interfaces/msg/JointWrench.msg create mode 100644 ros_gz_shims/ros_ign_interfaces/msg/Light.msg create mode 100644 ros_gz_shims/ros_ign_interfaces/msg/StringVec.msg create mode 100644 ros_gz_shims/ros_ign_interfaces/msg/TrackVisual.msg create mode 100644 ros_gz_shims/ros_ign_interfaces/msg/VideoRecord.msg create mode 100644 ros_gz_shims/ros_ign_interfaces/msg/WorldControl.msg create mode 100644 ros_gz_shims/ros_ign_interfaces/msg/WorldReset.msg create mode 100644 ros_gz_shims/ros_ign_interfaces/package.xml create mode 100644 ros_gz_shims/ros_ign_interfaces/srv/ControlWorld.srv create mode 100644 ros_gz_shims/ros_ign_interfaces/srv/DeleteEntity.srv create mode 100644 ros_gz_shims/ros_ign_interfaces/srv/SetEntityPose.srv create mode 100644 ros_gz_shims/ros_ign_interfaces/srv/SpawnEntity.srv diff --git a/.github/workflows/build-and-test.sh b/.github/workflows/build-and-test.sh index 792f07c7..1ac4206d 100755 --- a/.github/workflows/build-and-test.sh +++ b/.github/workflows/build-and-test.sh @@ -11,12 +11,12 @@ apt update -qq apt install -qq -y lsb-release wget curl build-essential # Garden only has nightlies for now -if [ "$IGNITION_VERSION" == "garden" ]; then +if [ "$GZ_VERSION" == "garden" ]; then echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-stable.list echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-nightly `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-nightly.list wget https://packages.osrfoundation.org/gazebo.key -O - | apt-key add - - IGN_DEPS="libgz-sim7-dev" + GZ_DEPS="libgz-sim7-dev" fi # Fortress comes through rosdep for Focal and Jammy @@ -25,7 +25,7 @@ fi echo "deb http://packages.ros.org/ros2-testing/ubuntu `lsb_release -cs` main" > /etc/apt/sources.list.d/ros2-testing.list curl -s https://raw.githubusercontent.com/ros/rosdistro/master/ros.asc | apt-key add - apt-get update -qq -apt-get install -y $IGN_DEPS \ +apt-get install -y $GZ_DEPS \ python3-colcon-common-extensions \ python3-rosdep diff --git a/.github/workflows/ros2-ci.yml b/.github/workflows/ros2-ci.yml index 23411595..571be23a 100644 --- a/.github/workflows/ros2-ci.yml +++ b/.github/workflows/ros2-ci.yml @@ -3,21 +3,21 @@ name: ROS2 CI on: [push, pull_request] jobs: - ros_ign_ci: - name: ros_ign CI + ros_gz_ci: + name: ros_gz CI runs-on: ubuntu-latest strategy: fail-fast: false matrix: include: - docker-image: "ubuntu:22.04" - ignition-version: "fortress" + gz-version: "fortress" ros-distro: "humble" - docker-image: "ubuntu:22.04" - ignition-version: "fortress" + gz-version: "fortress" ros-distro: "rolling" - docker-image: "ubuntu:22.04" - ignition-version: "garden" + gz-version: "garden" ros-distro: "rolling" container: image: ${{ matrix.docker-image }} @@ -28,5 +28,5 @@ jobs: run: .github/workflows/build-and-test.sh env: DOCKER_IMAGE: ${{ matrix.docker-image }} - IGNITION_VERSION: ${{ matrix.ignition-version }} + GZ_VERSION: ${{ matrix.gz-version }} ROS_DISTRO: ${{ matrix.ros-distro }} diff --git a/README.md b/README.md index 811c65fa..a4630556 100644 --- a/README.md +++ b/README.md @@ -25,24 +25,24 @@ Rolling | Garden (not released) | [ros2](https://github.com/gazebosim/ros_gz/tre This repository holds packages that provide integration between [ROS](http://www.ros.org/) and [Gazebo](https://gazebosim.org): -* [ros_ign](https://github.com/gazebosim/ros_gz/tree/ros2/ros_ign): +* [ros_gz](https://github.com/gazebosim/ros_gz/tree/ros2/ros_gz): Metapackage which provides all the other packages. -* [ros_ign_image](https://github.com/gazebosim/ros_gz/tree/ros2/ros_ign_image): +* [ros_gz_image](https://github.com/gazebosim/ros_gz/tree/ros2/ros_gz_image): Unidirectional transport bridge for images from [Gazebo Transport](https://gazebosim.org/libs/transport) to ROS using [image_transport](http://wiki.ros.org/image_transport). -* [ros_ign_bridge](https://github.com/gazebosim/ros_gz/tree/ros2/ros_ign_bridge): +* [ros_gz_bridge](https://github.com/gazebosim/ros_gz/tree/ros2/ros_gz_bridge): Bidirectional transport bridge between [Gazebo Transport](https://gazebosim.org/libs/transport) and ROS. -* [ros_ign_gazebo](https://github.com/gazebosim/ros_gz/tree/ros2/ros_ign_gazebo): +* [ros_gz_sim](https://github.com/gazebosim/ros_gz/tree/ros2/ros_gz_sim): Convenient launch files and executables for using [Gazebo Sim](https://gazebosim.org/libs/gazebo) with ROS. -* [ros_ign_gazebo_demos](https://github.com/gazebosim/ros_gz/tree/ros2/ros_ign_gazebo_demos): +* [ros_gz_sim_demos](https://github.com/gazebosim/ros_gz/tree/ros2/ros_gz_sim_demos): Demos using the ROS-Gazebo integration. -* [ros_ign_point_cloud](https://github.com/gazebosim/ros_gz/tree/ros2/ros_ign_point_cloud): +* [ros_gz_point_cloud](https://github.com/gazebosim/ros_gz/tree/ros2/ros_gz_point_cloud): Plugins for publishing point clouds to ROS from [Gazebo Sim](https://gazebosim.org/libs/gazebo) simulations. @@ -61,7 +61,7 @@ They are hosted at https://packages.ros.org. curl -s https://raw.githubusercontent.com/ros/rosdistro/master/ros.asc | sudo apt-key add - sudo apt-get update -1. Install `ros_ign` +1. Install `ros_gz` sudo apt install ros-rolling-ros-ign @@ -77,14 +77,14 @@ Be sure you've installed Install either [Edifice, Fortress, or Garden](https://gazebosim.org/docs). -Set the `IGNITION_VERSION` environment variable to the Gazebo version you'd +Set the `GZ_VERSION` environment variable to the Gazebo version you'd like to compile against. For example: - export IGNITION_VERSION=edifice + export GZ_VERSION=edifice > You only need to set this variable when compiling, not when running. -#### Compile ros_ign +#### Compile ros_gz The following steps are for Linux and OSX. diff --git a/RELEASING.md b/RELEASING.md index c56a9fef..d0578661 100644 --- a/RELEASING.md +++ b/RELEASING.md @@ -1,7 +1,7 @@ -# Release a new version of ros_ign +# Release a new version of ros_gz Different branches of this repository support different combinations of -ROS 1, ROS 2 and Ignition. Refer to the [README](README.md) to see what +ROS 1, ROS 2 and Gazebo. Refer to the [README](README.md) to see what combinations are supported. We use 2 separate approaches for releasing ROS-enabled binaries: @@ -12,9 +12,9 @@ We use 2 separate approaches for releasing ROS-enabled binaries: for ROS users. Releasing into ROS packages is ideal, but that's only possible if the necessary -Ignition libraries are available either through official Ubuntu packages, or +Gazebo libraries are available either through official Ubuntu packages, or directly from https://packages.ros.org. This situation varies according to the -Ignition version: +Gazebo version: * Citadel is available from: * https://packages.osrfoundation.org: all Ubuntu versions @@ -24,22 +24,22 @@ Ignition version: * https://packages.osrfoundation.org: all Ubuntu versions * https://packages.ros.org: only Ubuntu Focal, once ROS 2 Galactic is out -Another factor to take into consideration is which Ignition version is officially +Another factor to take into consideration is which Gazebo version is officially supported for each ROS distro according to the following REPS: * ROS 1: [REP-0003](https://ros.org/reps/rep-0003.html) * ROS 2: [REP-2000](https://www.ros.org/reps/rep-2000.html) -These factors determine which ROS + Ignition combinations are released into each +These factors determine which ROS + Gazebo combinations are released into each repository. ## Versioning -All `ros_ign` packages are under fast development and haven't reached version +All `ros_gz` packages are under fast development and haven't reached version 1.0 yet. The team will make an effort to keep changes backwards compatible within a ROS distribution, but API / ABI / behaviour may be broken if necessary. -The versioning scheme uses the minor version to identify ROS and Ignition +The versioning scheme uses the minor version to identify ROS and Gazebo versions: * 1st digit: @@ -61,7 +61,7 @@ versions: * Fortress: 4 * Garden: 5 -ROS | Ignition | Version +ROS | Gazebo | Version -- | -- | -- Melodic | Blueprint | 0.100.X Melodic | Citadel | 0.101.X @@ -90,7 +90,7 @@ Foxy | Edifice | 0.223.X * `catkin_generate_changelog` * `catkin_prepare_release` -1. Install `rosdep` for Ignition packages and run rosdep update +1. Install `rosdep` for Gazebo packages and run rosdep update ``` sudo bash -c 'echo "yaml https://github.com/osrf/osrf-rosdep/raw/master/ignition/ignition.yaml" >> /etc/ros/rosdep/sources.list.d/00-ignition.list' rosdep update @@ -98,7 +98,7 @@ Foxy | Edifice | 0.223.X 1. Bloom it into a custom repository ``` - BLOOM_RELEASE_REPO_BASE=https://github.com/osrf/ bloom-release --no-pull-request --rosdistro melodic --track melodic ros_ign + BLOOM_RELEASE_REPO_BASE=https://github.com/osrf/ bloom-release --no-pull-request --rosdistro melodic --track melodic ros_gz ``` Will fail fedora: ignore and continue: @@ -110,5 +110,5 @@ Foxy | Edifice | 0.223.X 1. Use [release-tools](https://bitbucket.org/osrf/release-tools)'s script to launch jenkins jobs: ``` cd release-tools/bloom - ./ros_ign_bridge-release.py.bash 0.8.0 https://github.com/osrf/ros_ign-release --ignition-version + ./ros_gz_bridge-release.py.bash 0.8.0 https://github.com/gazebosim/ros_ign-release --gz-version ``` diff --git a/ros_gz/CHANGELOG.rst b/ros_gz/CHANGELOG.rst index 57261393..6df90aa3 100644 --- a/ros_gz/CHANGELOG.rst +++ b/ros_gz/CHANGELOG.rst @@ -1,10 +1,10 @@ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package ros_ign +Changelog for package ros_gz ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 0.244.3 (2022-05-19) -------------------- -* [ros2] README updates (service bridge, Gazebo rename) (`#252 `_) +* [ros2] README updates (service bridge, Gazebo rename) (`#252 `_) * Contributors: Louise Poubel 0.244.2 (2022-04-25) @@ -29,10 +29,10 @@ Changelog for package ros_ign 0.221.0 (2020-07-23) -------------------- -* Added ros_ign_gazebo to ros_ign package.xml (`#81 `_) -* Update Dashing docs (`#62 `_) -* Port ign_ros_gazebo_demos to ROS2 (`#58 `_) -* Enable ROS2 CI for Dashing branch (`#43 `_) +* Added ros_gz_sim to ros_gz package.xml (`#81 `_) +* Update Dashing docs (`#62 `_) +* Port ign_ros_gazebo_demos to ROS2 (`#58 `_) +* Enable ROS2 CI for Dashing branch (`#43 `_) * Rename packages and fix compilation + tests * Move files ros1 -> ros * Contributors: Alejandro Hernández Cordero, Jose Luis Rivero, Louise Poubel, chapulina @@ -49,8 +49,8 @@ Changelog for package ros_ign 0.6.1 (2019-08-04) ------------------ * Merge pull request `#35 `_ from osrf/image_meta - Add ros_ign_image to metapackage -* Add ros_ign_image to metapackage + Add ros_gz_image to metapackage +* Add ros_gz_image to metapackage Signed-off-by: chapulina typo Signed-off-by: chapulina diff --git a/ros_gz/CMakeLists.txt b/ros_gz/CMakeLists.txt index 80524e92..db4e01a7 100644 --- a/ros_gz/CMakeLists.txt +++ b/ros_gz/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.5) -project(ros_ign) +project(ros_gz) find_package(ament_cmake REQUIRED) if(BUILD_TESTING) diff --git a/ros_gz/README.md b/ros_gz/README.md index b57cdcf8..7053b126 100644 --- a/ros_gz/README.md +++ b/ros_gz/README.md @@ -1,4 +1,4 @@ # ROS-Gazebo packages -`ros_ign` is a metapackage that installs all packages integrating +`ros_gz` is a metapackage that installs all packages integrating [ROS](http://www.ros.org/) and [Gazebo](https://gazebosim.org): diff --git a/ros_gz/package.xml b/ros_gz/package.xml index 53963119..c3d97f87 100644 --- a/ros_gz/package.xml +++ b/ros_gz/package.xml @@ -3,9 +3,9 @@ - ros_ign + ros_gz 0.244.3 - Meta-package containing interfaces for using ROS 2 with Ignition simulation. + Meta-package containing interfaces for using ROS 2 with Gazebo simulation. Louise Poubel Apache 2.0 @@ -15,7 +15,7 @@ ros_ign_gazebo ros_ign_gazebo_demos ros_ign_image - + ament_lint_auto diff --git a/ros_gz_bridge/CHANGELOG.rst b/ros_gz_bridge/CHANGELOG.rst index 041b03de..8653f773 100644 --- a/ros_gz_bridge/CHANGELOG.rst +++ b/ros_gz_bridge/CHANGELOG.rst @@ -1,99 +1,99 @@ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package ros_ign_bridge +Changelog for package ros_gz_bridge ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 0.244.3 (2022-05-19) -------------------- -* Feature: set QoS options to override durability (`#250 `_) +* Feature: set QoS options to override durability (`#250 `_) Co-authored-by: Louise Poubel -* [ros2] README updates (service bridge, Gazebo rename) (`#252 `_) -* Fix linter tests (`#251 `_) +* [ros2] README updates (service bridge, Gazebo rename) (`#252 `_) +* Fix linter tests (`#251 `_) Co-authored-by: Louise Poubel -* Adds pose and twist with covariance messages bridging (`#222 `_) +* Adds pose and twist with covariance messages bridging (`#222 `_) * Added pose, twist and odometry with covariance messages bridging * Contributors: Aditya Pande, Daisuke Nishimatsu, Louise Poubel 0.244.2 (2022-04-25) -------------------- -* Support bridging services (`#211 `_) -* Added reminder to hit play to receive images. (`#237 `_) -* Updated `ign topic` commnds on README (`#221 `_) -* Add conversions for ros_ign_interfaces/WorldControl and builtin_interfaces/Time (`#216 `_) -* [ros_ign_interfaces] Add GuiCamera, StringVec, TrackVisual, VideoRecord (`#214 `_) -* Break apart ros_subscriber test translation unit (`#212 `_) -* Bring ros2 branch up-to-date with Rolling (`#213 `_) -* Add missing dependency on rclcpp (`#209 `_) -* Separate galactic branch from ros2 branch (`#201 `_) -* 🏁 Dome EOL (`#198 `_) +* Support bridging services (`#211 `_) +* Added reminder to hit play to receive images. (`#237 `_) +* Updated `ign topic` commnds on README (`#221 `_) +* Add conversions for ros_gz_interfaces/WorldControl and builtin_interfaces/Time (`#216 `_) +* [ros_gz_interfaces] Add GuiCamera, StringVec, TrackVisual, VideoRecord (`#214 `_) +* Break apart ros_subscriber test translation unit (`#212 `_) +* Bring ros2 branch up-to-date with Rolling (`#213 `_) +* Add missing dependency on rclcpp (`#209 `_) +* Separate galactic branch from ros2 branch (`#201 `_) +* 🏁 Dome EOL (`#198 `_) * Contributors: Aditya Pande, Ivan Santiago Paunovic, Joep Tool, Louise Poubel, Michael Carroll 0.244.1 (2022-01-04) -------------------- -* Improve modularity of ign/ros publisher tests (`#194 `_) +* Improve modularity of ign/ros publisher tests (`#194 `_) * Contributors: Michael Carroll 0.244.0 (2021-12-30) -------------------- -* Default to Fortress for Rolling (future Humble) (`#195 `_) -* [ros2] 🏁 Dome EOL (`#199 `_) -* New Light Message, also bridge Color (`#187 `_) -* Statically link each translation unit (`#193 `_) -* Break apart convert and factories translation unit (`#192 `_) -* Fixed ROS subscriber test in ros_ign_bridge (`#189 `_) -* Enable QoS overrides (`#181 `_) -* Fixed ros ign bridge documentation (`#178 `_) -* Expose Contacts through ROS bridge (`#175 `_) +* Default to Fortress for Rolling (future Humble) (`#195 `_) +* [ros2] 🏁 Dome EOL (`#199 `_) +* New Light Message, also bridge Color (`#187 `_) +* Statically link each translation unit (`#193 `_) +* Break apart convert and factories translation unit (`#192 `_) +* Fixed ROS subscriber test in ros_gz_bridge (`#189 `_) +* Enable QoS overrides (`#181 `_) +* Fixed ros ign bridge documentation (`#178 `_) +* Expose Contacts through ROS bridge (`#175 `_) * Contributors: Alejandro Hernández Cordero, Guillaume Doisy, Louise Poubel, Michael Carroll, Vatan Aksoy Tezer, William Lew 0.233.2 (2021-07-20) -------------------- -* [ros2] Update version docs, add Galactic and Fortress (`#164 `_) +* [ros2] Update version docs, add Galactic and Fortress (`#164 `_) * Contributors: Louise Poubel 0.233.1 (2021-04-16) -------------------- -* Default to Edifice for Rolling (`#150 `_) -* Ignore local publications for ROS 2 subscriber (`#146 `_) +* Default to Edifice for Rolling (`#150 `_) +* Ignore local publications for ROS 2 subscriber (`#146 `_) - Note: Does not work with all rmw implementations (e.g.: FastRTPS) -* Update documentation for installation instructions and bridge examples (`#142 `_) -* Edifice support (`#140 `_) -* Add JointTrajectory message conversion (`#121 `_) +* Update documentation for installation instructions and bridge examples (`#142 `_) +* Edifice support (`#140 `_) +* Add JointTrajectory message conversion (`#121 `_) Conversion between - ignition::msgs::JointTrajectory - trajectory_msgs::msg::JointTrajectory -* Add TFMessage / Pose_V and Float64 / Double conversions (`#117 `_) - Addresses issue `#116 `_ -* Updated prereq & branch name (`#113 `_) -* Update releases (`#108 `_) -* Updated README.md (`#104 `_) -* Add support for Dome (`#103 `_) +* Add TFMessage / Pose_V and Float64 / Double conversions (`#117 `_) + Addresses issue `#116 `_ +* Updated prereq & branch name (`#113 `_) +* Update releases (`#108 `_) +* Updated README.md (`#104 `_) +* Add support for Dome (`#103 `_) * Contributors: Alejandro Hernández Cordero, Andrej Orsula, Florent Audonnet, Jenn, Louise Poubel, Luca Della Vedova 0.221.1 (2020-08-19) -------------------- -* Add pkg-config as a buildtool dependency (`#102 `_) -* Port ros_ign_bridge tests to ROS 2 (`#98 `_) -* Rename test_utils.hpp (`#98 `_) +* Add pkg-config as a buildtool dependency (`#102 `_) +* Port ros_gz_bridge tests to ROS 2 (`#98 `_) +* Rename test_utils.hpp (`#98 `_) * Contributors: Louise Poubel, ahcorde 0.221.0 (2020-07-23) -------------------- -* Install only what's necessary, rename builtin_interfaces (`#95 `_) -* Move headers to src, rename builtin_interfaces (`#95 `_) -* Integer support (`#91 `_) +* Install only what's necessary, rename builtin_interfaces (`#95 `_) +* Move headers to src, rename builtin_interfaces (`#95 `_) +* Integer support (`#91 `_) Adds Int32 to the bridge. -* [ros2] Fixed CI - Added Foxy (`#89 `_) +* [ros2] Fixed CI - Added Foxy (`#89 `_) Co-authored-by: Louise Poubel -* Ignore ros-args in parameter bridge (`#65 `_) -* Update Dashing docs (`#62 `_) -* Update dependencies to Citadel (`#57 `_) -* [WIP] Port ign_ros_gazebo_demos to ROS2 (`#58 `_) - Port ros_ign_image to ROS2 - Port ros_ign_gazebo_demos to ROS2 -* Add support for std_msgs/Empty (`#53 `_) -* Add support for std_msgs/Bool (`#50 `_) -* [ros2] Port ros_ign_bridge to ROS2 (`#45 `_) -* Enable ROS2 CI for Dashing branch (`#43 `_) +* Ignore ros-args in parameter bridge (`#65 `_) +* Update Dashing docs (`#62 `_) +* Update dependencies to Citadel (`#57 `_) +* [WIP] Port ign_ros_gazebo_demos to ROS2 (`#58 `_) + Port ros_gz_image to ROS2 + Port ros_gz_sim_demos to ROS2 +* Add support for std_msgs/Empty (`#53 `_) +* Add support for std_msgs/Bool (`#50 `_) +* [ros2] Port ros_gz_bridge to ROS2 (`#45 `_) +* Enable ROS2 CI for Dashing branch (`#43 `_) * Make all API and comments ROS-version agnostic * Rename packages and fix compilation + tests * Move files ros1 -> ros diff --git a/ros_gz_bridge/CMakeLists.txt b/ros_gz_bridge/CMakeLists.txt index 8c2a5f06..57249f0f 100644 --- a/ros_gz_bridge/CMakeLists.txt +++ b/ros_gz_bridge/CMakeLists.txt @@ -1,6 +1,6 @@ cmake_minimum_required(VERSION 3.5) -project(ros_ign_bridge) +project(ros_gz_bridge) # Default to C++14 if(NOT CMAKE_CXX_STANDARD) @@ -15,31 +15,37 @@ find_package(builtin_interfaces REQUIRED) find_package(geometry_msgs REQUIRED) find_package(nav_msgs REQUIRED) find_package(rclcpp REQUIRED) -find_package(ros_ign_interfaces REQUIRED) +find_package(ros_gz_interfaces REQUIRED) find_package(rosgraph_msgs REQUIRED) find_package(sensor_msgs REQUIRED) find_package(std_msgs REQUIRED) find_package(tf2_msgs REQUIRED) find_package(trajectory_msgs REQUIRED) +# TODO(CH3): Deprecated. Remove on tock. +if("$ENV{GZ_VERSION}" STREQUAL "" AND NOT "$ENV{IGNITION_VERSION}" STREQUAL "") + message(DEPRECATION "Environment variable [IGNITION_VERSION] is deprecated. Use [GZ_VERSION] instead.") + set(ENV{GZ_VERSION} ENV{IGNITION_VERSION}) +endif() + # Edifice -if("$ENV{IGNITION_VERSION}" STREQUAL "edifice") +if("$ENV{GZ_VERSION}" STREQUAL "edifice") find_package(ignition-transport10 REQUIRED) - set(IGN_TRANSPORT_VER ${ignition-transport10_VERSION_MAJOR}) + set(GZ_TRANSPORT_VER ${ignition-transport10_VERSION_MAJOR}) find_package(ignition-msgs7 REQUIRED) - set(IGN_MSGS_VER ${ignition-msgs7_VERSION_MAJOR}) + set(GZ_MSGS_VER ${ignition-msgs7_VERSION_MAJOR}) set(GZ_TARGET_PREFIX ignition) message(STATUS "Compiling against Ignition Edifice") # Garden -elseif("$ENV{IGNITION_VERSION}" STREQUAL "garden") +elseif("$ENV{GZ_VERSION}" STREQUAL "garden") find_package(gz-transport12 REQUIRED) - set(IGN_TRANSPORT_VER ${gz-transport12_VERSION_MAJOR}) + set(GZ_TRANSPORT_VER ${gz-transport12_VERSION_MAJOR}) find_package(gz-msgs9 REQUIRED) - set(IGN_MSGS_VER ${gz-msgs9_VERSION_MAJOR}) + set(GZ_MSGS_VER ${gz-msgs9_VERSION_MAJOR}) set(GZ_TARGET_PREFIX gz) @@ -47,10 +53,10 @@ elseif("$ENV{IGNITION_VERSION}" STREQUAL "garden") # Default to Fortress else() find_package(ignition-transport11 REQUIRED) - set(IGN_TRANSPORT_VER ${ignition-transport11_VERSION_MAJOR}) + set(GZ_TRANSPORT_VER ${ignition-transport11_VERSION_MAJOR}) find_package(ignition-msgs8 REQUIRED) - set(IGN_MSGS_VER ${ignition-msgs8_VERSION_MAJOR}) + set(GZ_MSGS_VER ${ignition-msgs8_VERSION_MAJOR}) set(GZ_TARGET_PREFIX ignition) @@ -61,7 +67,7 @@ set(PACKAGES builtin_interfaces geometry_msgs nav_msgs - ros_ign_interfaces + ros_gz_interfaces rosgraph_msgs sensor_msgs std_msgs @@ -93,8 +99,8 @@ foreach(PKG ${PACKAGES}) ) target_link_libraries(${PKG}_bridge bridge_utils - ${GZ_TARGET_PREFIX}-msgs${IGN_MSGS_VER}::core - ${GZ_TARGET_PREFIX}-transport${IGN_TRANSPORT_VER}::core + ${GZ_TARGET_PREFIX}-msgs${GZ_MSGS_VER}::core + ${GZ_TARGET_PREFIX}-transport${GZ_TRANSPORT_VER}::core rclcpp::rclcpp ) set_target_properties(${PKG}_bridge @@ -108,14 +114,14 @@ set(bridge_executables ) set(bridge_lib - ros_ign_bridge_lib + ros_gz_bridge_lib ) add_library(${bridge_lib} SHARED src/factories.cpp src/factory_interface.cpp - src/service_factories/ros_ign_interfaces.cpp + src/service_factories/ros_gz_interfaces.cpp ) target_include_directories(${bridge_lib} @@ -146,8 +152,8 @@ foreach(bridge ${bridge_executables}) ) target_link_libraries(${bridge} ${bridge_lib} - ${GZ_TARGET_PREFIX}-msgs${IGN_MSGS_VER}::core - ${GZ_TARGET_PREFIX}-transport${IGN_TRANSPORT_VER}::core + ${GZ_TARGET_PREFIX}-msgs${GZ_MSGS_VER}::core + ${GZ_TARGET_PREFIX}-transport${GZ_TRANSPORT_VER}::core ) ament_target_dependencies(${bridge} "rclcpp" @@ -167,7 +173,7 @@ if(BUILD_TESTING) ament_find_gtest() add_library(test_utils - test/utils/ign_test_msg.cpp + test/utils/gz_test_msg.cpp test/utils/ros_test_msg.cpp ) @@ -176,15 +182,15 @@ if(BUILD_TESTING) ) target_link_libraries(test_utils ${GTEST_LIBRARIES} - ${GZ_TARGET_PREFIX}-msgs${IGN_MSGS_VER}::core - ${GZ_TARGET_PREFIX}-transport${IGN_TRANSPORT_VER}::core + ${GZ_TARGET_PREFIX}-msgs${GZ_MSGS_VER}::core + ${GZ_TARGET_PREFIX}-transport${GZ_TRANSPORT_VER}::core ) ament_target_dependencies(test_utils builtin_interfaces geometry_msgs nav_msgs rclcpp - ros_ign_interfaces + ros_gz_interfaces rosgraph_msgs sensor_msgs std_msgs @@ -200,7 +206,7 @@ if(BUILD_TESTING) test/subscribers/ros_subscriber/builtin_interfaces_subscriber.cpp test/subscribers/ros_subscriber/geometry_msgs_subscriber.cpp test/subscribers/ros_subscriber/nav_msgs_subscriber.cpp - test/subscribers/ros_subscriber/ros_ign_interfaces_subscriber.cpp + test/subscribers/ros_subscriber/ros_gz_interfaces_subscriber.cpp test/subscribers/ros_subscriber/rosgraph_msgs_subscriber.cpp test/subscribers/ros_subscriber/sensor_msgs_subscriber.cpp test/subscribers/ros_subscriber/std_msgs_subscriber.cpp @@ -208,14 +214,14 @@ if(BUILD_TESTING) target_link_libraries(test_ros_subscriber test_utils) - add_executable(test_ign_publisher test/publishers/ign_publisher.cpp) - target_link_libraries(test_ign_publisher test_utils) + add_executable(test_gz_publisher test/publishers/gz_publisher.cpp) + target_link_libraries(test_gz_publisher test_utils) - add_executable(test_ign_subscriber test/subscribers/ign_subscriber.cpp) - target_link_libraries(test_ign_subscriber test_utils) + add_executable(test_gz_subscriber test/subscribers/gz_subscriber.cpp) + target_link_libraries(test_gz_subscriber test_utils) - add_executable(test_ign_server test/serverclient/ign_server.cpp) - target_link_libraries(test_ign_server test_utils) + add_executable(test_gz_server test/serverclient/gz_server.cpp) + target_link_libraries(test_gz_server test_utils) add_executable(test_ros_client test/serverclient/ros_client.cpp) target_link_libraries(test_ros_client test_utils) @@ -224,9 +230,9 @@ if(BUILD_TESTING) test_ros_client test_ros_publisher test_ros_subscriber - test_ign_publisher - test_ign_server - test_ign_subscriber + test_gz_publisher + test_gz_server + test_gz_subscriber DESTINATION lib/${PROJECT_NAME} ) @@ -234,11 +240,11 @@ if(BUILD_TESTING) TIMEOUT 200 ) - add_launch_test(test/launch/test_ign_subscriber.launch.py + add_launch_test(test/launch/test_gz_subscriber.launch.py TIMEOUT 200 ) - add_launch_test(test/launch/test_ign_server.launch.py + add_launch_test(test/launch/test_gz_server.launch.py TIMEOUT 200 ) endif() diff --git a/ros_gz_bridge/README.md b/ros_gz_bridge/README.md index 8d65736d..f69666ea 100644 --- a/ros_gz_bridge/README.md +++ b/ros_gz_bridge/README.md @@ -31,16 +31,16 @@ The following message types can be bridged for topics: | mav_msgs/msg/Actuators (TODO) | ignition::msgs::Actuators (TODO) | | nav_msgs/msg/Odometry | ignition::msgs::Odometry | | nav_msgs/msg/Odometry | ignition::msgs::OdometryWithCovariance | -| ros_ign_interfaces/msg/Contact | ignition::msgs::Contact | -| ros_ign_interfaces/msg/Contacts | ignition::msgs::Contacts | -| ros_ign_interfaces/msg/Entity | ignition::msgs::Entity | -| ros_ign_interfaces/msg/GuiCamera | ignition::msgs::GUICamera | -| ros_ign_interfaces/msg/JointWrench | ignition::msgs::JointWrench | -| ros_ign_interfaces/msg/Light | ignition::msgs::Light | -| ros_ign_interfaces/msg/StringVec | ignition::msgs::StringMsg_V | -| ros_ign_interfaces/msg/TrackVisual | ignition::msgs::TrackVisual | -| ros_ign_interfaces/msg/VideoRecord | ignition::msgs::VideoRecord | -| ros_ign_interfaces/msg/WorldControl | ignition::msgs::WorldControl | +| ros_gz_interfaces/msg/Contact | ignition::msgs::Contact | +| ros_gz_interfaces/msg/Contacts | ignition::msgs::Contacts | +| ros_gz_interfaces/msg/Entity | ignition::msgs::Entity | +| ros_gz_interfaces/msg/GuiCamera | ignition::msgs::GUICamera | +| ros_gz_interfaces/msg/JointWrench | ignition::msgs::JointWrench | +| ros_gz_interfaces/msg/Light | ignition::msgs::Light | +| ros_gz_interfaces/msg/StringVec | ignition::msgs::StringMsg_V | +| ros_gz_interfaces/msg/TrackVisual | ignition::msgs::TrackVisual | +| ros_gz_interfaces/msg/VideoRecord | ignition::msgs::VideoRecord | +| ros_gz_interfaces/msg/WorldControl | ignition::msgs::WorldControl | | rosgraph_msgs/msg/Clock | ignition::msgs::Clock | | sensor_msgs/msg/BatteryState | ignition::msgs::BatteryState | | sensor_msgs/msg/CameraInfo | ignition::msgs::CameraInfo | @@ -58,9 +58,9 @@ And the following for services: | ROS type | Gazebo request | Gazebo response | |--------------------------------------|:--------------------------:| --------------------- | -| ros_ign_interfaces/srv/ControlWorld | ignition.msgs.WorldControl | ignition.msgs.Boolean | +| ros_gz_interfaces/srv/ControlWorld | ignition.msgs.WorldControl | ignition.msgs.Boolean | -Run `ros2 run ros_ign_bridge parameter_bridge -h` for instructions. +Run `ros2 run ros_gz_bridge parameter_bridge -h` for instructions. ## Example 1a: Gazebo Transport talker and ROS 2 listener @@ -69,7 +69,7 @@ Start the parameter bridge which will watch the specified topics. ``` # Shell A: . ~/bridge_ws/install/setup.bash -ros2 run ros_ign_bridge parameter_bridge /chatter@std_msgs/msg/String@ignition.msgs.StringMsg +ros2 run ros_gz_bridge parameter_bridge /chatter@std_msgs/msg/String@ignition.msgs.StringMsg ``` Now we start the ROS listener. @@ -94,7 +94,7 @@ Start the parameter bridge which will watch the specified topics. ``` # Shell A: . ~/bridge_ws/install/setup.bash -ros2 run ros_ign_bridge parameter_bridge /chatter@std_msgs/msg/String@ignition.msgs.StringMsg +ros2 run ros_gz_bridge parameter_bridge /chatter@std_msgs/msg/String@ignition.msgs.StringMsg ``` Now we start the Gazebo Transport listener. @@ -139,7 +139,7 @@ Then we start the parameter bridge with the previous topic. ``` # Shell B: . ~/bridge_ws/install/setup.bash -ros2 run ros_ign_bridge parameter_bridge /rgbd_camera/image@sensor_msgs/msg/Image@ignition.msgs.Image +ros2 run ros_gz_bridge parameter_bridge /rgbd_camera/image@sensor_msgs/msg/Image@ignition.msgs.Image ``` Now we start the ROS GUI: @@ -164,7 +164,7 @@ In this example, we're going to run an executable that starts a bidirectional bridge for a specific topic and message type. We'll use the `static_bridge` executable that is installed with the bridge. -The example's code can be found under `ros_ign_bridge/src/static_bridge.cpp`. +The example's code can be found under `ros_gz_bridge/src/static_bridge.cpp`. In the code, it's possible to see how the bridge is hardcoded to bridge string messages published on the `/chatter` topic. @@ -172,7 +172,7 @@ Let's give it a try, starting with Gazebo -> ROS 2. On terminal A, start the bridge: -`ros2 run ros_ign_bridge static_bridge` +`ros2 run ros_gz_bridge static_bridge` On terminal B, we start a ROS 2 listener: @@ -202,7 +202,7 @@ It's possible to make ROS service requests into Gazebo. Let's try unpausing the On terminal A, start the service bridge: -`ros2 run ros_ign_bridge parameter_bridge /world/shapes/control@ros_ign_interfaces/srv/ControlWorld` +`ros2 run ros_gz_bridge parameter_bridge /world/shapes/control@ros_gz_interfaces/srv/ControlWorld` On terminal B, start Gazebo, it will be paused by default: @@ -211,5 +211,5 @@ On terminal B, start Gazebo, it will be paused by default: On terminal C, make a ROS request to unpause simulation: ``` -ros2 service call /world//control ros_ign_interfaces/srv/ControlWorld "{world_control: {pause: false}}" +ros2 service call /world//control ros_gz_interfaces/srv/ControlWorld "{world_control: {pause: false}}" ``` diff --git a/ros_gz_bridge/include/ros_gz_bridge/convert.hpp b/ros_gz_bridge/include/ros_gz_bridge/convert.hpp index 7d0d0e3f..b426c3c0 100644 --- a/ros_gz_bridge/include/ros_gz_bridge/convert.hpp +++ b/ros_gz_bridge/include/ros_gz_bridge/convert.hpp @@ -12,16 +12,16 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef ROS_IGN_BRIDGE__CONVERT_HPP_ -#define ROS_IGN_BRIDGE__CONVERT_HPP_ +#ifndef ROS_GZ_BRIDGE__CONVERT_HPP_ +#define ROS_GZ_BRIDGE__CONVERT_HPP_ -#include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include +#include -#endif // ROS_IGN_BRIDGE__CONVERT_HPP_ +#endif // ROS_GZ_BRIDGE__CONVERT_HPP_ diff --git a/ros_gz_bridge/include/ros_gz_bridge/convert/builtin_interfaces.hpp b/ros_gz_bridge/include/ros_gz_bridge/convert/builtin_interfaces.hpp index 52892a74..a2b1999e 100644 --- a/ros_gz_bridge/include/ros_gz_bridge/convert/builtin_interfaces.hpp +++ b/ros_gz_bridge/include/ros_gz_bridge/convert/builtin_interfaces.hpp @@ -12,30 +12,30 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef ROS_IGN_BRIDGE__CONVERT__BUILTIN_INTERFACES_HPP_ -#define ROS_IGN_BRIDGE__CONVERT__BUILTIN_INTERFACES_HPP_ +#ifndef ROS_GZ_BRIDGE__CONVERT__BUILTIN_INTERFACES_HPP_ +#define ROS_GZ_BRIDGE__CONVERT__BUILTIN_INTERFACES_HPP_ #include #include -#include "ros_ign_bridge/convert_decl.hpp" +#include "ros_gz_bridge/convert_decl.hpp" -namespace ros_ign_bridge +namespace ros_gz_bridge { template<> void -convert_ros_to_ign( +convert_ros_to_gz( const builtin_interfaces::msg::Time & ros_msg, - ignition::msgs::Time & ign_msg); + ignition::msgs::Time & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::Time & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Time & gz_msg, builtin_interfaces::msg::Time & ros_msg); -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge -#endif // ROS_IGN_BRIDGE__CONVERT__BUILTIN_INTERFACES_HPP_ +#endif // ROS_GZ_BRIDGE__CONVERT__BUILTIN_INTERFACES_HPP_ diff --git a/ros_gz_bridge/include/ros_gz_bridge/convert/geometry_msgs.hpp b/ros_gz_bridge/include/ros_gz_bridge/convert/geometry_msgs.hpp index 8df05b14..e67ee598 100644 --- a/ros_gz_bridge/include/ros_gz_bridge/convert/geometry_msgs.hpp +++ b/ros_gz_bridge/include/ros_gz_bridge/convert/geometry_msgs.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef ROS_IGN_BRIDGE__CONVERT__GEOMETRY_MSGS_HPP_ -#define ROS_IGN_BRIDGE__CONVERT__GEOMETRY_MSGS_HPP_ +#ifndef ROS_GZ_BRIDGE__CONVERT__GEOMETRY_MSGS_HPP_ +#define ROS_GZ_BRIDGE__CONVERT__GEOMETRY_MSGS_HPP_ -// Ignition messages +// Gazebo Msgs #include #include #include @@ -36,144 +36,144 @@ #include #include -#include +#include -namespace ros_ign_bridge +namespace ros_gz_bridge { // geometry_msgs template<> void -convert_ros_to_ign( +convert_ros_to_gz( const geometry_msgs::msg::Quaternion & ros_msg, - ignition::msgs::Quaternion & ign_msg); + ignition::msgs::Quaternion & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::Quaternion & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Quaternion & gz_msg, geometry_msgs::msg::Quaternion & ros_msg); template<> void -convert_ros_to_ign( +convert_ros_to_gz( const geometry_msgs::msg::Vector3 & ros_msg, - ignition::msgs::Vector3d & ign_msg); + ignition::msgs::Vector3d & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::Vector3d & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Vector3d & gz_msg, geometry_msgs::msg::Vector3 & ros_msg); template<> void -convert_ros_to_ign( +convert_ros_to_gz( const geometry_msgs::msg::Point & ros_msg, - ignition::msgs::Vector3d & ign_msg); + ignition::msgs::Vector3d & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::Vector3d & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Vector3d & gz_msg, geometry_msgs::msg::Point & ros_msg); template<> void -convert_ros_to_ign( +convert_ros_to_gz( const geometry_msgs::msg::Pose & ros_msg, - ignition::msgs::Pose & ign_msg); + ignition::msgs::Pose & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::Pose & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Pose & gz_msg, geometry_msgs::msg::Pose & ros_msg); template<> void -convert_ros_to_ign( +convert_ros_to_gz( const geometry_msgs::msg::PoseWithCovariance & ros_msg, - ignition::msgs::PoseWithCovariance & ign_msg); + ignition::msgs::PoseWithCovariance & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::PoseWithCovariance & ign_msg, +convert_gz_to_ros( + const ignition::msgs::PoseWithCovariance & gz_msg, geometry_msgs::msg::PoseWithCovariance & ros_msg); template<> void -convert_ros_to_ign( +convert_ros_to_gz( const geometry_msgs::msg::PoseStamped & ros_msg, - ignition::msgs::Pose & ign_msg); + ignition::msgs::Pose & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::Pose & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Pose & gz_msg, geometry_msgs::msg::PoseStamped & ros_msg); template<> void -convert_ros_to_ign( +convert_ros_to_gz( const geometry_msgs::msg::Transform & ros_msg, - ignition::msgs::Pose & ign_msg); + ignition::msgs::Pose & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::Pose & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Pose & gz_msg, geometry_msgs::msg::Transform & ros_msg); template<> void -convert_ros_to_ign( +convert_ros_to_gz( const geometry_msgs::msg::TransformStamped & ros_msg, - ignition::msgs::Pose & ign_msg); + ignition::msgs::Pose & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::Pose & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Pose & gz_msg, geometry_msgs::msg::TransformStamped & ros_msg); template<> void -convert_ros_to_ign( +convert_ros_to_gz( const geometry_msgs::msg::Twist & ros_msg, - ignition::msgs::Twist & ign_msg); + ignition::msgs::Twist & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::Twist & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Twist & gz_msg, geometry_msgs::msg::Twist & ros_msg); template<> void -convert_ros_to_ign( +convert_ros_to_gz( const geometry_msgs::msg::TwistWithCovariance & ros_msg, - ignition::msgs::TwistWithCovariance & ign_msg); + ignition::msgs::TwistWithCovariance & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::TwistWithCovariance & ign_msg, +convert_gz_to_ros( + const ignition::msgs::TwistWithCovariance & gz_msg, geometry_msgs::msg::TwistWithCovariance & ros_msg); template<> void -convert_ros_to_ign( +convert_ros_to_gz( const geometry_msgs::msg::Wrench & ros_msg, - ignition::msgs::Wrench & ign_msg); + ignition::msgs::Wrench & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::Wrench & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Wrench & gz_msg, geometry_msgs::msg::Wrench & ros_msg); -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge -#endif // ROS_IGN_BRIDGE__CONVERT__GEOMETRY_MSGS_HPP_ +#endif // ROS_GZ_BRIDGE__CONVERT__GEOMETRY_MSGS_HPP_ diff --git a/ros_gz_bridge/include/ros_gz_bridge/convert/nav_msgs.hpp b/ros_gz_bridge/include/ros_gz_bridge/convert/nav_msgs.hpp index 882bc4ce..4c52c5b9 100644 --- a/ros_gz_bridge/include/ros_gz_bridge/convert/nav_msgs.hpp +++ b/ros_gz_bridge/include/ros_gz_bridge/convert/nav_msgs.hpp @@ -12,45 +12,45 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef ROS_IGN_BRIDGE__CONVERT__NAV_MSGS_HPP_ -#define ROS_IGN_BRIDGE__CONVERT__NAV_MSGS_HPP_ +#ifndef ROS_GZ_BRIDGE__CONVERT__NAV_MSGS_HPP_ +#define ROS_GZ_BRIDGE__CONVERT__NAV_MSGS_HPP_ -// Ignition messages +// Gazebo Msgs #include #include // ROS 2 messages #include -#include +#include -namespace ros_ign_bridge +namespace ros_gz_bridge { // nav_msgs template<> void -convert_ros_to_ign( +convert_ros_to_gz( const nav_msgs::msg::Odometry & ros_msg, - ignition::msgs::Odometry & ign_msg); + ignition::msgs::Odometry & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::Odometry & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Odometry & gz_msg, nav_msgs::msg::Odometry & ros_msg); template<> void -convert_ros_to_ign( +convert_ros_to_gz( const nav_msgs::msg::Odometry & ros_msg, - ignition::msgs::OdometryWithCovariance & ign_msg); + ignition::msgs::OdometryWithCovariance & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::OdometryWithCovariance & ign_msg, +convert_gz_to_ros( + const ignition::msgs::OdometryWithCovariance & gz_msg, nav_msgs::msg::Odometry & ros_msg); -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge -#endif // ROS_IGN_BRIDGE__CONVERT__NAV_MSGS_HPP_ +#endif // ROS_GZ_BRIDGE__CONVERT__NAV_MSGS_HPP_ diff --git a/ros_gz_bridge/include/ros_gz_bridge/convert/ros_gz_interfaces.hpp b/ros_gz_bridge/include/ros_gz_bridge/convert/ros_gz_interfaces.hpp index c0d0340f..0fe64821 100644 --- a/ros_gz_bridge/include/ros_gz_bridge/convert/ros_gz_interfaces.hpp +++ b/ros_gz_bridge/include/ros_gz_bridge/convert/ros_gz_interfaces.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef ROS_IGN_BRIDGE__CONVERT__ROS_IGN_INTERFACES_HPP_ -#define ROS_IGN_BRIDGE__CONVERT__ROS_IGN_INTERFACES_HPP_ +#ifndef ROS_GZ_BRIDGE__CONVERT__ROS_GZ_INTERFACES_HPP_ +#define ROS_GZ_BRIDGE__CONVERT__ROS_GZ_INTERFACES_HPP_ -// Ignition messages +// Gazebo Msgs #include #include #include @@ -28,153 +28,153 @@ #include // ROS 2 messages -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include - -namespace ros_ign_bridge +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +namespace ros_gz_bridge { template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::JointWrench & ros_msg, - ignition::msgs::JointWrench & ign_msg); +convert_ros_to_gz( + const ros_gz_interfaces::msg::JointWrench & ros_msg, + ignition::msgs::JointWrench & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::JointWrench & ign_msg, - ros_ign_interfaces::msg::JointWrench & ros_msg); +convert_gz_to_ros( + const ignition::msgs::JointWrench & gz_msg, + ros_gz_interfaces::msg::JointWrench & ros_msg); template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::Entity & ros_msg, - ignition::msgs::Entity & ign_msg); +convert_ros_to_gz( + const ros_gz_interfaces::msg::Entity & ros_msg, + ignition::msgs::Entity & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::Entity & ign_msg, - ros_ign_interfaces::msg::Entity & ros_msg); +convert_gz_to_ros( + const ignition::msgs::Entity & gz_msg, + ros_gz_interfaces::msg::Entity & ros_msg); template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::Contact & ros_msg, - ignition::msgs::Contact & ign_msg); +convert_ros_to_gz( + const ros_gz_interfaces::msg::Contact & ros_msg, + ignition::msgs::Contact & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::Contact & ign_msg, - ros_ign_interfaces::msg::Contact & ros_msg); +convert_gz_to_ros( + const ignition::msgs::Contact & gz_msg, + ros_gz_interfaces::msg::Contact & ros_msg); template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::Contacts & ros_msg, - ignition::msgs::Contacts & ign_msg); +convert_ros_to_gz( + const ros_gz_interfaces::msg::Contacts & ros_msg, + ignition::msgs::Contacts & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::Contacts & ign_msg, - ros_ign_interfaces::msg::Contacts & ros_msg); +convert_gz_to_ros( + const ignition::msgs::Contacts & gz_msg, + ros_gz_interfaces::msg::Contacts & ros_msg); template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::GuiCamera & ros_msg, - ignition::msgs::GUICamera & ign_msg); +convert_ros_to_gz( + const ros_gz_interfaces::msg::GuiCamera & ros_msg, + ignition::msgs::GUICamera & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::GUICamera & ign_msg, - ros_ign_interfaces::msg::GuiCamera & ros_msg); +convert_gz_to_ros( + const ignition::msgs::GUICamera & gz_msg, + ros_gz_interfaces::msg::GuiCamera & ros_msg); template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::Light & ros_msg, - ignition::msgs::Light & ign_msg); +convert_ros_to_gz( + const ros_gz_interfaces::msg::Light & ros_msg, + ignition::msgs::Light & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::Light & ign_msg, - ros_ign_interfaces::msg::Light & ros_msg); +convert_gz_to_ros( + const ignition::msgs::Light & gz_msg, + ros_gz_interfaces::msg::Light & ros_msg); template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::StringVec & ros_msg, - ignition::msgs::StringMsg_V & ign_msg); +convert_ros_to_gz( + const ros_gz_interfaces::msg::StringVec & ros_msg, + ignition::msgs::StringMsg_V & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::StringMsg_V & ign_msg, - ros_ign_interfaces::msg::StringVec & ros_msg); +convert_gz_to_ros( + const ignition::msgs::StringMsg_V & gz_msg, + ros_gz_interfaces::msg::StringVec & ros_msg); template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::TrackVisual & ros_msg, - ignition::msgs::TrackVisual & ign_msg); +convert_ros_to_gz( + const ros_gz_interfaces::msg::TrackVisual & ros_msg, + ignition::msgs::TrackVisual & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::TrackVisual & ign_msg, - ros_ign_interfaces::msg::TrackVisual & ros_msg); +convert_gz_to_ros( + const ignition::msgs::TrackVisual & gz_msg, + ros_gz_interfaces::msg::TrackVisual & ros_msg); template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::VideoRecord & ros_msg, - ignition::msgs::VideoRecord & ign_msg); +convert_ros_to_gz( + const ros_gz_interfaces::msg::VideoRecord & ros_msg, + ignition::msgs::VideoRecord & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::VideoRecord & ign_msg, - ros_ign_interfaces::msg::VideoRecord & ros_msg); +convert_gz_to_ros( + const ignition::msgs::VideoRecord & gz_msg, + ros_gz_interfaces::msg::VideoRecord & ros_msg); template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::WorldControl & ros_msg, - ignition::msgs::WorldControl & ign_msg); +convert_ros_to_gz( + const ros_gz_interfaces::msg::WorldControl & ros_msg, + ignition::msgs::WorldControl & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::WorldControl & ign_msg, - ros_ign_interfaces::msg::WorldControl & ros_msg); +convert_gz_to_ros( + const ignition::msgs::WorldControl & gz_msg, + ros_gz_interfaces::msg::WorldControl & ros_msg); template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::WorldReset & ros_msg, - ignition::msgs::WorldReset & ign_msg); +convert_ros_to_gz( + const ros_gz_interfaces::msg::WorldReset & ros_msg, + ignition::msgs::WorldReset & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::WorldReset & ign_msg, - ros_ign_interfaces::msg::WorldReset & ros_msg); -} // namespace ros_ign_bridge +convert_gz_to_ros( + const ignition::msgs::WorldReset & gz_msg, + ros_gz_interfaces::msg::WorldReset & ros_msg); +} // namespace ros_gz_bridge -#endif // ROS_IGN_BRIDGE__CONVERT__ROS_IGN_INTERFACES_HPP_ +#endif // ROS_GZ_BRIDGE__CONVERT__ROS_GZ_INTERFACES_HPP_ diff --git a/ros_gz_bridge/include/ros_gz_bridge/convert/rosgraph_msgs.hpp b/ros_gz_bridge/include/ros_gz_bridge/convert/rosgraph_msgs.hpp index 1356a264..c67073bb 100644 --- a/ros_gz_bridge/include/ros_gz_bridge/convert/rosgraph_msgs.hpp +++ b/ros_gz_bridge/include/ros_gz_bridge/convert/rosgraph_msgs.hpp @@ -12,32 +12,32 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef ROS_IGN_BRIDGE__CONVERT__ROSGRAPH_MSGS_HPP_ -#define ROS_IGN_BRIDGE__CONVERT__ROSGRAPH_MSGS_HPP_ +#ifndef ROS_GZ_BRIDGE__CONVERT__ROSGRAPH_MSGS_HPP_ +#define ROS_GZ_BRIDGE__CONVERT__ROSGRAPH_MSGS_HPP_ -// Ignition messages +// Gazebo Msgs #include // ROS 2 messages #include -#include +#include -namespace ros_ign_bridge +namespace ros_gz_bridge { template<> void -convert_ign_to_ros( - const ignition::msgs::Clock & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Clock & gz_msg, rosgraph_msgs::msg::Clock & ros_msg); template<> void -convert_ros_to_ign( +convert_ros_to_gz( const rosgraph_msgs::msg::Clock & ros_msg, - ignition::msgs::Clock & ign_msg); + ignition::msgs::Clock & gz_msg); -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge -#endif // ROS_IGN_BRIDGE__CONVERT__ROSGRAPH_MSGS_HPP_ +#endif // ROS_GZ_BRIDGE__CONVERT__ROSGRAPH_MSGS_HPP_ diff --git a/ros_gz_bridge/include/ros_gz_bridge/convert/sensor_msgs.hpp b/ros_gz_bridge/include/ros_gz_bridge/convert/sensor_msgs.hpp index c2405004..de6724f4 100644 --- a/ros_gz_bridge/include/ros_gz_bridge/convert/sensor_msgs.hpp +++ b/ros_gz_bridge/include/ros_gz_bridge/convert/sensor_msgs.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef ROS_IGN_BRIDGE__CONVERT__SENSOR_MSGS_HPP_ -#define ROS_IGN_BRIDGE__CONVERT__SENSOR_MSGS_HPP_ +#ifndef ROS_GZ_BRIDGE__CONVERT__SENSOR_MSGS_HPP_ +#define ROS_GZ_BRIDGE__CONVERT__SENSOR_MSGS_HPP_ -// Ignition messages +// Gazebo Msgs #include #include #include @@ -37,120 +37,120 @@ #include #include -#include +#include -namespace ros_ign_bridge +namespace ros_gz_bridge { // sensor_msgs template<> void -convert_ros_to_ign( +convert_ros_to_gz( const sensor_msgs::msg::FluidPressure & ros_msg, - ignition::msgs::FluidPressure & ign_msg); + ignition::msgs::FluidPressure & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::FluidPressure & ign_msg, +convert_gz_to_ros( + const ignition::msgs::FluidPressure & gz_msg, sensor_msgs::msg::FluidPressure & ros_msg); template<> void -convert_ros_to_ign( +convert_ros_to_gz( const sensor_msgs::msg::Image & ros_msg, - ignition::msgs::Image & ign_msg); + ignition::msgs::Image & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::Image & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Image & gz_msg, sensor_msgs::msg::Image & ros_msg); template<> void -convert_ros_to_ign( +convert_ros_to_gz( const sensor_msgs::msg::CameraInfo & ros_msg, - ignition::msgs::CameraInfo & ign_msg); + ignition::msgs::CameraInfo & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::CameraInfo & ign_msg, +convert_gz_to_ros( + const ignition::msgs::CameraInfo & gz_msg, sensor_msgs::msg::CameraInfo & ros_msg); template<> void -convert_ros_to_ign( +convert_ros_to_gz( const sensor_msgs::msg::Imu & ros_msg, - ignition::msgs::IMU & ign_msg); + ignition::msgs::IMU & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::IMU & ign_msg, +convert_gz_to_ros( + const ignition::msgs::IMU & gz_msg, sensor_msgs::msg::Imu & ros_msg); template<> void -convert_ros_to_ign( +convert_ros_to_gz( const sensor_msgs::msg::JointState & ros_msg, - ignition::msgs::Model & ign_msg); + ignition::msgs::Model & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::Model & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Model & gz_msg, sensor_msgs::msg::JointState & ros_msg); template<> void -convert_ros_to_ign( +convert_ros_to_gz( const sensor_msgs::msg::LaserScan & ros_msg, - ignition::msgs::LaserScan & ign_msg); + ignition::msgs::LaserScan & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::LaserScan & ign_msg, +convert_gz_to_ros( + const ignition::msgs::LaserScan & gz_msg, sensor_msgs::msg::LaserScan & ros_msg); template<> void -convert_ros_to_ign( +convert_ros_to_gz( const sensor_msgs::msg::MagneticField & ros_msg, - ignition::msgs::Magnetometer & ign_msg); + ignition::msgs::Magnetometer & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::Magnetometer & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Magnetometer & gz_msg, sensor_msgs::msg::MagneticField & ros_msg); template<> void -convert_ros_to_ign( +convert_ros_to_gz( const sensor_msgs::msg::PointCloud2 & ros_msg, - ignition::msgs::PointCloudPacked & ign_msg); + ignition::msgs::PointCloudPacked & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::PointCloudPacked & ign_msg, +convert_gz_to_ros( + const ignition::msgs::PointCloudPacked & gz_msg, sensor_msgs::msg::PointCloud2 & ros_msg); template<> void -convert_ros_to_ign( +convert_ros_to_gz( const sensor_msgs::msg::BatteryState & ros_msg, - ignition::msgs::BatteryState & ign_msg); + ignition::msgs::BatteryState & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::BatteryState & ign_msg, +convert_gz_to_ros( + const ignition::msgs::BatteryState & gz_msg, sensor_msgs::msg::BatteryState & ros_msg); -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge -#endif // ROS_IGN_BRIDGE__CONVERT__SENSOR_MSGS_HPP_ +#endif // ROS_GZ_BRIDGE__CONVERT__SENSOR_MSGS_HPP_ diff --git a/ros_gz_bridge/include/ros_gz_bridge/convert/std_msgs.hpp b/ros_gz_bridge/include/ros_gz_bridge/convert/std_msgs.hpp index 10ebeeb1..155a7cdd 100644 --- a/ros_gz_bridge/include/ros_gz_bridge/convert/std_msgs.hpp +++ b/ros_gz_bridge/include/ros_gz_bridge/convert/std_msgs.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef ROS_IGN_BRIDGE__CONVERT__STD_MSGS_HPP_ -#define ROS_IGN_BRIDGE__CONVERT__STD_MSGS_HPP_ +#ifndef ROS_GZ_BRIDGE__CONVERT__STD_MSGS_HPP_ +#define ROS_GZ_BRIDGE__CONVERT__STD_MSGS_HPP_ -// Ignition messages +// Gazebo Msgs #include #include #include @@ -37,119 +37,119 @@ #include #include -#include +#include -namespace ros_ign_bridge +namespace ros_gz_bridge { template<> void -convert_ros_to_ign( +convert_ros_to_gz( const std_msgs::msg::Bool & ros_msg, - ignition::msgs::Boolean & ign_msg); + ignition::msgs::Boolean & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::Boolean & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Boolean & gz_msg, std_msgs::msg::Bool & ros_msg); template<> void -convert_ros_to_ign( +convert_ros_to_gz( const std_msgs::msg::ColorRGBA & ros_msg, - ignition::msgs::Color & ign_msg); + ignition::msgs::Color & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::Color & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Color & gz_msg, std_msgs::msg::ColorRGBA & ros_msg); template<> void -convert_ros_to_ign( +convert_ros_to_gz( const std_msgs::msg::Empty & ros_msg, - ignition::msgs::Empty & ign_msg); + ignition::msgs::Empty & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::Empty & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Empty & gz_msg, std_msgs::msg::Empty & ros_msg); template<> void -convert_ros_to_ign( +convert_ros_to_gz( const std_msgs::msg::UInt32 & ros_msg, - ignition::msgs::UInt32 & ign_msg); + ignition::msgs::UInt32 & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::UInt32 & ign_msg, +convert_gz_to_ros( + const ignition::msgs::UInt32 & gz_msg, std_msgs::msg::UInt32 & ros_msg); template<> void -convert_ros_to_ign( +convert_ros_to_gz( const std_msgs::msg::Float32 & ros_msg, - ignition::msgs::Float & ign_msg); + ignition::msgs::Float & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::Float & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Float & gz_msg, std_msgs::msg::Float32 & ros_msg); template<> void -convert_ros_to_ign( +convert_ros_to_gz( const std_msgs::msg::Float64 & ros_msg, - ignition::msgs::Double & ign_msg); + ignition::msgs::Double & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::Double & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Double & gz_msg, std_msgs::msg::Float64 & ros_msg); template<> void -convert_ros_to_ign( +convert_ros_to_gz( const std_msgs::msg::Header & ros_msg, - ignition::msgs::Header & ign_msg); + ignition::msgs::Header & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::Header & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Header & gz_msg, std_msgs::msg::Header & ros_msg); template<> void -convert_ros_to_ign( +convert_ros_to_gz( const std_msgs::msg::Int32 & ros_msg, - ignition::msgs::Int32 & ign_msg); + ignition::msgs::Int32 & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::Int32 & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Int32 & gz_msg, std_msgs::msg::Int32 & ros_msg); template<> void -convert_ros_to_ign( +convert_ros_to_gz( const std_msgs::msg::String & ros_msg, - ignition::msgs::StringMsg & ign_msg); + ignition::msgs::StringMsg & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::StringMsg & ign_msg, +convert_gz_to_ros( + const ignition::msgs::StringMsg & gz_msg, std_msgs::msg::String & ros_msg); -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge -#endif // ROS_IGN_BRIDGE__CONVERT__STD_MSGS_HPP_ +#endif // ROS_GZ_BRIDGE__CONVERT__STD_MSGS_HPP_ diff --git a/ros_gz_bridge/include/ros_gz_bridge/convert/tf2_msgs.hpp b/ros_gz_bridge/include/ros_gz_bridge/convert/tf2_msgs.hpp index b7052a9f..a254df5c 100644 --- a/ros_gz_bridge/include/ros_gz_bridge/convert/tf2_msgs.hpp +++ b/ros_gz_bridge/include/ros_gz_bridge/convert/tf2_msgs.hpp @@ -12,32 +12,32 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef ROS_IGN_BRIDGE__CONVERT__TF2_MSGS_HPP_ -#define ROS_IGN_BRIDGE__CONVERT__TF2_MSGS_HPP_ +#ifndef ROS_GZ_BRIDGE__CONVERT__TF2_MSGS_HPP_ +#define ROS_GZ_BRIDGE__CONVERT__TF2_MSGS_HPP_ -// Ignition messages +// Gazebo Msgs #include // ROS 2 messages #include -#include +#include -namespace ros_ign_bridge +namespace ros_gz_bridge { template<> void -convert_ros_to_ign( +convert_ros_to_gz( const tf2_msgs::msg::TFMessage & ros_msg, - ignition::msgs::Pose_V & ign_msg); + ignition::msgs::Pose_V & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::Pose_V & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Pose_V & gz_msg, tf2_msgs::msg::TFMessage & ros_msg); -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge -#endif // ROS_IGN_BRIDGE__CONVERT__TF2_MSGS_HPP_ +#endif // ROS_GZ_BRIDGE__CONVERT__TF2_MSGS_HPP_ diff --git a/ros_gz_bridge/include/ros_gz_bridge/convert/trajectory_msgs.hpp b/ros_gz_bridge/include/ros_gz_bridge/convert/trajectory_msgs.hpp index 90a2edec..f3efbbe2 100644 --- a/ros_gz_bridge/include/ros_gz_bridge/convert/trajectory_msgs.hpp +++ b/ros_gz_bridge/include/ros_gz_bridge/convert/trajectory_msgs.hpp @@ -12,45 +12,45 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef ROS_IGN_BRIDGE__CONVERT__TRAJECTORY_MSGS_HPP_ -#define ROS_IGN_BRIDGE__CONVERT__TRAJECTORY_MSGS_HPP_ +#ifndef ROS_GZ_BRIDGE__CONVERT__TRAJECTORY_MSGS_HPP_ +#define ROS_GZ_BRIDGE__CONVERT__TRAJECTORY_MSGS_HPP_ -// Ignition messages +// Gazebo Msgs #include // ROS 2 messages #include -#include +#include -namespace ros_ign_bridge +namespace ros_gz_bridge { template<> void -convert_ros_to_ign( +convert_ros_to_gz( const trajectory_msgs::msg::JointTrajectoryPoint & ros_msg, - ignition::msgs::JointTrajectoryPoint & ign_msg); + ignition::msgs::JointTrajectoryPoint & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::JointTrajectoryPoint & ign_msg, +convert_gz_to_ros( + const ignition::msgs::JointTrajectoryPoint & gz_msg, trajectory_msgs::msg::JointTrajectoryPoint & ros_msg); template<> void -convert_ros_to_ign( +convert_ros_to_gz( const trajectory_msgs::msg::JointTrajectory & ros_msg, - ignition::msgs::JointTrajectory & ign_msg); + ignition::msgs::JointTrajectory & gz_msg); template<> void -convert_ign_to_ros( - const ignition::msgs::JointTrajectory & ign_msg, +convert_gz_to_ros( + const ignition::msgs::JointTrajectory & gz_msg, trajectory_msgs::msg::JointTrajectory & ros_msg); -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge -#endif // ROS_IGN_BRIDGE__CONVERT__TRAJECTORY_MSGS_HPP_ +#endif // ROS_GZ_BRIDGE__CONVERT__TRAJECTORY_MSGS_HPP_ diff --git a/ros_gz_bridge/include/ros_gz_bridge/convert_decl.hpp b/ros_gz_bridge/include/ros_gz_bridge/convert_decl.hpp index d27ce61f..31419975 100644 --- a/ros_gz_bridge/include/ros_gz_bridge/convert_decl.hpp +++ b/ros_gz_bridge/include/ros_gz_bridge/convert_decl.hpp @@ -12,24 +12,24 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef ROS_IGN_BRIDGE__CONVERT_DECL_HPP_ -#define ROS_IGN_BRIDGE__CONVERT_DECL_HPP_ +#ifndef ROS_GZ_BRIDGE__CONVERT_DECL_HPP_ +#define ROS_GZ_BRIDGE__CONVERT_DECL_HPP_ -namespace ros_ign_bridge +namespace ros_gz_bridge { -template +template void -convert_ros_to_ign( +convert_ros_to_gz( const ROS_T & ros_msg, - IGN_T & ign_msg); + GZ_T & gz_msg); -template +template void -convert_ign_to_ros( - const IGN_T & ign_msg, +convert_gz_to_ros( + const GZ_T & gz_msg, ROS_T & ros_msg); -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge -#endif // ROS_IGN_BRIDGE__CONVERT_DECL_HPP_ +#endif // ROS_GZ_BRIDGE__CONVERT_DECL_HPP_ diff --git a/ros_gz_bridge/package.xml b/ros_gz_bridge/package.xml index 17cbe5ec..93dc975d 100644 --- a/ros_gz_bridge/package.xml +++ b/ros_gz_bridge/package.xml @@ -1,9 +1,9 @@ - ros_ign_bridge + ros_gz_bridge 0.244.3 - Bridge communication between ROS and Ignition Transport + Bridge communication between ROS and Gazebo Transport Louise Poubel Apache 2.0 @@ -16,7 +16,7 @@ geometry_msgs nav_msgs rclcpp - ros_ign_interfaces + ros_gz_interfaces rosgraph_msgs sensor_msgs std_msgs @@ -24,16 +24,16 @@ trajectory_msgs - gz-msgs9 - gz-transport12 + gz-msgs9 + gz-transport12 - ignition-msgs8 - ignition-transport11 - ignition-msgs8 - ignition-transport11 + ignition-msgs8 + ignition-transport11 + ignition-msgs8 + ignition-transport11 - ignition-msgs7 - ignition-transport10 + ignition-msgs7 + ignition-transport10 ament_cmake_gtest ament_lint_auto diff --git a/ros_gz_bridge/src/bridge.hpp b/ros_gz_bridge/src/bridge.hpp index a11c501d..5990eb69 100644 --- a/ros_gz_bridge/src/bridge.hpp +++ b/ros_gz_bridge/src/bridge.hpp @@ -22,18 +22,18 @@ #include "factories.hpp" -namespace ros_ign_bridge +namespace ros_gz_bridge { struct BridgeRosToIgnHandles { rclcpp::SubscriptionBase::SharedPtr ros_subscriber; - ignition::transport::Node::Publisher ign_publisher; + ignition::transport::Node::Publisher gz_publisher; }; struct BridgeIgnToRosHandles { - std::shared_ptr ign_subscriber; + std::shared_ptr gz_subscriber; rclcpp::PublisherBase::SharedPtr ros_publisher; }; @@ -45,51 +45,51 @@ struct BridgeHandles struct BridgeIgnServicesToRosHandles { - std::shared_ptr ign_node; + std::shared_ptr gz_node; rclcpp::ServiceBase::SharedPtr ros_service; }; BridgeRosToIgnHandles -create_bridge_from_ros_to_ign( +create_bridge_from_ros_to_gz( rclcpp::Node::SharedPtr ros_node, - std::shared_ptr ign_node, + std::shared_ptr gz_node, const std::string & ros_type_name, const std::string & ros_topic_name, size_t subscriber_queue_size, - const std::string & ign_type_name, - const std::string & ign_topic_name, + const std::string & gz_type_name, + const std::string & gz_topic_name, size_t publisher_queue_size) { - auto factory = get_factory(ros_type_name, ign_type_name); - auto ign_pub = factory->create_ign_publisher(ign_node, ign_topic_name, publisher_queue_size); + auto factory = get_factory(ros_type_name, gz_type_name); + auto gz_pub = factory->create_gz_publisher(gz_node, gz_topic_name, publisher_queue_size); auto ros_sub = factory->create_ros_subscriber( - ros_node, ros_topic_name, subscriber_queue_size, ign_pub); + ros_node, ros_topic_name, subscriber_queue_size, gz_pub); BridgeRosToIgnHandles handles; handles.ros_subscriber = ros_sub; - handles.ign_publisher = ign_pub; + handles.gz_publisher = gz_pub; return handles; } BridgeIgnToRosHandles -create_bridge_from_ign_to_ros( - std::shared_ptr ign_node, +create_bridge_from_gz_to_ros( + std::shared_ptr gz_node, rclcpp::Node::SharedPtr ros_node, - const std::string & ign_type_name, - const std::string & ign_topic_name, + const std::string & gz_type_name, + const std::string & gz_topic_name, size_t subscriber_queue_size, const std::string & ros_type_name, const std::string & ros_topic_name, size_t publisher_queue_size) { - auto factory = get_factory(ros_type_name, ign_type_name); + auto factory = get_factory(ros_type_name, gz_type_name); auto ros_pub = factory->create_ros_publisher(ros_node, ros_topic_name, publisher_queue_size); - factory->create_ign_subscriber(ign_node, ign_topic_name, subscriber_queue_size, ros_pub); + factory->create_gz_subscriber(gz_node, gz_topic_name, subscriber_queue_size, ros_pub); BridgeIgnToRosHandles handles; - handles.ign_subscriber = ign_node; + handles.gz_subscriber = gz_node; handles.ros_publisher = ros_pub; return handles; } @@ -97,39 +97,39 @@ create_bridge_from_ign_to_ros( BridgeHandles create_bidirectional_bridge( rclcpp::Node::SharedPtr ros_node, - std::shared_ptr ign_node, + std::shared_ptr gz_node, const std::string & ros_type_name, - const std::string & ign_type_name, + const std::string & gz_type_name, const std::string & topic_name, size_t queue_size = 10) { BridgeHandles handles; - handles.bridgeRosToIgn = create_bridge_from_ros_to_ign( - ros_node, ign_node, - ros_type_name, topic_name, queue_size, ign_type_name, topic_name, queue_size); - handles.bridgeIgnToRos = create_bridge_from_ign_to_ros( - ign_node, ros_node, - ign_type_name, topic_name, queue_size, ros_type_name, topic_name, queue_size); + handles.bridgeRosToIgn = create_bridge_from_ros_to_gz( + ros_node, gz_node, + ros_type_name, topic_name, queue_size, gz_type_name, topic_name, queue_size); + handles.bridgeIgnToRos = create_bridge_from_gz_to_ros( + gz_node, ros_node, + gz_type_name, topic_name, queue_size, ros_type_name, topic_name, queue_size); return handles; } BridgeIgnServicesToRosHandles create_service_bridge( rclcpp::Node::SharedPtr ros_node, - std::shared_ptr ign_node, + std::shared_ptr gz_node, const std::string & ros_type_name, - const std::string & ign_req_type_name, - const std::string & ign_rep_type_name, + const std::string & gz_req_type_name, + const std::string & gz_rep_type_name, const std::string & service_name) { BridgeIgnServicesToRosHandles handles; - auto factory = get_service_factory(ros_type_name, ign_req_type_name, ign_rep_type_name); - auto ros_srv = factory->create_ros_service(ros_node, ign_node, service_name); + auto factory = get_service_factory(ros_type_name, gz_req_type_name, gz_rep_type_name); + auto ros_srv = factory->create_ros_service(ros_node, gz_node, service_name); handles.ros_service = ros_srv; - handles.ign_node = ign_node; + handles.gz_node = gz_node; return handles; } -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge #endif // BRIDGE_HPP_ diff --git a/ros_gz_bridge/src/convert/builtin_interfaces.cpp b/ros_gz_bridge/src/convert/builtin_interfaces.cpp index 728c1847..fa5548eb 100644 --- a/ros_gz_bridge/src/convert/builtin_interfaces.cpp +++ b/ros_gz_bridge/src/convert/builtin_interfaces.cpp @@ -12,27 +12,27 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "ros_ign_bridge/convert/builtin_interfaces.hpp" +#include "ros_gz_bridge/convert/builtin_interfaces.hpp" -namespace ros_ign_bridge +namespace ros_gz_bridge { template<> void -convert_ros_to_ign( +convert_ros_to_gz( const builtin_interfaces::msg::Time & ros_msg, - ignition::msgs::Time & ign_msg) + ignition::msgs::Time & gz_msg) { - ign_msg.set_sec(ros_msg.sec); - ign_msg.set_nsec(ros_msg.nanosec); + gz_msg.set_sec(ros_msg.sec); + gz_msg.set_nsec(ros_msg.nanosec); } template<> void -convert_ign_to_ros( - const ignition::msgs::Time & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Time & gz_msg, builtin_interfaces::msg::Time & ros_msg) { - ros_msg.sec = ign_msg.sec(); - ros_msg.nanosec = ign_msg.nsec(); + ros_msg.sec = gz_msg.sec(); + ros_msg.nanosec = gz_msg.nsec(); } -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge diff --git a/ros_gz_bridge/src/convert/geometry_msgs.cpp b/ros_gz_bridge/src/convert/geometry_msgs.cpp index 15bd0261..039d5bd2 100644 --- a/ros_gz_bridge/src/convert/geometry_msgs.cpp +++ b/ros_gz_bridge/src/convert/geometry_msgs.cpp @@ -13,124 +13,124 @@ // limitations under the License. #include "convert/utils.hpp" -#include "ros_ign_bridge/convert/geometry_msgs.hpp" +#include "ros_gz_bridge/convert/geometry_msgs.hpp" -namespace ros_ign_bridge +namespace ros_gz_bridge { template<> void -convert_ros_to_ign( +convert_ros_to_gz( const geometry_msgs::msg::Quaternion & ros_msg, - ignition::msgs::Quaternion & ign_msg) + ignition::msgs::Quaternion & gz_msg) { - ign_msg.set_x(ros_msg.x); - ign_msg.set_y(ros_msg.y); - ign_msg.set_z(ros_msg.z); - ign_msg.set_w(ros_msg.w); + gz_msg.set_x(ros_msg.x); + gz_msg.set_y(ros_msg.y); + gz_msg.set_z(ros_msg.z); + gz_msg.set_w(ros_msg.w); } template<> void -convert_ign_to_ros( - const ignition::msgs::Quaternion & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Quaternion & gz_msg, geometry_msgs::msg::Quaternion & ros_msg) { - ros_msg.x = ign_msg.x(); - ros_msg.y = ign_msg.y(); - ros_msg.z = ign_msg.z(); - ros_msg.w = ign_msg.w(); + ros_msg.x = gz_msg.x(); + ros_msg.y = gz_msg.y(); + ros_msg.z = gz_msg.z(); + ros_msg.w = gz_msg.w(); } template<> void -convert_ros_to_ign( +convert_ros_to_gz( const geometry_msgs::msg::Vector3 & ros_msg, - ignition::msgs::Vector3d & ign_msg) + ignition::msgs::Vector3d & gz_msg) { - ign_msg.set_x(ros_msg.x); - ign_msg.set_y(ros_msg.y); - ign_msg.set_z(ros_msg.z); + gz_msg.set_x(ros_msg.x); + gz_msg.set_y(ros_msg.y); + gz_msg.set_z(ros_msg.z); } template<> void -convert_ign_to_ros( - const ignition::msgs::Vector3d & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Vector3d & gz_msg, geometry_msgs::msg::Vector3 & ros_msg) { - ros_msg.x = ign_msg.x(); - ros_msg.y = ign_msg.y(); - ros_msg.z = ign_msg.z(); + ros_msg.x = gz_msg.x(); + ros_msg.y = gz_msg.y(); + ros_msg.z = gz_msg.z(); } template<> void -convert_ros_to_ign( +convert_ros_to_gz( const geometry_msgs::msg::Point & ros_msg, - ignition::msgs::Vector3d & ign_msg) + ignition::msgs::Vector3d & gz_msg) { - ign_msg.set_x(ros_msg.x); - ign_msg.set_y(ros_msg.y); - ign_msg.set_z(ros_msg.z); + gz_msg.set_x(ros_msg.x); + gz_msg.set_y(ros_msg.y); + gz_msg.set_z(ros_msg.z); } template<> void -convert_ign_to_ros( - const ignition::msgs::Vector3d & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Vector3d & gz_msg, geometry_msgs::msg::Point & ros_msg) { - ros_msg.x = ign_msg.x(); - ros_msg.y = ign_msg.y(); - ros_msg.z = ign_msg.z(); + ros_msg.x = gz_msg.x(); + ros_msg.y = gz_msg.y(); + ros_msg.z = gz_msg.z(); } template<> void -convert_ros_to_ign( +convert_ros_to_gz( const geometry_msgs::msg::Pose & ros_msg, - ignition::msgs::Pose & ign_msg) + ignition::msgs::Pose & gz_msg) { - convert_ros_to_ign(ros_msg.position, *ign_msg.mutable_position()); - convert_ros_to_ign(ros_msg.orientation, *ign_msg.mutable_orientation()); + convert_ros_to_gz(ros_msg.position, *gz_msg.mutable_position()); + convert_ros_to_gz(ros_msg.orientation, *gz_msg.mutable_orientation()); } template<> void -convert_ign_to_ros( - const ignition::msgs::Pose & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Pose & gz_msg, geometry_msgs::msg::Pose & ros_msg) { - convert_ign_to_ros(ign_msg.position(), ros_msg.position); - convert_ign_to_ros(ign_msg.orientation(), ros_msg.orientation); + convert_gz_to_ros(gz_msg.position(), ros_msg.position); + convert_gz_to_ros(gz_msg.orientation(), ros_msg.orientation); } template<> void -convert_ros_to_ign( +convert_ros_to_gz( const geometry_msgs::msg::PoseWithCovariance & ros_msg, - ignition::msgs::PoseWithCovariance & ign_msg) + ignition::msgs::PoseWithCovariance & gz_msg) { - convert_ros_to_ign(ros_msg.pose.position, *ign_msg.mutable_pose()->mutable_position()); - convert_ros_to_ign(ros_msg.pose.orientation, *ign_msg.mutable_pose()->mutable_orientation()); + convert_ros_to_gz(ros_msg.pose.position, *gz_msg.mutable_pose()->mutable_position()); + convert_ros_to_gz(ros_msg.pose.orientation, *gz_msg.mutable_pose()->mutable_orientation()); for (const auto & elem : ros_msg.covariance) { - ign_msg.mutable_covariance()->add_data(elem); + gz_msg.mutable_covariance()->add_data(elem); } } template<> void -convert_ign_to_ros( - const ignition::msgs::PoseWithCovariance & ign_msg, +convert_gz_to_ros( + const ignition::msgs::PoseWithCovariance & gz_msg, geometry_msgs::msg::PoseWithCovariance & ros_msg) { - convert_ign_to_ros(ign_msg.pose().position(), ros_msg.pose.position); - convert_ign_to_ros(ign_msg.pose().orientation(), ros_msg.pose.orientation); - int data_size = ign_msg.covariance().data_size(); + convert_gz_to_ros(gz_msg.pose().position(), ros_msg.pose.position); + convert_gz_to_ros(gz_msg.pose().orientation(), ros_msg.pose.orientation); + int data_size = gz_msg.covariance().data_size(); if (data_size == 36) { for (int i = 0; i < data_size; i++) { - auto data = ign_msg.covariance().data()[i]; + auto data = gz_msg.covariance().data()[i]; ros_msg.covariance[i] = data; } } @@ -138,70 +138,70 @@ convert_ign_to_ros( template<> void -convert_ros_to_ign( +convert_ros_to_gz( const geometry_msgs::msg::PoseStamped & ros_msg, - ignition::msgs::Pose & ign_msg) + ignition::msgs::Pose & gz_msg) { - convert_ros_to_ign(ros_msg.header, (*ign_msg.mutable_header())); - convert_ros_to_ign(ros_msg.pose, ign_msg); + convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header())); + convert_ros_to_gz(ros_msg.pose, gz_msg); } template<> void -convert_ign_to_ros( - const ignition::msgs::Pose & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Pose & gz_msg, geometry_msgs::msg::PoseStamped & ros_msg) { - convert_ign_to_ros(ign_msg.header(), ros_msg.header); - convert_ign_to_ros(ign_msg, ros_msg.pose); + convert_gz_to_ros(gz_msg.header(), ros_msg.header); + convert_gz_to_ros(gz_msg, ros_msg.pose); } template<> void -convert_ros_to_ign( +convert_ros_to_gz( const geometry_msgs::msg::Transform & ros_msg, - ignition::msgs::Pose & ign_msg) + ignition::msgs::Pose & gz_msg) { - convert_ros_to_ign(ros_msg.translation, *ign_msg.mutable_position()); - convert_ros_to_ign(ros_msg.rotation, *ign_msg.mutable_orientation()); + convert_ros_to_gz(ros_msg.translation, *gz_msg.mutable_position()); + convert_ros_to_gz(ros_msg.rotation, *gz_msg.mutable_orientation()); } template<> void -convert_ign_to_ros( - const ignition::msgs::Pose & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Pose & gz_msg, geometry_msgs::msg::Transform & ros_msg) { - convert_ign_to_ros(ign_msg.position(), ros_msg.translation); - convert_ign_to_ros(ign_msg.orientation(), ros_msg.rotation); + convert_gz_to_ros(gz_msg.position(), ros_msg.translation); + convert_gz_to_ros(gz_msg.orientation(), ros_msg.rotation); } template<> void -convert_ros_to_ign( +convert_ros_to_gz( const geometry_msgs::msg::TransformStamped & ros_msg, - ignition::msgs::Pose & ign_msg) + ignition::msgs::Pose & gz_msg) { - convert_ros_to_ign(ros_msg.header, (*ign_msg.mutable_header())); - convert_ros_to_ign(ros_msg.transform, ign_msg); + convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header())); + convert_ros_to_gz(ros_msg.transform, gz_msg); - auto newPair = ign_msg.mutable_header()->add_data(); + auto newPair = gz_msg.mutable_header()->add_data(); newPair->set_key("child_frame_id"); newPair->add_value(ros_msg.child_frame_id); } template<> void -convert_ign_to_ros( - const ignition::msgs::Pose & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Pose & gz_msg, geometry_msgs::msg::TransformStamped & ros_msg) { - convert_ign_to_ros(ign_msg.header(), ros_msg.header); - convert_ign_to_ros(ign_msg, ros_msg.transform); - for (auto i = 0; i < ign_msg.header().data_size(); ++i) { - auto aPair = ign_msg.header().data(i); + convert_gz_to_ros(gz_msg.header(), ros_msg.header); + convert_gz_to_ros(gz_msg, ros_msg.transform); + for (auto i = 0; i < gz_msg.header().data_size(); ++i) { + auto aPair = gz_msg.header().data(i); if (aPair.key() == "child_frame_id" && aPair.value_size() > 0) { - ros_msg.child_frame_id = frame_id_ign_to_ros(aPair.value(0)); + ros_msg.child_frame_id = frame_id_gz_to_ros(aPair.value(0)); break; } } @@ -209,49 +209,49 @@ convert_ign_to_ros( template<> void -convert_ros_to_ign( +convert_ros_to_gz( const geometry_msgs::msg::Twist & ros_msg, - ignition::msgs::Twist & ign_msg) + ignition::msgs::Twist & gz_msg) { - convert_ros_to_ign(ros_msg.linear, (*ign_msg.mutable_linear())); - convert_ros_to_ign(ros_msg.angular, (*ign_msg.mutable_angular())); + convert_ros_to_gz(ros_msg.linear, (*gz_msg.mutable_linear())); + convert_ros_to_gz(ros_msg.angular, (*gz_msg.mutable_angular())); } template<> void -convert_ign_to_ros( - const ignition::msgs::Twist & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Twist & gz_msg, geometry_msgs::msg::Twist & ros_msg) { - convert_ign_to_ros(ign_msg.linear(), ros_msg.linear); - convert_ign_to_ros(ign_msg.angular(), ros_msg.angular); + convert_gz_to_ros(gz_msg.linear(), ros_msg.linear); + convert_gz_to_ros(gz_msg.angular(), ros_msg.angular); } template<> void -convert_ros_to_ign( +convert_ros_to_gz( const geometry_msgs::msg::TwistWithCovariance & ros_msg, - ignition::msgs::TwistWithCovariance & ign_msg) + ignition::msgs::TwistWithCovariance & gz_msg) { - convert_ros_to_ign(ros_msg.twist.linear, (*ign_msg.mutable_twist()->mutable_linear())); - convert_ros_to_ign(ros_msg.twist.angular, (*ign_msg.mutable_twist()->mutable_angular())); + convert_ros_to_gz(ros_msg.twist.linear, (*gz_msg.mutable_twist()->mutable_linear())); + convert_ros_to_gz(ros_msg.twist.angular, (*gz_msg.mutable_twist()->mutable_angular())); for (const auto & elem : ros_msg.covariance) { - ign_msg.mutable_covariance()->add_data(elem); + gz_msg.mutable_covariance()->add_data(elem); } } template<> void -convert_ign_to_ros( - const ignition::msgs::TwistWithCovariance & ign_msg, +convert_gz_to_ros( + const ignition::msgs::TwistWithCovariance & gz_msg, geometry_msgs::msg::TwistWithCovariance & ros_msg) { - convert_ign_to_ros(ign_msg.twist().linear(), ros_msg.twist.linear); - convert_ign_to_ros(ign_msg.twist().angular(), ros_msg.twist.angular); - int data_size = ign_msg.covariance().data_size(); + convert_gz_to_ros(gz_msg.twist().linear(), ros_msg.twist.linear); + convert_gz_to_ros(gz_msg.twist().angular(), ros_msg.twist.angular); + int data_size = gz_msg.covariance().data_size(); if (data_size == 36) { for (int i = 0; i < data_size; i++) { - auto data = ign_msg.covariance().data()[i]; + auto data = gz_msg.covariance().data()[i]; ros_msg.covariance[i] = data; } } @@ -259,22 +259,22 @@ convert_ign_to_ros( template<> void -convert_ros_to_ign( +convert_ros_to_gz( const geometry_msgs::msg::Wrench & ros_msg, - ignition::msgs::Wrench & ign_msg) + ignition::msgs::Wrench & gz_msg) { - convert_ros_to_ign(ros_msg.force, (*ign_msg.mutable_force())); - convert_ros_to_ign(ros_msg.torque, (*ign_msg.mutable_torque())); + convert_ros_to_gz(ros_msg.force, (*gz_msg.mutable_force())); + convert_ros_to_gz(ros_msg.torque, (*gz_msg.mutable_torque())); } template<> void -convert_ign_to_ros( - const ignition::msgs::Wrench & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Wrench & gz_msg, geometry_msgs::msg::Wrench & ros_msg) { - convert_ign_to_ros(ign_msg.force(), ros_msg.force); - convert_ign_to_ros(ign_msg.torque(), ros_msg.torque); + convert_gz_to_ros(gz_msg.force(), ros_msg.force); + convert_gz_to_ros(gz_msg.torque(), ros_msg.torque); } -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge diff --git a/ros_gz_bridge/src/convert/nav_msgs.cpp b/ros_gz_bridge/src/convert/nav_msgs.cpp index 297debe7..092ac3f1 100644 --- a/ros_gz_bridge/src/convert/nav_msgs.cpp +++ b/ros_gz_bridge/src/convert/nav_msgs.cpp @@ -13,40 +13,40 @@ // limitations under the License. #include "convert/utils.hpp" -#include "ros_ign_bridge/convert/nav_msgs.hpp" +#include "ros_gz_bridge/convert/nav_msgs.hpp" -namespace ros_ign_bridge +namespace ros_gz_bridge { template<> void -convert_ros_to_ign( +convert_ros_to_gz( const nav_msgs::msg::Odometry & ros_msg, - ignition::msgs::Odometry & ign_msg) + ignition::msgs::Odometry & gz_msg) { - convert_ros_to_ign(ros_msg.header, (*ign_msg.mutable_header())); - convert_ros_to_ign(ros_msg.pose.pose, (*ign_msg.mutable_pose())); - convert_ros_to_ign(ros_msg.twist.twist, (*ign_msg.mutable_twist())); + convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header())); + convert_ros_to_gz(ros_msg.pose.pose, (*gz_msg.mutable_pose())); + convert_ros_to_gz(ros_msg.twist.twist, (*gz_msg.mutable_twist())); - auto childFrame = ign_msg.mutable_header()->add_data(); + auto childFrame = gz_msg.mutable_header()->add_data(); childFrame->set_key("child_frame_id"); childFrame->add_value(ros_msg.child_frame_id); } template<> void -convert_ign_to_ros( - const ignition::msgs::Odometry & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Odometry & gz_msg, nav_msgs::msg::Odometry & ros_msg) { - convert_ign_to_ros(ign_msg.header(), ros_msg.header); - convert_ign_to_ros(ign_msg.pose(), ros_msg.pose.pose); - convert_ign_to_ros(ign_msg.twist(), ros_msg.twist.twist); + convert_gz_to_ros(gz_msg.header(), ros_msg.header); + convert_gz_to_ros(gz_msg.pose(), ros_msg.pose.pose); + convert_gz_to_ros(gz_msg.twist(), ros_msg.twist.twist); - for (auto i = 0; i < ign_msg.header().data_size(); ++i) { - auto a_pair = ign_msg.header().data(i); + for (auto i = 0; i < gz_msg.header().data_size(); ++i) { + auto a_pair = gz_msg.header().data(i); if (a_pair.key() == "child_frame_id" && a_pair.value_size() > 0) { - ros_msg.child_frame_id = frame_id_ign_to_ros(a_pair.value(0)); + ros_msg.child_frame_id = frame_id_gz_to_ros(a_pair.value(0)); break; } } @@ -54,36 +54,36 @@ convert_ign_to_ros( template<> void -convert_ros_to_ign( +convert_ros_to_gz( const nav_msgs::msg::Odometry & ros_msg, - ignition::msgs::OdometryWithCovariance & ign_msg) + ignition::msgs::OdometryWithCovariance & gz_msg) { - convert_ros_to_ign(ros_msg.header, (*ign_msg.mutable_header())); - convert_ros_to_ign(ros_msg.pose, (*ign_msg.mutable_pose_with_covariance())); - convert_ros_to_ign(ros_msg.twist, (*ign_msg.mutable_twist_with_covariance())); + convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header())); + convert_ros_to_gz(ros_msg.pose, (*gz_msg.mutable_pose_with_covariance())); + convert_ros_to_gz(ros_msg.twist, (*gz_msg.mutable_twist_with_covariance())); - auto childFrame = ign_msg.mutable_header()->add_data(); + auto childFrame = gz_msg.mutable_header()->add_data(); childFrame->set_key("child_frame_id"); childFrame->add_value(ros_msg.child_frame_id); } template<> void -convert_ign_to_ros( - const ignition::msgs::OdometryWithCovariance & ign_msg, +convert_gz_to_ros( + const ignition::msgs::OdometryWithCovariance & gz_msg, nav_msgs::msg::Odometry & ros_msg) { - convert_ign_to_ros(ign_msg.header(), ros_msg.header); - convert_ign_to_ros(ign_msg.pose_with_covariance(), ros_msg.pose); - convert_ign_to_ros(ign_msg.twist_with_covariance(), ros_msg.twist); + convert_gz_to_ros(gz_msg.header(), ros_msg.header); + convert_gz_to_ros(gz_msg.pose_with_covariance(), ros_msg.pose); + convert_gz_to_ros(gz_msg.twist_with_covariance(), ros_msg.twist); - for (auto i = 0; i < ign_msg.header().data_size(); ++i) { - auto a_pair = ign_msg.header().data(i); + for (auto i = 0; i < gz_msg.header().data_size(); ++i) { + auto a_pair = gz_msg.header().data(i); if (a_pair.key() == "child_frame_id" && a_pair.value_size() > 0) { - ros_msg.child_frame_id = frame_id_ign_to_ros(a_pair.value(0)); + ros_msg.child_frame_id = frame_id_gz_to_ros(a_pair.value(0)); break; } } } -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge diff --git a/ros_gz_bridge/src/convert/ros_gz_interfaces.cpp b/ros_gz_bridge/src/convert/ros_gz_interfaces.cpp index 9b51ff02..6b282bbb 100644 --- a/ros_gz_bridge/src/convert/ros_gz_interfaces.cpp +++ b/ros_gz_bridge/src/convert/ros_gz_interfaces.cpp @@ -12,73 +12,73 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "ros_ign_bridge/convert/ros_ign_interfaces.hpp" +#include "ros_gz_bridge/convert/ros_gz_interfaces.hpp" -namespace ros_ign_bridge +namespace ros_gz_bridge { template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::JointWrench & ros_msg, - ignition::msgs::JointWrench & ign_msg) +convert_ros_to_gz( + const ros_gz_interfaces::msg::JointWrench & ros_msg, + ignition::msgs::JointWrench & gz_msg) { - convert_ros_to_ign(ros_msg.header, (*ign_msg.mutable_header())); - ign_msg.set_body_1_name(ros_msg.body_1_name.data); - ign_msg.set_body_2_name(ros_msg.body_2_name.data); - ign_msg.set_body_1_id(ros_msg.body_1_id.data); - ign_msg.set_body_2_id(ros_msg.body_2_id.data); - convert_ros_to_ign(ros_msg.body_1_wrench, (*ign_msg.mutable_body_1_wrench())); - convert_ros_to_ign(ros_msg.body_2_wrench, (*ign_msg.mutable_body_2_wrench())); + convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header())); + gz_msg.set_body_1_name(ros_msg.body_1_name.data); + gz_msg.set_body_2_name(ros_msg.body_2_name.data); + gz_msg.set_body_1_id(ros_msg.body_1_id.data); + gz_msg.set_body_2_id(ros_msg.body_2_id.data); + convert_ros_to_gz(ros_msg.body_1_wrench, (*gz_msg.mutable_body_1_wrench())); + convert_ros_to_gz(ros_msg.body_2_wrench, (*gz_msg.mutable_body_2_wrench())); } template<> void -convert_ign_to_ros( - const ignition::msgs::JointWrench & ign_msg, - ros_ign_interfaces::msg::JointWrench & ros_msg) +convert_gz_to_ros( + const ignition::msgs::JointWrench & gz_msg, + ros_gz_interfaces::msg::JointWrench & ros_msg) { - convert_ign_to_ros(ign_msg.header(), ros_msg.header); - ros_msg.body_1_name.data = ign_msg.body_1_name(); - ros_msg.body_2_name.data = ign_msg.body_2_name(); - ros_msg.body_1_id.data = ign_msg.body_1_id(); - ros_msg.body_2_id.data = ign_msg.body_2_id(); - convert_ign_to_ros(ign_msg.body_1_wrench(), ros_msg.body_1_wrench); - convert_ign_to_ros(ign_msg.body_2_wrench(), ros_msg.body_2_wrench); + convert_gz_to_ros(gz_msg.header(), ros_msg.header); + ros_msg.body_1_name.data = gz_msg.body_1_name(); + ros_msg.body_2_name.data = gz_msg.body_2_name(); + ros_msg.body_1_id.data = gz_msg.body_1_id(); + ros_msg.body_2_id.data = gz_msg.body_2_id(); + convert_gz_to_ros(gz_msg.body_1_wrench(), ros_msg.body_1_wrench); + convert_gz_to_ros(gz_msg.body_2_wrench(), ros_msg.body_2_wrench); } template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::Entity & ros_msg, - ignition::msgs::Entity & ign_msg) +convert_ros_to_gz( + const ros_gz_interfaces::msg::Entity & ros_msg, + ignition::msgs::Entity & gz_msg) { - ign_msg.set_id(ros_msg.id); - ign_msg.set_name(ros_msg.name); + gz_msg.set_id(ros_msg.id); + gz_msg.set_name(ros_msg.name); switch (ros_msg.type) { - case ros_ign_interfaces::msg::Entity::NONE: - ign_msg.set_type(ignition::msgs::Entity::NONE); + case ros_gz_interfaces::msg::Entity::NONE: + gz_msg.set_type(ignition::msgs::Entity::NONE); break; - case ros_ign_interfaces::msg::Entity::LIGHT: - ign_msg.set_type(ignition::msgs::Entity::LIGHT); + case ros_gz_interfaces::msg::Entity::LIGHT: + gz_msg.set_type(ignition::msgs::Entity::LIGHT); break; - case ros_ign_interfaces::msg::Entity::MODEL: - ign_msg.set_type(ignition::msgs::Entity::MODEL); + case ros_gz_interfaces::msg::Entity::MODEL: + gz_msg.set_type(ignition::msgs::Entity::MODEL); break; - case ros_ign_interfaces::msg::Entity::LINK: - ign_msg.set_type(ignition::msgs::Entity::LINK); + case ros_gz_interfaces::msg::Entity::LINK: + gz_msg.set_type(ignition::msgs::Entity::LINK); break; - case ros_ign_interfaces::msg::Entity::VISUAL: - ign_msg.set_type(ignition::msgs::Entity::VISUAL); + case ros_gz_interfaces::msg::Entity::VISUAL: + gz_msg.set_type(ignition::msgs::Entity::VISUAL); break; - case ros_ign_interfaces::msg::Entity::COLLISION: - ign_msg.set_type(ignition::msgs::Entity::COLLISION); + case ros_gz_interfaces::msg::Entity::COLLISION: + gz_msg.set_type(ignition::msgs::Entity::COLLISION); break; - case ros_ign_interfaces::msg::Entity::SENSOR: - ign_msg.set_type(ignition::msgs::Entity::SENSOR); + case ros_gz_interfaces::msg::Entity::SENSOR: + gz_msg.set_type(ignition::msgs::Entity::SENSOR); break; - case ros_ign_interfaces::msg::Entity::JOINT: - ign_msg.set_type(ignition::msgs::Entity::JOINT); + case ros_gz_interfaces::msg::Entity::JOINT: + gz_msg.set_type(ignition::msgs::Entity::JOINT); break; default: std::cerr << "Unsupported entity type [" << ros_msg.type << "]\n"; @@ -87,357 +87,357 @@ convert_ros_to_ign( template<> void -convert_ign_to_ros( - const ignition::msgs::Entity & ign_msg, - ros_ign_interfaces::msg::Entity & ros_msg) +convert_gz_to_ros( + const ignition::msgs::Entity & gz_msg, + ros_gz_interfaces::msg::Entity & ros_msg) { - ros_msg.id = ign_msg.id(); - ros_msg.name = ign_msg.name(); - if (ign_msg.type() == ignition::msgs::Entity::Type::Entity_Type_NONE) { - ros_msg.type = ros_ign_interfaces::msg::Entity::NONE; - } else if (ign_msg.type() == ignition::msgs::Entity::LIGHT) { - ros_msg.type = ros_ign_interfaces::msg::Entity::LIGHT; - } else if (ign_msg.type() == ignition::msgs::Entity::MODEL) { - ros_msg.type = ros_ign_interfaces::msg::Entity::MODEL; - } else if (ign_msg.type() == ignition::msgs::Entity::LINK) { - ros_msg.type = ros_ign_interfaces::msg::Entity::LINK; - } else if (ign_msg.type() == ignition::msgs::Entity::VISUAL) { - ros_msg.type = ros_ign_interfaces::msg::Entity::VISUAL; - } else if (ign_msg.type() == ignition::msgs::Entity::COLLISION) { - ros_msg.type = ros_ign_interfaces::msg::Entity::COLLISION; - } else if (ign_msg.type() == ignition::msgs::Entity::SENSOR) { - ros_msg.type = ros_ign_interfaces::msg::Entity::SENSOR; - } else if (ign_msg.type() == ignition::msgs::Entity::JOINT) { - ros_msg.type = ros_ign_interfaces::msg::Entity::JOINT; + ros_msg.id = gz_msg.id(); + ros_msg.name = gz_msg.name(); + if (gz_msg.type() == ignition::msgs::Entity::Type::Entity_Type_NONE) { + ros_msg.type = ros_gz_interfaces::msg::Entity::NONE; + } else if (gz_msg.type() == ignition::msgs::Entity::LIGHT) { + ros_msg.type = ros_gz_interfaces::msg::Entity::LIGHT; + } else if (gz_msg.type() == ignition::msgs::Entity::MODEL) { + ros_msg.type = ros_gz_interfaces::msg::Entity::MODEL; + } else if (gz_msg.type() == ignition::msgs::Entity::LINK) { + ros_msg.type = ros_gz_interfaces::msg::Entity::LINK; + } else if (gz_msg.type() == ignition::msgs::Entity::VISUAL) { + ros_msg.type = ros_gz_interfaces::msg::Entity::VISUAL; + } else if (gz_msg.type() == ignition::msgs::Entity::COLLISION) { + ros_msg.type = ros_gz_interfaces::msg::Entity::COLLISION; + } else if (gz_msg.type() == ignition::msgs::Entity::SENSOR) { + ros_msg.type = ros_gz_interfaces::msg::Entity::SENSOR; + } else if (gz_msg.type() == ignition::msgs::Entity::JOINT) { + ros_msg.type = ros_gz_interfaces::msg::Entity::JOINT; } else { std::cerr << "Unsupported Entity [" << - ign_msg.type() << "]" << std::endl; + gz_msg.type() << "]" << std::endl; } } template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::Contact & ros_msg, - ignition::msgs::Contact & ign_msg) +convert_ros_to_gz( + const ros_gz_interfaces::msg::Contact & ros_msg, + ignition::msgs::Contact & gz_msg) { - convert_ros_to_ign(ros_msg.collision1, (*ign_msg.mutable_collision1())); - convert_ros_to_ign(ros_msg.collision1, (*ign_msg.mutable_collision2())); - ign_msg.clear_position(); + convert_ros_to_gz(ros_msg.collision1, (*gz_msg.mutable_collision1())); + convert_ros_to_gz(ros_msg.collision1, (*gz_msg.mutable_collision2())); + gz_msg.clear_position(); for (auto const & ros_position : ros_msg.positions) { - auto ign_position = ign_msg.add_position(); - convert_ros_to_ign(ros_position, *ign_position); + auto gz_position = gz_msg.add_position(); + convert_ros_to_gz(ros_position, *gz_position); } - ign_msg.clear_normal(); + gz_msg.clear_normal(); for (const auto & ros_normal : ros_msg.normals) { - auto ign_normal = ign_msg.add_normal(); - convert_ros_to_ign(ros_normal, *ign_normal); + auto gz_normal = gz_msg.add_normal(); + convert_ros_to_gz(ros_normal, *gz_normal); } for (const auto & ros_depth : ros_msg.depths) { - ign_msg.add_depth(ros_depth); + gz_msg.add_depth(ros_depth); } - ign_msg.clear_wrench(); + gz_msg.clear_wrench(); for (const auto & ros_wrench : ros_msg.wrenches) { - auto ign_wrench = ign_msg.add_wrench(); - convert_ros_to_ign(ros_wrench, *ign_wrench); + auto gz_wrench = gz_msg.add_wrench(); + convert_ros_to_gz(ros_wrench, *gz_wrench); } } template<> void -convert_ign_to_ros( - const ignition::msgs::Contact & ign_msg, - ros_ign_interfaces::msg::Contact & ros_msg) +convert_gz_to_ros( + const ignition::msgs::Contact & gz_msg, + ros_gz_interfaces::msg::Contact & ros_msg) { - convert_ign_to_ros(ign_msg.collision1(), ros_msg.collision1); - convert_ign_to_ros(ign_msg.collision2(), ros_msg.collision2); - for (auto i = 0; i < ign_msg.position_size(); ++i) { + convert_gz_to_ros(gz_msg.collision1(), ros_msg.collision1); + convert_gz_to_ros(gz_msg.collision2(), ros_msg.collision2); + for (auto i = 0; i < gz_msg.position_size(); ++i) { geometry_msgs::msg::Vector3 ros_position; - convert_ign_to_ros(ign_msg.position(i), ros_position); + convert_gz_to_ros(gz_msg.position(i), ros_position); ros_msg.positions.push_back(ros_position); } - for (auto i = 0; i < ign_msg.normal_size(); ++i) { + for (auto i = 0; i < gz_msg.normal_size(); ++i) { geometry_msgs::msg::Vector3 ros_normal; - convert_ign_to_ros(ign_msg.normal(i), ros_normal); + convert_gz_to_ros(gz_msg.normal(i), ros_normal); ros_msg.normals.push_back(ros_normal); } - for (auto i = 0; i < ign_msg.depth_size(); ++i) { - ros_msg.depths.push_back(ign_msg.depth(i)); + for (auto i = 0; i < gz_msg.depth_size(); ++i) { + ros_msg.depths.push_back(gz_msg.depth(i)); } - for (auto i = 0; i < ign_msg.wrench_size(); ++i) { - ros_ign_interfaces::msg::JointWrench ros_joint_wrench; - convert_ign_to_ros(ign_msg.wrench(i), ros_joint_wrench); + for (auto i = 0; i < gz_msg.wrench_size(); ++i) { + ros_gz_interfaces::msg::JointWrench ros_joint_wrench; + convert_gz_to_ros(gz_msg.wrench(i), ros_joint_wrench); ros_msg.wrenches.push_back(ros_joint_wrench); } } template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::Contacts & ros_msg, - ignition::msgs::Contacts & ign_msg) +convert_ros_to_gz( + const ros_gz_interfaces::msg::Contacts & ros_msg, + ignition::msgs::Contacts & gz_msg) { - convert_ros_to_ign(ros_msg.header, (*ign_msg.mutable_header())); - ign_msg.clear_contact(); + convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header())); + gz_msg.clear_contact(); for (const auto & ros_contact : ros_msg.contacts) { - auto ign_contact = ign_msg.add_contact(); - convert_ros_to_ign(ros_contact, *ign_contact); + auto gz_contact = gz_msg.add_contact(); + convert_ros_to_gz(ros_contact, *gz_contact); } } template<> void -convert_ign_to_ros( - const ignition::msgs::Contacts & ign_msg, - ros_ign_interfaces::msg::Contacts & ros_msg) +convert_gz_to_ros( + const ignition::msgs::Contacts & gz_msg, + ros_gz_interfaces::msg::Contacts & ros_msg) { - convert_ign_to_ros(ign_msg.header(), ros_msg.header); - for (auto i = 0; i < ign_msg.contact_size(); ++i) { - ros_ign_interfaces::msg::Contact ros_contact; - convert_ign_to_ros(ign_msg.contact(i), ros_contact); + convert_gz_to_ros(gz_msg.header(), ros_msg.header); + for (auto i = 0; i < gz_msg.contact_size(); ++i) { + ros_gz_interfaces::msg::Contact ros_contact; + convert_gz_to_ros(gz_msg.contact(i), ros_contact); ros_msg.contacts.push_back(ros_contact); } } template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::GuiCamera & ros_msg, - ignition::msgs::GUICamera & ign_msg) +convert_ros_to_gz( + const ros_gz_interfaces::msg::GuiCamera & ros_msg, + ignition::msgs::GUICamera & gz_msg) { - convert_ros_to_ign(ros_msg.header, *ign_msg.mutable_header()); - ign_msg.set_name(ros_msg.name); - ign_msg.set_view_controller(ros_msg.view_controller); - convert_ros_to_ign(ros_msg.pose, *ign_msg.mutable_pose()); - convert_ros_to_ign(ros_msg.track, *ign_msg.mutable_track()); - ign_msg.set_projection_type(ros_msg.projection_type); + convert_ros_to_gz(ros_msg.header, *gz_msg.mutable_header()); + gz_msg.set_name(ros_msg.name); + gz_msg.set_view_controller(ros_msg.view_controller); + convert_ros_to_gz(ros_msg.pose, *gz_msg.mutable_pose()); + convert_ros_to_gz(ros_msg.track, *gz_msg.mutable_track()); + gz_msg.set_projection_type(ros_msg.projection_type); } template<> void -convert_ign_to_ros( - const ignition::msgs::GUICamera & ign_msg, - ros_ign_interfaces::msg::GuiCamera & ros_msg) +convert_gz_to_ros( + const ignition::msgs::GUICamera & gz_msg, + ros_gz_interfaces::msg::GuiCamera & ros_msg) { - convert_ign_to_ros(ign_msg.header(), ros_msg.header); - ros_msg.name = ign_msg.name(); - ros_msg.view_controller = ign_msg.view_controller(); - convert_ign_to_ros(ign_msg.pose(), ros_msg.pose); - convert_ign_to_ros(ign_msg.track(), ros_msg.track); - ros_msg.projection_type = ign_msg.projection_type(); + convert_gz_to_ros(gz_msg.header(), ros_msg.header); + ros_msg.name = gz_msg.name(); + ros_msg.view_controller = gz_msg.view_controller(); + convert_gz_to_ros(gz_msg.pose(), ros_msg.pose); + convert_gz_to_ros(gz_msg.track(), ros_msg.track); + ros_msg.projection_type = gz_msg.projection_type(); } template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::Light & ros_msg, - ignition::msgs::Light & ign_msg) +convert_ros_to_gz( + const ros_gz_interfaces::msg::Light & ros_msg, + ignition::msgs::Light & gz_msg) { - convert_ros_to_ign(ros_msg.header, (*ign_msg.mutable_header())); + convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header())); - ign_msg.set_name(ros_msg.name); + gz_msg.set_name(ros_msg.name); if (ros_msg.type == 0) { - ign_msg.set_type(ignition::msgs::Light_LightType::Light_LightType_POINT); + gz_msg.set_type(ignition::msgs::Light_LightType::Light_LightType_POINT); } else if (ros_msg.type == 1) { - ign_msg.set_type(ignition::msgs::Light_LightType::Light_LightType_SPOT); + gz_msg.set_type(ignition::msgs::Light_LightType::Light_LightType_SPOT); } else if (ros_msg.type == 2) { - ign_msg.set_type( + gz_msg.set_type( ignition::msgs::Light_LightType::Light_LightType_DIRECTIONAL); } - convert_ros_to_ign(ros_msg.pose, *ign_msg.mutable_pose()); - convert_ros_to_ign(ros_msg.diffuse, *ign_msg.mutable_diffuse()); - convert_ros_to_ign(ros_msg.specular, *ign_msg.mutable_specular()); - ign_msg.set_attenuation_constant(ros_msg.attenuation_constant); - ign_msg.set_attenuation_linear(ros_msg.attenuation_linear); - ign_msg.set_attenuation_quadratic(ros_msg.attenuation_quadratic); - convert_ros_to_ign(ros_msg.direction, *ign_msg.mutable_direction()); - ign_msg.set_range(ros_msg.range); - ign_msg.set_cast_shadows(ros_msg.cast_shadows); - ign_msg.set_spot_inner_angle(ros_msg.spot_inner_angle); - ign_msg.set_spot_outer_angle(ros_msg.spot_outer_angle); - ign_msg.set_spot_falloff(ros_msg.spot_falloff); + convert_ros_to_gz(ros_msg.pose, *gz_msg.mutable_pose()); + convert_ros_to_gz(ros_msg.diffuse, *gz_msg.mutable_diffuse()); + convert_ros_to_gz(ros_msg.specular, *gz_msg.mutable_specular()); + gz_msg.set_attenuation_constant(ros_msg.attenuation_constant); + gz_msg.set_attenuation_linear(ros_msg.attenuation_linear); + gz_msg.set_attenuation_quadratic(ros_msg.attenuation_quadratic); + convert_ros_to_gz(ros_msg.direction, *gz_msg.mutable_direction()); + gz_msg.set_range(ros_msg.range); + gz_msg.set_cast_shadows(ros_msg.cast_shadows); + gz_msg.set_spot_inner_angle(ros_msg.spot_inner_angle); + gz_msg.set_spot_outer_angle(ros_msg.spot_outer_angle); + gz_msg.set_spot_falloff(ros_msg.spot_falloff); - ign_msg.set_id(ros_msg.id); + gz_msg.set_id(ros_msg.id); - ign_msg.set_parent_id(ros_msg.parent_id); + gz_msg.set_parent_id(ros_msg.parent_id); - ign_msg.set_intensity(ros_msg.intensity); + gz_msg.set_intensity(ros_msg.intensity); } template<> void -convert_ign_to_ros( - const ignition::msgs::Light & ign_msg, - ros_ign_interfaces::msg::Light & ros_msg) +convert_gz_to_ros( + const ignition::msgs::Light & gz_msg, + ros_gz_interfaces::msg::Light & ros_msg) { - convert_ign_to_ros(ign_msg.header(), ros_msg.header); + convert_gz_to_ros(gz_msg.header(), ros_msg.header); - ros_msg.name = ign_msg.name(); - if (ign_msg.type() == + ros_msg.name = gz_msg.name(); + if (gz_msg.type() == ignition::msgs::Light_LightType::Light_LightType_POINT) { ros_msg.type = 0; - } else if (ign_msg.type() == ignition::msgs::Light_LightType::Light_LightType_SPOT) { + } else if (gz_msg.type() == ignition::msgs::Light_LightType::Light_LightType_SPOT) { ros_msg.type = 1; - } else if (ign_msg.type() == ignition::msgs::Light_LightType::Light_LightType_DIRECTIONAL) { + } else if (gz_msg.type() == ignition::msgs::Light_LightType::Light_LightType_DIRECTIONAL) { ros_msg.type = 2; } - convert_ign_to_ros(ign_msg.pose(), ros_msg.pose); - convert_ign_to_ros(ign_msg.diffuse(), ros_msg.diffuse); - convert_ign_to_ros(ign_msg.specular(), ros_msg.specular); - ros_msg.attenuation_constant = ign_msg.attenuation_constant(); - ros_msg.attenuation_linear = ign_msg.attenuation_linear(); - ros_msg.attenuation_quadratic = ign_msg.attenuation_quadratic(); - convert_ign_to_ros(ign_msg.direction(), ros_msg.direction); - ros_msg.range = ign_msg.range(); - ros_msg.cast_shadows = ign_msg.cast_shadows(); - ros_msg.spot_inner_angle = ign_msg.spot_inner_angle(); - ros_msg.spot_outer_angle = ign_msg.spot_outer_angle(); - ros_msg.spot_falloff = ign_msg.spot_falloff(); + convert_gz_to_ros(gz_msg.pose(), ros_msg.pose); + convert_gz_to_ros(gz_msg.diffuse(), ros_msg.diffuse); + convert_gz_to_ros(gz_msg.specular(), ros_msg.specular); + ros_msg.attenuation_constant = gz_msg.attenuation_constant(); + ros_msg.attenuation_linear = gz_msg.attenuation_linear(); + ros_msg.attenuation_quadratic = gz_msg.attenuation_quadratic(); + convert_gz_to_ros(gz_msg.direction(), ros_msg.direction); + ros_msg.range = gz_msg.range(); + ros_msg.cast_shadows = gz_msg.cast_shadows(); + ros_msg.spot_inner_angle = gz_msg.spot_inner_angle(); + ros_msg.spot_outer_angle = gz_msg.spot_outer_angle(); + ros_msg.spot_falloff = gz_msg.spot_falloff(); - ros_msg.id = ign_msg.id(); + ros_msg.id = gz_msg.id(); - ros_msg.parent_id = ign_msg.parent_id(); + ros_msg.parent_id = gz_msg.parent_id(); - ros_msg.intensity = ign_msg.intensity(); + ros_msg.intensity = gz_msg.intensity(); } template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::StringVec & ros_msg, - ignition::msgs::StringMsg_V & ign_msg) +convert_ros_to_gz( + const ros_gz_interfaces::msg::StringVec & ros_msg, + ignition::msgs::StringMsg_V & gz_msg) { - convert_ros_to_ign(ros_msg.header, *ign_msg.mutable_header()); + convert_ros_to_gz(ros_msg.header, *gz_msg.mutable_header()); for (const auto & elem : ros_msg.data) { - auto * new_elem = ign_msg.add_data(); + auto * new_elem = gz_msg.add_data(); *new_elem = elem; } } template<> void -convert_ign_to_ros( - const ignition::msgs::StringMsg_V & ign_msg, - ros_ign_interfaces::msg::StringVec & ros_msg) +convert_gz_to_ros( + const ignition::msgs::StringMsg_V & gz_msg, + ros_gz_interfaces::msg::StringVec & ros_msg) { - convert_ign_to_ros(ign_msg.header(), ros_msg.header); - for (const auto & elem : ign_msg.data()) { + convert_gz_to_ros(gz_msg.header(), ros_msg.header); + for (const auto & elem : gz_msg.data()) { ros_msg.data.emplace_back(elem); } } template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::TrackVisual & ros_msg, - ignition::msgs::TrackVisual & ign_msg) +convert_ros_to_gz( + const ros_gz_interfaces::msg::TrackVisual & ros_msg, + ignition::msgs::TrackVisual & gz_msg) { - convert_ros_to_ign(ros_msg.header, *ign_msg.mutable_header()); - ign_msg.set_name(ros_msg.name); - ign_msg.set_id(ros_msg.id); - ign_msg.set_inherit_orientation(ros_msg.inherit_orientation); - ign_msg.set_min_dist(ros_msg.min_dist); - ign_msg.set_max_dist(ros_msg.max_dist); - ign_msg.set_static_(ros_msg.is_static); - ign_msg.set_use_model_frame(ros_msg.use_model_frame); - convert_ros_to_ign(ros_msg.xyz, *ign_msg.mutable_xyz()); - ign_msg.set_inherit_yaw(ros_msg.inherit_yaw); + convert_ros_to_gz(ros_msg.header, *gz_msg.mutable_header()); + gz_msg.set_name(ros_msg.name); + gz_msg.set_id(ros_msg.id); + gz_msg.set_inherit_orientation(ros_msg.inherit_orientation); + gz_msg.set_min_dist(ros_msg.min_dist); + gz_msg.set_max_dist(ros_msg.max_dist); + gz_msg.set_static_(ros_msg.is_static); + gz_msg.set_use_model_frame(ros_msg.use_model_frame); + convert_ros_to_gz(ros_msg.xyz, *gz_msg.mutable_xyz()); + gz_msg.set_inherit_yaw(ros_msg.inherit_yaw); } template<> void -convert_ign_to_ros( - const ignition::msgs::TrackVisual & ign_msg, - ros_ign_interfaces::msg::TrackVisual & ros_msg) +convert_gz_to_ros( + const ignition::msgs::TrackVisual & gz_msg, + ros_gz_interfaces::msg::TrackVisual & ros_msg) { - convert_ign_to_ros(ign_msg.header(), ros_msg.header); - ros_msg.name = ign_msg.name(); - ros_msg.id = ign_msg.id(); - ros_msg.inherit_orientation = ign_msg.inherit_orientation(); - ros_msg.min_dist = ign_msg.min_dist(); - ros_msg.max_dist = ign_msg.max_dist(); - ros_msg.is_static = ign_msg.static_(); - ros_msg.use_model_frame = ign_msg.use_model_frame(); - convert_ign_to_ros(ign_msg.xyz(), ros_msg.xyz); - ros_msg.inherit_yaw = ign_msg.inherit_yaw(); + convert_gz_to_ros(gz_msg.header(), ros_msg.header); + ros_msg.name = gz_msg.name(); + ros_msg.id = gz_msg.id(); + ros_msg.inherit_orientation = gz_msg.inherit_orientation(); + ros_msg.min_dist = gz_msg.min_dist(); + ros_msg.max_dist = gz_msg.max_dist(); + ros_msg.is_static = gz_msg.static_(); + ros_msg.use_model_frame = gz_msg.use_model_frame(); + convert_gz_to_ros(gz_msg.xyz(), ros_msg.xyz); + ros_msg.inherit_yaw = gz_msg.inherit_yaw(); } template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::VideoRecord & ros_msg, - ignition::msgs::VideoRecord & ign_msg) +convert_ros_to_gz( + const ros_gz_interfaces::msg::VideoRecord & ros_msg, + ignition::msgs::VideoRecord & gz_msg) { - convert_ros_to_ign(ros_msg.header, *ign_msg.mutable_header()); - ign_msg.set_start(ros_msg.start); - ign_msg.set_stop(ros_msg.stop); - ign_msg.set_format(ros_msg.format); - ign_msg.set_save_filename(ros_msg.save_filename); + convert_ros_to_gz(ros_msg.header, *gz_msg.mutable_header()); + gz_msg.set_start(ros_msg.start); + gz_msg.set_stop(ros_msg.stop); + gz_msg.set_format(ros_msg.format); + gz_msg.set_save_filename(ros_msg.save_filename); } template<> void -convert_ign_to_ros( - const ignition::msgs::VideoRecord & ign_msg, - ros_ign_interfaces::msg::VideoRecord & ros_msg) +convert_gz_to_ros( + const ignition::msgs::VideoRecord & gz_msg, + ros_gz_interfaces::msg::VideoRecord & ros_msg) { - convert_ign_to_ros(ign_msg.header(), ros_msg.header); - ros_msg.start = ign_msg.start(); - ros_msg.stop = ign_msg.stop(); - ros_msg.format = ign_msg.format(); - ros_msg.save_filename = ign_msg.save_filename(); + convert_gz_to_ros(gz_msg.header(), ros_msg.header); + ros_msg.start = gz_msg.start(); + ros_msg.stop = gz_msg.stop(); + ros_msg.format = gz_msg.format(); + ros_msg.save_filename = gz_msg.save_filename(); } template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::WorldControl & ros_msg, - ignition::msgs::WorldControl & ign_msg) +convert_ros_to_gz( + const ros_gz_interfaces::msg::WorldControl & ros_msg, + ignition::msgs::WorldControl & gz_msg) { - ign_msg.set_pause(ros_msg.pause); - ign_msg.set_step(ros_msg.step); - ign_msg.set_multi_step(ros_msg.multi_step); - convert_ros_to_ign(ros_msg.reset, *ign_msg.mutable_reset()); - ign_msg.set_seed(ros_msg.seed); - convert_ros_to_ign(ros_msg.run_to_sim_time, *ign_msg.mutable_run_to_sim_time()); + gz_msg.set_pause(ros_msg.pause); + gz_msg.set_step(ros_msg.step); + gz_msg.set_multi_step(ros_msg.multi_step); + convert_ros_to_gz(ros_msg.reset, *gz_msg.mutable_reset()); + gz_msg.set_seed(ros_msg.seed); + convert_ros_to_gz(ros_msg.run_to_sim_time, *gz_msg.mutable_run_to_sim_time()); } template<> void -convert_ign_to_ros( - const ignition::msgs::WorldControl & ign_msg, - ros_ign_interfaces::msg::WorldControl & ros_msg) +convert_gz_to_ros( + const ignition::msgs::WorldControl & gz_msg, + ros_gz_interfaces::msg::WorldControl & ros_msg) { - ros_msg.pause = ign_msg.pause(); - ros_msg.step = ign_msg.step(); - ros_msg.multi_step = ign_msg.multi_step(); - convert_ign_to_ros(ign_msg.reset(), ros_msg.reset); - ros_msg.seed = ign_msg.seed(); - convert_ign_to_ros(ign_msg.run_to_sim_time(), ros_msg.run_to_sim_time); + ros_msg.pause = gz_msg.pause(); + ros_msg.step = gz_msg.step(); + ros_msg.multi_step = gz_msg.multi_step(); + convert_gz_to_ros(gz_msg.reset(), ros_msg.reset); + ros_msg.seed = gz_msg.seed(); + convert_gz_to_ros(gz_msg.run_to_sim_time(), ros_msg.run_to_sim_time); } template<> void -convert_ros_to_ign( - const ros_ign_interfaces::msg::WorldReset & ros_msg, - ignition::msgs::WorldReset & ign_msg) +convert_ros_to_gz( + const ros_gz_interfaces::msg::WorldReset & ros_msg, + ignition::msgs::WorldReset & gz_msg) { - ign_msg.set_all(ros_msg.all); - ign_msg.set_time_only(ros_msg.time_only); - ign_msg.set_model_only(ros_msg.model_only); + gz_msg.set_all(ros_msg.all); + gz_msg.set_time_only(ros_msg.time_only); + gz_msg.set_model_only(ros_msg.model_only); } template<> void -convert_ign_to_ros( - const ignition::msgs::WorldReset & ign_msg, - ros_ign_interfaces::msg::WorldReset & ros_msg) +convert_gz_to_ros( + const ignition::msgs::WorldReset & gz_msg, + ros_gz_interfaces::msg::WorldReset & ros_msg) { - ros_msg.all = ign_msg.all(); - ros_msg.time_only = ign_msg.time_only(); - ros_msg.model_only = ign_msg.model_only(); + ros_msg.all = gz_msg.all(); + ros_msg.time_only = gz_msg.time_only(); + ros_msg.model_only = gz_msg.model_only(); } -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge diff --git a/ros_gz_bridge/src/convert/rosgraph_msgs.cpp b/ros_gz_bridge/src/convert/rosgraph_msgs.cpp index f73aa342..c6da7fc9 100644 --- a/ros_gz_bridge/src/convert/rosgraph_msgs.cpp +++ b/ros_gz_bridge/src/convert/rosgraph_msgs.cpp @@ -15,28 +15,28 @@ #include #include "convert/utils.hpp" -#include "ros_ign_bridge/convert/rosgraph_msgs.hpp" +#include "ros_gz_bridge/convert/rosgraph_msgs.hpp" -namespace ros_ign_bridge +namespace ros_gz_bridge { template<> void -convert_ign_to_ros( - const ignition::msgs::Clock & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Clock & gz_msg, rosgraph_msgs::msg::Clock & ros_msg) { - ros_msg.clock = rclcpp::Time(ign_msg.sim().sec(), ign_msg.sim().nsec()); + ros_msg.clock = rclcpp::Time(gz_msg.sim().sec(), gz_msg.sim().nsec()); } template<> void -convert_ros_to_ign( +convert_ros_to_gz( const rosgraph_msgs::msg::Clock & ros_msg, - ignition::msgs::Clock & ign_msg) + ignition::msgs::Clock & gz_msg) { - ign_msg.mutable_sim()->set_sec(ros_msg.clock.sec); - ign_msg.mutable_sim()->set_nsec(ros_msg.clock.nanosec); + gz_msg.mutable_sim()->set_sec(ros_msg.clock.sec); + gz_msg.mutable_sim()->set_nsec(ros_msg.clock.nanosec); } -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge diff --git a/ros_gz_bridge/src/convert/sensor_msgs.cpp b/ros_gz_bridge/src/convert/sensor_msgs.cpp index 3da2265d..4903d6e7 100644 --- a/ros_gz_bridge/src/convert/sensor_msgs.cpp +++ b/ros_gz_bridge/src/convert/sensor_msgs.cpp @@ -15,146 +15,146 @@ #include #include "convert/utils.hpp" -#include "ros_ign_bridge/convert/sensor_msgs.hpp" +#include "ros_gz_bridge/convert/sensor_msgs.hpp" -namespace ros_ign_bridge +namespace ros_gz_bridge { template<> void -convert_ros_to_ign( +convert_ros_to_gz( const sensor_msgs::msg::FluidPressure & ros_msg, - ignition::msgs::FluidPressure & ign_msg) + ignition::msgs::FluidPressure & gz_msg) { - convert_ros_to_ign(ros_msg.header, (*ign_msg.mutable_header())); - ign_msg.set_pressure(ros_msg.fluid_pressure); - ign_msg.set_variance(ros_msg.variance); + convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header())); + gz_msg.set_pressure(ros_msg.fluid_pressure); + gz_msg.set_variance(ros_msg.variance); } template<> void -convert_ign_to_ros( - const ignition::msgs::FluidPressure & ign_msg, +convert_gz_to_ros( + const ignition::msgs::FluidPressure & gz_msg, sensor_msgs::msg::FluidPressure & ros_msg) { - convert_ign_to_ros(ign_msg.header(), ros_msg.header); - ros_msg.fluid_pressure = ign_msg.pressure(); - ros_msg.variance = ign_msg.variance(); + convert_gz_to_ros(gz_msg.header(), ros_msg.header); + ros_msg.fluid_pressure = gz_msg.pressure(); + ros_msg.variance = gz_msg.variance(); } template<> void -convert_ros_to_ign( +convert_ros_to_gz( const sensor_msgs::msg::Image & ros_msg, - ignition::msgs::Image & ign_msg) + ignition::msgs::Image & gz_msg) { - convert_ros_to_ign(ros_msg.header, (*ign_msg.mutable_header())); + convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header())); - ign_msg.set_width(ros_msg.width); - ign_msg.set_height(ros_msg.height); + gz_msg.set_width(ros_msg.width); + gz_msg.set_height(ros_msg.height); unsigned int num_channels; unsigned int octets_per_channel; if (ros_msg.encoding == "mono8") { - ign_msg.set_pixel_format_type(ignition::msgs::PixelFormatType::L_INT8); + gz_msg.set_pixel_format_type(ignition::msgs::PixelFormatType::L_INT8); num_channels = 1; octets_per_channel = 1u; } else if (ros_msg.encoding == "mono16") { - ign_msg.set_pixel_format_type(ignition::msgs::PixelFormatType::L_INT16); + gz_msg.set_pixel_format_type(ignition::msgs::PixelFormatType::L_INT16); num_channels = 1; octets_per_channel = 2u; } else if (ros_msg.encoding == "rgb8") { - ign_msg.set_pixel_format_type(ignition::msgs::PixelFormatType::RGB_INT8); + gz_msg.set_pixel_format_type(ignition::msgs::PixelFormatType::RGB_INT8); num_channels = 3; octets_per_channel = 1u; } else if (ros_msg.encoding == "rgba8") { - ign_msg.set_pixel_format_type(ignition::msgs::PixelFormatType::RGBA_INT8); + gz_msg.set_pixel_format_type(ignition::msgs::PixelFormatType::RGBA_INT8); num_channels = 4; octets_per_channel = 1u; } else if (ros_msg.encoding == "bgra8") { - ign_msg.set_pixel_format_type(ignition::msgs::PixelFormatType::BGRA_INT8); + gz_msg.set_pixel_format_type(ignition::msgs::PixelFormatType::BGRA_INT8); num_channels = 4; octets_per_channel = 1u; } else if (ros_msg.encoding == "rgb16") { - ign_msg.set_pixel_format_type(ignition::msgs::PixelFormatType::RGB_INT16); + gz_msg.set_pixel_format_type(ignition::msgs::PixelFormatType::RGB_INT16); num_channels = 3; octets_per_channel = 2u; } else if (ros_msg.encoding == "bgr8") { - ign_msg.set_pixel_format_type(ignition::msgs::PixelFormatType::BGR_INT8); + gz_msg.set_pixel_format_type(ignition::msgs::PixelFormatType::BGR_INT8); num_channels = 3; octets_per_channel = 1u; } else if (ros_msg.encoding == "bgr16") { - ign_msg.set_pixel_format_type(ignition::msgs::PixelFormatType::BGR_INT16); + gz_msg.set_pixel_format_type(ignition::msgs::PixelFormatType::BGR_INT16); num_channels = 3; octets_per_channel = 2u; } else if (ros_msg.encoding == "32FC1") { - ign_msg.set_pixel_format_type(ignition::msgs::PixelFormatType::R_FLOAT32); + gz_msg.set_pixel_format_type(ignition::msgs::PixelFormatType::R_FLOAT32); num_channels = 1; octets_per_channel = 4u; } else { - ign_msg.set_pixel_format_type(ignition::msgs::PixelFormatType::UNKNOWN_PIXEL_FORMAT); + gz_msg.set_pixel_format_type(ignition::msgs::PixelFormatType::UNKNOWN_PIXEL_FORMAT); std::cerr << "Unsupported pixel format [" << ros_msg.encoding << "]" << std::endl; return; } - ign_msg.set_step(ign_msg.width() * num_channels * octets_per_channel); + gz_msg.set_step(gz_msg.width() * num_channels * octets_per_channel); - ign_msg.set_data(&(ros_msg.data[0]), ign_msg.step() * ign_msg.height()); + gz_msg.set_data(&(ros_msg.data[0]), gz_msg.step() * gz_msg.height()); } template<> void -convert_ign_to_ros( - const ignition::msgs::Image & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Image & gz_msg, sensor_msgs::msg::Image & ros_msg) { - convert_ign_to_ros(ign_msg.header(), ros_msg.header); + convert_gz_to_ros(gz_msg.header(), ros_msg.header); - ros_msg.height = ign_msg.height(); - ros_msg.width = ign_msg.width(); + ros_msg.height = gz_msg.height(); + ros_msg.width = gz_msg.width(); unsigned int num_channels; unsigned int octets_per_channel; - if (ign_msg.pixel_format_type() == ignition::msgs::PixelFormatType::L_INT8) { + if (gz_msg.pixel_format_type() == ignition::msgs::PixelFormatType::L_INT8) { ros_msg.encoding = "mono8"; num_channels = 1; octets_per_channel = 1u; - } else if (ign_msg.pixel_format_type() == ignition::msgs::PixelFormatType::L_INT16) { + } else if (gz_msg.pixel_format_type() == ignition::msgs::PixelFormatType::L_INT16) { ros_msg.encoding = "mono16"; num_channels = 1; octets_per_channel = 2u; - } else if (ign_msg.pixel_format_type() == ignition::msgs::PixelFormatType::RGB_INT8) { + } else if (gz_msg.pixel_format_type() == ignition::msgs::PixelFormatType::RGB_INT8) { ros_msg.encoding = "rgb8"; num_channels = 3; octets_per_channel = 1u; - } else if (ign_msg.pixel_format_type() == ignition::msgs::PixelFormatType::RGBA_INT8) { + } else if (gz_msg.pixel_format_type() == ignition::msgs::PixelFormatType::RGBA_INT8) { ros_msg.encoding = "rgba8"; num_channels = 4; octets_per_channel = 1u; - } else if (ign_msg.pixel_format_type() == ignition::msgs::PixelFormatType::BGRA_INT8) { + } else if (gz_msg.pixel_format_type() == ignition::msgs::PixelFormatType::BGRA_INT8) { ros_msg.encoding = "bgra8"; num_channels = 4; octets_per_channel = 1u; - } else if (ign_msg.pixel_format_type() == ignition::msgs::PixelFormatType::RGB_INT16) { + } else if (gz_msg.pixel_format_type() == ignition::msgs::PixelFormatType::RGB_INT16) { ros_msg.encoding = "rgb16"; num_channels = 3; octets_per_channel = 2u; - } else if (ign_msg.pixel_format_type() == ignition::msgs::PixelFormatType::BGR_INT8) { + } else if (gz_msg.pixel_format_type() == ignition::msgs::PixelFormatType::BGR_INT8) { ros_msg.encoding = "bgr8"; num_channels = 3; octets_per_channel = 1u; - } else if (ign_msg.pixel_format_type() == ignition::msgs::PixelFormatType::BGR_INT16) { + } else if (gz_msg.pixel_format_type() == ignition::msgs::PixelFormatType::BGR_INT16) { ros_msg.encoding = "bgr16"; num_channels = 3; octets_per_channel = 2u; - } else if (ign_msg.pixel_format_type() == ignition::msgs::PixelFormatType::R_FLOAT32) { + } else if (gz_msg.pixel_format_type() == ignition::msgs::PixelFormatType::R_FLOAT32) { ros_msg.encoding = "32FC1"; num_channels = 1; octets_per_channel = 4u; } else { - std::cerr << "Unsupported pixel format [" << ign_msg.pixel_format_type() << "]" << std::endl; + std::cerr << "Unsupported pixel format [" << gz_msg.pixel_format_type() << "]" << std::endl; return; } @@ -164,23 +164,23 @@ convert_ign_to_ros( auto count = ros_msg.step * ros_msg.height; ros_msg.data.resize(ros_msg.step * ros_msg.height); std::copy( - ign_msg.data().begin(), - ign_msg.data().begin() + count, + gz_msg.data().begin(), + gz_msg.data().begin() + count, ros_msg.data.begin()); } template<> void -convert_ros_to_ign( +convert_ros_to_gz( const sensor_msgs::msg::CameraInfo & ros_msg, - ignition::msgs::CameraInfo & ign_msg) + ignition::msgs::CameraInfo & gz_msg) { - convert_ros_to_ign(ros_msg.header, (*ign_msg.mutable_header())); + convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header())); - ign_msg.set_width(ros_msg.width); - ign_msg.set_height(ros_msg.height); + gz_msg.set_width(ros_msg.width); + gz_msg.set_height(ros_msg.height); - auto distortion = ign_msg.mutable_distortion(); + auto distortion = gz_msg.mutable_distortion(); if (ros_msg.distortion_model == "plumb_bob") { distortion->set_model(ignition::msgs::CameraInfo::Distortion::PLUMB_BOB); } else if (ros_msg.distortion_model == "rational_polynomial") { @@ -195,34 +195,34 @@ convert_ros_to_ign( distortion->add_k(i); } - auto intrinsics = ign_msg.mutable_intrinsics(); + auto intrinsics = gz_msg.mutable_intrinsics(); for (double i : ros_msg.k) { intrinsics->add_k(i); } - auto projection = ign_msg.mutable_projection(); + auto projection = gz_msg.mutable_projection(); for (double i : ros_msg.p) { projection->add_p(i); } for (auto i = 0u; i < ros_msg.r.size(); ++i) { - ign_msg.add_rectification_matrix(ros_msg.r[i]); + gz_msg.add_rectification_matrix(ros_msg.r[i]); } } template<> void -convert_ign_to_ros( - const ignition::msgs::CameraInfo & ign_msg, +convert_gz_to_ros( + const ignition::msgs::CameraInfo & gz_msg, sensor_msgs::msg::CameraInfo & ros_msg) { - convert_ign_to_ros(ign_msg.header(), ros_msg.header); + convert_gz_to_ros(gz_msg.header(), ros_msg.header); - ros_msg.height = ign_msg.height(); - ros_msg.width = ign_msg.width(); + ros_msg.height = gz_msg.height(); + ros_msg.width = gz_msg.width(); - if (ign_msg.has_distortion()) { - const auto & distortion = ign_msg.distortion(); + if (gz_msg.has_distortion()) { + const auto & distortion = gz_msg.distortion(); if (distortion.model() == ignition::msgs::CameraInfo::Distortion::PLUMB_BOB) { ros_msg.distortion_model = "plumb_bob"; } else if (distortion.model() == ignition::msgs::CameraInfo::Distortion::RATIONAL_POLYNOMIAL) { @@ -239,67 +239,67 @@ convert_ign_to_ros( } } - if (ign_msg.has_intrinsics()) { - const auto & intrinsics = ign_msg.intrinsics(); + if (gz_msg.has_intrinsics()) { + const auto & intrinsics = gz_msg.intrinsics(); for (auto i = 0; i < intrinsics.k_size(); ++i) { ros_msg.k[i] = intrinsics.k(i); } } - if (ign_msg.has_projection()) { - const auto & projection = ign_msg.projection(); + if (gz_msg.has_projection()) { + const auto & projection = gz_msg.projection(); for (auto i = 0; i < projection.p_size(); ++i) { ros_msg.p[i] = projection.p(i); } } - for (auto i = 0; i < ign_msg.rectification_matrix_size(); ++i) { - ros_msg.r[i] = ign_msg.rectification_matrix(i); + for (auto i = 0; i < gz_msg.rectification_matrix_size(); ++i) { + ros_msg.r[i] = gz_msg.rectification_matrix(i); } } template<> void -convert_ros_to_ign( +convert_ros_to_gz( const sensor_msgs::msg::Imu & ros_msg, - ignition::msgs::IMU & ign_msg) + ignition::msgs::IMU & gz_msg) { - convert_ros_to_ign(ros_msg.header, (*ign_msg.mutable_header())); + convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header())); // ToDo: Verify that this is the expected value (probably not). - ign_msg.set_entity_name(ros_msg.header.frame_id); + gz_msg.set_entity_name(ros_msg.header.frame_id); - convert_ros_to_ign(ros_msg.orientation, (*ign_msg.mutable_orientation())); - convert_ros_to_ign(ros_msg.angular_velocity, (*ign_msg.mutable_angular_velocity())); - convert_ros_to_ign(ros_msg.linear_acceleration, (*ign_msg.mutable_linear_acceleration())); + convert_ros_to_gz(ros_msg.orientation, (*gz_msg.mutable_orientation())); + convert_ros_to_gz(ros_msg.angular_velocity, (*gz_msg.mutable_angular_velocity())); + convert_ros_to_gz(ros_msg.linear_acceleration, (*gz_msg.mutable_linear_acceleration())); } template<> void -convert_ign_to_ros( - const ignition::msgs::IMU & ign_msg, +convert_gz_to_ros( + const ignition::msgs::IMU & gz_msg, sensor_msgs::msg::Imu & ros_msg) { - convert_ign_to_ros(ign_msg.header(), ros_msg.header); - convert_ign_to_ros(ign_msg.orientation(), ros_msg.orientation); - convert_ign_to_ros(ign_msg.angular_velocity(), ros_msg.angular_velocity); - convert_ign_to_ros(ign_msg.linear_acceleration(), ros_msg.linear_acceleration); + convert_gz_to_ros(gz_msg.header(), ros_msg.header); + convert_gz_to_ros(gz_msg.orientation(), ros_msg.orientation); + convert_gz_to_ros(gz_msg.angular_velocity(), ros_msg.angular_velocity); + convert_gz_to_ros(gz_msg.linear_acceleration(), ros_msg.linear_acceleration); - // Covariances not supported in Ignition::msgs::IMU + // Covariances not supported in Gazebo::msgs::IMU } template<> void -convert_ros_to_ign( +convert_ros_to_gz( const sensor_msgs::msg::JointState & ros_msg, - ignition::msgs::Model & ign_msg) + ignition::msgs::Model & gz_msg) { - convert_ros_to_ign(ros_msg.header, (*ign_msg.mutable_header())); + convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header())); for (auto i = 0u; i < ros_msg.position.size(); ++i) { - auto newJoint = ign_msg.add_joint(); + auto newJoint = gz_msg.add_joint(); newJoint->set_name(ros_msg.name[i]); newJoint->mutable_axis1()->set_position(ros_msg.position[i]); newJoint->mutable_axis1()->set_velocity(ros_msg.velocity[i]); @@ -309,72 +309,72 @@ convert_ros_to_ign( template<> void -convert_ign_to_ros( - const ignition::msgs::Model & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Model & gz_msg, sensor_msgs::msg::JointState & ros_msg) { - convert_ign_to_ros(ign_msg.header(), ros_msg.header); + convert_gz_to_ros(gz_msg.header(), ros_msg.header); - for (auto i = 0; i < ign_msg.joint_size(); ++i) { - ros_msg.name.push_back(ign_msg.joint(i).name()); - ros_msg.position.push_back(ign_msg.joint(i).axis1().position()); - ros_msg.velocity.push_back(ign_msg.joint(i).axis1().velocity()); - ros_msg.effort.push_back(ign_msg.joint(i).axis1().force()); + for (auto i = 0; i < gz_msg.joint_size(); ++i) { + ros_msg.name.push_back(gz_msg.joint(i).name()); + ros_msg.position.push_back(gz_msg.joint(i).axis1().position()); + ros_msg.velocity.push_back(gz_msg.joint(i).axis1().velocity()); + ros_msg.effort.push_back(gz_msg.joint(i).axis1().force()); } } template<> void -convert_ros_to_ign( +convert_ros_to_gz( const sensor_msgs::msg::LaserScan & ros_msg, - ignition::msgs::LaserScan & ign_msg) + ignition::msgs::LaserScan & gz_msg) { const unsigned int num_readings = (ros_msg.angle_max - ros_msg.angle_min) / ros_msg.angle_increment; - convert_ros_to_ign(ros_msg.header, (*ign_msg.mutable_header())); - ign_msg.set_frame(ros_msg.header.frame_id); - ign_msg.set_angle_min(ros_msg.angle_min); - ign_msg.set_angle_max(ros_msg.angle_max); - ign_msg.set_angle_step(ros_msg.angle_increment); - ign_msg.set_range_min(ros_msg.range_min); - ign_msg.set_range_max(ros_msg.range_max); - ign_msg.set_count(num_readings); + convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header())); + gz_msg.set_frame(ros_msg.header.frame_id); + gz_msg.set_angle_min(ros_msg.angle_min); + gz_msg.set_angle_max(ros_msg.angle_max); + gz_msg.set_angle_step(ros_msg.angle_increment); + gz_msg.set_range_min(ros_msg.range_min); + gz_msg.set_range_max(ros_msg.range_max); + gz_msg.set_count(num_readings); // Not supported in sensor_msgs::msg::LaserScan. - ign_msg.set_vertical_angle_min(0.0); - ign_msg.set_vertical_angle_max(0.0); - ign_msg.set_vertical_angle_step(0.0); - ign_msg.set_vertical_count(0u); - - for (auto i = 0u; i < ign_msg.count(); ++i) { - ign_msg.add_ranges(ros_msg.ranges[i]); - ign_msg.add_intensities(ros_msg.intensities[i]); + gz_msg.set_vertical_angle_min(0.0); + gz_msg.set_vertical_angle_max(0.0); + gz_msg.set_vertical_angle_step(0.0); + gz_msg.set_vertical_count(0u); + + for (auto i = 0u; i < gz_msg.count(); ++i) { + gz_msg.add_ranges(ros_msg.ranges[i]); + gz_msg.add_intensities(ros_msg.intensities[i]); } } template<> void -convert_ign_to_ros( - const ignition::msgs::LaserScan & ign_msg, +convert_gz_to_ros( + const ignition::msgs::LaserScan & gz_msg, sensor_msgs::msg::LaserScan & ros_msg) { - convert_ign_to_ros(ign_msg.header(), ros_msg.header); - ros_msg.header.frame_id = frame_id_ign_to_ros(ign_msg.frame()); + convert_gz_to_ros(gz_msg.header(), ros_msg.header); + ros_msg.header.frame_id = frame_id_gz_to_ros(gz_msg.frame()); - ros_msg.angle_min = ign_msg.angle_min(); - ros_msg.angle_max = ign_msg.angle_max(); - ros_msg.angle_increment = ign_msg.angle_step(); + ros_msg.angle_min = gz_msg.angle_min(); + ros_msg.angle_max = gz_msg.angle_max(); + ros_msg.angle_increment = gz_msg.angle_step(); // Not supported in ignition::msgs::LaserScan. ros_msg.time_increment = 0.0; ros_msg.scan_time = 0.0; - ros_msg.range_min = ign_msg.range_min(); - ros_msg.range_max = ign_msg.range_max(); + ros_msg.range_min = gz_msg.range_min(); + ros_msg.range_max = gz_msg.range_max(); - auto count = ign_msg.count(); - auto vertical_count = ign_msg.vertical_count(); + auto count = gz_msg.count(); + auto vertical_count = gz_msg.vertical_count(); // If there are multiple vertical beams, use the one in the middle. size_t start = (vertical_count / 2) * count; @@ -382,59 +382,59 @@ convert_ign_to_ros( // Copy ranges into ROS message. ros_msg.ranges.resize(count); std::copy( - ign_msg.ranges().begin() + start, - ign_msg.ranges().begin() + start + count, + gz_msg.ranges().begin() + start, + gz_msg.ranges().begin() + start + count, ros_msg.ranges.begin()); // Copy intensities into ROS message. ros_msg.intensities.resize(count); std::copy( - ign_msg.intensities().begin() + start, - ign_msg.intensities().begin() + start + count, + gz_msg.intensities().begin() + start, + gz_msg.intensities().begin() + start + count, ros_msg.intensities.begin()); } template<> void -convert_ros_to_ign( +convert_ros_to_gz( const sensor_msgs::msg::MagneticField & ros_msg, - ignition::msgs::Magnetometer & ign_msg) + ignition::msgs::Magnetometer & gz_msg) { - convert_ros_to_ign(ros_msg.header, (*ign_msg.mutable_header())); - convert_ros_to_ign(ros_msg.magnetic_field, (*ign_msg.mutable_field_tesla())); + convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header())); + convert_ros_to_gz(ros_msg.magnetic_field, (*gz_msg.mutable_field_tesla())); } template<> void -convert_ign_to_ros( - const ignition::msgs::Magnetometer & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Magnetometer & gz_msg, sensor_msgs::msg::MagneticField & ros_msg) { - convert_ign_to_ros(ign_msg.header(), ros_msg.header); - convert_ign_to_ros(ign_msg.field_tesla(), ros_msg.magnetic_field); + convert_gz_to_ros(gz_msg.header(), ros_msg.header); + convert_gz_to_ros(gz_msg.field_tesla(), ros_msg.magnetic_field); - // magnetic_field_covariance is not supported in Ignition::Msgs::Magnetometer. + // magnetic_field_covariance is not supported in Gazebo::Msgs::Magnetometer. } template<> void -convert_ros_to_ign( +convert_ros_to_gz( const sensor_msgs::msg::PointCloud2 & ros_msg, - ignition::msgs::PointCloudPacked & ign_msg) + ignition::msgs::PointCloudPacked & gz_msg) { - convert_ros_to_ign(ros_msg.header, (*ign_msg.mutable_header())); + convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header())); - ign_msg.set_height(ros_msg.height); - ign_msg.set_width(ros_msg.width); - ign_msg.set_is_bigendian(ros_msg.is_bigendian); - ign_msg.set_point_step(ros_msg.point_step); - ign_msg.set_row_step(ros_msg.row_step); - ign_msg.set_is_dense(ros_msg.is_dense); - ign_msg.mutable_data()->resize(ros_msg.data.size()); - memcpy(ign_msg.mutable_data()->data(), ros_msg.data.data(), ros_msg.data.size()); + gz_msg.set_height(ros_msg.height); + gz_msg.set_width(ros_msg.width); + gz_msg.set_is_bigendian(ros_msg.is_bigendian); + gz_msg.set_point_step(ros_msg.point_step); + gz_msg.set_row_step(ros_msg.row_step); + gz_msg.set_is_dense(ros_msg.is_dense); + gz_msg.mutable_data()->resize(ros_msg.data.size()); + memcpy(gz_msg.mutable_data()->data(), ros_msg.data.data(), ros_msg.data.size()); for (const auto & field : ros_msg.fields) { - ignition::msgs::PointCloudPacked::Field * pf = ign_msg.add_field(); + ignition::msgs::PointCloudPacked::Field * pf = gz_msg.add_field(); pf->set_name(field.name); pf->set_count(field.count); pf->set_offset(field.offset); @@ -470,27 +470,27 @@ convert_ros_to_ign( template<> void -convert_ign_to_ros( - const ignition::msgs::PointCloudPacked & ign_msg, +convert_gz_to_ros( + const ignition::msgs::PointCloudPacked & gz_msg, sensor_msgs::msg::PointCloud2 & ros_msg) { - convert_ign_to_ros(ign_msg.header(), ros_msg.header); - - ros_msg.height = ign_msg.height(); - ros_msg.width = ign_msg.width(); - ros_msg.is_bigendian = ign_msg.is_bigendian(); - ros_msg.point_step = ign_msg.point_step(); - ros_msg.row_step = ign_msg.row_step(); - ros_msg.is_dense = ign_msg.is_dense(); - ros_msg.data.resize(ign_msg.data().size()); - memcpy(ros_msg.data.data(), ign_msg.data().c_str(), ign_msg.data().size()); - - for (int i = 0; i < ign_msg.field_size(); ++i) { + convert_gz_to_ros(gz_msg.header(), ros_msg.header); + + ros_msg.height = gz_msg.height(); + ros_msg.width = gz_msg.width(); + ros_msg.is_bigendian = gz_msg.is_bigendian(); + ros_msg.point_step = gz_msg.point_step(); + ros_msg.row_step = gz_msg.row_step(); + ros_msg.is_dense = gz_msg.is_dense(); + ros_msg.data.resize(gz_msg.data().size()); + memcpy(ros_msg.data.data(), gz_msg.data().c_str(), gz_msg.data().size()); + + for (int i = 0; i < gz_msg.field_size(); ++i) { sensor_msgs::msg::PointField pf; - pf.name = ign_msg.field(i).name(); - pf.count = ign_msg.field(i).count(); - pf.offset = ign_msg.field(i).offset(); - switch (ign_msg.field(i).datatype()) { + pf.name = gz_msg.field(i).name(); + pf.count = gz_msg.field(i).count(); + pf.offset = gz_msg.field(i).offset(); + switch (gz_msg.field(i).datatype()) { default: case ignition::msgs::PointCloudPacked::Field::INT8: pf.datatype = sensor_msgs::msg::PointField::INT8; @@ -523,33 +523,33 @@ convert_ign_to_ros( template<> void -convert_ros_to_ign( +convert_ros_to_gz( const sensor_msgs::msg::BatteryState & ros_msg, - ignition::msgs::BatteryState & ign_msg) + ignition::msgs::BatteryState & gz_msg) { - convert_ros_to_ign(ros_msg.header, (*ign_msg.mutable_header())); + convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header())); - ign_msg.set_voltage(ros_msg.voltage); - ign_msg.set_current(ros_msg.current); - ign_msg.set_charge(ros_msg.charge); - ign_msg.set_capacity(ros_msg.capacity); - ign_msg.set_percentage(ros_msg.percentage); + gz_msg.set_voltage(ros_msg.voltage); + gz_msg.set_current(ros_msg.current); + gz_msg.set_charge(ros_msg.charge); + gz_msg.set_capacity(ros_msg.capacity); + gz_msg.set_percentage(ros_msg.percentage); switch (ros_msg.power_supply_status) { case sensor_msgs::msg::BatteryState::POWER_SUPPLY_STATUS_UNKNOWN: - ign_msg.set_power_supply_status(ignition::msgs::BatteryState::UNKNOWN); + gz_msg.set_power_supply_status(ignition::msgs::BatteryState::UNKNOWN); break; case sensor_msgs::msg::BatteryState::POWER_SUPPLY_STATUS_CHARGING: - ign_msg.set_power_supply_status(ignition::msgs::BatteryState::CHARGING); + gz_msg.set_power_supply_status(ignition::msgs::BatteryState::CHARGING); break; case sensor_msgs::msg::BatteryState::POWER_SUPPLY_STATUS_DISCHARGING: - ign_msg.set_power_supply_status(ignition::msgs::BatteryState::DISCHARGING); + gz_msg.set_power_supply_status(ignition::msgs::BatteryState::DISCHARGING); break; case sensor_msgs::msg::BatteryState::POWER_SUPPLY_STATUS_NOT_CHARGING: - ign_msg.set_power_supply_status(ignition::msgs::BatteryState::NOT_CHARGING); + gz_msg.set_power_supply_status(ignition::msgs::BatteryState::NOT_CHARGING); break; case sensor_msgs::msg::BatteryState::POWER_SUPPLY_STATUS_FULL: - ign_msg.set_power_supply_status(ignition::msgs::BatteryState::FULL); + gz_msg.set_power_supply_status(ignition::msgs::BatteryState::FULL); break; default: std::cerr << "Unsupported power supply status [" << ros_msg.power_supply_status << "]\n"; @@ -558,32 +558,32 @@ convert_ros_to_ign( template<> void -convert_ign_to_ros( - const ignition::msgs::BatteryState & ign_msg, +convert_gz_to_ros( + const ignition::msgs::BatteryState & gz_msg, sensor_msgs::msg::BatteryState & ros_msg) { - convert_ign_to_ros(ign_msg.header(), ros_msg.header); + convert_gz_to_ros(gz_msg.header(), ros_msg.header); - ros_msg.voltage = ign_msg.voltage(); - ros_msg.current = ign_msg.current(); - ros_msg.charge = ign_msg.charge(); - ros_msg.capacity = ign_msg.capacity(); + ros_msg.voltage = gz_msg.voltage(); + ros_msg.current = gz_msg.current(); + ros_msg.charge = gz_msg.charge(); + ros_msg.capacity = gz_msg.capacity(); ros_msg.design_capacity = std::numeric_limits::quiet_NaN(); - ros_msg.percentage = ign_msg.percentage(); + ros_msg.percentage = gz_msg.percentage(); - if (ign_msg.power_supply_status() == ignition::msgs::BatteryState::UNKNOWN) { + if (gz_msg.power_supply_status() == ignition::msgs::BatteryState::UNKNOWN) { ros_msg.power_supply_status = sensor_msgs::msg::BatteryState::POWER_SUPPLY_STATUS_UNKNOWN; - } else if (ign_msg.power_supply_status() == ignition::msgs::BatteryState::CHARGING) { + } else if (gz_msg.power_supply_status() == ignition::msgs::BatteryState::CHARGING) { ros_msg.power_supply_status = sensor_msgs::msg::BatteryState::POWER_SUPPLY_STATUS_CHARGING; - } else if (ign_msg.power_supply_status() == ignition::msgs::BatteryState::DISCHARGING) { + } else if (gz_msg.power_supply_status() == ignition::msgs::BatteryState::DISCHARGING) { ros_msg.power_supply_status = sensor_msgs::msg::BatteryState::POWER_SUPPLY_STATUS_DISCHARGING; - } else if (ign_msg.power_supply_status() == ignition::msgs::BatteryState::NOT_CHARGING) { + } else if (gz_msg.power_supply_status() == ignition::msgs::BatteryState::NOT_CHARGING) { ros_msg.power_supply_status = sensor_msgs::msg::BatteryState::POWER_SUPPLY_STATUS_NOT_CHARGING; - } else if (ign_msg.power_supply_status() == ignition::msgs::BatteryState::FULL) { + } else if (gz_msg.power_supply_status() == ignition::msgs::BatteryState::FULL) { ros_msg.power_supply_status = sensor_msgs::msg::BatteryState::POWER_SUPPLY_STATUS_FULL; } else { std::cerr << "Unsupported power supply status [" << - ign_msg.power_supply_status() << "]" << std::endl; + gz_msg.power_supply_status() << "]" << std::endl; } ros_msg.power_supply_health = sensor_msgs::msg::BatteryState::POWER_SUPPLY_HEALTH_UNKNOWN; @@ -592,4 +592,4 @@ convert_ign_to_ros( ros_msg.present = true; } -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge diff --git a/ros_gz_bridge/src/convert/std_msgs.cpp b/ros_gz_bridge/src/convert/std_msgs.cpp index 08923ea6..dcde74b3 100644 --- a/ros_gz_bridge/src/convert/std_msgs.cpp +++ b/ros_gz_bridge/src/convert/std_msgs.cpp @@ -13,57 +13,57 @@ // limitations under the License. #include "convert/utils.hpp" -#include "ros_ign_bridge/convert/builtin_interfaces.hpp" -#include "ros_ign_bridge/convert/std_msgs.hpp" +#include "ros_gz_bridge/convert/builtin_interfaces.hpp" +#include "ros_gz_bridge/convert/std_msgs.hpp" -namespace ros_ign_bridge +namespace ros_gz_bridge { template<> void -convert_ros_to_ign( +convert_ros_to_gz( const std_msgs::msg::Bool & ros_msg, - ignition::msgs::Boolean & ign_msg) + ignition::msgs::Boolean & gz_msg) { - ign_msg.set_data(ros_msg.data); + gz_msg.set_data(ros_msg.data); } template<> void -convert_ign_to_ros( - const ignition::msgs::Boolean & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Boolean & gz_msg, std_msgs::msg::Bool & ros_msg) { - ros_msg.data = ign_msg.data(); + ros_msg.data = gz_msg.data(); } template<> void -convert_ros_to_ign( +convert_ros_to_gz( const std_msgs::msg::ColorRGBA & ros_msg, - ignition::msgs::Color & ign_msg) + ignition::msgs::Color & gz_msg) { - ign_msg.set_r(ros_msg.r); - ign_msg.set_g(ros_msg.g); - ign_msg.set_b(ros_msg.b); - ign_msg.set_a(ros_msg.a); + gz_msg.set_r(ros_msg.r); + gz_msg.set_g(ros_msg.g); + gz_msg.set_b(ros_msg.b); + gz_msg.set_a(ros_msg.a); } template<> void -convert_ign_to_ros( - const ignition::msgs::Color & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Color & gz_msg, std_msgs::msg::ColorRGBA & ros_msg) { - ros_msg.r = ign_msg.r(); - ros_msg.g = ign_msg.g(); - ros_msg.b = ign_msg.b(); - ros_msg.a = ign_msg.a(); + ros_msg.r = gz_msg.r(); + ros_msg.g = gz_msg.g(); + ros_msg.b = gz_msg.b(); + ros_msg.a = gz_msg.a(); } template<> void -convert_ros_to_ign( +convert_ros_to_gz( const std_msgs::msg::Empty &, ignition::msgs::Empty &) { @@ -71,7 +71,7 @@ convert_ros_to_ign( template<> void -convert_ign_to_ros( +convert_gz_to_ros( const ignition::msgs::Empty &, std_msgs::msg::Empty &) { @@ -79,119 +79,119 @@ convert_ign_to_ros( template<> void -convert_ros_to_ign( +convert_ros_to_gz( const std_msgs::msg::UInt32 & ros_msg, - ignition::msgs::UInt32 & ign_msg) + ignition::msgs::UInt32 & gz_msg) { - ign_msg.set_data(ros_msg.data); + gz_msg.set_data(ros_msg.data); } template<> void -convert_ign_to_ros( - const ignition::msgs::UInt32 & ign_msg, +convert_gz_to_ros( + const ignition::msgs::UInt32 & gz_msg, std_msgs::msg::UInt32 & ros_msg) { - ros_msg.data = ign_msg.data(); + ros_msg.data = gz_msg.data(); } template<> void -convert_ros_to_ign( +convert_ros_to_gz( const std_msgs::msg::Float32 & ros_msg, - ignition::msgs::Float & ign_msg) + ignition::msgs::Float & gz_msg) { - ign_msg.set_data(ros_msg.data); + gz_msg.set_data(ros_msg.data); } template<> void -convert_ign_to_ros( - const ignition::msgs::Float & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Float & gz_msg, std_msgs::msg::Float32 & ros_msg) { - ros_msg.data = ign_msg.data(); + ros_msg.data = gz_msg.data(); } template<> void -convert_ros_to_ign( +convert_ros_to_gz( const std_msgs::msg::Float64 & ros_msg, - ignition::msgs::Double & ign_msg) + ignition::msgs::Double & gz_msg) { - ign_msg.set_data(ros_msg.data); + gz_msg.set_data(ros_msg.data); } template<> void -convert_ign_to_ros( - const ignition::msgs::Double & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Double & gz_msg, std_msgs::msg::Float64 & ros_msg) { - ros_msg.data = ign_msg.data(); + ros_msg.data = gz_msg.data(); } template<> void -convert_ros_to_ign( +convert_ros_to_gz( const std_msgs::msg::Header & ros_msg, - ignition::msgs::Header & ign_msg) + ignition::msgs::Header & gz_msg) { - convert_ros_to_ign(ros_msg.stamp, *ign_msg.mutable_stamp()); - auto newPair = ign_msg.add_data(); + convert_ros_to_gz(ros_msg.stamp, *gz_msg.mutable_stamp()); + auto newPair = gz_msg.add_data(); newPair->set_key("frame_id"); newPair->add_value(ros_msg.frame_id); } template<> void -convert_ros_to_ign( +convert_ros_to_gz( const std_msgs::msg::Int32 & ros_msg, - ignition::msgs::Int32 & ign_msg) + ignition::msgs::Int32 & gz_msg) { - ign_msg.set_data(ros_msg.data); + gz_msg.set_data(ros_msg.data); } template<> void -convert_ign_to_ros( - const ignition::msgs::Int32 & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Int32 & gz_msg, std_msgs::msg::Int32 & ros_msg) { - ros_msg.data = ign_msg.data(); + ros_msg.data = gz_msg.data(); } template<> void -convert_ign_to_ros( - const ignition::msgs::Header & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Header & gz_msg, std_msgs::msg::Header & ros_msg) { - convert_ign_to_ros(ign_msg.stamp(), ros_msg.stamp); - for (auto i = 0; i < ign_msg.data_size(); ++i) { - auto aPair = ign_msg.data(i); + convert_gz_to_ros(gz_msg.stamp(), ros_msg.stamp); + for (auto i = 0; i < gz_msg.data_size(); ++i) { + auto aPair = gz_msg.data(i); if (aPair.key() == "frame_id" && aPair.value_size() > 0) { - ros_msg.frame_id = frame_id_ign_to_ros(aPair.value(0)); + ros_msg.frame_id = frame_id_gz_to_ros(aPair.value(0)); } } } template<> void -convert_ros_to_ign( +convert_ros_to_gz( const std_msgs::msg::String & ros_msg, - ignition::msgs::StringMsg & ign_msg) + ignition::msgs::StringMsg & gz_msg) { - ign_msg.set_data(ros_msg.data); + gz_msg.set_data(ros_msg.data); } template<> void -convert_ign_to_ros( - const ignition::msgs::StringMsg & ign_msg, +convert_gz_to_ros( + const ignition::msgs::StringMsg & gz_msg, std_msgs::msg::String & ros_msg) { - ros_msg.data = ign_msg.data(); + ros_msg.data = gz_msg.data(); } -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge diff --git a/ros_gz_bridge/src/convert/tf2_msgs.cpp b/ros_gz_bridge/src/convert/tf2_msgs.cpp index 27992fd9..2a1b2142 100644 --- a/ros_gz_bridge/src/convert/tf2_msgs.cpp +++ b/ros_gz_bridge/src/convert/tf2_msgs.cpp @@ -13,42 +13,42 @@ // limitations under the License. #include "convert/utils.hpp" -#include "ros_ign_bridge/convert/tf2_msgs.hpp" +#include "ros_gz_bridge/convert/tf2_msgs.hpp" -namespace ros_ign_bridge +namespace ros_gz_bridge { template<> void -convert_ros_to_ign( +convert_ros_to_gz( const tf2_msgs::msg::TFMessage & ros_msg, - ignition::msgs::Pose_V & ign_msg) + ignition::msgs::Pose_V & gz_msg) { - ign_msg.clear_pose(); + gz_msg.clear_pose(); for (auto const & t : ros_msg.transforms) { - auto p = ign_msg.add_pose(); - convert_ros_to_ign(t, *p); + auto p = gz_msg.add_pose(); + convert_ros_to_gz(t, *p); } if (!ros_msg.transforms.empty()) { - convert_ros_to_ign( + convert_ros_to_gz( ros_msg.transforms[0].header, - (*ign_msg.mutable_header())); + (*gz_msg.mutable_header())); } } template<> void -convert_ign_to_ros( - const ignition::msgs::Pose_V & ign_msg, +convert_gz_to_ros( + const ignition::msgs::Pose_V & gz_msg, tf2_msgs::msg::TFMessage & ros_msg) { ros_msg.transforms.clear(); - for (auto const & p : ign_msg.pose()) { + for (auto const & p : gz_msg.pose()) { geometry_msgs::msg::TransformStamped tf; - convert_ign_to_ros(p, tf); + convert_gz_to_ros(p, tf); ros_msg.transforms.push_back(tf); } } -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge diff --git a/ros_gz_bridge/src/convert/trajectory_msgs.cpp b/ros_gz_bridge/src/convert/trajectory_msgs.cpp index 9c24cf3f..db877c2e 100644 --- a/ros_gz_bridge/src/convert/trajectory_msgs.cpp +++ b/ros_gz_bridge/src/convert/trajectory_msgs.cpp @@ -15,94 +15,94 @@ #include #include "convert/utils.hpp" -#include "ros_ign_bridge/convert/trajectory_msgs.hpp" +#include "ros_gz_bridge/convert/trajectory_msgs.hpp" -namespace ros_ign_bridge +namespace ros_gz_bridge { template<> void -convert_ros_to_ign( +convert_ros_to_gz( const trajectory_msgs::msg::JointTrajectoryPoint & ros_msg, - ignition::msgs::JointTrajectoryPoint & ign_msg) + ignition::msgs::JointTrajectoryPoint & gz_msg) { for (const auto & ros_position : ros_msg.positions) { - ign_msg.add_positions(ros_position); + gz_msg.add_positions(ros_position); } for (const auto & ros_velocity : ros_msg.velocities) { - ign_msg.add_velocities(ros_velocity); + gz_msg.add_velocities(ros_velocity); } for (const auto & ros_acceleration : ros_msg.accelerations) { - ign_msg.add_accelerations(ros_acceleration); + gz_msg.add_accelerations(ros_acceleration); } for (const auto & ros_effort : ros_msg.effort) { - ign_msg.add_effort(ros_effort); + gz_msg.add_effort(ros_effort); } - ignition::msgs::Duration * ign_duration = ign_msg.mutable_time_from_start(); - ign_duration->set_sec(ros_msg.time_from_start.sec); - ign_duration->set_nsec(ros_msg.time_from_start.nanosec); + ignition::msgs::Duration * gz_duration = gz_msg.mutable_time_from_start(); + gz_duration->set_sec(ros_msg.time_from_start.sec); + gz_duration->set_nsec(ros_msg.time_from_start.nanosec); } template<> void -convert_ign_to_ros( - const ignition::msgs::JointTrajectoryPoint & ign_msg, +convert_gz_to_ros( + const ignition::msgs::JointTrajectoryPoint & gz_msg, trajectory_msgs::msg::JointTrajectoryPoint & ros_msg) { - for (auto i = 0; i < ign_msg.positions_size(); ++i) { - ros_msg.positions.push_back(ign_msg.positions(i)); + for (auto i = 0; i < gz_msg.positions_size(); ++i) { + ros_msg.positions.push_back(gz_msg.positions(i)); } - for (auto i = 0; i < ign_msg.velocities_size(); ++i) { - ros_msg.velocities.push_back(ign_msg.velocities(i)); + for (auto i = 0; i < gz_msg.velocities_size(); ++i) { + ros_msg.velocities.push_back(gz_msg.velocities(i)); } - for (auto i = 0; i < ign_msg.accelerations_size(); ++i) { - ros_msg.accelerations.push_back(ign_msg.accelerations(i)); + for (auto i = 0; i < gz_msg.accelerations_size(); ++i) { + ros_msg.accelerations.push_back(gz_msg.accelerations(i)); } - for (auto i = 0; i < ign_msg.effort_size(); ++i) { - ros_msg.effort.push_back(ign_msg.effort(i)); + for (auto i = 0; i < gz_msg.effort_size(); ++i) { + ros_msg.effort.push_back(gz_msg.effort(i)); } ros_msg.time_from_start = rclcpp::Duration( - ign_msg.time_from_start().sec(), - ign_msg.time_from_start().nsec()); + gz_msg.time_from_start().sec(), + gz_msg.time_from_start().nsec()); } template<> void -convert_ros_to_ign( +convert_ros_to_gz( const trajectory_msgs::msg::JointTrajectory & ros_msg, - ignition::msgs::JointTrajectory & ign_msg) + ignition::msgs::JointTrajectory & gz_msg) { - convert_ros_to_ign(ros_msg.header, (*ign_msg.mutable_header())); + convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header())); for (const auto & ros_joint_name : ros_msg.joint_names) { - ign_msg.add_joint_names(ros_joint_name); + gz_msg.add_joint_names(ros_joint_name); } for (const auto & ros_point : ros_msg.points) { - ignition::msgs::JointTrajectoryPoint * ign_point = ign_msg.add_points(); - convert_ros_to_ign(ros_point, (*ign_point)); + ignition::msgs::JointTrajectoryPoint * gz_point = gz_msg.add_points(); + convert_ros_to_gz(ros_point, (*gz_point)); } } template<> void -convert_ign_to_ros( - const ignition::msgs::JointTrajectory & ign_msg, +convert_gz_to_ros( + const ignition::msgs::JointTrajectory & gz_msg, trajectory_msgs::msg::JointTrajectory & ros_msg) { - convert_ign_to_ros(ign_msg.header(), ros_msg.header); + convert_gz_to_ros(gz_msg.header(), ros_msg.header); - for (auto i = 0; i < ign_msg.joint_names_size(); ++i) { - ros_msg.joint_names.push_back(ign_msg.joint_names(i)); + for (auto i = 0; i < gz_msg.joint_names_size(); ++i) { + ros_msg.joint_names.push_back(gz_msg.joint_names(i)); } - for (auto i = 0; i < ign_msg.points_size(); ++i) { + for (auto i = 0; i < gz_msg.points_size(); ++i) { trajectory_msgs::msg::JointTrajectoryPoint ros_point; - convert_ign_to_ros(ign_msg.points(i), ros_point); + convert_gz_to_ros(gz_msg.points(i), ros_point); ros_msg.points.push_back(ros_point); } } -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge diff --git a/ros_gz_bridge/src/convert/utils.cpp b/ros_gz_bridge/src/convert/utils.cpp index 5bc889b8..89838389 100644 --- a/ros_gz_bridge/src/convert/utils.cpp +++ b/ros_gz_bridge/src/convert/utils.cpp @@ -16,7 +16,7 @@ #include -namespace ros_ign_bridge +namespace ros_gz_bridge { // This can be used to replace `::` with `/` to make frame_id compatible with TF @@ -44,9 +44,9 @@ std::string replace_delimiter( } -std::string frame_id_ign_to_ros(const std::string & frame_id) +std::string frame_id_gz_to_ros(const std::string & frame_id) { return replace_delimiter(frame_id, "::", "/"); } -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge diff --git a/ros_gz_bridge/src/convert/utils.hpp b/ros_gz_bridge/src/convert/utils.hpp index 955658d3..1d510004 100644 --- a/ros_gz_bridge/src/convert/utils.hpp +++ b/ros_gz_bridge/src/convert/utils.hpp @@ -17,7 +17,7 @@ #include -namespace ros_ign_bridge +namespace ros_gz_bridge { // This can be used to replace `::` with `/` to make frame_id compatible with TF @@ -26,8 +26,8 @@ std::string replace_delimiter( const std::string & old_delim, const std::string new_delim); -std::string frame_id_ign_to_ros(const std::string & frame_id); +std::string frame_id_gz_to_ros(const std::string & frame_id); -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge #endif // CONVERT__UTILS_HPP_ diff --git a/ros_gz_bridge/src/factories.cpp b/ros_gz_bridge/src/factories.cpp index 210c5824..c5cf0aeb 100644 --- a/ros_gz_bridge/src/factories.cpp +++ b/ros_gz_bridge/src/factories.cpp @@ -20,49 +20,49 @@ #include "factories/builtin_interfaces.hpp" #include "factories/geometry_msgs.hpp" #include "factories/nav_msgs.hpp" -#include "factories/ros_ign_interfaces.hpp" +#include "factories/ros_gz_interfaces.hpp" #include "factories/rosgraph_msgs.hpp" #include "factories/sensor_msgs.hpp" #include "factories/std_msgs.hpp" #include "factories/tf2_msgs.hpp" #include "factories/trajectory_msgs.hpp" -#include "service_factories/ros_ign_interfaces.hpp" +#include "service_factories/ros_gz_interfaces.hpp" -namespace ros_ign_bridge +namespace ros_gz_bridge { std::shared_ptr get_factory_impl( const std::string & ros_type_name, - const std::string & ign_type_name) + const std::string & gz_type_name) { std::shared_ptr impl; - impl = get_factory__builtin_interfaces(ros_type_name, ign_type_name); + impl = get_factory__builtin_interfaces(ros_type_name, gz_type_name); if (impl) {return impl;} - impl = get_factory__std_msgs(ros_type_name, ign_type_name); + impl = get_factory__std_msgs(ros_type_name, gz_type_name); if (impl) {return impl;} - impl = get_factory__geometry_msgs(ros_type_name, ign_type_name); + impl = get_factory__geometry_msgs(ros_type_name, gz_type_name); if (impl) {return impl;} - impl = get_factory__nav_msgs(ros_type_name, ign_type_name); + impl = get_factory__nav_msgs(ros_type_name, gz_type_name); if (impl) {return impl;} - impl = get_factory__ros_ign_interfaces(ros_type_name, ign_type_name); + impl = get_factory__ros_gz_interfaces(ros_type_name, gz_type_name); if (impl) {return impl;} - impl = get_factory__rosgraph_msgs(ros_type_name, ign_type_name); + impl = get_factory__rosgraph_msgs(ros_type_name, gz_type_name); if (impl) {return impl;} - impl = get_factory__sensor_msgs(ros_type_name, ign_type_name); + impl = get_factory__sensor_msgs(ros_type_name, gz_type_name); if (impl) {return impl;} - impl = get_factory__tf2_msgs(ros_type_name, ign_type_name); + impl = get_factory__tf2_msgs(ros_type_name, gz_type_name); if (impl) {return impl;} - impl = get_factory__trajectory_msgs(ros_type_name, ign_type_name); + impl = get_factory__trajectory_msgs(ros_type_name, gz_type_name); if (impl) {return impl;} return nullptr; @@ -71,10 +71,10 @@ get_factory_impl( std::shared_ptr get_factory( const std::string & ros_type_name, - const std::string & ign_type_name) + const std::string & gz_type_name) { std::shared_ptr factory; - factory = get_factory_impl(ros_type_name, ign_type_name); + factory = get_factory_impl(ros_type_name, gz_type_name); if (factory) { return factory; } @@ -85,20 +85,20 @@ get_factory( std::shared_ptr get_service_factory( const std::string & ros_type_name, - const std::string & ign_req_type_name, - const std::string & ign_rep_type_name) + const std::string & gz_req_type_name, + const std::string & gz_rep_type_name) { std::shared_ptr impl; - impl = get_service_factory__ros_ign_interfaces( - ros_type_name, ign_req_type_name, ign_rep_type_name); + impl = get_service_factory__ros_gz_interfaces( + ros_type_name, gz_req_type_name, gz_rep_type_name); if (impl) {return impl;} std::ostringstream oss{"No template specialization for the specified service type {"}; - oss << ros_type_name << "}, ign request type {" << ign_req_type_name - << "}, ign request type {" << ign_req_type_name << "}, ign reply type name {" - << ign_rep_type_name << "}"; + oss << ros_type_name << "}, gz request type {" << gz_req_type_name + << "}, gz request type {" << gz_req_type_name << "}, gz reply type name {" + << gz_rep_type_name << "}"; throw std::runtime_error(oss.str()); } -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge diff --git a/ros_gz_bridge/src/factories.hpp b/ros_gz_bridge/src/factories.hpp index 105b09eb..f6f6b5c4 100644 --- a/ros_gz_bridge/src/factories.hpp +++ b/ros_gz_bridge/src/factories.hpp @@ -21,20 +21,20 @@ #include "factory_interface.hpp" #include "service_factory_interface.hpp" -namespace ros_ign_bridge +namespace ros_gz_bridge { std::shared_ptr get_factory( const std::string & ros_type_name, - const std::string & ign_type_name); + const std::string & gz_type_name); std::shared_ptr get_service_factory( const std::string & ros_type_name, - const std::string & ign_req_type_name, - const std::string & ign_rep_type_name); + const std::string & gz_req_type_name, + const std::string & gz_rep_type_name); -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge #endif // FACTORIES_HPP_ diff --git a/ros_gz_bridge/src/factories/builtin_interfaces.cpp b/ros_gz_bridge/src/factories/builtin_interfaces.cpp index 20336cfa..40334b64 100644 --- a/ros_gz_bridge/src/factories/builtin_interfaces.cpp +++ b/ros_gz_bridge/src/factories/builtin_interfaces.cpp @@ -18,26 +18,26 @@ #include #include "factory.hpp" -#include "ros_ign_bridge/convert/builtin_interfaces.hpp" +#include "ros_gz_bridge/convert/builtin_interfaces.hpp" -namespace ros_ign_bridge +namespace ros_gz_bridge { std::shared_ptr get_factory__builtin_interfaces( const std::string & ros_type_name, - const std::string & ign_type_name) + const std::string & gz_type_name) { if ( (ros_type_name == "builtin_interfaces/msg/Time" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.Time") + gz_type_name == "ignition.msgs.Time") { return std::make_shared< Factory< builtin_interfaces::msg::Time, ignition::msgs::Time > - >("builtin_interfaces/msg/Time", ign_type_name); + >("builtin_interfaces/msg/Time", gz_type_name); } return nullptr; } @@ -47,11 +47,11 @@ void Factory< builtin_interfaces::msg::Time, ignition::msgs::Time ->::convert_ros_to_ign( +>::convert_ros_to_gz( const builtin_interfaces::msg::Time & ros_msg, - ignition::msgs::Time & ign_msg) + ignition::msgs::Time & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> @@ -59,10 +59,10 @@ void Factory< builtin_interfaces::msg::Time, ignition::msgs::Time ->::convert_ign_to_ros( - const ignition::msgs::Time & ign_msg, +>::convert_gz_to_ros( + const ignition::msgs::Time & gz_msg, builtin_interfaces::msg::Time & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge diff --git a/ros_gz_bridge/src/factories/builtin_interfaces.hpp b/ros_gz_bridge/src/factories/builtin_interfaces.hpp index bd98ad61..7f741594 100644 --- a/ros_gz_bridge/src/factories/builtin_interfaces.hpp +++ b/ros_gz_bridge/src/factories/builtin_interfaces.hpp @@ -20,14 +20,14 @@ #include "factory_interface.hpp" -namespace ros_ign_bridge +namespace ros_gz_bridge { std::shared_ptr get_factory__builtin_interfaces( const std::string & ros_type_name, - const std::string & ign_type_name); + const std::string & gz_type_name); -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge #endif // FACTORIES__BUILTIN_INTERFACES_HPP_ diff --git a/ros_gz_bridge/src/factories/geometry_msgs.cpp b/ros_gz_bridge/src/factories/geometry_msgs.cpp index 48d7887a..bad30459 100644 --- a/ros_gz_bridge/src/factories/geometry_msgs.cpp +++ b/ros_gz_bridge/src/factories/geometry_msgs.cpp @@ -18,128 +18,128 @@ #include #include "factory.hpp" -#include "ros_ign_bridge/convert/geometry_msgs.hpp" +#include "ros_gz_bridge/convert/geometry_msgs.hpp" -namespace ros_ign_bridge +namespace ros_gz_bridge { std::shared_ptr get_factory__geometry_msgs( const std::string & ros_type_name, - const std::string & ign_type_name) + const std::string & gz_type_name) { if ((ros_type_name == "geometry_msgs/msg/Quaternion" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.Quaternion") + gz_type_name == "ignition.msgs.Quaternion") { return std::make_shared< Factory< geometry_msgs::msg::Quaternion, ignition::msgs::Quaternion > - >("geometry_msgs/msg/Quaternion", ign_type_name); + >("geometry_msgs/msg/Quaternion", gz_type_name); } if ((ros_type_name == "geometry_msgs/msg/Vector3" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.Vector3d") + gz_type_name == "ignition.msgs.Vector3d") { return std::make_shared< Factory< geometry_msgs::msg::Vector3, ignition::msgs::Vector3d > - >("geometry_msgs/msg/Vector3", ign_type_name); + >("geometry_msgs/msg/Vector3", gz_type_name); } if ((ros_type_name == "geometry_msgs/msg/Point" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.Vector3d") + gz_type_name == "ignition.msgs.Vector3d") { return std::make_shared< Factory< geometry_msgs::msg::Point, ignition::msgs::Vector3d > - >("geometry_msgs/msg/Point", ign_type_name); + >("geometry_msgs/msg/Point", gz_type_name); } if ((ros_type_name == "geometry_msgs/msg/Pose" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.Pose") + gz_type_name == "ignition.msgs.Pose") { return std::make_shared< Factory< geometry_msgs::msg::Pose, ignition::msgs::Pose > - >("geometry_msgs/msg/Pose", ign_type_name); + >("geometry_msgs/msg/Pose", gz_type_name); } if ((ros_type_name == "geometry_msgs/msg/PoseWithCovariance" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.PoseWithCovariance") + gz_type_name == "ignition.msgs.PoseWithCovariance") { return std::make_shared< Factory< geometry_msgs::msg::PoseWithCovariance, ignition::msgs::PoseWithCovariance > - >("geometry_msgs/msg/PoseWithCovariance", ign_type_name); + >("geometry_msgs/msg/PoseWithCovariance", gz_type_name); } if ((ros_type_name == "geometry_msgs/msg/PoseStamped" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.Pose") + gz_type_name == "ignition.msgs.Pose") { return std::make_shared< Factory< geometry_msgs::msg::PoseStamped, ignition::msgs::Pose > - >("geometry_msgs/msg/PoseStamped", ign_type_name); + >("geometry_msgs/msg/PoseStamped", gz_type_name); } if ((ros_type_name == "geometry_msgs/msg/Transform" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.Pose") + gz_type_name == "ignition.msgs.Pose") { return std::make_shared< Factory< geometry_msgs::msg::Transform, ignition::msgs::Pose > - >("geometry_msgs/msg/Transform", ign_type_name); + >("geometry_msgs/msg/Transform", gz_type_name); } if ((ros_type_name == "geometry_msgs/msg/TransformStamped" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.Pose") + gz_type_name == "ignition.msgs.Pose") { return std::make_shared< Factory< geometry_msgs::msg::TransformStamped, ignition::msgs::Pose > - >("geometry_msgs/msg/TransformStamped", ign_type_name); + >("geometry_msgs/msg/TransformStamped", gz_type_name); } if ( (ros_type_name == "geometry_msgs/msg/Twist" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.Twist") + gz_type_name == "ignition.msgs.Twist") { return std::make_shared< Factory< geometry_msgs::msg::Twist, ignition::msgs::Twist > - >("geometry_msgs/msg/Twist", ign_type_name); + >("geometry_msgs/msg/Twist", gz_type_name); } if ( (ros_type_name == "geometry_msgs/msg/TwistWithCovariance" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.TwistWithCovariance") + gz_type_name == "ignition.msgs.TwistWithCovariance") { return std::make_shared< Factory< geometry_msgs::msg::TwistWithCovariance, ignition::msgs::TwistWithCovariance > - >("geometry_msgs/msg/TwistWithCovariance", ign_type_name); + >("geometry_msgs/msg/TwistWithCovariance", gz_type_name); } if ( (ros_type_name == "geometry_msgs/msg/Wrench" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.Wrench") + gz_type_name == "ignition.msgs.Wrench") { return std::make_shared< Factory< geometry_msgs::msg::Wrench, ignition::msgs::Wrench > - >("geometry_msgs/msg/Wrench", ign_type_name); + >("geometry_msgs/msg/Wrench", gz_type_name); } return nullptr; } @@ -149,11 +149,11 @@ void Factory< geometry_msgs::msg::Quaternion, ignition::msgs::Quaternion ->::convert_ros_to_ign( +>::convert_ros_to_gz( const geometry_msgs::msg::Quaternion & ros_msg, - ignition::msgs::Quaternion & ign_msg) + ignition::msgs::Quaternion & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> @@ -161,11 +161,11 @@ void Factory< geometry_msgs::msg::Quaternion, ignition::msgs::Quaternion ->::convert_ign_to_ros( - const ignition::msgs::Quaternion & ign_msg, +>::convert_gz_to_ros( + const ignition::msgs::Quaternion & gz_msg, geometry_msgs::msg::Quaternion & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } template<> @@ -173,11 +173,11 @@ void Factory< geometry_msgs::msg::Vector3, ignition::msgs::Vector3d ->::convert_ros_to_ign( +>::convert_ros_to_gz( const geometry_msgs::msg::Vector3 & ros_msg, - ignition::msgs::Vector3d & ign_msg) + ignition::msgs::Vector3d & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> @@ -185,11 +185,11 @@ void Factory< geometry_msgs::msg::Vector3, ignition::msgs::Vector3d ->::convert_ign_to_ros( - const ignition::msgs::Vector3d & ign_msg, +>::convert_gz_to_ros( + const ignition::msgs::Vector3d & gz_msg, geometry_msgs::msg::Vector3 & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } template<> @@ -197,11 +197,11 @@ void Factory< geometry_msgs::msg::Point, ignition::msgs::Vector3d ->::convert_ros_to_ign( +>::convert_ros_to_gz( const geometry_msgs::msg::Point & ros_msg, - ignition::msgs::Vector3d & ign_msg) + ignition::msgs::Vector3d & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> @@ -209,11 +209,11 @@ void Factory< geometry_msgs::msg::Point, ignition::msgs::Vector3d ->::convert_ign_to_ros( - const ignition::msgs::Vector3d & ign_msg, +>::convert_gz_to_ros( + const ignition::msgs::Vector3d & gz_msg, geometry_msgs::msg::Point & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } template<> @@ -221,11 +221,11 @@ void Factory< geometry_msgs::msg::Pose, ignition::msgs::Pose ->::convert_ros_to_ign( +>::convert_ros_to_gz( const geometry_msgs::msg::Pose & ros_msg, - ignition::msgs::Pose & ign_msg) + ignition::msgs::Pose & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> @@ -233,11 +233,11 @@ void Factory< geometry_msgs::msg::Pose, ignition::msgs::Pose ->::convert_ign_to_ros( - const ignition::msgs::Pose & ign_msg, +>::convert_gz_to_ros( + const ignition::msgs::Pose & gz_msg, geometry_msgs::msg::Pose & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } template<> @@ -245,11 +245,11 @@ void Factory< geometry_msgs::msg::PoseWithCovariance, ignition::msgs::PoseWithCovariance ->::convert_ros_to_ign( +>::convert_ros_to_gz( const geometry_msgs::msg::PoseWithCovariance & ros_msg, - ignition::msgs::PoseWithCovariance & ign_msg) + ignition::msgs::PoseWithCovariance & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> @@ -257,11 +257,11 @@ void Factory< geometry_msgs::msg::PoseWithCovariance, ignition::msgs::PoseWithCovariance ->::convert_ign_to_ros( - const ignition::msgs::PoseWithCovariance & ign_msg, +>::convert_gz_to_ros( + const ignition::msgs::PoseWithCovariance & gz_msg, geometry_msgs::msg::PoseWithCovariance & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } template<> @@ -269,11 +269,11 @@ void Factory< geometry_msgs::msg::PoseStamped, ignition::msgs::Pose ->::convert_ros_to_ign( +>::convert_ros_to_gz( const geometry_msgs::msg::PoseStamped & ros_msg, - ignition::msgs::Pose & ign_msg) + ignition::msgs::Pose & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> @@ -281,11 +281,11 @@ void Factory< geometry_msgs::msg::PoseStamped, ignition::msgs::Pose ->::convert_ign_to_ros( - const ignition::msgs::Pose & ign_msg, +>::convert_gz_to_ros( + const ignition::msgs::Pose & gz_msg, geometry_msgs::msg::PoseStamped & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } template<> @@ -293,11 +293,11 @@ void Factory< geometry_msgs::msg::Transform, ignition::msgs::Pose ->::convert_ros_to_ign( +>::convert_ros_to_gz( const geometry_msgs::msg::Transform & ros_msg, - ignition::msgs::Pose & ign_msg) + ignition::msgs::Pose & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> @@ -305,11 +305,11 @@ void Factory< geometry_msgs::msg::Transform, ignition::msgs::Pose ->::convert_ign_to_ros( - const ignition::msgs::Pose & ign_msg, +>::convert_gz_to_ros( + const ignition::msgs::Pose & gz_msg, geometry_msgs::msg::Transform & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } template<> @@ -317,11 +317,11 @@ void Factory< geometry_msgs::msg::TransformStamped, ignition::msgs::Pose ->::convert_ros_to_ign( +>::convert_ros_to_gz( const geometry_msgs::msg::TransformStamped & ros_msg, - ignition::msgs::Pose & ign_msg) + ignition::msgs::Pose & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> @@ -329,11 +329,11 @@ void Factory< geometry_msgs::msg::TransformStamped, ignition::msgs::Pose ->::convert_ign_to_ros( - const ignition::msgs::Pose & ign_msg, +>::convert_gz_to_ros( + const ignition::msgs::Pose & gz_msg, geometry_msgs::msg::TransformStamped & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } template<> @@ -341,11 +341,11 @@ void Factory< geometry_msgs::msg::Twist, ignition::msgs::Twist ->::convert_ros_to_ign( +>::convert_ros_to_gz( const geometry_msgs::msg::Twist & ros_msg, - ignition::msgs::Twist & ign_msg) + ignition::msgs::Twist & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> @@ -353,11 +353,11 @@ void Factory< geometry_msgs::msg::Twist, ignition::msgs::Twist ->::convert_ign_to_ros( - const ignition::msgs::Twist & ign_msg, +>::convert_gz_to_ros( + const ignition::msgs::Twist & gz_msg, geometry_msgs::msg::Twist & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } template<> @@ -365,11 +365,11 @@ void Factory< geometry_msgs::msg::TwistWithCovariance, ignition::msgs::TwistWithCovariance ->::convert_ros_to_ign( +>::convert_ros_to_gz( const geometry_msgs::msg::TwistWithCovariance & ros_msg, - ignition::msgs::TwistWithCovariance & ign_msg) + ignition::msgs::TwistWithCovariance & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> @@ -377,11 +377,11 @@ void Factory< geometry_msgs::msg::TwistWithCovariance, ignition::msgs::TwistWithCovariance ->::convert_ign_to_ros( - const ignition::msgs::TwistWithCovariance & ign_msg, +>::convert_gz_to_ros( + const ignition::msgs::TwistWithCovariance & gz_msg, geometry_msgs::msg::TwistWithCovariance & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } template<> @@ -389,11 +389,11 @@ void Factory< geometry_msgs::msg::Wrench, ignition::msgs::Wrench ->::convert_ros_to_ign( +>::convert_ros_to_gz( const geometry_msgs::msg::Wrench & ros_msg, - ignition::msgs::Wrench & ign_msg) + ignition::msgs::Wrench & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> @@ -401,11 +401,11 @@ void Factory< geometry_msgs::msg::Wrench, ignition::msgs::Wrench ->::convert_ign_to_ros( - const ignition::msgs::Wrench & ign_msg, +>::convert_gz_to_ros( + const ignition::msgs::Wrench & gz_msg, geometry_msgs::msg::Wrench & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge diff --git a/ros_gz_bridge/src/factories/geometry_msgs.hpp b/ros_gz_bridge/src/factories/geometry_msgs.hpp index f47f2651..19eaee55 100644 --- a/ros_gz_bridge/src/factories/geometry_msgs.hpp +++ b/ros_gz_bridge/src/factories/geometry_msgs.hpp @@ -20,14 +20,14 @@ #include "factory_interface.hpp" -namespace ros_ign_bridge +namespace ros_gz_bridge { std::shared_ptr get_factory__geometry_msgs( const std::string & ros_type_name, - const std::string & ign_type_name); + const std::string & gz_type_name); -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge #endif // FACTORIES__GEOMETRY_MSGS_HPP_ diff --git a/ros_gz_bridge/src/factories/nav_msgs.cpp b/ros_gz_bridge/src/factories/nav_msgs.cpp index f6845c8d..62ab0f2b 100644 --- a/ros_gz_bridge/src/factories/nav_msgs.cpp +++ b/ros_gz_bridge/src/factories/nav_msgs.cpp @@ -18,35 +18,35 @@ #include #include "factory.hpp" -#include "ros_ign_bridge/convert/nav_msgs.hpp" +#include "ros_gz_bridge/convert/nav_msgs.hpp" -namespace ros_ign_bridge +namespace ros_gz_bridge { std::shared_ptr get_factory__nav_msgs( const std::string & ros_type_name, - const std::string & ign_type_name) + const std::string & gz_type_name) { if ((ros_type_name == "nav_msgs/msg/Odometry" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.Odometry") + gz_type_name == "ignition.msgs.Odometry") { return std::make_shared< Factory< nav_msgs::msg::Odometry, ignition::msgs::Odometry > - >("nav_msgs/msg/Odometry", ign_type_name); + >("nav_msgs/msg/Odometry", gz_type_name); } if ((ros_type_name == "nav_msgs/msg/Odometry" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.OdometryWithCovariance") + gz_type_name == "ignition.msgs.OdometryWithCovariance") { return std::make_shared< Factory< nav_msgs::msg::Odometry, ignition::msgs::OdometryWithCovariance > - >("nav_msgs/msg/Odometry", ign_type_name); + >("nav_msgs/msg/Odometry", gz_type_name); } return nullptr; } @@ -56,11 +56,11 @@ void Factory< nav_msgs::msg::Odometry, ignition::msgs::Odometry ->::convert_ros_to_ign( +>::convert_ros_to_gz( const nav_msgs::msg::Odometry & ros_msg, - ignition::msgs::Odometry & ign_msg) + ignition::msgs::Odometry & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> @@ -68,11 +68,11 @@ void Factory< nav_msgs::msg::Odometry, ignition::msgs::Odometry ->::convert_ign_to_ros( - const ignition::msgs::Odometry & ign_msg, +>::convert_gz_to_ros( + const ignition::msgs::Odometry & gz_msg, nav_msgs::msg::Odometry & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } template<> @@ -80,11 +80,11 @@ void Factory< nav_msgs::msg::Odometry, ignition::msgs::OdometryWithCovariance ->::convert_ros_to_ign( +>::convert_ros_to_gz( const nav_msgs::msg::Odometry & ros_msg, - ignition::msgs::OdometryWithCovariance & ign_msg) + ignition::msgs::OdometryWithCovariance & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> @@ -92,11 +92,11 @@ void Factory< nav_msgs::msg::Odometry, ignition::msgs::OdometryWithCovariance ->::convert_ign_to_ros( - const ignition::msgs::OdometryWithCovariance & ign_msg, +>::convert_gz_to_ros( + const ignition::msgs::OdometryWithCovariance & gz_msg, nav_msgs::msg::Odometry & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge diff --git a/ros_gz_bridge/src/factories/nav_msgs.hpp b/ros_gz_bridge/src/factories/nav_msgs.hpp index ad5ab4aa..318c7287 100644 --- a/ros_gz_bridge/src/factories/nav_msgs.hpp +++ b/ros_gz_bridge/src/factories/nav_msgs.hpp @@ -20,14 +20,14 @@ #include "factory_interface.hpp" -namespace ros_ign_bridge +namespace ros_gz_bridge { std::shared_ptr get_factory__nav_msgs( const std::string & ros_type_name, - const std::string & ign_type_name); + const std::string & gz_type_name); -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge #endif // FACTORIES__NAV_MSGS_HPP_ diff --git a/ros_gz_bridge/src/factories/ros_gz_interfaces.cpp b/ros_gz_bridge/src/factories/ros_gz_interfaces.cpp index 62893892..5f1fe185 100644 --- a/ros_gz_bridge/src/factories/ros_gz_interfaces.cpp +++ b/ros_gz_bridge/src/factories/ros_gz_interfaces.cpp @@ -12,125 +12,125 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "factories/ros_ign_interfaces.hpp" +#include "factories/ros_gz_interfaces.hpp" #include #include #include "factory.hpp" -#include "ros_ign_bridge/convert/ros_ign_interfaces.hpp" +#include "ros_gz_bridge/convert/ros_gz_interfaces.hpp" -namespace ros_ign_bridge +namespace ros_gz_bridge { std::shared_ptr -get_factory__ros_ign_interfaces( +get_factory__ros_gz_interfaces( const std::string & ros_type_name, - const std::string & ign_type_name) + const std::string & gz_type_name) { if ( - (ros_type_name == "ros_ign_interfaces/msg/JointWrench" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.JointWrench") + (ros_type_name == "ros_gz_interfaces/msg/JointWrench" || ros_type_name.empty()) && + gz_type_name == "ignition.msgs.JointWrench") { return std::make_shared< Factory< - ros_ign_interfaces::msg::JointWrench, + ros_gz_interfaces::msg::JointWrench, ignition::msgs::JointWrench > - >("ros_ign_interfaces/msg/JointWrench", ign_type_name); + >("ros_gz_interfaces/msg/JointWrench", gz_type_name); } if ( - (ros_type_name == "ros_ign_interfaces/msg/Entity" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.Entity") + (ros_type_name == "ros_gz_interfaces/msg/Entity" || ros_type_name.empty()) && + gz_type_name == "ignition.msgs.Entity") { return std::make_shared< Factory< - ros_ign_interfaces::msg::Entity, + ros_gz_interfaces::msg::Entity, ignition::msgs::Entity > - >("ros_ign_interfaces/msg/Entity", ign_type_name); + >("ros_gz_interfaces/msg/Entity", gz_type_name); } if ( - (ros_type_name == "ros_ign_interfaces/msg/Contact" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.Contact") + (ros_type_name == "ros_gz_interfaces/msg/Contact" || ros_type_name.empty()) && + gz_type_name == "ignition.msgs.Contact") { return std::make_shared< Factory< - ros_ign_interfaces::msg::Contact, + ros_gz_interfaces::msg::Contact, ignition::msgs::Contact > - >("ros_ign_interfaces/msg/Contact", ign_type_name); + >("ros_gz_interfaces/msg/Contact", gz_type_name); } if ( - (ros_type_name == "ros_ign_interfaces/msg/Contacts" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.Contacts") + (ros_type_name == "ros_gz_interfaces/msg/Contacts" || ros_type_name.empty()) && + gz_type_name == "ignition.msgs.Contacts") { return std::make_shared< Factory< - ros_ign_interfaces::msg::Contacts, + ros_gz_interfaces::msg::Contacts, ignition::msgs::Contacts > - >("ros_ign_interfaces/msg/Contacts", ign_type_name); + >("ros_gz_interfaces/msg/Contacts", gz_type_name); } - if ((ros_type_name == "ros_ign_interfaces/msg/GuiCamera" || - ros_type_name.empty()) && ign_type_name == "ignition.msgs.GUICamera") + if ((ros_type_name == "ros_gz_interfaces/msg/GuiCamera" || + ros_type_name.empty()) && gz_type_name == "ignition.msgs.GUICamera") { return std::make_shared< Factory< - ros_ign_interfaces::msg::GuiCamera, + ros_gz_interfaces::msg::GuiCamera, ignition::msgs::GUICamera > - >("ros_ign_interfaces/msg/GuiCamera", ign_type_name); + >("ros_gz_interfaces/msg/GuiCamera", gz_type_name); } - if ((ros_type_name == "ros_ign_interfaces/msg/Light" || - ros_type_name.empty()) && ign_type_name == "ignition.msgs.Light") + if ((ros_type_name == "ros_gz_interfaces/msg/Light" || + ros_type_name.empty()) && gz_type_name == "ignition.msgs.Light") { return std::make_shared< Factory< - ros_ign_interfaces::msg::Light, + ros_gz_interfaces::msg::Light, ignition::msgs::Light > - >("ros_ign_interfaces/msg/Light", ign_type_name); + >("ros_gz_interfaces/msg/Light", gz_type_name); } - if ((ros_type_name == "ros_ign_interfaces/msg/StringVec" || - ros_type_name.empty()) && ign_type_name == "ignition.msgs.StringMsg_V") + if ((ros_type_name == "ros_gz_interfaces/msg/StringVec" || + ros_type_name.empty()) && gz_type_name == "ignition.msgs.StringMsg_V") { return std::make_shared< Factory< - ros_ign_interfaces::msg::StringVec, + ros_gz_interfaces::msg::StringVec, ignition::msgs::StringMsg_V > - >("ros_ign_interfaces/msg/StringVec", ign_type_name); + >("ros_gz_interfaces/msg/StringVec", gz_type_name); } - if ((ros_type_name == "ros_ign_interfaces/msg/TrackVisual" || - ros_type_name.empty()) && ign_type_name == "ignition.msgs.TrackVisual") + if ((ros_type_name == "ros_gz_interfaces/msg/TrackVisual" || + ros_type_name.empty()) && gz_type_name == "ignition.msgs.TrackVisual") { return std::make_shared< Factory< - ros_ign_interfaces::msg::TrackVisual, + ros_gz_interfaces::msg::TrackVisual, ignition::msgs::TrackVisual > - >("ros_ign_interfaces/msg/TrackVisual", ign_type_name); + >("ros_gz_interfaces/msg/TrackVisual", gz_type_name); } - if ((ros_type_name == "ros_ign_interfaces/msg/VideoRecord" || - ros_type_name.empty()) && ign_type_name == "ignition.msgs.VideoRecord") + if ((ros_type_name == "ros_gz_interfaces/msg/VideoRecord" || + ros_type_name.empty()) && gz_type_name == "ignition.msgs.VideoRecord") { return std::make_shared< Factory< - ros_ign_interfaces::msg::VideoRecord, + ros_gz_interfaces::msg::VideoRecord, ignition::msgs::VideoRecord > - >("ros_ign_interfaces/msg/VideoRecord", ign_type_name); + >("ros_gz_interfaces/msg/VideoRecord", gz_type_name); } - if ((ros_type_name == "ros_ign_interfaces/msg/WorldControl" || - ros_type_name.empty()) && ign_type_name == "ignition.msgs.WorldControl") + if ((ros_type_name == "ros_gz_interfaces/msg/WorldControl" || + ros_type_name.empty()) && gz_type_name == "ignition.msgs.WorldControl") { return std::make_shared< Factory< - ros_ign_interfaces::msg::WorldControl, + ros_gz_interfaces::msg::WorldControl, ignition::msgs::WorldControl > - >("ros_ign_interfaces/msg/WorldControl", ign_type_name); + >("ros_gz_interfaces/msg/WorldControl", gz_type_name); } return nullptr; } @@ -138,240 +138,240 @@ get_factory__ros_ign_interfaces( template<> void Factory< - ros_ign_interfaces::msg::JointWrench, + ros_gz_interfaces::msg::JointWrench, ignition::msgs::JointWrench ->::convert_ros_to_ign( - const ros_ign_interfaces::msg::JointWrench & ros_msg, - ignition::msgs::JointWrench & ign_msg) +>::convert_ros_to_gz( + const ros_gz_interfaces::msg::JointWrench & ros_msg, + ignition::msgs::JointWrench & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> void Factory< - ros_ign_interfaces::msg::JointWrench, + ros_gz_interfaces::msg::JointWrench, ignition::msgs::JointWrench ->::convert_ign_to_ros( - const ignition::msgs::JointWrench & ign_msg, - ros_ign_interfaces::msg::JointWrench & ros_msg) +>::convert_gz_to_ros( + const ignition::msgs::JointWrench & gz_msg, + ros_gz_interfaces::msg::JointWrench & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } template<> void Factory< - ros_ign_interfaces::msg::Entity, + ros_gz_interfaces::msg::Entity, ignition::msgs::Entity ->::convert_ros_to_ign( - const ros_ign_interfaces::msg::Entity & ros_msg, - ignition::msgs::Entity & ign_msg) +>::convert_ros_to_gz( + const ros_gz_interfaces::msg::Entity & ros_msg, + ignition::msgs::Entity & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> void Factory< - ros_ign_interfaces::msg::Entity, + ros_gz_interfaces::msg::Entity, ignition::msgs::Entity ->::convert_ign_to_ros( - const ignition::msgs::Entity & ign_msg, - ros_ign_interfaces::msg::Entity & ros_msg) +>::convert_gz_to_ros( + const ignition::msgs::Entity & gz_msg, + ros_gz_interfaces::msg::Entity & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } template<> void Factory< - ros_ign_interfaces::msg::Contact, + ros_gz_interfaces::msg::Contact, ignition::msgs::Contact ->::convert_ros_to_ign( - const ros_ign_interfaces::msg::Contact & ros_msg, - ignition::msgs::Contact & ign_msg) +>::convert_ros_to_gz( + const ros_gz_interfaces::msg::Contact & ros_msg, + ignition::msgs::Contact & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> void Factory< - ros_ign_interfaces::msg::Contact, + ros_gz_interfaces::msg::Contact, ignition::msgs::Contact ->::convert_ign_to_ros( - const ignition::msgs::Contact & ign_msg, - ros_ign_interfaces::msg::Contact & ros_msg) +>::convert_gz_to_ros( + const ignition::msgs::Contact & gz_msg, + ros_gz_interfaces::msg::Contact & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } template<> void Factory< - ros_ign_interfaces::msg::Contacts, + ros_gz_interfaces::msg::Contacts, ignition::msgs::Contacts ->::convert_ros_to_ign( - const ros_ign_interfaces::msg::Contacts & ros_msg, - ignition::msgs::Contacts & ign_msg) +>::convert_ros_to_gz( + const ros_gz_interfaces::msg::Contacts & ros_msg, + ignition::msgs::Contacts & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> void Factory< - ros_ign_interfaces::msg::Contacts, + ros_gz_interfaces::msg::Contacts, ignition::msgs::Contacts ->::convert_ign_to_ros( - const ignition::msgs::Contacts & ign_msg, - ros_ign_interfaces::msg::Contacts & ros_msg) +>::convert_gz_to_ros( + const ignition::msgs::Contacts & gz_msg, + ros_gz_interfaces::msg::Contacts & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } template<> void Factory< - ros_ign_interfaces::msg::GuiCamera, + ros_gz_interfaces::msg::GuiCamera, ignition::msgs::GUICamera ->::convert_ros_to_ign( - const ros_ign_interfaces::msg::GuiCamera & ros_msg, - ignition::msgs::GUICamera & ign_msg) +>::convert_ros_to_gz( + const ros_gz_interfaces::msg::GuiCamera & ros_msg, + ignition::msgs::GUICamera & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> void Factory< - ros_ign_interfaces::msg::GuiCamera, + ros_gz_interfaces::msg::GuiCamera, ignition::msgs::GUICamera ->::convert_ign_to_ros( - const ignition::msgs::GUICamera & ign_msg, - ros_ign_interfaces::msg::GuiCamera & ros_msg) +>::convert_gz_to_ros( + const ignition::msgs::GUICamera & gz_msg, + ros_gz_interfaces::msg::GuiCamera & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } template<> void Factory< - ros_ign_interfaces::msg::Light, + ros_gz_interfaces::msg::Light, ignition::msgs::Light ->::convert_ros_to_ign( - const ros_ign_interfaces::msg::Light & ros_msg, - ignition::msgs::Light & ign_msg) +>::convert_ros_to_gz( + const ros_gz_interfaces::msg::Light & ros_msg, + ignition::msgs::Light & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> void Factory< - ros_ign_interfaces::msg::Light, + ros_gz_interfaces::msg::Light, ignition::msgs::Light ->::convert_ign_to_ros( - const ignition::msgs::Light & ign_msg, - ros_ign_interfaces::msg::Light & ros_msg) +>::convert_gz_to_ros( + const ignition::msgs::Light & gz_msg, + ros_gz_interfaces::msg::Light & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } template<> void Factory< - ros_ign_interfaces::msg::StringVec, + ros_gz_interfaces::msg::StringVec, ignition::msgs::StringMsg_V ->::convert_ros_to_ign( - const ros_ign_interfaces::msg::StringVec & ros_msg, - ignition::msgs::StringMsg_V & ign_msg) +>::convert_ros_to_gz( + const ros_gz_interfaces::msg::StringVec & ros_msg, + ignition::msgs::StringMsg_V & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> void Factory< - ros_ign_interfaces::msg::StringVec, + ros_gz_interfaces::msg::StringVec, ignition::msgs::StringMsg_V ->::convert_ign_to_ros( - const ignition::msgs::StringMsg_V & ign_msg, - ros_ign_interfaces::msg::StringVec & ros_msg) +>::convert_gz_to_ros( + const ignition::msgs::StringMsg_V & gz_msg, + ros_gz_interfaces::msg::StringVec & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } template<> void Factory< - ros_ign_interfaces::msg::TrackVisual, + ros_gz_interfaces::msg::TrackVisual, ignition::msgs::TrackVisual ->::convert_ros_to_ign( - const ros_ign_interfaces::msg::TrackVisual & ros_msg, - ignition::msgs::TrackVisual & ign_msg) +>::convert_ros_to_gz( + const ros_gz_interfaces::msg::TrackVisual & ros_msg, + ignition::msgs::TrackVisual & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> void Factory< - ros_ign_interfaces::msg::TrackVisual, + ros_gz_interfaces::msg::TrackVisual, ignition::msgs::TrackVisual ->::convert_ign_to_ros( - const ignition::msgs::TrackVisual & ign_msg, - ros_ign_interfaces::msg::TrackVisual & ros_msg) +>::convert_gz_to_ros( + const ignition::msgs::TrackVisual & gz_msg, + ros_gz_interfaces::msg::TrackVisual & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } template<> void Factory< - ros_ign_interfaces::msg::VideoRecord, + ros_gz_interfaces::msg::VideoRecord, ignition::msgs::VideoRecord ->::convert_ros_to_ign( - const ros_ign_interfaces::msg::VideoRecord & ros_msg, - ignition::msgs::VideoRecord & ign_msg) +>::convert_ros_to_gz( + const ros_gz_interfaces::msg::VideoRecord & ros_msg, + ignition::msgs::VideoRecord & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> void Factory< - ros_ign_interfaces::msg::VideoRecord, + ros_gz_interfaces::msg::VideoRecord, ignition::msgs::VideoRecord ->::convert_ign_to_ros( - const ignition::msgs::VideoRecord & ign_msg, - ros_ign_interfaces::msg::VideoRecord & ros_msg) +>::convert_gz_to_ros( + const ignition::msgs::VideoRecord & gz_msg, + ros_gz_interfaces::msg::VideoRecord & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } template<> void Factory< - ros_ign_interfaces::msg::WorldControl, + ros_gz_interfaces::msg::WorldControl, ignition::msgs::WorldControl ->::convert_ros_to_ign( - const ros_ign_interfaces::msg::WorldControl & ros_msg, - ignition::msgs::WorldControl & ign_msg) +>::convert_ros_to_gz( + const ros_gz_interfaces::msg::WorldControl & ros_msg, + ignition::msgs::WorldControl & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> void Factory< - ros_ign_interfaces::msg::WorldControl, + ros_gz_interfaces::msg::WorldControl, ignition::msgs::WorldControl ->::convert_ign_to_ros( - const ignition::msgs::WorldControl & ign_msg, - ros_ign_interfaces::msg::WorldControl & ros_msg) +>::convert_gz_to_ros( + const ignition::msgs::WorldControl & gz_msg, + ros_gz_interfaces::msg::WorldControl & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge diff --git a/ros_gz_bridge/src/factories/ros_gz_interfaces.hpp b/ros_gz_bridge/src/factories/ros_gz_interfaces.hpp index 86593619..84c57a01 100644 --- a/ros_gz_bridge/src/factories/ros_gz_interfaces.hpp +++ b/ros_gz_bridge/src/factories/ros_gz_interfaces.hpp @@ -12,22 +12,22 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef FACTORIES__ROS_IGN_INTERFACES_HPP_ -#define FACTORIES__ROS_IGN_INTERFACES_HPP_ +#ifndef FACTORIES__ROS_GZ_INTERFACES_HPP_ +#define FACTORIES__ROS_GZ_INTERFACES_HPP_ #include #include #include "factory_interface.hpp" -namespace ros_ign_bridge +namespace ros_gz_bridge { std::shared_ptr -get_factory__ros_ign_interfaces( +get_factory__ros_gz_interfaces( const std::string & ros_type_name, - const std::string & ign_type_name); + const std::string & gz_type_name); -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge -#endif // FACTORIES__ROS_IGN_INTERFACES_HPP_ +#endif // FACTORIES__ROS_GZ_INTERFACES_HPP_ diff --git a/ros_gz_bridge/src/factories/rosgraph_msgs.cpp b/ros_gz_bridge/src/factories/rosgraph_msgs.cpp index 2cb6d260..a22a00e2 100644 --- a/ros_gz_bridge/src/factories/rosgraph_msgs.cpp +++ b/ros_gz_bridge/src/factories/rosgraph_msgs.cpp @@ -18,25 +18,25 @@ #include #include "factory.hpp" -#include "ros_ign_bridge/convert/rosgraph_msgs.hpp" +#include "ros_gz_bridge/convert/rosgraph_msgs.hpp" -namespace ros_ign_bridge +namespace ros_gz_bridge { std::shared_ptr get_factory__rosgraph_msgs( const std::string & ros_type_name, - const std::string & ign_type_name) + const std::string & gz_type_name) { if ((ros_type_name == "rosgraph_msgs/msg/Clock" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.Clock") + gz_type_name == "ignition.msgs.Clock") { return std::make_shared< Factory< rosgraph_msgs::msg::Clock, ignition::msgs::Clock > - >("rosgraph_msgs/msg/Clock", ign_type_name); + >("rosgraph_msgs/msg/Clock", gz_type_name); } return nullptr; } @@ -46,11 +46,11 @@ void Factory< rosgraph_msgs::msg::Clock, ignition::msgs::Clock ->::convert_ros_to_ign( +>::convert_ros_to_gz( const rosgraph_msgs::msg::Clock & ros_msg, - ignition::msgs::Clock & ign_msg) + ignition::msgs::Clock & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> @@ -58,11 +58,11 @@ void Factory< rosgraph_msgs::msg::Clock, ignition::msgs::Clock ->::convert_ign_to_ros( - const ignition::msgs::Clock & ign_msg, +>::convert_gz_to_ros( + const ignition::msgs::Clock & gz_msg, rosgraph_msgs::msg::Clock & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge diff --git a/ros_gz_bridge/src/factories/rosgraph_msgs.hpp b/ros_gz_bridge/src/factories/rosgraph_msgs.hpp index 08d64f1e..3a5a549a 100644 --- a/ros_gz_bridge/src/factories/rosgraph_msgs.hpp +++ b/ros_gz_bridge/src/factories/rosgraph_msgs.hpp @@ -20,14 +20,14 @@ #include "factory_interface.hpp" -namespace ros_ign_bridge +namespace ros_gz_bridge { std::shared_ptr get_factory__rosgraph_msgs( const std::string & ros_type_name, - const std::string & ign_type_name); + const std::string & gz_type_name); -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge #endif // FACTORIES__ROSGRAPH_MSGS_HPP_ diff --git a/ros_gz_bridge/src/factories/sensor_msgs.cpp b/ros_gz_bridge/src/factories/sensor_msgs.cpp index 36c236d4..f67b77cc 100644 --- a/ros_gz_bridge/src/factories/sensor_msgs.cpp +++ b/ros_gz_bridge/src/factories/sensor_msgs.cpp @@ -18,105 +18,105 @@ #include #include "factory.hpp" -#include "ros_ign_bridge/convert/sensor_msgs.hpp" +#include "ros_gz_bridge/convert/sensor_msgs.hpp" -namespace ros_ign_bridge +namespace ros_gz_bridge { std::shared_ptr get_factory__sensor_msgs( const std::string & ros_type_name, - const std::string & ign_type_name) + const std::string & gz_type_name) { if ((ros_type_name == "sensor_msgs/msg/FluidPressure" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.FluidPressure") + gz_type_name == "ignition.msgs.FluidPressure") { return std::make_shared< Factory< sensor_msgs::msg::FluidPressure, ignition::msgs::FluidPressure > - >("sensor_msgs/msg/FluidPressure", ign_type_name); + >("sensor_msgs/msg/FluidPressure", gz_type_name); } if ((ros_type_name == "sensor_msgs/msg/Image" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.Image") + gz_type_name == "ignition.msgs.Image") { return std::make_shared< Factory< sensor_msgs::msg::Image, ignition::msgs::Image > - >("sensor_msgs/msg/Image", ign_type_name); + >("sensor_msgs/msg/Image", gz_type_name); } if ((ros_type_name == "sensor_msgs/msg/CameraInfo" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.CameraInfo") + gz_type_name == "ignition.msgs.CameraInfo") { return std::make_shared< Factory< sensor_msgs::msg::CameraInfo, ignition::msgs::CameraInfo > - >("sensor_msgs/msg/CameraInfo", ign_type_name); + >("sensor_msgs/msg/CameraInfo", gz_type_name); } if ((ros_type_name == "sensor_msgs/msg/Imu" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.IMU") + gz_type_name == "ignition.msgs.IMU") { return std::make_shared< Factory< sensor_msgs::msg::Imu, ignition::msgs::IMU > - >("sensor_msgs/msg/Imu", ign_type_name); + >("sensor_msgs/msg/Imu", gz_type_name); } if ((ros_type_name == "sensor_msgs/msg/JointState" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.Model") + gz_type_name == "ignition.msgs.Model") { return std::make_shared< Factory< sensor_msgs::msg::JointState, ignition::msgs::Model > - >("sensor_msgs/msg/JointState", ign_type_name); + >("sensor_msgs/msg/JointState", gz_type_name); } if ((ros_type_name == "sensor_msgs/msg/LaserScan" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.LaserScan") + gz_type_name == "ignition.msgs.LaserScan") { return std::make_shared< Factory< sensor_msgs::msg::LaserScan, ignition::msgs::LaserScan > - >("sensor_msgs/msg/LaserScan", ign_type_name); + >("sensor_msgs/msg/LaserScan", gz_type_name); } if ((ros_type_name == "sensor_msgs/msg/MagneticField" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.Magnetometer") + gz_type_name == "ignition.msgs.Magnetometer") { return std::make_shared< Factory< sensor_msgs::msg::MagneticField, ignition::msgs::Magnetometer > - >("sensor_msgs/msg/Magnetometer", ign_type_name); + >("sensor_msgs/msg/Magnetometer", gz_type_name); } if ((ros_type_name == "sensor_msgs/msg/PointCloud2" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.PointCloudPacked") + gz_type_name == "ignition.msgs.PointCloudPacked") { return std::make_shared< Factory< sensor_msgs::msg::PointCloud2, ignition::msgs::PointCloudPacked > - >("sensor_msgs/msg/PointCloud2", ign_type_name); + >("sensor_msgs/msg/PointCloud2", gz_type_name); } if ((ros_type_name == "sensor_msgs/msg/BatteryState" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.BatteryState") + gz_type_name == "ignition.msgs.BatteryState") { return std::make_shared< Factory< sensor_msgs::msg::BatteryState, ignition::msgs::BatteryState > - >("sensor_msgs/msg/BatteryState", ign_type_name); + >("sensor_msgs/msg/BatteryState", gz_type_name); } return nullptr; } @@ -126,11 +126,11 @@ void Factory< sensor_msgs::msg::FluidPressure, ignition::msgs::FluidPressure ->::convert_ros_to_ign( +>::convert_ros_to_gz( const sensor_msgs::msg::FluidPressure & ros_msg, - ignition::msgs::FluidPressure & ign_msg) + ignition::msgs::FluidPressure & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> @@ -138,11 +138,11 @@ void Factory< sensor_msgs::msg::FluidPressure, ignition::msgs::FluidPressure ->::convert_ign_to_ros( - const ignition::msgs::FluidPressure & ign_msg, +>::convert_gz_to_ros( + const ignition::msgs::FluidPressure & gz_msg, sensor_msgs::msg::FluidPressure & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } template<> @@ -150,11 +150,11 @@ void Factory< sensor_msgs::msg::Image, ignition::msgs::Image ->::convert_ros_to_ign( +>::convert_ros_to_gz( const sensor_msgs::msg::Image & ros_msg, - ignition::msgs::Image & ign_msg) + ignition::msgs::Image & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> @@ -162,11 +162,11 @@ void Factory< sensor_msgs::msg::Image, ignition::msgs::Image ->::convert_ign_to_ros( - const ignition::msgs::Image & ign_msg, +>::convert_gz_to_ros( + const ignition::msgs::Image & gz_msg, sensor_msgs::msg::Image & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } template<> @@ -174,11 +174,11 @@ void Factory< sensor_msgs::msg::CameraInfo, ignition::msgs::CameraInfo ->::convert_ros_to_ign( +>::convert_ros_to_gz( const sensor_msgs::msg::CameraInfo & ros_msg, - ignition::msgs::CameraInfo & ign_msg) + ignition::msgs::CameraInfo & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> @@ -186,11 +186,11 @@ void Factory< sensor_msgs::msg::CameraInfo, ignition::msgs::CameraInfo ->::convert_ign_to_ros( - const ignition::msgs::CameraInfo & ign_msg, +>::convert_gz_to_ros( + const ignition::msgs::CameraInfo & gz_msg, sensor_msgs::msg::CameraInfo & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } template<> @@ -198,11 +198,11 @@ void Factory< sensor_msgs::msg::Imu, ignition::msgs::IMU ->::convert_ros_to_ign( +>::convert_ros_to_gz( const sensor_msgs::msg::Imu & ros_msg, - ignition::msgs::IMU & ign_msg) + ignition::msgs::IMU & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> @@ -210,11 +210,11 @@ void Factory< sensor_msgs::msg::Imu, ignition::msgs::IMU ->::convert_ign_to_ros( - const ignition::msgs::IMU & ign_msg, +>::convert_gz_to_ros( + const ignition::msgs::IMU & gz_msg, sensor_msgs::msg::Imu & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } template<> @@ -222,11 +222,11 @@ void Factory< sensor_msgs::msg::JointState, ignition::msgs::Model ->::convert_ros_to_ign( +>::convert_ros_to_gz( const sensor_msgs::msg::JointState & ros_msg, - ignition::msgs::Model & ign_msg) + ignition::msgs::Model & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> @@ -234,11 +234,11 @@ void Factory< sensor_msgs::msg::JointState, ignition::msgs::Model ->::convert_ign_to_ros( - const ignition::msgs::Model & ign_msg, +>::convert_gz_to_ros( + const ignition::msgs::Model & gz_msg, sensor_msgs::msg::JointState & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } template<> @@ -246,11 +246,11 @@ void Factory< sensor_msgs::msg::LaserScan, ignition::msgs::LaserScan ->::convert_ros_to_ign( +>::convert_ros_to_gz( const sensor_msgs::msg::LaserScan & ros_msg, - ignition::msgs::LaserScan & ign_msg) + ignition::msgs::LaserScan & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> @@ -258,11 +258,11 @@ void Factory< sensor_msgs::msg::LaserScan, ignition::msgs::LaserScan ->::convert_ign_to_ros( - const ignition::msgs::LaserScan & ign_msg, +>::convert_gz_to_ros( + const ignition::msgs::LaserScan & gz_msg, sensor_msgs::msg::LaserScan & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } template<> @@ -270,11 +270,11 @@ void Factory< sensor_msgs::msg::MagneticField, ignition::msgs::Magnetometer ->::convert_ros_to_ign( +>::convert_ros_to_gz( const sensor_msgs::msg::MagneticField & ros_msg, - ignition::msgs::Magnetometer & ign_msg) + ignition::msgs::Magnetometer & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> @@ -282,11 +282,11 @@ void Factory< sensor_msgs::msg::MagneticField, ignition::msgs::Magnetometer ->::convert_ign_to_ros( - const ignition::msgs::Magnetometer & ign_msg, +>::convert_gz_to_ros( + const ignition::msgs::Magnetometer & gz_msg, sensor_msgs::msg::MagneticField & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } template<> @@ -294,11 +294,11 @@ void Factory< sensor_msgs::msg::PointCloud2, ignition::msgs::PointCloudPacked ->::convert_ros_to_ign( +>::convert_ros_to_gz( const sensor_msgs::msg::PointCloud2 & ros_msg, - ignition::msgs::PointCloudPacked & ign_msg) + ignition::msgs::PointCloudPacked & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> @@ -306,11 +306,11 @@ void Factory< sensor_msgs::msg::PointCloud2, ignition::msgs::PointCloudPacked ->::convert_ign_to_ros( - const ignition::msgs::PointCloudPacked & ign_msg, +>::convert_gz_to_ros( + const ignition::msgs::PointCloudPacked & gz_msg, sensor_msgs::msg::PointCloud2 & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } template<> @@ -318,11 +318,11 @@ void Factory< sensor_msgs::msg::BatteryState, ignition::msgs::BatteryState ->::convert_ros_to_ign( +>::convert_ros_to_gz( const sensor_msgs::msg::BatteryState & ros_msg, - ignition::msgs::BatteryState & ign_msg) + ignition::msgs::BatteryState & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> @@ -330,11 +330,11 @@ void Factory< sensor_msgs::msg::BatteryState, ignition::msgs::BatteryState ->::convert_ign_to_ros( - const ignition::msgs::BatteryState & ign_msg, +>::convert_gz_to_ros( + const ignition::msgs::BatteryState & gz_msg, sensor_msgs::msg::BatteryState & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge diff --git a/ros_gz_bridge/src/factories/sensor_msgs.hpp b/ros_gz_bridge/src/factories/sensor_msgs.hpp index 542039ee..bd8ece28 100644 --- a/ros_gz_bridge/src/factories/sensor_msgs.hpp +++ b/ros_gz_bridge/src/factories/sensor_msgs.hpp @@ -20,14 +20,14 @@ #include "factory_interface.hpp" -namespace ros_ign_bridge +namespace ros_gz_bridge { std::shared_ptr get_factory__sensor_msgs( const std::string & ros_type_name, - const std::string & ign_type_name); + const std::string & gz_type_name); -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge #endif // FACTORIES__SENSOR_MSGS_HPP_ diff --git a/ros_gz_bridge/src/factories/std_msgs.cpp b/ros_gz_bridge/src/factories/std_msgs.cpp index 0ce63c6b..87a29590 100644 --- a/ros_gz_bridge/src/factories/std_msgs.cpp +++ b/ros_gz_bridge/src/factories/std_msgs.cpp @@ -18,106 +18,106 @@ #include #include "factory.hpp" -#include "ros_ign_bridge/convert/std_msgs.hpp" +#include "ros_gz_bridge/convert/std_msgs.hpp" -namespace ros_ign_bridge +namespace ros_gz_bridge { std::shared_ptr get_factory__std_msgs( const std::string & ros_type_name, - const std::string & ign_type_name) + const std::string & gz_type_name) { // mapping from string to specialized template if ((ros_type_name == "std_msgs/msg/Bool" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.Boolean") + gz_type_name == "ignition.msgs.Boolean") { return std::make_shared< Factory< std_msgs::msg::Bool, ignition::msgs::Boolean > - >("std_msgs/msg/Bool", ign_type_name); + >("std_msgs/msg/Bool", gz_type_name); } if ((ros_type_name == "std_msgs/msg/ColorRGBA" || - ros_type_name.empty()) && ign_type_name == "ignition.msgs.Color") + ros_type_name.empty()) && gz_type_name == "ignition.msgs.Color") { return std::make_shared< Factory< std_msgs::msg::ColorRGBA, ignition::msgs::Color > - >("std_msgs/msg/ColorRGBA", ign_type_name); + >("std_msgs/msg/ColorRGBA", gz_type_name); } if ((ros_type_name == "std_msgs/msg/Empty" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.Empty") + gz_type_name == "ignition.msgs.Empty") { return std::make_shared< Factory< std_msgs::msg::Empty, ignition::msgs::Empty > - >("std_msgs/msg/Empty", ign_type_name); + >("std_msgs/msg/Empty", gz_type_name); } if ((ros_type_name == "std_msgs/msg/Float32" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.Float") + gz_type_name == "ignition.msgs.Float") { return std::make_shared< Factory< std_msgs::msg::Float32, ignition::msgs::Float > - >("std_msgs/msg/Float32", ign_type_name); + >("std_msgs/msg/Float32", gz_type_name); } if ((ros_type_name == "std_msgs/msg/Float64" || ros_type_name == "") && - ign_type_name == "ignition.msgs.Double") + gz_type_name == "ignition.msgs.Double") { return std::make_shared< Factory< std_msgs::msg::Float64, ignition::msgs::Double > - >("std_msgs/msg/Float64", ign_type_name); + >("std_msgs/msg/Float64", gz_type_name); } if ((ros_type_name == "std_msgs/msg/Header" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.Header") + gz_type_name == "ignition.msgs.Header") { return std::make_shared< Factory< std_msgs::msg::Header, ignition::msgs::Header > - >("std_msgs/msg/Header", ign_type_name); + >("std_msgs/msg/Header", gz_type_name); } if ((ros_type_name == "std_msgs/msg/Int32" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.Int32") + gz_type_name == "ignition.msgs.Int32") { return std::make_shared< Factory< std_msgs::msg::Int32, ignition::msgs::Int32 > - >("std_msgs/msg/Int32", ign_type_name); + >("std_msgs/msg/Int32", gz_type_name); } if ((ros_type_name == "std_msgs/msg/UInt32" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.UInt32") + gz_type_name == "ignition.msgs.UInt32") { return std::make_shared< Factory< std_msgs::msg::UInt32, ignition::msgs::UInt32 > - >("std_msgs/msg/Int32", ign_type_name); + >("std_msgs/msg/Int32", gz_type_name); } if ((ros_type_name == "std_msgs/msg/String" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.StringMsg") + gz_type_name == "ignition.msgs.StringMsg") { return std::make_shared< Factory< std_msgs::msg::String, ignition::msgs::StringMsg > - >("std_msgs/msg/String", ign_type_name); + >("std_msgs/msg/String", gz_type_name); } return nullptr; } @@ -127,11 +127,11 @@ void Factory< std_msgs::msg::Bool, ignition::msgs::Boolean ->::convert_ros_to_ign( +>::convert_ros_to_gz( const std_msgs::msg::Bool & ros_msg, - ignition::msgs::Boolean & ign_msg) + ignition::msgs::Boolean & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> @@ -139,11 +139,11 @@ void Factory< std_msgs::msg::Bool, ignition::msgs::Boolean ->::convert_ign_to_ros( - const ignition::msgs::Boolean & ign_msg, +>::convert_gz_to_ros( + const ignition::msgs::Boolean & gz_msg, std_msgs::msg::Bool & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } template<> @@ -151,11 +151,11 @@ void Factory< std_msgs::msg::ColorRGBA, ignition::msgs::Color ->::convert_ros_to_ign( +>::convert_ros_to_gz( const std_msgs::msg::ColorRGBA & ros_msg, - ignition::msgs::Color & ign_msg) + ignition::msgs::Color & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> @@ -163,11 +163,11 @@ void Factory< std_msgs::msg::ColorRGBA, ignition::msgs::Color ->::convert_ign_to_ros( - const ignition::msgs::Color & ign_msg, +>::convert_gz_to_ros( + const ignition::msgs::Color & gz_msg, std_msgs::msg::ColorRGBA & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } template<> @@ -175,11 +175,11 @@ void Factory< std_msgs::msg::Empty, ignition::msgs::Empty ->::convert_ros_to_ign( +>::convert_ros_to_gz( const std_msgs::msg::Empty & ros_msg, - ignition::msgs::Empty & ign_msg) + ignition::msgs::Empty & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> @@ -187,11 +187,11 @@ void Factory< std_msgs::msg::Empty, ignition::msgs::Empty ->::convert_ign_to_ros( - const ignition::msgs::Empty & ign_msg, +>::convert_gz_to_ros( + const ignition::msgs::Empty & gz_msg, std_msgs::msg::Empty & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } template<> @@ -199,11 +199,11 @@ void Factory< std_msgs::msg::Float32, ignition::msgs::Float ->::convert_ros_to_ign( +>::convert_ros_to_gz( const std_msgs::msg::Float32 & ros_msg, - ignition::msgs::Float & ign_msg) + ignition::msgs::Float & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> @@ -211,11 +211,11 @@ void Factory< std_msgs::msg::Float32, ignition::msgs::Float ->::convert_ign_to_ros( - const ignition::msgs::Float & ign_msg, +>::convert_gz_to_ros( + const ignition::msgs::Float & gz_msg, std_msgs::msg::Float32 & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } template<> @@ -223,11 +223,11 @@ void Factory< std_msgs::msg::Float64, ignition::msgs::Double ->::convert_ros_to_ign( +>::convert_ros_to_gz( const std_msgs::msg::Float64 & ros_msg, - ignition::msgs::Double & ign_msg) + ignition::msgs::Double & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> @@ -235,11 +235,11 @@ void Factory< std_msgs::msg::Float64, ignition::msgs::Double ->::convert_ign_to_ros( - const ignition::msgs::Double & ign_msg, +>::convert_gz_to_ros( + const ignition::msgs::Double & gz_msg, std_msgs::msg::Float64 & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } template<> @@ -247,11 +247,11 @@ void Factory< std_msgs::msg::Int32, ignition::msgs::Int32 ->::convert_ros_to_ign( +>::convert_ros_to_gz( const std_msgs::msg::Int32 & ros_msg, - ignition::msgs::Int32 & ign_msg) + ignition::msgs::Int32 & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> @@ -259,11 +259,11 @@ void Factory< std_msgs::msg::Int32, ignition::msgs::Int32 ->::convert_ign_to_ros( - const ignition::msgs::Int32 & ign_msg, +>::convert_gz_to_ros( + const ignition::msgs::Int32 & gz_msg, std_msgs::msg::Int32 & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } template<> @@ -271,11 +271,11 @@ void Factory< std_msgs::msg::UInt32, ignition::msgs::UInt32 ->::convert_ros_to_ign( +>::convert_ros_to_gz( const std_msgs::msg::UInt32 & ros_msg, - ignition::msgs::UInt32 & ign_msg) + ignition::msgs::UInt32 & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> @@ -283,11 +283,11 @@ void Factory< std_msgs::msg::UInt32, ignition::msgs::UInt32 ->::convert_ign_to_ros( - const ignition::msgs::UInt32 & ign_msg, +>::convert_gz_to_ros( + const ignition::msgs::UInt32 & gz_msg, std_msgs::msg::UInt32 & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } template<> @@ -295,11 +295,11 @@ void Factory< std_msgs::msg::Header, ignition::msgs::Header ->::convert_ros_to_ign( +>::convert_ros_to_gz( const std_msgs::msg::Header & ros_msg, - ignition::msgs::Header & ign_msg) + ignition::msgs::Header & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> @@ -307,11 +307,11 @@ void Factory< std_msgs::msg::Header, ignition::msgs::Header ->::convert_ign_to_ros( - const ignition::msgs::Header & ign_msg, +>::convert_gz_to_ros( + const ignition::msgs::Header & gz_msg, std_msgs::msg::Header & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } template<> @@ -319,11 +319,11 @@ void Factory< std_msgs::msg::String, ignition::msgs::StringMsg ->::convert_ros_to_ign( +>::convert_ros_to_gz( const std_msgs::msg::String & ros_msg, - ignition::msgs::StringMsg & ign_msg) + ignition::msgs::StringMsg & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> @@ -331,11 +331,11 @@ void Factory< std_msgs::msg::String, ignition::msgs::StringMsg ->::convert_ign_to_ros( - const ignition::msgs::StringMsg & ign_msg, +>::convert_gz_to_ros( + const ignition::msgs::StringMsg & gz_msg, std_msgs::msg::String & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge diff --git a/ros_gz_bridge/src/factories/std_msgs.hpp b/ros_gz_bridge/src/factories/std_msgs.hpp index c6fa5591..1747cad3 100644 --- a/ros_gz_bridge/src/factories/std_msgs.hpp +++ b/ros_gz_bridge/src/factories/std_msgs.hpp @@ -20,14 +20,14 @@ #include "factory_interface.hpp" -namespace ros_ign_bridge +namespace ros_gz_bridge { std::shared_ptr get_factory__std_msgs( const std::string & ros_type_name, - const std::string & ign_type_name); + const std::string & gz_type_name); -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge #endif // FACTORIES__STD_MSGS_HPP_ diff --git a/ros_gz_bridge/src/factories/tf2_msgs.cpp b/ros_gz_bridge/src/factories/tf2_msgs.cpp index bdd70f9c..7ea503dc 100644 --- a/ros_gz_bridge/src/factories/tf2_msgs.cpp +++ b/ros_gz_bridge/src/factories/tf2_msgs.cpp @@ -18,26 +18,26 @@ #include #include "factory.hpp" -#include "ros_ign_bridge/convert/tf2_msgs.hpp" +#include "ros_gz_bridge/convert/tf2_msgs.hpp" -namespace ros_ign_bridge +namespace ros_gz_bridge { std::shared_ptr get_factory__tf2_msgs( const std::string & ros_type_name, - const std::string & ign_type_name) + const std::string & gz_type_name) { if ( (ros_type_name == "tf2_msgs/msg/TFMessage" || ros_type_name == "") && - ign_type_name == "ignition.msgs.Pose_V") + gz_type_name == "ignition.msgs.Pose_V") { return std::make_shared< Factory< tf2_msgs::msg::TFMessage, ignition::msgs::Pose_V > - >("tf2_msgs/msg/TFMessage", ign_type_name); + >("tf2_msgs/msg/TFMessage", gz_type_name); } return nullptr; } @@ -47,11 +47,11 @@ void Factory< tf2_msgs::msg::TFMessage, ignition::msgs::Pose_V ->::convert_ros_to_ign( +>::convert_ros_to_gz( const tf2_msgs::msg::TFMessage & ros_msg, - ignition::msgs::Pose_V & ign_msg) + ignition::msgs::Pose_V & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> @@ -59,11 +59,11 @@ void Factory< tf2_msgs::msg::TFMessage, ignition::msgs::Pose_V ->::convert_ign_to_ros( - const ignition::msgs::Pose_V & ign_msg, +>::convert_gz_to_ros( + const ignition::msgs::Pose_V & gz_msg, tf2_msgs::msg::TFMessage & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge diff --git a/ros_gz_bridge/src/factories/tf2_msgs.hpp b/ros_gz_bridge/src/factories/tf2_msgs.hpp index 45178c4c..6154b1ed 100644 --- a/ros_gz_bridge/src/factories/tf2_msgs.hpp +++ b/ros_gz_bridge/src/factories/tf2_msgs.hpp @@ -20,14 +20,14 @@ #include "factory_interface.hpp" -namespace ros_ign_bridge +namespace ros_gz_bridge { std::shared_ptr get_factory__tf2_msgs( const std::string & ros_type_name, - const std::string & ign_type_name); + const std::string & gz_type_name); -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge #endif // FACTORIES__TF2_MSGS_HPP_ diff --git a/ros_gz_bridge/src/factories/trajectory_msgs.cpp b/ros_gz_bridge/src/factories/trajectory_msgs.cpp index f502cc4a..31a6d063 100644 --- a/ros_gz_bridge/src/factories/trajectory_msgs.cpp +++ b/ros_gz_bridge/src/factories/trajectory_msgs.cpp @@ -18,25 +18,25 @@ #include #include "factory.hpp" -#include "ros_ign_bridge/convert/trajectory_msgs.hpp" +#include "ros_gz_bridge/convert/trajectory_msgs.hpp" -namespace ros_ign_bridge +namespace ros_gz_bridge { std::shared_ptr get_factory__trajectory_msgs( const std::string & ros_type_name, - const std::string & ign_type_name) + const std::string & gz_type_name) { if ((ros_type_name == "trajectory_msgs/msg/JointTrajectory" || ros_type_name.empty()) && - ign_type_name == "ignition.msgs.JointTrajectory") + gz_type_name == "ignition.msgs.JointTrajectory") { return std::make_shared< Factory< trajectory_msgs::msg::JointTrajectory, ignition::msgs::JointTrajectory > - >("trajectory_msgs/msg/JointTrajectory", ign_type_name); + >("trajectory_msgs/msg/JointTrajectory", gz_type_name); } return nullptr; } @@ -46,11 +46,11 @@ void Factory< trajectory_msgs::msg::JointTrajectoryPoint, ignition::msgs::JointTrajectoryPoint ->::convert_ros_to_ign( +>::convert_ros_to_gz( const trajectory_msgs::msg::JointTrajectoryPoint & ros_msg, - ignition::msgs::JointTrajectoryPoint & ign_msg) + ignition::msgs::JointTrajectoryPoint & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> @@ -58,11 +58,11 @@ void Factory< trajectory_msgs::msg::JointTrajectoryPoint, ignition::msgs::JointTrajectoryPoint ->::convert_ign_to_ros( - const ignition::msgs::JointTrajectoryPoint & ign_msg, +>::convert_gz_to_ros( + const ignition::msgs::JointTrajectoryPoint & gz_msg, trajectory_msgs::msg::JointTrajectoryPoint & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } template<> @@ -70,11 +70,11 @@ void Factory< trajectory_msgs::msg::JointTrajectory, ignition::msgs::JointTrajectory ->::convert_ros_to_ign( +>::convert_ros_to_gz( const trajectory_msgs::msg::JointTrajectory & ros_msg, - ignition::msgs::JointTrajectory & ign_msg) + ignition::msgs::JointTrajectory & gz_msg) { - ros_ign_bridge::convert_ros_to_ign(ros_msg, ign_msg); + ros_gz_bridge::convert_ros_to_gz(ros_msg, gz_msg); } template<> @@ -82,12 +82,12 @@ void Factory< trajectory_msgs::msg::JointTrajectory, ignition::msgs::JointTrajectory ->::convert_ign_to_ros( - const ignition::msgs::JointTrajectory & ign_msg, +>::convert_gz_to_ros( + const ignition::msgs::JointTrajectory & gz_msg, trajectory_msgs::msg::JointTrajectory & ros_msg) { - ros_ign_bridge::convert_ign_to_ros(ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(gz_msg, ros_msg); } -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge diff --git a/ros_gz_bridge/src/factories/trajectory_msgs.hpp b/ros_gz_bridge/src/factories/trajectory_msgs.hpp index b1907dc3..1d0246fc 100644 --- a/ros_gz_bridge/src/factories/trajectory_msgs.hpp +++ b/ros_gz_bridge/src/factories/trajectory_msgs.hpp @@ -20,14 +20,14 @@ #include "factory_interface.hpp" -namespace ros_ign_bridge +namespace ros_gz_bridge { std::shared_ptr get_factory__trajectory_msgs( const std::string & ros_type_name, - const std::string & ign_type_name); + const std::string & gz_type_name); -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge #endif // FACTORIES__TRAJECTORY_MSGS_HPP_ diff --git a/ros_gz_bridge/src/factory.hpp b/ros_gz_bridge/src/factory.hpp index 7a59ab04..9d31595f 100644 --- a/ros_gz_bridge/src/factory.hpp +++ b/ros_gz_bridge/src/factory.hpp @@ -27,17 +27,17 @@ #include "factory_interface.hpp" -namespace ros_ign_bridge +namespace ros_gz_bridge { -template +template class Factory : public FactoryInterface { public: Factory( - const std::string & ros_type_name, const std::string & ign_type_name) + const std::string & ros_type_name, const std::string & gz_type_name) : ros_type_name_(ros_type_name), - ign_type_name_(ign_type_name) + gz_type_name_(gz_type_name) {} rclcpp::PublisherBase::SharedPtr @@ -64,12 +64,12 @@ class Factory : public FactoryInterface } ignition::transport::Node::Publisher - create_ign_publisher( - std::shared_ptr ign_node, + create_gz_publisher( + std::shared_ptr gz_node, const std::string & topic_name, size_t /*queue_size*/) { - return ign_node->Advertise(topic_name); + return gz_node->Advertise(topic_name); } rclcpp::SubscriptionBase::SharedPtr @@ -77,12 +77,12 @@ class Factory : public FactoryInterface rclcpp::Node::SharedPtr ros_node, const std::string & topic_name, size_t queue_size, - ignition::transport::Node::Publisher & ign_pub) + ignition::transport::Node::Publisher & gz_pub) { std::function)> fn = std::bind( - &Factory::ros_callback, - std::placeholders::_1, ign_pub, - ros_type_name_, ign_type_name_, + &Factory::ros_callback, + std::placeholders::_1, gz_pub, + ros_type_name_, gz_type_name_, ros_node); auto options = rclcpp::SubscriptionOptions(); // Ignore messages that are published from this bridge. @@ -97,20 +97,20 @@ class Factory : public FactoryInterface } void - create_ign_subscriber( + create_gz_subscriber( std::shared_ptr node, const std::string & topic_name, size_t /*queue_size*/, rclcpp::PublisherBase::SharedPtr ros_pub) { - std::function subCb = - [this, ros_pub](const IGN_T & _msg, + [this, ros_pub](const GZ_T & _msg, const ignition::transport::MessageInfo & _info) { // Ignore messages that are published from this bridge. if (!_info.IntraProcess()) { - this->ign_callback(_msg, ros_pub); + this->gz_callback(_msg, ros_pub); } }; @@ -121,27 +121,27 @@ class Factory : public FactoryInterface static void ros_callback( std::shared_ptr ros_msg, - ignition::transport::Node::Publisher & ign_pub, + ignition::transport::Node::Publisher & gz_pub, const std::string & ros_type_name, - const std::string & ign_type_name, + const std::string & gz_type_name, rclcpp::Node::SharedPtr ros_node) { - IGN_T ign_msg; - convert_ros_to_ign(*ros_msg, ign_msg); - ign_pub.Publish(ign_msg); + GZ_T gz_msg; + convert_ros_to_gz(*ros_msg, gz_msg); + gz_pub.Publish(gz_msg); RCLCPP_INFO_ONCE( ros_node->get_logger(), - "Passing message from ROS %s to Ignition %s (showing msg only once per type)", - ros_type_name.c_str(), ign_type_name.c_str()); + "Passing message from ROS %s to Gazebo %s (showing msg only once per type)", + ros_type_name.c_str(), gz_type_name.c_str()); } static - void ign_callback( - const IGN_T & ign_msg, + void gz_callback( + const GZ_T & gz_msg, rclcpp::PublisherBase::SharedPtr ros_pub) { ROS_T ros_msg; - convert_ign_to_ros(ign_msg, ros_msg); + convert_gz_to_ros(gz_msg, ros_msg); std::shared_ptr> pub = std::dynamic_pointer_cast>(ros_pub); if (pub != nullptr) { @@ -154,19 +154,19 @@ class Factory : public FactoryInterface // public defined outside of the class static void - convert_ros_to_ign( + convert_ros_to_gz( const ROS_T & ros_msg, - IGN_T & ign_msg); + GZ_T & gz_msg); static void - convert_ign_to_ros( - const IGN_T & ign_msg, + convert_gz_to_ros( + const GZ_T & gz_msg, ROS_T & ros_msg); std::string ros_type_name_; - std::string ign_type_name_; + std::string gz_type_name_; }; -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge #endif // FACTORY_HPP_ diff --git a/ros_gz_bridge/src/factory_interface.cpp b/ros_gz_bridge/src/factory_interface.cpp index 4f0e91e0..aedc6bdb 100644 --- a/ros_gz_bridge/src/factory_interface.cpp +++ b/ros_gz_bridge/src/factory_interface.cpp @@ -14,11 +14,11 @@ #include "factory_interface.hpp" -namespace ros_ign_bridge +namespace ros_gz_bridge { FactoryInterface::~FactoryInterface() { } -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge diff --git a/ros_gz_bridge/src/factory_interface.hpp b/ros_gz_bridge/src/factory_interface.hpp index 8cca78dd..8f014655 100644 --- a/ros_gz_bridge/src/factory_interface.hpp +++ b/ros_gz_bridge/src/factory_interface.hpp @@ -18,13 +18,13 @@ #include #include -// include Ignition Transport +// include Gazebo Transport #include // include ROS 2 #include -namespace ros_ign_bridge +namespace ros_gz_bridge { class FactoryInterface @@ -42,8 +42,8 @@ class FactoryInterface virtual ignition::transport::Node::Publisher - create_ign_publisher( - std::shared_ptr ign_node, + create_gz_publisher( + std::shared_ptr gz_node, const std::string & topic_name, size_t queue_size) = 0; @@ -53,17 +53,17 @@ class FactoryInterface rclcpp::Node::SharedPtr ros_node, const std::string & topic_name, size_t queue_size, - ignition::transport::Node::Publisher & ign_pub) = 0; + ignition::transport::Node::Publisher & gz_pub) = 0; virtual void - create_ign_subscriber( + create_gz_subscriber( std::shared_ptr node, const std::string & topic_name, size_t queue_size, rclcpp::PublisherBase::SharedPtr ros_pub) = 0; }; -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge #endif // FACTORY_INTERFACE_HPP_ diff --git a/ros_gz_bridge/src/parameter_bridge.cpp b/ros_gz_bridge/src/parameter_bridge.cpp index 3ceb19f6..3966971f 100644 --- a/ros_gz_bridge/src/parameter_bridge.cpp +++ b/ros_gz_bridge/src/parameter_bridge.cpp @@ -18,7 +18,7 @@ #include #include -// include Ignition Transport +// include Gazebo Transport #include // include ROS 2 @@ -31,10 +31,10 @@ enum Direction { // Both directions. BIDIRECTIONAL = 0, - // Only from IGN to ROS - FROM_IGN_TO_ROS = 1, - // Only from ROS to IGN - FROM_ROS_TO_IGN = 2, + // Only from GZ to ROS + FROM_GZ_TO_ROS = 1, + // Only from ROS to GZ + FROM_ROS_TO_GZ = 2, // Unspecified, only used for services DIR_UNSPECIFIED = 3, }; @@ -42,37 +42,37 @@ enum Direction ////////////////////////////////////////////////// void usage() { - std::cout << "Bridge a collection of ROS2 and Ignition Transport topics and services.\n\n" << + std::cout << "Bridge a collection of ROS2 and Gazebo Transport topics and services.\n\n" << " parameter_bridge [ ..] " << " [ ..]\n\n" << "Topics: The first @ symbol delimits the topic name from the message types.\n" << "Following the first @ symbol is the ROS message type.\n" << "The ROS message type is followed by an @, [, or ] symbol where\n" << " @ == a bidirectional bridge, \n" << - " [ == a bridge from Ignition to ROS,\n" << - " ] == a bridge from ROS to Ignition.\n" << - "Following the direction symbol is the Ignition Transport message " << + " [ == a bridge from Gazebo to ROS,\n" << + " ] == a bridge from ROS to Gazebo.\n" << + "Following the direction symbol is the Gazebo Transport message " << "type.\n\n" << "Services: The first @ symbol delimits the service name from the types.\n" << "Following the first @ symbol is the ROS service type.\n" << - "Optionally, you can include the Ignition request and response type\n" << + "Optionally, you can include the Gazebo request and response type\n" << "separated by the @ symbol.\n" << - "It is only supported to expose Ignition servces as ROS services, i.e.\n" - "the ROS service will forward request to the Ignition service and then forward\n" + "It is only supported to expose Gazebo servces as ROS services, i.e.\n" + "the ROS service will forward request to the Gazebo service and then forward\n" "the response back to the ROS client.\n\n" "A bidirectional bridge example:\n" << " parameter_bridge /chatter@std_msgs/String@ignition.msgs" << ".StringMsg\n\n" << - "A bridge from Ignition to ROS example:\n" << + "A bridge from Gazebo to ROS example:\n" << " parameter_bridge /chatter@std_msgs/String[ignition.msgs" << ".StringMsg\n\n" << - "A bridge from ROS to Ignition example:\n" << + "A bridge from ROS to Gazebo example:\n" << " parameter_bridge /chatter@std_msgs/String]ignition.msgs" << ".StringMsg\n" << "A service bridge:\n" << - " parameter_bridge /world/default/control@ros_ign_interfaces/srv/ControlWorld\n" << + " parameter_bridge /world/default/control@ros_gz_interfaces/srv/ControlWorld\n" << "Or equivalently:\n" << - " parameter_bridge /world/default/control@ros_ign_interfaces/srv/ControlWorld@" + " parameter_bridge /world/default/control@ros_gz_interfaces/srv/ControlWorld@" "ignition.msgs.WorldControl@ignition.msgs.Boolean\n" << std::endl; } @@ -89,15 +89,15 @@ int main(int argc, char * argv[]) auto filteredArgs = rclcpp::init_and_remove_ros_arguments(argc, argv); // ROS 2 node - auto ros_node = std::make_shared("ros_ign_bridge"); + auto ros_node = std::make_shared("ros_gz_bridge"); - // Ignition node - auto ign_node = std::make_shared(); + // Gazebo node + auto gz_node = std::make_shared(); - std::vector bidirectional_handles; - std::vector ign_to_ros_handles; - std::vector ros_to_ign_handles; - std::vector service_bridge_handles; + std::vector bidirectional_handles; + std::vector gz_to_ros_handles; + std::vector ros_to_gz_handles; + std::vector service_bridge_handles; // Filter arguments (i.e. remove ros args) then parse all the remaining ones const std::string delim = "@"; @@ -128,17 +128,17 @@ int main(int argc, char * argv[]) } else if (delimPos == std::string::npos) { direction = DIR_UNSPECIFIED; } else { - direction = FROM_ROS_TO_IGN; + direction = FROM_ROS_TO_GZ; } } else { - direction = FROM_IGN_TO_ROS; + direction = FROM_GZ_TO_ROS; } } std::string ros_type_name = arg.substr(0, delimPos); arg.erase(0, delimPos + delim.size()); if (ros_type_name.find("/srv/") != std::string::npos) { - std::string ign_req_type_name; - std::string ign_rep_type_name; + std::string gz_req_type_name; + std::string gz_rep_type_name; if (direction != DIR_UNSPECIFIED && direction != BIDIRECTIONAL) { usage(); return -1; @@ -149,18 +149,18 @@ int main(int argc, char * argv[]) usage(); return -1; } - ign_req_type_name = arg.substr(0, delimPos); + gz_req_type_name = arg.substr(0, delimPos); arg.erase(0, delimPos + delim.size()); - ign_rep_type_name = std::move(arg); + gz_rep_type_name = std::move(arg); } try { service_bridge_handles.push_back( - ros_ign_bridge::create_service_bridge( + ros_gz_bridge::create_service_bridge( ros_node, - ign_node, + gz_node, ros_type_name, - ign_req_type_name, - ign_rep_type_name, + gz_req_type_name, + gz_rep_type_name, topic_name)); } catch (std::runtime_error & e) { std::cerr << e.what() << std::endl; @@ -173,43 +173,43 @@ int main(int argc, char * argv[]) usage(); return -1; } - std::string ign_type_name = arg; + std::string gz_type_name = arg; try { switch (direction) { default: case BIDIRECTIONAL: bidirectional_handles.push_back( - ros_ign_bridge::create_bidirectional_bridge( - ros_node, ign_node, - ros_type_name, ign_type_name, + ros_gz_bridge::create_bidirectional_bridge( + ros_node, gz_node, + ros_type_name, gz_type_name, topic_name, queue_size)); break; - case FROM_IGN_TO_ROS: - ign_to_ros_handles.push_back( - ros_ign_bridge::create_bridge_from_ign_to_ros( - ign_node, ros_node, - ign_type_name, topic_name, queue_size, + case FROM_GZ_TO_ROS: + gz_to_ros_handles.push_back( + ros_gz_bridge::create_bridge_from_gz_to_ros( + gz_node, ros_node, + gz_type_name, topic_name, queue_size, ros_type_name, topic_name, queue_size)); break; - case FROM_ROS_TO_IGN: - ros_to_ign_handles.push_back( - ros_ign_bridge::create_bridge_from_ros_to_ign( - ros_node, ign_node, + case FROM_ROS_TO_GZ: + ros_to_gz_handles.push_back( + ros_gz_bridge::create_bridge_from_ros_to_gz( + ros_node, gz_node, ros_type_name, topic_name, queue_size, - ign_type_name, topic_name, queue_size)); + gz_type_name, topic_name, queue_size)); break; } } catch (std::runtime_error & _e) { std::cerr << "Failed to create a bridge for topic [" << topic_name << "] " << "with ROS2 type [" << ros_type_name << "] and " << - "Ignition Transport type [" << ign_type_name << "]" << std::endl; + "Gazebo Transport type [" << gz_type_name << "]" << std::endl; } } // ROS 2 spinner rclcpp::spin(ros_node); - // Wait for ign node shutdown + // Wait for gz node shutdown ignition::transport::waitForShutdown(); return 0; diff --git a/ros_gz_bridge/src/service_factories/ros_gz_interfaces.cpp b/ros_gz_bridge/src/service_factories/ros_gz_interfaces.cpp index 70f9e788..4a810435 100644 --- a/ros_gz_bridge/src/service_factories/ros_gz_interfaces.cpp +++ b/ros_gz_bridge/src/service_factories/ros_gz_interfaces.cpp @@ -12,34 +12,34 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "factories/ros_ign_interfaces.hpp" +#include "factories/ros_gz_interfaces.hpp" #include #include -#include "ros_ign_interfaces/srv/control_world.hpp" +#include "ros_gz_interfaces/srv/control_world.hpp" #include "service_factory.hpp" -#include "ros_ign_bridge/convert/ros_ign_interfaces.hpp" +#include "ros_gz_bridge/convert/ros_gz_interfaces.hpp" -namespace ros_ign_bridge +namespace ros_gz_bridge { std::shared_ptr -get_service_factory__ros_ign_interfaces( +get_service_factory__ros_gz_interfaces( const std::string & ros_type_name, - const std::string & ign_req_type_name, - const std::string & ign_rep_type_name) + const std::string & gz_req_type_name, + const std::string & gz_rep_type_name) { if ( - ros_type_name == "ros_ign_interfaces/srv/ControlWorld" && - (ign_req_type_name.empty() || ign_req_type_name == "ignition.msgs.WorldControl") && - (ign_rep_type_name.empty() || ign_rep_type_name == "ignition.msgs.Boolean")) + ros_type_name == "ros_gz_interfaces/srv/ControlWorld" && + (gz_req_type_name.empty() || gz_req_type_name == "ignition.msgs.WorldControl") && + (gz_rep_type_name.empty() || gz_rep_type_name == "ignition.msgs.Boolean")) { return std::make_shared< ServiceFactory< - ros_ign_interfaces::srv::ControlWorld, + ros_gz_interfaces::srv::ControlWorld, ignition::msgs::WorldControl, ignition::msgs::Boolean> >(ros_type_name, "ignition.msgs.WorldControl", "ignition.msgs.Boolean"); @@ -49,29 +49,29 @@ get_service_factory__ros_ign_interfaces( template<> void -convert_ros_to_ign( - const ros_ign_interfaces::srv::ControlWorld::Request & ros_req, - ignition::msgs::WorldControl & ign_req) +convert_ros_to_gz( + const ros_gz_interfaces::srv::ControlWorld::Request & ros_req, + ignition::msgs::WorldControl & gz_req) { - convert_ros_to_ign(ros_req.world_control, ign_req); + convert_ros_to_gz(ros_req.world_control, gz_req); } template<> void -convert_ign_to_ros( - const ignition::msgs::Boolean & ign_rep, - ros_ign_interfaces::srv::ControlWorld::Response & ros_res) +convert_gz_to_ros( + const ignition::msgs::Boolean & gz_rep, + ros_gz_interfaces::srv::ControlWorld::Response & ros_res) { - ros_res.success = ign_rep.data(); + ros_res.success = gz_rep.data(); } template<> bool -send_response_on_error(ros_ign_interfaces::srv::ControlWorld::Response & ros_res) +send_response_on_error(ros_gz_interfaces::srv::ControlWorld::Response & ros_res) { // TODO(now): Is it worth it to have a different field to encode ignition request errors? // Currently we're reusing the success field, which seems fine for this case. ros_res.success = false; return true; } -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge diff --git a/ros_gz_bridge/src/service_factories/ros_gz_interfaces.hpp b/ros_gz_bridge/src/service_factories/ros_gz_interfaces.hpp index b28a9e27..572c1b70 100644 --- a/ros_gz_bridge/src/service_factories/ros_gz_interfaces.hpp +++ b/ros_gz_bridge/src/service_factories/ros_gz_interfaces.hpp @@ -12,23 +12,23 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef SERVICE_FACTORIES__ROS_IGN_INTERFACES_HPP_ -#define SERVICE_FACTORIES__ROS_IGN_INTERFACES_HPP_ +#ifndef SERVICE_FACTORIES__ROS_GZ_INTERFACES_HPP_ +#define SERVICE_FACTORIES__ROS_GZ_INTERFACES_HPP_ #include #include #include "service_factory_interface.hpp" -namespace ros_ign_bridge +namespace ros_gz_bridge { std::shared_ptr -get_service_factory__ros_ign_interfaces( +get_service_factory__ros_gz_interfaces( const std::string & ros_type_name, - const std::string & ign_req_type_name, - const std::string & ign_rep_type_name); + const std::string & gz_req_type_name, + const std::string & gz_rep_type_name); -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge -#endif // SERVICE_FACTORIES__ROS_IGN_INTERFACES_HPP_ +#endif // SERVICE_FACTORIES__ROS_GZ_INTERFACES_HPP_ diff --git a/ros_gz_bridge/src/service_factory.hpp b/ros_gz_bridge/src/service_factory.hpp index a01637d6..d4a44d74 100644 --- a/ros_gz_bridge/src/service_factory.hpp +++ b/ros_gz_bridge/src/service_factory.hpp @@ -24,11 +24,11 @@ #include -#include "ros_ign_bridge/convert_decl.hpp" +#include "ros_gz_bridge/convert_decl.hpp" #include "service_factory_interface.hpp" -namespace ros_ign_bridge +namespace ros_gz_bridge { template @@ -40,22 +40,22 @@ class ServiceFactory : public ServiceFactoryInterface { public: ServiceFactory( - const std::string & ros_type_name, const std::string & ign_req_type_name, - const std::string & ign_rep_type_name) + const std::string & ros_type_name, const std::string & gz_req_type_name, + const std::string & gz_rep_type_name) : ros_type_name_(ros_type_name), - ign_req_type_name_(ign_req_type_name), - ign_rep_type_name_(ign_rep_type_name) + gz_req_type_name_(gz_req_type_name), + gz_rep_type_name_(gz_rep_type_name) {} rclcpp::ServiceBase::SharedPtr create_ros_service( rclcpp::Node::SharedPtr ros_node, - std::shared_ptr ign_node, + std::shared_ptr gz_node, const std::string & service_name) override { return ros_node->create_service( service_name, - [ign_node = std::move(ign_node), service_name]( + [gz_node = std::move(gz_node), service_name]( std::shared_ptr> srv_handle, std::shared_ptr reqid, std::shared_ptr ros_req) @@ -74,24 +74,24 @@ class ServiceFactory : public ServiceFactoryInterface srv_handle->send_response(*reqid, ros_res); } } - convert_ign_to_ros(reply, ros_res); + convert_gz_to_ros(reply, ros_res); srv_handle->send_response(*reqid, ros_res); }; - IgnRequestT ign_req; - convert_ros_to_ign(*ros_req, ign_req); - ign_node->Request( + IgnRequestT gz_req; + convert_ros_to_gz(*ros_req, gz_req); + gz_node->Request( service_name, - ign_req, + gz_req, callback); }); } private: std::string ros_type_name_; - std::string ign_req_type_name_; - std::string ign_rep_type_name_; + std::string gz_req_type_name_; + std::string gz_rep_type_name_; }; -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge #endif // SERVICE_FACTORY_HPP_ diff --git a/ros_gz_bridge/src/service_factory_interface.hpp b/ros_gz_bridge/src/service_factory_interface.hpp index 29d6ad4a..4905994e 100644 --- a/ros_gz_bridge/src/service_factory_interface.hpp +++ b/ros_gz_bridge/src/service_factory_interface.hpp @@ -23,7 +23,7 @@ #include #include -namespace ros_ign_bridge +namespace ros_gz_bridge { class ServiceFactoryInterface @@ -33,10 +33,10 @@ class ServiceFactoryInterface rclcpp::ServiceBase::SharedPtr create_ros_service( rclcpp::Node::SharedPtr ros_node, - std::shared_ptr ign_node, + std::shared_ptr gz_node, const std::string & service_name) = 0; }; -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge #endif // SERVICE_FACTORY_INTERFACE_HPP_ diff --git a/ros_gz_bridge/src/static_bridge.cpp b/ros_gz_bridge/src/static_bridge.cpp index 0f431223..5288d2c3 100644 --- a/ros_gz_bridge/src/static_bridge.cpp +++ b/ros_gz_bridge/src/static_bridge.cpp @@ -15,7 +15,7 @@ #include #include -// include Ignition Transport +// include Gazebo Transport #include // include ROS 2 @@ -31,21 +31,21 @@ int main(int argc, char * argv[]) rclcpp::init(argc, argv); auto ros_node = std::make_shared("test_node"); - // Ignition node - auto ign_node = std::make_shared(); + // Gazebo node + auto gz_node = std::make_shared(); // bridge one example topic std::string topic_name = "chatter"; std::string ros_type_name = "std_msgs/msg/String"; - std::string ign_type_name = "ignition.msgs.StringMsg"; + std::string gz_type_name = "ignition.msgs.StringMsg"; size_t queue_size = 10; - auto handles = ros_ign_bridge::create_bidirectional_bridge( - ros_node, ign_node, ros_type_name, ign_type_name, topic_name, queue_size); + auto handles = ros_gz_bridge::create_bidirectional_bridge( + ros_node, gz_node, ros_type_name, gz_type_name, topic_name, queue_size); rclcpp::spin(ros_node); - // Wait for ign node shutdown + // Wait for gz node shutdown ignition::transport::waitForShutdown(); return 0; diff --git a/ros_gz_bridge/test/launch/test_gz_server.launch.py b/ros_gz_bridge/test/launch/test_gz_server.launch.py index f9fd4d53..13770de5 100644 --- a/ros_gz_bridge/test/launch/test_gz_server.launch.py +++ b/ros_gz_bridge/test/launch/test_gz_server.launch.py @@ -24,22 +24,22 @@ def generate_test_description(): server = Node( - package='ros_ign_bridge', - executable='test_ign_server', + package='ros_gz_bridge', + executable='test_gz_server', output='screen' ) process_under_test = Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='test_ros_client', output='screen' ) # Bridge bridge = Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='parameter_bridge', arguments=[ - '/ign_ros/test/serviceclient/world_control@ros_ign_interfaces/srv/ControlWorld', + '/gz_ros/test/serviceclient/world_control@ros_gz_interfaces/srv/ControlWorld', ], output='screen' ) diff --git a/ros_gz_bridge/test/launch/test_gz_subscriber.launch.py b/ros_gz_bridge/test/launch/test_gz_subscriber.launch.py index 2df7cb00..7430e662 100644 --- a/ros_gz_bridge/test/launch/test_gz_subscriber.launch.py +++ b/ros_gz_bridge/test/launch/test_gz_subscriber.launch.py @@ -24,19 +24,19 @@ def generate_test_description(): publisher = Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='test_ros_publisher', output='screen' ) process_under_test = Node( - package='ros_ign_bridge', - executable='test_ign_subscriber', + package='ros_gz_bridge', + executable='test_gz_subscriber', output='screen' ) # Bridge bridge = Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='parameter_bridge', arguments=[ '/time@builtin_interfaces/msg/Time@ignition.msgs.Time', @@ -63,15 +63,15 @@ def generate_test_description(): '/twist_with_covariance@geometry_msgs/msg/TwistWithCovariance@' 'ignition.msgs.TwistWithCovariance', '/wrench@geometry_msgs/msg/Wrench@ignition.msgs.Wrench', - '/joint_wrench@ros_ign_interfaces/msg/JointWrench@ignition.msgs.JointWrench', - '/entity@ros_ign_interfaces/msg/Entity@ignition.msgs.Entity', - '/contact@ros_ign_interfaces/msg/Contact@ignition.msgs.Contact', - '/contacts@ros_ign_interfaces/msg/Contacts@ignition.msgs.Contacts', - '/light@ros_ign_interfaces/msg/Light@ignition.msgs.Light', - '/gui_camera@ros_ign_interfaces/msg/GuiCamera@ignition.msgs.GUICamera', - '/stringmsg_v@ros_ign_interfaces/msg/StringVec@ignition.msgs.StringMsg_V', - '/track_visual@ros_ign_interfaces/msg/TrackVisual@ignition.msgs.TrackVisual', - '/video_record@ros_ign_interfaces/msg/VideoRecord@ignition.msgs.VideoRecord', + '/joint_wrench@ros_gz_interfaces/msg/JointWrench@ignition.msgs.JointWrench', + '/entity@ros_gz_interfaces/msg/Entity@ignition.msgs.Entity', + '/contact@ros_gz_interfaces/msg/Contact@ignition.msgs.Contact', + '/contacts@ros_gz_interfaces/msg/Contacts@ignition.msgs.Contacts', + '/light@ros_gz_interfaces/msg/Light@ignition.msgs.Light', + '/gui_camera@ros_gz_interfaces/msg/GuiCamera@ignition.msgs.GUICamera', + '/stringmsg_v@ros_gz_interfaces/msg/StringVec@ignition.msgs.StringMsg_V', + '/track_visual@ros_gz_interfaces/msg/TrackVisual@ignition.msgs.TrackVisual', + '/video_record@ros_gz_interfaces/msg/VideoRecord@ignition.msgs.VideoRecord', '/image@sensor_msgs/msg/Image@ignition.msgs.Image', '/camera_info@sensor_msgs/msg/CameraInfo@ignition.msgs.CameraInfo', '/fluid_pressure@sensor_msgs/msg/FluidPressure@ignition.msgs.FluidPressure', diff --git a/ros_gz_bridge/test/launch/test_ros_subscriber.launch.py b/ros_gz_bridge/test/launch/test_ros_subscriber.launch.py index 93415b7a..f411ea30 100644 --- a/ros_gz_bridge/test/launch/test_ros_subscriber.launch.py +++ b/ros_gz_bridge/test/launch/test_ros_subscriber.launch.py @@ -24,19 +24,19 @@ def generate_test_description(): publisher = Node( - package='ros_ign_bridge', - executable='test_ign_publisher', + package='ros_gz_bridge', + executable='test_gz_publisher', output='screen' ) process_under_test = Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='test_ros_subscriber', output='screen' ) # Bridge bridge = Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='parameter_bridge', arguments=[ '/time@builtin_interfaces/msg/Time@ignition.msgs.Time', @@ -63,15 +63,15 @@ def generate_test_description(): '/twist_with_covariance@geometry_msgs/msg/TwistWithCovariance@' 'ignition.msgs.TwistWithCovariance', '/wrench@geometry_msgs/msg/Wrench@ignition.msgs.Wrench', - '/joint_wrench@ros_ign_interfaces/msg/JointWrench@ignition.msgs.JointWrench', - '/entity@ros_ign_interfaces/msg/Entity@ignition.msgs.Entity', - '/contact@ros_ign_interfaces/msg/Contact@ignition.msgs.Contact', - '/contacts@ros_ign_interfaces/msg/Contacts@ignition.msgs.Contacts', - '/light@ros_ign_interfaces/msg/Light@ignition.msgs.Light', - '/gui_camera@ros_ign_interfaces/msg/GuiCamera@ignition.msgs.GUICamera', - '/stringmsg_v@ros_ign_interfaces/msg/StringVec@ignition.msgs.StringMsg_V', - '/track_visual@ros_ign_interfaces/msg/TrackVisual@ignition.msgs.TrackVisual', - '/video_record@ros_ign_interfaces/msg/VideoRecord@ignition.msgs.VideoRecord', + '/joint_wrench@ros_gz_interfaces/msg/JointWrench@ignition.msgs.JointWrench', + '/entity@ros_gz_interfaces/msg/Entity@ignition.msgs.Entity', + '/contact@ros_gz_interfaces/msg/Contact@ignition.msgs.Contact', + '/contacts@ros_gz_interfaces/msg/Contacts@ignition.msgs.Contacts', + '/light@ros_gz_interfaces/msg/Light@ignition.msgs.Light', + '/gui_camera@ros_gz_interfaces/msg/GuiCamera@ignition.msgs.GUICamera', + '/stringmsg_v@ros_gz_interfaces/msg/StringVec@ignition.msgs.StringMsg_V', + '/track_visual@ros_gz_interfaces/msg/TrackVisual@ignition.msgs.TrackVisual', + '/video_record@ros_gz_interfaces/msg/VideoRecord@ignition.msgs.VideoRecord', '/image@sensor_msgs/msg/Image@ignition.msgs.Image', '/camera_info@sensor_msgs/msg/CameraInfo@ignition.msgs.CameraInfo', '/fluid_pressure@sensor_msgs/msg/FluidPressure@ignition.msgs.FluidPressure', diff --git a/ros_gz_bridge/test/publishers/gz_publisher.cpp b/ros_gz_bridge/test/publishers/gz_publisher.cpp index 28aa36d6..aa32bfc7 100644 --- a/ros_gz_bridge/test/publishers/gz_publisher.cpp +++ b/ros_gz_bridge/test/publishers/gz_publisher.cpp @@ -23,7 +23,7 @@ #include #include "utils/test_utils.hpp" -#include "utils/ign_test_msg.hpp" +#include "utils/gz_test_msg.hpp" /// \brief Flag used to break the publisher loop and terminate the program. static std::atomic g_terminatePub(false); @@ -52,17 +52,17 @@ int main(int /*argc*/, char **/*argv*/) // ignition::msgs::Color. auto color_pub = node.Advertise("color"); ignition::msgs::Color color_msg; - ros_ign_bridge::testing::createTestMsg(color_msg); + ros_gz_bridge::testing::createTestMsg(color_msg); // ignition::msgs::Light. auto light_pub = node.Advertise("light"); ignition::msgs::Light light_msg; - ros_ign_bridge::testing::createTestMsg(light_msg); + ros_gz_bridge::testing::createTestMsg(light_msg); // ignition::msgs::Boolean. auto bool_pub = node.Advertise("bool"); ignition::msgs::Boolean bool_msg; - ros_ign_bridge::testing::createTestMsg(bool_msg); + ros_gz_bridge::testing::createTestMsg(bool_msg); // ignition::msgs::Empty. auto empty_pub = node.Advertise("empty"); @@ -71,209 +71,209 @@ int main(int /*argc*/, char **/*argv*/) // ignition::msgs::Float. auto float_pub = node.Advertise("float"); ignition::msgs::Float float_msg; - ros_ign_bridge::testing::createTestMsg(float_msg); + ros_gz_bridge::testing::createTestMsg(float_msg); // ignition::msgs::Double. auto double_pub = node.Advertise("double"); ignition::msgs::Double double_msg; - ros_ign_bridge::testing::createTestMsg(double_msg); + ros_gz_bridge::testing::createTestMsg(double_msg); // ignition::msgs::Uint32. auto uint32_pub = node.Advertise("uint32"); ignition::msgs::UInt32 uint32_msg; - ros_ign_bridge::testing::createTestMsg(uint32_msg); + ros_gz_bridge::testing::createTestMsg(uint32_msg); // ignition::msgs::Header. auto header_pub = node.Advertise("header"); ignition::msgs::Header header_msg; - ros_ign_bridge::testing::createTestMsg(header_msg); + ros_gz_bridge::testing::createTestMsg(header_msg); // ignition::msgs::StringMsg. auto string_pub = node.Advertise("string"); ignition::msgs::StringMsg string_msg; - ros_ign_bridge::testing::createTestMsg(string_msg); + ros_gz_bridge::testing::createTestMsg(string_msg); // ignition::msgs::Quaternion. auto quaternion_pub = node.Advertise("quaternion"); ignition::msgs::Quaternion quaternion_msg; - ros_ign_bridge::testing::createTestMsg(quaternion_msg); + ros_gz_bridge::testing::createTestMsg(quaternion_msg); // ignition::msgs::Vector3d. auto vector3_pub = node.Advertise("vector3"); ignition::msgs::Vector3d vector3_msg; - ros_ign_bridge::testing::createTestMsg(vector3_msg); + ros_gz_bridge::testing::createTestMsg(vector3_msg); // ignition::msgs::Clock. auto clock_pub = node.Advertise("clock"); ignition::msgs::Clock clock_msg; - ros_ign_bridge::testing::createTestMsg(clock_msg); + ros_gz_bridge::testing::createTestMsg(clock_msg); // ignition::msgs::Point. auto point_pub = node.Advertise("point"); ignition::msgs::Vector3d point_msg; - ros_ign_bridge::testing::createTestMsg(point_msg); + ros_gz_bridge::testing::createTestMsg(point_msg); // ignition::msgs::Pose. auto pose_pub = node.Advertise("pose"); ignition::msgs::Pose pose_msg; - ros_ign_bridge::testing::createTestMsg(pose_msg); + ros_gz_bridge::testing::createTestMsg(pose_msg); // ignition::msgs::PoseWithCovariance. auto pose_cov_pub = node.Advertise("pose_with_covariance"); ignition::msgs::PoseWithCovariance pose_cov_msg; - ros_ign_bridge::testing::createTestMsg(pose_cov_msg); + ros_gz_bridge::testing::createTestMsg(pose_cov_msg); // ignition::msgs::PoseStamped. auto pose_stamped_pub = node.Advertise("pose_stamped"); ignition::msgs::Pose pose_stamped_msg; - ros_ign_bridge::testing::createTestMsg(pose_stamped_msg); + ros_gz_bridge::testing::createTestMsg(pose_stamped_msg); // ignition::msgs::Transform. auto transform_pub = node.Advertise("transform"); ignition::msgs::Pose transform_msg; - ros_ign_bridge::testing::createTestMsg(transform_msg); + ros_gz_bridge::testing::createTestMsg(transform_msg); // ignition::msgs::TransformStamped. auto transform_stamped_pub = node.Advertise("transform_stamped"); ignition::msgs::Pose transform_stamped_msg; - ros_ign_bridge::testing::createTestMsg(transform_stamped_msg); + ros_gz_bridge::testing::createTestMsg(transform_stamped_msg); // ignition::msgs::Pose_V. auto tf2_message_pub = node.Advertise("tf2_message"); ignition::msgs::Pose_V tf2_msg; - ros_ign_bridge::testing::createTestMsg(tf2_msg); + ros_gz_bridge::testing::createTestMsg(tf2_msg); // ignition::msgs::Image. auto image_pub = node.Advertise("image"); ignition::msgs::Image image_msg; - ros_ign_bridge::testing::createTestMsg(image_msg); + ros_gz_bridge::testing::createTestMsg(image_msg); // ignition::msgs::CameraInfo. auto camera_info_pub = node.Advertise("camera_info"); ignition::msgs::CameraInfo camera_info_msg; - ros_ign_bridge::testing::createTestMsg(camera_info_msg); + ros_gz_bridge::testing::createTestMsg(camera_info_msg); // ignition::msgs::FluidPressure. auto fluid_pressure_pub = node.Advertise("fluid_pressure"); ignition::msgs::FluidPressure fluid_pressure_msg; - ros_ign_bridge::testing::createTestMsg(fluid_pressure_msg); + ros_gz_bridge::testing::createTestMsg(fluid_pressure_msg); // ignition::msgs::IMU. auto imu_pub = node.Advertise("imu"); ignition::msgs::IMU imu_msg; - ros_ign_bridge::testing::createTestMsg(imu_msg); + ros_gz_bridge::testing::createTestMsg(imu_msg); // ignition::msgs::LaserScan. auto laserscan_pub = node.Advertise("laserscan"); ignition::msgs::LaserScan laserscan_msg; - ros_ign_bridge::testing::createTestMsg(laserscan_msg); + ros_gz_bridge::testing::createTestMsg(laserscan_msg); // ignition::msgs::Magnetometer. auto magnetic_pub = node.Advertise("magnetic"); ignition::msgs::Magnetometer magnetometer_msg; - ros_ign_bridge::testing::createTestMsg(magnetometer_msg); + ros_gz_bridge::testing::createTestMsg(magnetometer_msg); // ignition::msgs::Actuators. auto actuators_pub = node.Advertise("actuators"); ignition::msgs::Actuators actuators_msg; - ros_ign_bridge::testing::createTestMsg(actuators_msg); + ros_gz_bridge::testing::createTestMsg(actuators_msg); // ignition::msgs::Odometry. auto odometry_pub = node.Advertise("odometry"); ignition::msgs::Odometry odometry_msg; - ros_ign_bridge::testing::createTestMsg(odometry_msg); + ros_gz_bridge::testing::createTestMsg(odometry_msg); // ignition::msgs::OdometryWithCovariance. auto odometry_cov_pub = node.Advertise( "odometry_with_covariance"); ignition::msgs::OdometryWithCovariance odometry_cov_msg; - ros_ign_bridge::testing::createTestMsg(odometry_cov_msg); + ros_gz_bridge::testing::createTestMsg(odometry_cov_msg); // ignition::msgs::Model. auto joint_states_pub = node.Advertise("joint_states"); ignition::msgs::Model joint_states_msg; - ros_ign_bridge::testing::createTestMsg(joint_states_msg); + ros_gz_bridge::testing::createTestMsg(joint_states_msg); // ignition::msgs::Twist. auto twist_pub = node.Advertise("twist"); ignition::msgs::Twist twist_msg; - ros_ign_bridge::testing::createTestMsg(twist_msg); + ros_gz_bridge::testing::createTestMsg(twist_msg); // ignition::msgs::TwistWithCovariance. auto twist_cov_pub = node.Advertise( "twist_with_covariance"); ignition::msgs::TwistWithCovariance twist_cov_msg; - ros_ign_bridge::testing::createTestMsg(twist_cov_msg); + ros_gz_bridge::testing::createTestMsg(twist_cov_msg); // ignition::msgs::Wrench. auto wrench_pub = node.Advertise("wrench"); ignition::msgs::Wrench wrench_msg; - ros_ign_bridge::testing::createTestMsg(wrench_msg); + ros_gz_bridge::testing::createTestMsg(wrench_msg); // ignition::msgs::JointWrench. auto joint_wrench_pub = node.Advertise("joint_wrench"); ignition::msgs::JointWrench joint_wrench_msg; - ros_ign_bridge::testing::createTestMsg(joint_wrench_msg); + ros_gz_bridge::testing::createTestMsg(joint_wrench_msg); // ignition::msgs::Entity. auto entity_pub = node.Advertise("entity"); ignition::msgs::Entity entity_msg; - ros_ign_bridge::testing::createTestMsg(entity_msg); + ros_gz_bridge::testing::createTestMsg(entity_msg); // ignition::msgs::Contact. auto contact_pub = node.Advertise("contact"); ignition::msgs::Contact contact_msg; - ros_ign_bridge::testing::createTestMsg(contact_msg); + ros_gz_bridge::testing::createTestMsg(contact_msg); // ignition::msgs::Contacts. auto contacts_pub = node.Advertise("contacts"); ignition::msgs::Contacts contacts_msg; - ros_ign_bridge::testing::createTestMsg(contacts_msg); + ros_gz_bridge::testing::createTestMsg(contacts_msg); // ignition::msgs::PointCloudPacked. auto pointcloudpacked_pub = node.Advertise( "pointcloud2"); ignition::msgs::PointCloudPacked pointcloudpacked_msg; - ros_ign_bridge::testing::createTestMsg(pointcloudpacked_msg); + ros_gz_bridge::testing::createTestMsg(pointcloudpacked_msg); // ignition::msgs::BatteryState. auto battery_state_pub = node.Advertise("battery_state"); ignition::msgs::BatteryState battery_state_msg; - ros_ign_bridge::testing::createTestMsg(battery_state_msg); + ros_gz_bridge::testing::createTestMsg(battery_state_msg); // ignition::msgs::JointTrajectory. auto joint_trajectory_pub = node.Advertise("joint_trajectory"); ignition::msgs::JointTrajectory joint_trajectory_msg; - ros_ign_bridge::testing::createTestMsg(joint_trajectory_msg); + ros_gz_bridge::testing::createTestMsg(joint_trajectory_msg); // ignition::msgs::GUICamera. auto gui_camera_pub = node.Advertise("gui_camera"); ignition::msgs::GUICamera gui_camera_msg; - ros_ign_bridge::testing::createTestMsg(gui_camera_msg); + ros_gz_bridge::testing::createTestMsg(gui_camera_msg); // ignition::msgs::StringMsg_V. auto stringmsg_v_pub = node.Advertise("stringmsg_v"); ignition::msgs::StringMsg_V stringmsg_v_msg; - ros_ign_bridge::testing::createTestMsg(stringmsg_v_msg); + ros_gz_bridge::testing::createTestMsg(stringmsg_v_msg); // ignition::msgs::Time. auto time_pub = node.Advertise("time"); ignition::msgs::Time time_msg; - ros_ign_bridge::testing::createTestMsg(time_msg); + ros_gz_bridge::testing::createTestMsg(time_msg); // ignition::msgs::TrackVisual. auto track_visual_pub = node.Advertise("track_visual"); ignition::msgs::TrackVisual track_visual_msg; - ros_ign_bridge::testing::createTestMsg(track_visual_msg); + ros_gz_bridge::testing::createTestMsg(track_visual_msg); // ignition::msgs::VideoRecord. auto video_record_pub = node.Advertise("video_record"); ignition::msgs::VideoRecord video_record_msg; - ros_ign_bridge::testing::createTestMsg(video_record_msg); + ros_gz_bridge::testing::createTestMsg(video_record_msg); // Publish messages at 100Hz. while (!g_terminatePub) { diff --git a/ros_gz_bridge/test/publishers/ros_publisher.cpp b/ros_gz_bridge/test/publishers/ros_publisher.cpp index 52f72a76..5aa45d1d 100644 --- a/ros_gz_bridge/test/publishers/ros_publisher.cpp +++ b/ros_gz_bridge/test/publishers/ros_publisher.cpp @@ -26,17 +26,17 @@ int main(int argc, char ** argv) // builtin_interfaces::msg::Time. auto time_pub = node->create_publisher("time", 1); builtin_interfaces::msg::Time time_msg; - ros_ign_bridge::testing::createTestMsg(time_msg); + ros_gz_bridge::testing::createTestMsg(time_msg); // std_msgs::msg::Color. auto color_pub = node->create_publisher("color", 1); std_msgs::msg::ColorRGBA color_msg; - ros_ign_bridge::testing::createTestMsg(color_msg); + ros_gz_bridge::testing::createTestMsg(color_msg); // std_msgs::msg::Bool. auto bool_pub = node->create_publisher("bool", 1); std_msgs::msg::Bool bool_msg; - ros_ign_bridge::testing::createTestMsg(bool_msg); + ros_gz_bridge::testing::createTestMsg(bool_msg); // std_msgs::msg::Empty. auto empty_pub = node->create_publisher("empty", 1); @@ -45,238 +45,238 @@ int main(int argc, char ** argv) // std_msgs::msg::Float32. auto float_pub = node->create_publisher("float", 1); std_msgs::msg::Float32 float_msg; - ros_ign_bridge::testing::createTestMsg(float_msg); + ros_gz_bridge::testing::createTestMsg(float_msg); // std_msgs::Float64. auto double_pub = node->create_publisher("double", 1); std_msgs::msg::Float64 double_msg; - ros_ign_bridge::testing::createTestMsg(double_msg); + ros_gz_bridge::testing::createTestMsg(double_msg); // std_msgs::UInt32. auto uint32_pub = node->create_publisher("uint32", 1); std_msgs::msg::UInt32 uint32_msg; - ros_ign_bridge::testing::createTestMsg(uint32_msg); + ros_gz_bridge::testing::createTestMsg(uint32_msg); // std_msgs::msg::Header. auto header_pub = node->create_publisher("header", 1); std_msgs::msg::Header header_msg; - ros_ign_bridge::testing::createTestMsg(header_msg); + ros_gz_bridge::testing::createTestMsg(header_msg); // std_msgs::msg::String. auto string_pub = node->create_publisher("string", 1); std_msgs::msg::String string_msg; - ros_ign_bridge::testing::createTestMsg(string_msg); + ros_gz_bridge::testing::createTestMsg(string_msg); // geometry_msgs::msg::Quaternion. auto quaternion_pub = node->create_publisher("quaternion", 1); geometry_msgs::msg::Quaternion quaternion_msg; - ros_ign_bridge::testing::createTestMsg(quaternion_msg); + ros_gz_bridge::testing::createTestMsg(quaternion_msg); // geometry_msgs::msg::Vector3. auto vector3_pub = node->create_publisher("vector3", 1); geometry_msgs::msg::Vector3 vector3_msg; - ros_ign_bridge::testing::createTestMsg(vector3_msg); + ros_gz_bridge::testing::createTestMsg(vector3_msg); // sensor_msgs::msg::Clock. auto clock_pub = node->create_publisher("clock", 1); rosgraph_msgs::msg::Clock clock_msg; - ros_ign_bridge::testing::createTestMsg(clock_msg); + ros_gz_bridge::testing::createTestMsg(clock_msg); // geometry_msgs::msg::Point. auto point_pub = node->create_publisher("point", 1); geometry_msgs::msg::Point point_msg; - ros_ign_bridge::testing::createTestMsg(point_msg); + ros_gz_bridge::testing::createTestMsg(point_msg); // geometry_msgs::msg::Pose. auto pose_pub = node->create_publisher("pose", 1); geometry_msgs::msg::Pose pose_msg; - ros_ign_bridge::testing::createTestMsg(pose_msg); + ros_gz_bridge::testing::createTestMsg(pose_msg); // geometry_msgs::msg::PoseWithCovariance. auto pose_cov_pub = node->create_publisher( "pose_with_covariance", 1); geometry_msgs::msg::PoseWithCovariance pose_cov_msg; - ros_ign_bridge::testing::createTestMsg(pose_cov_msg); + ros_gz_bridge::testing::createTestMsg(pose_cov_msg); // geometry_msgs::msg::PoseStamped. auto pose_stamped_pub = node->create_publisher("pose_stamped", 1); geometry_msgs::msg::PoseStamped pose_stamped_msg; - ros_ign_bridge::testing::createTestMsg(pose_stamped_msg); + ros_gz_bridge::testing::createTestMsg(pose_stamped_msg); // geometry_msgs::msg::Transform. auto transform_pub = node->create_publisher("transform", 1); geometry_msgs::msg::Transform transform_msg; - ros_ign_bridge::testing::createTestMsg(transform_msg); + ros_gz_bridge::testing::createTestMsg(transform_msg); // geometry_msgs::msg::TransformStamped. auto transform_stamped_pub = node->create_publisher("transform_stamped", 1); geometry_msgs::msg::TransformStamped transform_stamped_msg; - ros_ign_bridge::testing::createTestMsg(transform_stamped_msg); + ros_gz_bridge::testing::createTestMsg(transform_stamped_msg); // geometry_msgs::msg::Twist. auto twist_pub = node->create_publisher("twist", 1); geometry_msgs::msg::Twist twist_msg; - ros_ign_bridge::testing::createTestMsg(twist_msg); + ros_gz_bridge::testing::createTestMsg(twist_msg); // geometry_msgs::msg::TwistWithCovariance. auto twist_cov_pub = node->create_publisher( "twist_with_covariance", 1); geometry_msgs::msg::TwistWithCovariance twist_cov_msg; - ros_ign_bridge::testing::createTestMsg(twist_cov_msg); + ros_gz_bridge::testing::createTestMsg(twist_cov_msg); auto tf2_message_pub = node->create_publisher("tf2_message", 1); tf2_msgs::msg::TFMessage tf2_msg; - ros_ign_bridge::testing::createTestMsg(tf2_msg); + ros_gz_bridge::testing::createTestMsg(tf2_msg); // geometry_msgs::msg::Wrench. auto wrench_pub = node->create_publisher("wrench", 1); geometry_msgs::msg::Wrench wrench_msg; - ros_ign_bridge::testing::createTestMsg(wrench_msg); + ros_gz_bridge::testing::createTestMsg(wrench_msg); - // ros_ign_interfaces::msg::Light. + // ros_gz_interfaces::msg::Light. auto light_pub = - node->create_publisher("light", 1); - ros_ign_interfaces::msg::Light light_msg; - ros_ign_bridge::testing::createTestMsg(light_msg); + node->create_publisher("light", 1); + ros_gz_interfaces::msg::Light light_msg; + ros_gz_bridge::testing::createTestMsg(light_msg); - // ros_ign_interfaces::msg::JointWrench. + // ros_gz_interfaces::msg::JointWrench. auto joint_wrench_pub = - node->create_publisher("joint_wrench", 1); - ros_ign_interfaces::msg::JointWrench joint_wrench_msg; - ros_ign_bridge::testing::createTestMsg(joint_wrench_msg); + node->create_publisher("joint_wrench", 1); + ros_gz_interfaces::msg::JointWrench joint_wrench_msg; + ros_gz_bridge::testing::createTestMsg(joint_wrench_msg); - // ros_ign_interfaces::msg::Entity. + // ros_gz_interfaces::msg::Entity. auto entity_pub = - node->create_publisher("entity", 1); - ros_ign_interfaces::msg::Entity entity_msg; - ros_ign_bridge::testing::createTestMsg(entity_msg); + node->create_publisher("entity", 1); + ros_gz_interfaces::msg::Entity entity_msg; + ros_gz_bridge::testing::createTestMsg(entity_msg); - // ros_ign_interfaces::msg::Contact. + // ros_gz_interfaces::msg::Contact. auto contact_pub = - node->create_publisher("contact", 1); - ros_ign_interfaces::msg::Contact contact_msg; - ros_ign_bridge::testing::createTestMsg(contact_msg); + node->create_publisher("contact", 1); + ros_gz_interfaces::msg::Contact contact_msg; + ros_gz_bridge::testing::createTestMsg(contact_msg); - // ros_ign_interfaces::msg::Contacts. + // ros_gz_interfaces::msg::Contacts. auto contacts_pub = - node->create_publisher("contacts", 1); - ros_ign_interfaces::msg::Contacts contacts_msg; - ros_ign_bridge::testing::createTestMsg(contacts_msg); + node->create_publisher("contacts", 1); + ros_gz_interfaces::msg::Contacts contacts_msg; + ros_gz_bridge::testing::createTestMsg(contacts_msg); - // ros_ign_interfaces::msg::GuiCamera. + // ros_gz_interfaces::msg::GuiCamera. auto gui_camera_pub = - node->create_publisher("gui_camera", 1); - ros_ign_interfaces::msg::GuiCamera gui_camera_msg; - ros_ign_bridge::testing::createTestMsg(gui_camera_msg); + node->create_publisher("gui_camera", 1); + ros_gz_interfaces::msg::GuiCamera gui_camera_msg; + ros_gz_bridge::testing::createTestMsg(gui_camera_msg); - // ros_ign_interfaces::msg::StringVec. + // ros_gz_interfaces::msg::StringVec. auto stringmsg_v_pub = - node->create_publisher("stringmsg_v", 1); - ros_ign_interfaces::msg::StringVec stringmsg_v_msg; - ros_ign_bridge::testing::createTestMsg(stringmsg_v_msg); + node->create_publisher("stringmsg_v", 1); + ros_gz_interfaces::msg::StringVec stringmsg_v_msg; + ros_gz_bridge::testing::createTestMsg(stringmsg_v_msg); - // ros_ign_interfaces::msg::TrackVisual. + // ros_gz_interfaces::msg::TrackVisual. auto track_visual_pub = - node->create_publisher("track_visual", 1); - ros_ign_interfaces::msg::TrackVisual track_visual_msg; - ros_ign_bridge::testing::createTestMsg(track_visual_msg); + node->create_publisher("track_visual", 1); + ros_gz_interfaces::msg::TrackVisual track_visual_msg; + ros_gz_bridge::testing::createTestMsg(track_visual_msg); - // ros_ign_interfaces::msg::VideoRecord. + // ros_gz_interfaces::msg::VideoRecord. auto video_record_pub = - node->create_publisher("video_record", 1); - ros_ign_interfaces::msg::VideoRecord video_record_msg; - ros_ign_bridge::testing::createTestMsg(video_record_msg); + node->create_publisher("video_record", 1); + ros_gz_interfaces::msg::VideoRecord video_record_msg; + ros_gz_bridge::testing::createTestMsg(video_record_msg); // // mav_msgs::msg::Actuators. // auto actuators_pub = // node->create_publisher("actuators", 1); // mav_msgs::msg::Actuators actuators_msg; - // ros_ign_bridge::testing::createTestMsg(actuators_msg); + // ros_gz_bridge::testing::createTestMsg(actuators_msg); // nav_msgs::msg::Odometry. auto odometry_pub = node->create_publisher("odometry", 1); nav_msgs::msg::Odometry odometry_msg; - ros_ign_bridge::testing::createTestMsg(odometry_msg); + ros_gz_bridge::testing::createTestMsg(odometry_msg); // nav_msgs::msg::Odometry. auto odometry_cov_pub = node->create_publisher("odometry_with_covariance", 1); nav_msgs::msg::Odometry odometry_cov_msg; - ros_ign_bridge::testing::createTestMsg(odometry_cov_msg); + ros_gz_bridge::testing::createTestMsg(odometry_cov_msg); // sensor_msgs::msg::Image. auto image_pub = node->create_publisher("image", 1); sensor_msgs::msg::Image image_msg; - ros_ign_bridge::testing::createTestMsg(image_msg); + ros_gz_bridge::testing::createTestMsg(image_msg); // sensor_msgs::msg::CameraInfo. auto camera_info_pub = node->create_publisher("camera_info", 1); sensor_msgs::msg::CameraInfo camera_info_msg; - ros_ign_bridge::testing::createTestMsg(camera_info_msg); + ros_gz_bridge::testing::createTestMsg(camera_info_msg); // sensor_msgs::msg::FluidPressure. auto fluid_pressure_pub = node->create_publisher("fluid_pressure", 1); sensor_msgs::msg::FluidPressure fluid_pressure_msg; - ros_ign_bridge::testing::createTestMsg(fluid_pressure_msg); + ros_gz_bridge::testing::createTestMsg(fluid_pressure_msg); // sensor_msgs::msg::Imu. auto imu_pub = node->create_publisher("imu", 1); sensor_msgs::msg::Imu imu_msg; - ros_ign_bridge::testing::createTestMsg(imu_msg); + ros_gz_bridge::testing::createTestMsg(imu_msg); // sensor_msgs::msg::JointState. auto joint_states_pub = node->create_publisher("joint_states", 1); sensor_msgs::msg::JointState joint_states_msg; - ros_ign_bridge::testing::createTestMsg(joint_states_msg); + ros_gz_bridge::testing::createTestMsg(joint_states_msg); // sensor_msgs::msg::LaserScan. auto laserscan_pub = node->create_publisher("laserscan", 1); sensor_msgs::msg::LaserScan laserscan_msg; - ros_ign_bridge::testing::createTestMsg(laserscan_msg); + ros_gz_bridge::testing::createTestMsg(laserscan_msg); // sensor_msgs::msg::MagneticField. auto magnetic_pub = node->create_publisher("magnetic", 1); sensor_msgs::msg::MagneticField magnetic_msg; - ros_ign_bridge::testing::createTestMsg(magnetic_msg); + ros_gz_bridge::testing::createTestMsg(magnetic_msg); // sensor_msgs::msg::PointCloud2. auto pointcloud2_pub = node->create_publisher("pointcloud2", 1); sensor_msgs::msg::PointCloud2 pointcloud2_msg; - ros_ign_bridge::testing::createTestMsg(pointcloud2_msg); + ros_gz_bridge::testing::createTestMsg(pointcloud2_msg); // sensor_msgs::msg::BatteryState. auto battery_state_pub = node->create_publisher("battery_state", 1); sensor_msgs::msg::BatteryState battery_state_msg; - ros_ign_bridge::testing::createTestMsg(battery_state_msg); + ros_gz_bridge::testing::createTestMsg(battery_state_msg); // trajectory_msgs::msg::JointTrajectory. auto joint_trajectory_pub = node->create_publisher("joint_trajectory", 1); trajectory_msgs::msg::JointTrajectory joint_trajectory_msg; - ros_ign_bridge::testing::createTestMsg(joint_trajectory_msg); + ros_gz_bridge::testing::createTestMsg(joint_trajectory_msg); while (rclcpp::ok()) { // Publish all messages. diff --git a/ros_gz_bridge/test/serverclient/gz_server.cpp b/ros_gz_bridge/test/serverclient/gz_server.cpp index 3068a3ba..e757c4c4 100644 --- a/ros_gz_bridge/test/serverclient/gz_server.cpp +++ b/ros_gz_bridge/test/serverclient/gz_server.cpp @@ -24,7 +24,7 @@ #include #include "utils/test_utils.hpp" -#include "utils/ign_test_msg.hpp" +#include "utils/gz_test_msg.hpp" /// \brief Flag used to break the waiting loop and terminate the program. static std::atomic_flag g_terminateSrv(false); @@ -62,7 +62,7 @@ int main(int /*argc*/, char **/*argv*/) // ignition::msgs::WorldControl. node.Advertise( - "/ign_ros/test/serviceclient/world_control", + "/gz_ros/test/serviceclient/world_control", &control_world); // Requests are handled in another thread. diff --git a/ros_gz_bridge/test/serverclient/ros_client.cpp b/ros_gz_bridge/test/serverclient/ros_client.cpp index 1785ced9..ff21e464 100644 --- a/ros_gz_bridge/test/serverclient/ros_client.cpp +++ b/ros_gz_bridge/test/serverclient/ros_client.cpp @@ -19,7 +19,7 @@ #include "rclcpp/rclcpp.hpp" -#include "ros_ign_interfaces/srv/control_world.hpp" +#include "ros_gz_interfaces/srv/control_world.hpp" using namespace std::chrono_literals; @@ -27,12 +27,12 @@ using namespace std::chrono_literals; TEST(ROSClientTest, WorldControl) { rclcpp::init(0, NULL); - auto node = std::make_shared("test_ros_client_to_ign_service"); - auto client = node->create_client( - "/ign_ros/test/serviceclient/world_control"); + auto node = std::make_shared("test_ros_client_to_gz_service"); + auto client = node->create_client( + "/gz_ros/test/serviceclient/world_control"); std::this_thread::sleep_for(1s); ASSERT_TRUE(client->wait_for_service(5s)); - auto msg = std::make_shared(); + auto msg = std::make_shared(); auto future = client->async_send_request(msg); rclcpp::executors::SingleThreadedExecutor ex; ex.add_node(node); diff --git a/ros_gz_bridge/test/subscribers/gz_subscriber.cpp b/ros_gz_bridge/test/subscribers/gz_subscriber.cpp index 937459f1..84692a73 100644 --- a/ros_gz_bridge/test/subscribers/gz_subscriber.cpp +++ b/ros_gz_bridge/test/subscribers/gz_subscriber.cpp @@ -22,11 +22,11 @@ #include #include "utils/test_utils.hpp" -#include "utils/ign_test_msg.hpp" +#include "utils/gz_test_msg.hpp" ////////////////////////////////////////////////// -/// \brief A class for testing Ignition Transport topic subscription. -template +/// \brief A class for testing Gazebo Transport topic subscription. +template class MyTestClass { /// \brief Class constructor. @@ -41,9 +41,9 @@ class MyTestClass /// \brief Member function called each time a topic update is received. public: - void Cb(const IGN_T & _msg) + void Cb(const GZ_T & _msg) { - ros_ign_bridge::testing::compareTestMsg(std::make_shared(_msg)); + ros_gz_bridge::testing::compareTestMsg(std::make_shared(_msg)); this->callbackExecuted = true; } @@ -64,7 +64,7 @@ TEST(IgnSubscriberTest, Boolean) MyTestClass client("bool"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -76,7 +76,7 @@ TEST(IgnSubscriberTest, Empty) MyTestClass client("empty"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -88,7 +88,7 @@ TEST(IgnSubscriberTest, Float) MyTestClass client("float"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -100,7 +100,7 @@ TEST(IgnSubscriberTest, Double) MyTestClass client("double"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -112,7 +112,7 @@ TEST(IgnSubscriberTest, UInt32) MyTestClass client("uint32"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -124,7 +124,7 @@ TEST(IgnSubscriberTest, Header) MyTestClass client("header"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -136,7 +136,7 @@ TEST(IgnSubscriberTest, String) MyTestClass client("string"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -148,7 +148,7 @@ TEST(IgnSubscriberTest, Quaternion) MyTestClass client("quaternion"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -160,7 +160,7 @@ TEST(IgnSubscriberTest, Vector3) MyTestClass client("vector3"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -172,7 +172,7 @@ TEST(IgnSubscriberTest, Clock) MyTestClass client("clock"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -184,7 +184,7 @@ TEST(IgnSubscriberTest, Point) MyTestClass client("point"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -196,7 +196,7 @@ TEST(IgnSubscriberTest, Pose) MyTestClass client("pose"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -208,7 +208,7 @@ TEST(IgnSubscriberTest, PoseWithCovariance) MyTestClass client("pose_with_covariance"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -220,7 +220,7 @@ TEST(IgnSubscriberTest, PoseStamped) MyTestClass client("pose_stamped"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -232,7 +232,7 @@ TEST(IgnSubscriberTest, Transform) MyTestClass client("transform"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -244,7 +244,7 @@ TEST(IgnSubscriberTest, TransformStamped) MyTestClass client("transform_stamped"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -256,7 +256,7 @@ TEST(IgnSubscriberTest, TF2Message) MyTestClass client("tf2_message"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -268,7 +268,7 @@ TEST(IgnSubscriberTest, Twist) MyTestClass client("twist"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -280,7 +280,7 @@ TEST(IgnSubscriberTest, TwistWithCovariance) MyTestClass client("twist_with_covariance"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -292,7 +292,7 @@ TEST(IgnSubscriberTest, Wrench) MyTestClass client("wrench"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -304,7 +304,7 @@ TEST(IgnSubscriberTest, JointWrench) MyTestClass client("joint_wrench"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -316,7 +316,7 @@ TEST(IgnSubscriberTest, Entity) MyTestClass client("entity"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -328,7 +328,7 @@ TEST(IgnSubscriberTest, Contact) MyTestClass client("contact"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -340,7 +340,7 @@ TEST(IgnSubscriberTest, Contacts) MyTestClass client("contacts"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -352,7 +352,7 @@ TEST(IgnSubscriberTest, Image) MyTestClass client("image"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 500); EXPECT_TRUE(client.callbackExecuted); @@ -364,7 +364,7 @@ TEST(IgnSubscriberTest, CameraInfo) MyTestClass client("camera_info"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -376,7 +376,7 @@ TEST(IgnSubscriberTest, FluidPressure) MyTestClass client("fluid_pressure"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -388,7 +388,7 @@ TEST(IgnSubscriberTest, Imu) MyTestClass client("imu"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -400,7 +400,7 @@ TEST(IgnSubscriberTest, LaserScan) MyTestClass client("laserscan"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -412,7 +412,7 @@ TEST(IgnSubscriberTest, Magnetometer) MyTestClass client("magnetic"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -424,7 +424,7 @@ TEST(IgnSubscriberTest, Magnetometer) // MyTestClass client("actuators"); // // using namespace std::chrono_literals; -// ros_ign_bridge::testing::waitUntilBoolVar( +// ros_gz_bridge::testing::waitUntilBoolVar( // client.callbackExecuted, 100ms, 200); // // EXPECT_TRUE(client.callbackExecuted); @@ -436,7 +436,7 @@ TEST(IgnSubscriberTest, Odometry) MyTestClass client("odometry"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -448,7 +448,7 @@ TEST(IgnSubscriberTest, OdometryWithCovariance) MyTestClass client("odometry_with_covariance"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -460,7 +460,7 @@ TEST(IgnSubscriberTest, JointStates) MyTestClass client("joint_states"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -472,7 +472,7 @@ TEST(IgnSubscriberTest, PointCloudPacked) MyTestClass client("pointcloud2"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -484,7 +484,7 @@ TEST(IgnSubscriberTest, BatteryState) MyTestClass client("battery_state"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -496,7 +496,7 @@ TEST(IgnSubscriberTest, GuiCamera) MyTestClass client("gui_camera"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -508,7 +508,7 @@ TEST(IgnSubscriberTest, JointTrajectory) MyTestClass client("joint_trajectory"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -520,7 +520,7 @@ TEST(IgnSubscriberTest, StringMsg_V) MyTestClass client("stringmsg_v"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -532,7 +532,7 @@ TEST(IgnSubscriberTest, Time) MyTestClass client("time"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -544,7 +544,7 @@ TEST(IgnSubscriberTest, TrackVisual) MyTestClass client("track_visual"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -556,7 +556,7 @@ TEST(IgnSubscriberTest, VideoRecord) MyTestClass client("video_record"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVar( + ros_gz_bridge::testing::waitUntilBoolVar( client.callbackExecuted, 100ms, 200); EXPECT_TRUE(client.callbackExecuted); diff --git a/ros_gz_bridge/test/subscribers/ros_subscriber/builtin_interfaces_subscriber.cpp b/ros_gz_bridge/test/subscribers/ros_subscriber/builtin_interfaces_subscriber.cpp index 5b4f4e74..8447fdc9 100644 --- a/ros_gz_bridge/test/subscribers/ros_subscriber/builtin_interfaces_subscriber.cpp +++ b/ros_gz_bridge/test/subscribers/ros_subscriber/builtin_interfaces_subscriber.cpp @@ -27,7 +27,7 @@ TEST(ROSSubscriberTest, Time) MyTestClass client("time"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); diff --git a/ros_gz_bridge/test/subscribers/ros_subscriber/geometry_msgs_subscriber.cpp b/ros_gz_bridge/test/subscribers/ros_subscriber/geometry_msgs_subscriber.cpp index 3289891a..061c83bf 100644 --- a/ros_gz_bridge/test/subscribers/ros_subscriber/geometry_msgs_subscriber.cpp +++ b/ros_gz_bridge/test/subscribers/ros_subscriber/geometry_msgs_subscriber.cpp @@ -27,7 +27,7 @@ TEST(ROSSubscriberTest, Quaternion) MyTestClass client("quaternion"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -39,7 +39,7 @@ TEST(ROSSubscriberTest, Vector3) MyTestClass client("vector3"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -51,7 +51,7 @@ TEST(ROSSubscriberTest, Point) MyTestClass client("point"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -63,7 +63,7 @@ TEST(ROSSubscriberTest, Pose) MyTestClass client("pose"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -75,7 +75,7 @@ TEST(ROSSubscriberTest, PoseWithCovariance) MyTestClass client("pose_with_covariance"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -87,7 +87,7 @@ TEST(ROSSubscriberTest, PoseStamped) MyTestClass client("pose_stamped"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -99,7 +99,7 @@ TEST(ROSSubscriberTest, Transform) MyTestClass client("transform"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -111,7 +111,7 @@ TEST(ROSSubscriberTest, TransformStamped) MyTestClass client("transform_stamped"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -123,7 +123,7 @@ TEST(ROSSubscriberTest, TF2Message) MyTestClass client("tf2_message"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -135,7 +135,7 @@ TEST(ROSSubscriberTest, Twist) MyTestClass client("twist"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -147,7 +147,7 @@ TEST(ROSSubscriberTest, TwistWithCovariance) MyTestClass client("twist_with_covariance"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -159,7 +159,7 @@ TEST(ROSSubscriberTest, Wrench) MyTestClass client("wrench"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); diff --git a/ros_gz_bridge/test/subscribers/ros_subscriber/nav_msgs_subscriber.cpp b/ros_gz_bridge/test/subscribers/ros_subscriber/nav_msgs_subscriber.cpp index 7627378c..ecbdf254 100644 --- a/ros_gz_bridge/test/subscribers/ros_subscriber/nav_msgs_subscriber.cpp +++ b/ros_gz_bridge/test/subscribers/ros_subscriber/nav_msgs_subscriber.cpp @@ -27,7 +27,7 @@ TEST(ROSSubscriberTest, Odometry) MyTestClass client("odometry"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -39,7 +39,7 @@ TEST(ROSSubscriberTest, OdometryWithCovariance) MyTestClass client("odometry_with_covariance"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); diff --git a/ros_gz_bridge/test/subscribers/ros_subscriber/ros_gz_interfaces_subscriber.cpp b/ros_gz_bridge/test/subscribers/ros_subscriber/ros_gz_interfaces_subscriber.cpp index 6c81391e..a4e885e9 100644 --- a/ros_gz_bridge/test/subscribers/ros_subscriber/ros_gz_interfaces_subscriber.cpp +++ b/ros_gz_bridge/test/subscribers/ros_subscriber/ros_gz_interfaces_subscriber.cpp @@ -24,10 +24,10 @@ using ros_subscriber::MyTestClass; ///////////////////////////////////////////////// TEST(ROSSubscriberTest, Light) { - MyTestClass client("light"); + MyTestClass client("light"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -36,10 +36,10 @@ TEST(ROSSubscriberTest, Light) ///////////////////////////////////////////////// TEST(ROSSubscriberTest, JointWrench) { - MyTestClass client("joint_wrench"); + MyTestClass client("joint_wrench"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -48,10 +48,10 @@ TEST(ROSSubscriberTest, JointWrench) ///////////////////////////////////////////////// TEST(ROSSubscriberTest, Entity) { - MyTestClass client("entity"); + MyTestClass client("entity"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -60,10 +60,10 @@ TEST(ROSSubscriberTest, Entity) ///////////////////////////////////////////////// TEST(ROSSubscriberTest, Contact) { - MyTestClass client("contact"); + MyTestClass client("contact"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -72,10 +72,10 @@ TEST(ROSSubscriberTest, Contact) ///////////////////////////////////////////////// TEST(ROSSubscriberTest, Contacts) { - MyTestClass client("contacts"); + MyTestClass client("contacts"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -84,10 +84,10 @@ TEST(ROSSubscriberTest, Contacts) ///////////////////////////////////////////////// TEST(ROSSubscriberTest, GuiCamera) { - MyTestClass client("gui_camera"); + MyTestClass client("gui_camera"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -96,10 +96,10 @@ TEST(ROSSubscriberTest, GuiCamera) ///////////////////////////////////////////////// TEST(ROSSubscriberTest, StringVec) { - MyTestClass client("stringmsg_v"); + MyTestClass client("stringmsg_v"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -108,10 +108,10 @@ TEST(ROSSubscriberTest, StringVec) ///////////////////////////////////////////////// TEST(ROSSubscriberTest, TrackVisual) { - MyTestClass client("track_visual"); + MyTestClass client("track_visual"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -120,10 +120,10 @@ TEST(ROSSubscriberTest, TrackVisual) ///////////////////////////////////////////////// TEST(ROSSubscriberTest, VideoRecord) { - MyTestClass client("video_record"); + MyTestClass client("video_record"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); diff --git a/ros_gz_bridge/test/subscribers/ros_subscriber/ros_subscriber.hpp b/ros_gz_bridge/test/subscribers/ros_subscriber/ros_subscriber.hpp index f2809a91..06d55bd9 100644 --- a/ros_gz_bridge/test/subscribers/ros_subscriber/ros_subscriber.hpp +++ b/ros_gz_bridge/test/subscribers/ros_subscriber/ros_subscriber.hpp @@ -48,7 +48,7 @@ class MyTestClass public: void Cb(const ROS_T & _msg) { - ros_ign_bridge::testing::compareTestMsg(std::make_shared(_msg)); + ros_gz_bridge::testing::compareTestMsg(std::make_shared(_msg)); this->callbackExecuted = true; } diff --git a/ros_gz_bridge/test/subscribers/ros_subscriber/rosgraph_msgs_subscriber.cpp b/ros_gz_bridge/test/subscribers/ros_subscriber/rosgraph_msgs_subscriber.cpp index 817ae577..54ef72df 100644 --- a/ros_gz_bridge/test/subscribers/ros_subscriber/rosgraph_msgs_subscriber.cpp +++ b/ros_gz_bridge/test/subscribers/ros_subscriber/rosgraph_msgs_subscriber.cpp @@ -27,7 +27,7 @@ TEST(ROSSubscriberTest, Clock) MyTestClass client("clock"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); diff --git a/ros_gz_bridge/test/subscribers/ros_subscriber/sensor_msgs_subscriber.cpp b/ros_gz_bridge/test/subscribers/ros_subscriber/sensor_msgs_subscriber.cpp index af9757a8..0b6c294a 100644 --- a/ros_gz_bridge/test/subscribers/ros_subscriber/sensor_msgs_subscriber.cpp +++ b/ros_gz_bridge/test/subscribers/ros_subscriber/sensor_msgs_subscriber.cpp @@ -27,7 +27,7 @@ TEST(ROSSubscriberTest, Image) MyTestClass client("image"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -39,7 +39,7 @@ TEST(ROSSubscriberTest, CameraInfo) MyTestClass client("camera_info"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -51,7 +51,7 @@ TEST(ROSSubscriberTest, FluidPressure) MyTestClass client("fluid_pressure"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -63,7 +63,7 @@ TEST(ROSSubscriberTest, Imu) MyTestClass client("imu"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -75,7 +75,7 @@ TEST(ROSSubscriberTest, JointStates) MyTestClass client("joint_states"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -87,7 +87,7 @@ TEST(ROSSubscriberTest, LaserScan) MyTestClass client("laserscan"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -99,7 +99,7 @@ TEST(ROSSubscriberTest, MagneticField) MyTestClass client("magnetic"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -111,7 +111,7 @@ TEST(ROSSubscriberTest, PointCloud2) MyTestClass client("pointcloud2"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -123,7 +123,7 @@ TEST(ROSSubscriberTest, BatteryState) MyTestClass client("battery_state"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); diff --git a/ros_gz_bridge/test/subscribers/ros_subscriber/std_msgs_subscriber.cpp b/ros_gz_bridge/test/subscribers/ros_subscriber/std_msgs_subscriber.cpp index cc31514a..ebdb9567 100644 --- a/ros_gz_bridge/test/subscribers/ros_subscriber/std_msgs_subscriber.cpp +++ b/ros_gz_bridge/test/subscribers/ros_subscriber/std_msgs_subscriber.cpp @@ -27,7 +27,7 @@ TEST(ROSSubscriberTest, Color) MyTestClass client("color"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -39,7 +39,7 @@ TEST(ROSSubscriberTest, Bool) MyTestClass client("bool"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -51,7 +51,7 @@ TEST(ROSSubscriberTest, Empty) MyTestClass client("empty"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -63,7 +63,7 @@ TEST(ROSSubscriberTest, Float) MyTestClass client("float"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -75,7 +75,7 @@ TEST(ROSSubscriberTest, Double) MyTestClass client("double"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -87,7 +87,7 @@ TEST(ROSSubscriberTest, UInt32) MyTestClass client("uint32"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -99,7 +99,7 @@ TEST(ROSSubscriberTest, Header) MyTestClass client("header"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); @@ -111,7 +111,7 @@ TEST(ROSSubscriberTest, String) MyTestClass client("string"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); diff --git a/ros_gz_bridge/test/subscribers/ros_subscriber/trajectory_msgs_subscriber.cpp b/ros_gz_bridge/test/subscribers/ros_subscriber/trajectory_msgs_subscriber.cpp index 202e33f7..92469a78 100644 --- a/ros_gz_bridge/test/subscribers/ros_subscriber/trajectory_msgs_subscriber.cpp +++ b/ros_gz_bridge/test/subscribers/ros_subscriber/trajectory_msgs_subscriber.cpp @@ -27,7 +27,7 @@ TEST(ROSSubscriberTest, JointTrajectory) MyTestClass client("joint_trajectory"); using namespace std::chrono_literals; - ros_ign_bridge::testing::waitUntilBoolVarAndSpin( + ros_gz_bridge::testing::waitUntilBoolVarAndSpin( ros_subscriber::TestNode(), client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); diff --git a/ros_gz_bridge/test/utils/gz_test_msg.cpp b/ros_gz_bridge/test/utils/gz_test_msg.cpp index 42c3409a..81f02974 100644 --- a/ros_gz_bridge/test/utils/gz_test_msg.cpp +++ b/ros_gz_bridge/test/utils/gz_test_msg.cpp @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "ign_test_msg.hpp" +#include "gz_test_msg.hpp" #include #include #include -namespace ros_ign_bridge +namespace ros_gz_bridge { namespace testing { @@ -1226,4 +1226,4 @@ void compareTestMsg(const std::shared_ptr & _msg) } } // namespace testing -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge diff --git a/ros_gz_bridge/test/utils/gz_test_msg.hpp b/ros_gz_bridge/test/utils/gz_test_msg.hpp index 5ea1b386..cb2d253f 100644 --- a/ros_gz_bridge/test/utils/gz_test_msg.hpp +++ b/ros_gz_bridge/test/utils/gz_test_msg.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef UTILS__IGN_TEST_MSG_HPP_ -#define UTILS__IGN_TEST_MSG_HPP_ +#ifndef UTILS__GZ_TEST_MSG_HPP_ +#define UTILS__GZ_TEST_MSG_HPP_ #include #include @@ -58,7 +58,7 @@ #include -namespace ros_ign_bridge +namespace ros_gz_bridge { namespace testing { @@ -395,6 +395,6 @@ void createTestMsg(ignition::msgs::VideoRecord & _msg); void compareTestMsg(const std::shared_ptr & _msg); } // namespace testing -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge -#endif // UTILS__IGN_TEST_MSG_HPP_ +#endif // UTILS__GZ_TEST_MSG_HPP_ diff --git a/ros_gz_bridge/test/utils/ros_test_msg.cpp b/ros_gz_bridge/test/utils/ros_test_msg.cpp index 79da0add..5bee732d 100644 --- a/ros_gz_bridge/test/utils/ros_test_msg.cpp +++ b/ros_gz_bridge/test/utils/ros_test_msg.cpp @@ -19,7 +19,7 @@ #include #include -namespace ros_ign_bridge +namespace ros_gz_bridge { namespace testing { @@ -394,7 +394,7 @@ void compareTestMsg(const std::shared_ptr & _msg) compareTestMsg(std::make_shared(_msg->torque)); } -void createTestMsg(ros_ign_interfaces::msg::Light & _msg) +void createTestMsg(ros_gz_interfaces::msg::Light & _msg) { createTestMsg(_msg.header); @@ -421,9 +421,9 @@ void createTestMsg(ros_ign_interfaces::msg::Light & _msg) _msg.intensity = 125.0; } -void compareTestMsg(const std::shared_ptr & _msg) +void compareTestMsg(const std::shared_ptr & _msg) { - ros_ign_interfaces::msg::Light expected_msg; + ros_gz_interfaces::msg::Light expected_msg; createTestMsg(expected_msg); compareTestMsg(_msg->header); @@ -451,7 +451,7 @@ void compareTestMsg(const std::shared_ptr & _msg EXPECT_FLOAT_EQ(expected_msg.intensity, _msg->intensity); } -void createTestMsg(ros_ign_interfaces::msg::GuiCamera & _msg) +void createTestMsg(ros_gz_interfaces::msg::GuiCamera & _msg) { createTestMsg(_msg.header); createTestMsg(_msg.track); @@ -462,13 +462,13 @@ void createTestMsg(ros_ign_interfaces::msg::GuiCamera & _msg) _msg.projection_type = "test_gui_camera_projection_type"; } -void compareTestMsg(const std::shared_ptr & _msg) +void compareTestMsg(const std::shared_ptr & _msg) { - ros_ign_interfaces::msg::GuiCamera expected_msg; + ros_gz_interfaces::msg::GuiCamera expected_msg; createTestMsg(expected_msg); compareTestMsg(_msg->header); - compareTestMsg(std::make_shared(_msg->track)); + compareTestMsg(std::make_shared(_msg->track)); compareTestMsg(std::make_shared(_msg->pose)); EXPECT_EQ(expected_msg.name, _msg->name); @@ -476,16 +476,16 @@ void compareTestMsg(const std::shared_ptr & EXPECT_EQ(expected_msg.projection_type, _msg->projection_type); } -void createTestMsg(ros_ign_interfaces::msg::StringVec & _msg) +void createTestMsg(ros_gz_interfaces::msg::StringVec & _msg) { createTestMsg(_msg.header); _msg.data.emplace_back("test_string_msg_v_data"); } -void compareTestMsg(const std::shared_ptr & _msg) +void compareTestMsg(const std::shared_ptr & _msg) { - ros_ign_interfaces::msg::StringVec expected_msg; + ros_gz_interfaces::msg::StringVec expected_msg; createTestMsg(expected_msg); compareTestMsg(_msg->header); @@ -493,7 +493,7 @@ void compareTestMsg(const std::shared_ptr & EXPECT_EQ(expected_msg.data, _msg->data); } -void createTestMsg(ros_ign_interfaces::msg::TrackVisual & _msg) +void createTestMsg(ros_gz_interfaces::msg::TrackVisual & _msg) { createTestMsg(_msg.header); createTestMsg(_msg.xyz); @@ -508,9 +508,9 @@ void createTestMsg(ros_ign_interfaces::msg::TrackVisual & _msg) _msg.inherit_yaw = true; } -void compareTestMsg(const std::shared_ptr & _msg) +void compareTestMsg(const std::shared_ptr & _msg) { - ros_ign_interfaces::msg::TrackVisual expected_msg; + ros_gz_interfaces::msg::TrackVisual expected_msg; createTestMsg(expected_msg); compareTestMsg(_msg->header); @@ -526,7 +526,7 @@ void compareTestMsg(const std::shared_ptr EXPECT_EQ(expected_msg.inherit_yaw, _msg->inherit_yaw); } -void createTestMsg(ros_ign_interfaces::msg::VideoRecord & _msg) +void createTestMsg(ros_gz_interfaces::msg::VideoRecord & _msg) { createTestMsg(_msg.header); @@ -536,9 +536,9 @@ void createTestMsg(ros_ign_interfaces::msg::VideoRecord & _msg) _msg.save_filename = "test_video_record_save_filename"; } -void compareTestMsg(const std::shared_ptr & _msg) +void compareTestMsg(const std::shared_ptr & _msg) { - ros_ign_interfaces::msg::VideoRecord expected_msg; + ros_gz_interfaces::msg::VideoRecord expected_msg; createTestMsg(expected_msg); compareTestMsg(_msg->header); @@ -549,7 +549,7 @@ void compareTestMsg(const std::shared_ptr EXPECT_EQ(expected_msg.save_filename, _msg->save_filename); } -void createTestMsg(ros_ign_interfaces::msg::JointWrench & _msg) +void createTestMsg(ros_gz_interfaces::msg::JointWrench & _msg) { createTestMsg(_msg.header); _msg.body_1_name.data = "body1"; @@ -560,9 +560,9 @@ void createTestMsg(ros_ign_interfaces::msg::JointWrench & _msg) createTestMsg(_msg.body_2_wrench); } -void compareTestMsg(const std::shared_ptr & _msg) +void compareTestMsg(const std::shared_ptr & _msg) { - ros_ign_interfaces::msg::JointWrench expected_msg; + ros_gz_interfaces::msg::JointWrench expected_msg; createTestMsg(expected_msg); EXPECT_EQ(expected_msg.body_1_name, _msg->body_1_name); @@ -575,16 +575,16 @@ void compareTestMsg(const std::shared_ptr compareTestMsg(std::make_shared(_msg->body_2_wrench)); } -void createTestMsg(ros_ign_interfaces::msg::Entity & _msg) +void createTestMsg(ros_gz_interfaces::msg::Entity & _msg) { _msg.id = 1; _msg.name = "entity"; - _msg.type = ros_ign_interfaces::msg::Entity::VISUAL; + _msg.type = ros_gz_interfaces::msg::Entity::VISUAL; } -void compareTestMsg(const std::shared_ptr & _msg) +void compareTestMsg(const std::shared_ptr & _msg) { - ros_ign_interfaces::msg::Entity expected_msg; + ros_gz_interfaces::msg::Entity expected_msg; createTestMsg(expected_msg); EXPECT_EQ(expected_msg.id, _msg->id); @@ -592,7 +592,7 @@ void compareTestMsg(const std::shared_ptr & _ms EXPECT_EQ(expected_msg.type, _msg->type); } -void createTestMsg(ros_ign_interfaces::msg::Contact & _msg) +void createTestMsg(ros_gz_interfaces::msg::Contact & _msg) { createTestMsg(_msg.collision1); createTestMsg(_msg.collision2); @@ -600,7 +600,7 @@ void createTestMsg(ros_ign_interfaces::msg::Contact & _msg) geometry_msgs::msg::Vector3 vector_msg; createTestMsg(vector_msg); - ros_ign_interfaces::msg::JointWrench joint_wrench_msg; + ros_gz_interfaces::msg::JointWrench joint_wrench_msg; createTestMsg(joint_wrench_msg); for (int i = 0; i < 10; i++) { @@ -611,12 +611,12 @@ void createTestMsg(ros_ign_interfaces::msg::Contact & _msg) } } -void compareTestMsg(const std::shared_ptr & _msg) +void compareTestMsg(const std::shared_ptr & _msg) { - ros_ign_interfaces::msg::Contact expected_msg; + ros_gz_interfaces::msg::Contact expected_msg; createTestMsg(expected_msg); - compareTestMsg(std::make_shared(_msg->collision1)); - compareTestMsg(std::make_shared(_msg->collision2)); + compareTestMsg(std::make_shared(_msg->collision1)); + compareTestMsg(std::make_shared(_msg->collision2)); EXPECT_EQ(expected_msg.depths.size(), _msg->depths.size()); EXPECT_EQ(expected_msg.positions.size(), _msg->positions.size()); EXPECT_EQ(expected_msg.normals.size(), _msg->normals.size()); @@ -625,15 +625,15 @@ void compareTestMsg(const std::shared_ptr & _m EXPECT_EQ(expected_msg.depths.at(i), _msg->depths.at(i)); compareTestMsg(std::make_shared(_msg->positions.at(i))); compareTestMsg(std::make_shared(_msg->normals.at(i))); - compareTestMsg(std::make_shared(_msg->wrenches.at(i))); + compareTestMsg(std::make_shared(_msg->wrenches.at(i))); } } -void createTestMsg(ros_ign_interfaces::msg::Contacts & _msg) +void createTestMsg(ros_gz_interfaces::msg::Contacts & _msg) { createTestMsg(_msg.header); - ros_ign_interfaces::msg::Contact contact_msg; + ros_gz_interfaces::msg::Contact contact_msg; createTestMsg(contact_msg); for (int i = 0; i < 10; i++) { @@ -641,15 +641,15 @@ void createTestMsg(ros_ign_interfaces::msg::Contacts & _msg) } } -void compareTestMsg(const std::shared_ptr & _msg) +void compareTestMsg(const std::shared_ptr & _msg) { - ros_ign_interfaces::msg::Contacts expected_msg; + ros_gz_interfaces::msg::Contacts expected_msg; createTestMsg(expected_msg); compareTestMsg(_msg->header); EXPECT_EQ(expected_msg.contacts.size(), _msg->contacts.size()); for (size_t i = 0; i < _msg->contacts.size(); i++) { - compareTestMsg(std::make_shared(_msg->contacts.at(i))); + compareTestMsg(std::make_shared(_msg->contacts.at(i))); } } @@ -1074,4 +1074,4 @@ void compareTestMsg(const std::shared_ptr } } // namespace testing -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge diff --git a/ros_gz_bridge/test/utils/ros_test_msg.hpp b/ros_gz_bridge/test/utils/ros_test_msg.hpp index 84e7316c..fbe7668e 100644 --- a/ros_gz_bridge/test/utils/ros_test_msg.hpp +++ b/ros_gz_bridge/test/utils/ros_test_msg.hpp @@ -38,15 +38,15 @@ #include #include #include -#include -#include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include +#include +#include #include #include #include @@ -61,7 +61,7 @@ #include #include -namespace ros_ign_bridge +namespace ros_gz_bridge { namespace testing { @@ -286,79 +286,79 @@ void createTestMsg(nav_msgs::msg::Odometry & _msg); /// \param[in] _msg The message to compare. void compareTestMsg(const std::shared_ptr & _msg); -/// ros_ign_interfaces +/// ros_gz_interfaces /// \brief Create a message used for testing. /// \param[out] _msg The message populated. -void createTestMsg(ros_ign_interfaces::msg::JointWrench & _msg); +void createTestMsg(ros_gz_interfaces::msg::JointWrench & _msg); /// \brief Compare a message with the populated for testing. /// \param[in] _msg The message to compare. -void compareTestMsg(const std::shared_ptr & _msg); +void compareTestMsg(const std::shared_ptr & _msg); /// \brief Create a message used for testing. /// \param[out] _msg The message populated. -void createTestMsg(ros_ign_interfaces::msg::Light & _msg); +void createTestMsg(ros_gz_interfaces::msg::Light & _msg); /// \brief Compare a message with the populated for testing. /// \param[in] _msg The message to compare. -void compareTestMsg(const std::shared_ptr & _msg); +void compareTestMsg(const std::shared_ptr & _msg); /// \brief Create a message used for testing. /// \param[out] _msg The message populated. -void createTestMsg(ros_ign_interfaces::msg::Entity & _msg); +void createTestMsg(ros_gz_interfaces::msg::Entity & _msg); /// \brief Compare a message with the populated for testing. /// \param[in] _msg The message to compare. -void compareTestMsg(const std::shared_ptr & _msg); +void compareTestMsg(const std::shared_ptr & _msg); /// \brief Create a message used for testing. /// \param[out] _msg The message populated. -void createTestMsg(ros_ign_interfaces::msg::Contact & _msg); +void createTestMsg(ros_gz_interfaces::msg::Contact & _msg); /// \brief Compare a message with the populated for testing. /// \param[in] _msg The message to compare. -void compareTestMsg(const std::shared_ptr & _msg); +void compareTestMsg(const std::shared_ptr & _msg); /// \brief Create a message used for testing. /// \param[out] _msg The message populated. -void createTestMsg(ros_ign_interfaces::msg::Contacts & _msg); +void createTestMsg(ros_gz_interfaces::msg::Contacts & _msg); /// \brief Compare a message with the populated for testing. /// \param[in] _msg The message to compare. -void compareTestMsg(const std::shared_ptr & _msg); +void compareTestMsg(const std::shared_ptr & _msg); /// \brief Create a message used for testing. /// \param[out] _msg The message populated. -void createTestMsg(ros_ign_interfaces::msg::GuiCamera & _msg); +void createTestMsg(ros_gz_interfaces::msg::GuiCamera & _msg); /// \brief Compare a message with the populated for testing. /// \param[in] _msg The message to compare. -void compareTestMsg(const std::shared_ptr & _msg); +void compareTestMsg(const std::shared_ptr & _msg); /// \brief Create a message used for testing. /// \param[out] _msg The message populated. -void createTestMsg(ros_ign_interfaces::msg::StringVec & _msg); +void createTestMsg(ros_gz_interfaces::msg::StringVec & _msg); /// \brief Compare a message with the populated for testing. /// \param[in] _msg The message to compare. -void compareTestMsg(const std::shared_ptr & _msg); +void compareTestMsg(const std::shared_ptr & _msg); /// \brief Create a message used for testing. /// \param[out] _msg The message populated. -void createTestMsg(ros_ign_interfaces::msg::TrackVisual & _msg); +void createTestMsg(ros_gz_interfaces::msg::TrackVisual & _msg); /// \brief Compare a message with the populated for testing. /// \param[in] _msg The message to compare. -void compareTestMsg(const std::shared_ptr & _msg); +void compareTestMsg(const std::shared_ptr & _msg); /// \brief Create a message used for testing. /// \param[out] _msg The message populated. -void createTestMsg(ros_ign_interfaces::msg::VideoRecord & _msg); +void createTestMsg(ros_gz_interfaces::msg::VideoRecord & _msg); /// \brief Compare a message with the populated for testing. /// \param[in] _msg The message to compare. -void compareTestMsg(const std::shared_ptr & _msg); +void compareTestMsg(const std::shared_ptr & _msg); /// sensor_msgs @@ -453,6 +453,6 @@ void createTestMsg(trajectory_msgs::msg::JointTrajectory & _msg); void compareTestMsg(const std::shared_ptr & _msg); } // namespace testing -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge #endif // UTILS__ROS_TEST_MSG_HPP_ diff --git a/ros_gz_bridge/test/utils/test_utils.hpp b/ros_gz_bridge/test/utils/test_utils.hpp index a5d14a4e..c672cf7b 100644 --- a/ros_gz_bridge/test/utils/test_utils.hpp +++ b/ros_gz_bridge/test/utils/test_utils.hpp @@ -21,7 +21,7 @@ #include -namespace ros_ign_bridge +namespace ros_gz_bridge { namespace testing { @@ -73,5 +73,5 @@ void waitUntilBoolVarAndSpin( } } // namespace testing -} // namespace ros_ign_bridge +} // namespace ros_gz_bridge #endif // UTILS__TEST_UTILS_HPP_ diff --git a/ros_gz_image/CHANGELOG.rst b/ros_gz_image/CHANGELOG.rst index cad3d7c2..4b7e2c4f 100644 --- a/ros_gz_image/CHANGELOG.rst +++ b/ros_gz_image/CHANGELOG.rst @@ -4,17 +4,17 @@ Changelog for package ros1_ign_image 0.244.3 (2022-05-19) -------------------- -* [ros2] README updates (service bridge, Gazebo rename) (`#252 `_) -* Fix linter tests (`#251 `_) +* [ros2] README updates (service bridge, Gazebo rename) (`#252 `_) +* Fix linter tests (`#251 `_) Co-authored-by: Louise Poubel * Contributors: Daisuke Nishimatsu, Louise Poubel 0.244.2 (2022-04-25) -------------------- -* Bring ros2 branch up-to-date with Rolling (`#213 `_) -* Separate galactic branch from ros2 branch (`#201 `_) -* 🏁 Dome EOL (`#198 `_) -* Fix Deprecation Warning (`#158 `_) +* Bring ros2 branch up-to-date with Rolling (`#213 `_) +* Separate galactic branch from ros2 branch (`#201 `_) +* 🏁 Dome EOL (`#198 `_) +* Fix Deprecation Warning (`#158 `_) * Contributors: David V. Lu!!, Louise Poubel, Michael Carroll 0.244.1 (2022-01-04) @@ -22,39 +22,39 @@ Changelog for package ros1_ign_image 0.244.0 (2021-12-30) -------------------- -* Default to Fortress for Rolling (future Humble) (`#195 `_) -* [ros2] 🏁 Dome EOL (`#199 `_) -* Statically link each translation unit (`#193 `_) +* Default to Fortress for Rolling (future Humble) (`#195 `_) +* [ros2] 🏁 Dome EOL (`#199 `_) +* Statically link each translation unit (`#193 `_) * Contributors: Guillaume Doisy, Louise Poubel, Michael Carroll 0.233.2 (2021-07-20) -------------------- -* [ros2] Update version docs, add Galactic and Fortress (`#164 `_) -* Fix Deprecation Warning (`#158 `_) +* [ros2] Update version docs, add Galactic and Fortress (`#164 `_) +* Fix Deprecation Warning (`#158 `_) * Contributors: David V. Lu!!, Louise Poubel 0.233.1 (2021-04-16) -------------------- -* Default to Edifice for Rolling (`#150 `_) -* Edifice support (`#140 `_) -* Update releases (`#108 `_) -* Add support for Dome (`#103 `_) +* Default to Edifice for Rolling (`#150 `_) +* Edifice support (`#140 `_) +* Update releases (`#108 `_) +* Add support for Dome (`#103 `_) * Contributors: Louise Poubel, Luca Della Vedova 0.221.1 (2020-08-19) -------------------- -* Add pkg-config as a buildtool dependency (`#102 `_) +* Add pkg-config as a buildtool dependency (`#102 `_) * Contributors: Louise Poubel 0.221.0 (2020-07-23) -------------------- -* Install only what's necessary, rename builtin_interfaces (`#95 `_) -* Add CI for Eloquent (`#86 `_) -* Avoid the use of --ros-args arguments outside ros (`#84 `_) -* [WIP] Port ign_ros_gazebo_demos to ROS2 (`#58 `_) - Port ros_ign_image to ROS2 - Port ros_ign_gazebo_demos to ROS2 -* Enable ROS2 CI for Dashing branch (`#43 `_) +* Install only what's necessary, rename builtin_interfaces (`#95 `_) +* Add CI for Eloquent (`#86 `_) +* Avoid the use of --ros-args arguments outside ros (`#84 `_) +* [WIP] Port ign_ros_gazebo_demos to ROS2 (`#58 `_) + Port ros_gz_image to ROS2 + Port ros_gz_sim_demos to ROS2 +* Enable ROS2 CI for Dashing branch (`#43 `_) * Make all API and comments ROS-version agnostic * Rename packages and fix compilation + tests * Move files ros1 -> ros diff --git a/ros_gz_image/CMakeLists.txt b/ros_gz_image/CMakeLists.txt index 4d9c9c2e..5552287c 100644 --- a/ros_gz_image/CMakeLists.txt +++ b/ros_gz_image/CMakeLists.txt @@ -1,6 +1,6 @@ cmake_minimum_required(VERSION 3.5) -project(ros_ign_image) +project(ros_gz_image) # Default to C++17 if(NOT CMAKE_CXX_STANDARD) @@ -12,28 +12,35 @@ endif() find_package(ament_cmake REQUIRED) find_package(image_transport REQUIRED) -find_package(ros_ign_bridge REQUIRED) +find_package(ros_gz_bridge REQUIRED) find_package(rclcpp REQUIRED) find_package(sensor_msgs REQUIRED) + +# TODO(CH3): Deprecated. Remove on tock. +if("$ENV{GZ_VERSION}" STREQUAL "" AND NOT "$ENV{IGNITION_VERSION}" STREQUAL "") + message(DEPRECATION "Environment variable [IGNITION_VERSION] is deprecated. Use [GZ_VERSION] instead.") + set(ENV{GZ_VERSION} ENV{IGNITION_VERSION}) +endif() + # Edifice -if("$ENV{IGNITION_VERSION}" STREQUAL "edifice") +if("$ENV{GZ_VERSION}" STREQUAL "edifice") find_package(ignition-transport10 REQUIRED) - set(IGN_TRANSPORT_VER ${ignition-transport10_VERSION_MAJOR}) + set(GZ_TRANSPORT_VER ${ignition-transport10_VERSION_MAJOR}) find_package(ignition-msgs7 REQUIRED) - set(IGN_MSGS_VER ${ignition-msgs7_VERSION_MAJOR}) + set(GZ_MSGS_VER ${ignition-msgs7_VERSION_MAJOR}) set(GZ_TARGET_PREFIX ignition) message(STATUS "Compiling against Ignition Edifice") # Fortress -elseif("$ENV{IGNITION_VERSION}" STREQUAL "garden") +elseif("$ENV{GZ_VERSION}" STREQUAL "garden") find_package(gz-transport12 REQUIRED) - set(IGN_TRANSPORT_VER ${gz-transport12_VERSION_MAJOR}) + set(GZ_TRANSPORT_VER ${gz-transport12_VERSION_MAJOR}) find_package(gz-msgs9 REQUIRED) - set(IGN_MSGS_VER ${gz-msgs9_VERSION_MAJOR}) + set(GZ_MSGS_VER ${gz-msgs9_VERSION_MAJOR}) set(GZ_TARGET_PREFIX gz) @@ -41,10 +48,10 @@ elseif("$ENV{IGNITION_VERSION}" STREQUAL "garden") # Default to Fortress else() find_package(ignition-transport11 REQUIRED) - set(IGN_TRANSPORT_VER ${ignition-transport11_VERSION_MAJOR}) + set(GZ_TRANSPORT_VER ${ignition-transport11_VERSION_MAJOR}) find_package(ignition-msgs8 REQUIRED) - set(IGN_MSGS_VER ${ignition-msgs8_VERSION_MAJOR}) + set(GZ_MSGS_VER ${ignition-msgs8_VERSION_MAJOR}) set(GZ_TARGET_PREFIX ignition) @@ -62,13 +69,13 @@ add_executable(${executable} ) target_link_libraries(${executable} - ${GZ_TARGET_PREFIX}-msgs${IGN_MSGS_VER}::core - ${GZ_TARGET_PREFIX}-transport${IGN_TRANSPORT_VER}::core + ${GZ_TARGET_PREFIX}-msgs${GZ_MSGS_VER}::core + ${GZ_TARGET_PREFIX}-transport${GZ_TRANSPORT_VER}::core ) ament_target_dependencies(${executable} "image_transport" - "ros_ign_bridge" + "ros_gz_bridge" "rclcpp" "sensor_msgs" ) @@ -84,7 +91,7 @@ if(BUILD_TESTING) # find_package(rostest REQUIRED) # # set(test_publishers - # ign_publisher + # gz_publisher # ) # # set(test_subscribers @@ -97,8 +104,8 @@ if(BUILD_TESTING) # ) # target_link_libraries(${test_publisher}_image # ${catkin_LIBRARIES} - # ${GZ_TARGET_PREFIX}-msgs${IGN_MSGS_VER}::core - # ${GZ_TARGET_PREFIX}-transport${IGN_TRANSPORT_VER}::core + # ${GZ_TARGET_PREFIX}-msgs${GZ_MSGS_VER}::core + # ${GZ_TARGET_PREFIX}-transport${GZ_TRANSPORT_VER}::core # gtest # gtest_main # ) @@ -110,8 +117,8 @@ if(BUILD_TESTING) # test/subscribers/${test_subscriber}.cpp) # target_link_libraries(test_${test_subscriber}_image # ${catkin_LIBRARIES} - # ${GZ_TARGET_PREFIX}-msgs${IGN_MSGS_VER}::core - # ${GZ_TARGET_PREFIX}-transport${IGN_TRANSPORT_VER}::core + # ${GZ_TARGET_PREFIX}-msgs${GZ_MSGS_VER}::core + # ${GZ_TARGET_PREFIX}-transport${GZ_TRANSPORT_VER}::core # ) # endforeach(test_subscriber) endif() diff --git a/ros_gz_image/package.xml b/ros_gz_image/package.xml index 95e13e5c..6f6a37c5 100644 --- a/ros_gz_image/package.xml +++ b/ros_gz_image/package.xml @@ -1,7 +1,7 @@ - ros_ign_image + ros_gz_image 0.244.3 - Image utilities for Ignition simulation with ROS. + Image utilities for Gazebo simulation with ROS. Apache 2.0 Louise Poubel @@ -9,21 +9,21 @@ pkg-config image_transport - ros_ign_bridge + ros_gz_bridge rclcpp sensor_msgs - gz-msgs9 - gz-transport12 + gz-msgs9 + gz-transport12 - ignition-msgs8 - ignition-transport11 - ignition-msgs8 - ignition-transport11 + ignition-msgs8 + ignition-transport11 + ignition-msgs8 + ignition-transport11 - ignition-msgs7 - ignition-transport10 + ignition-msgs7 + ignition-transport10 ament_lint_auto ament_lint_common diff --git a/ros_gz_image/src/image_bridge.cpp b/ros_gz_image/src/image_bridge.cpp index ef4b8678..00aacca5 100644 --- a/ros_gz_image/src/image_bridge.cpp +++ b/ros_gz_image/src/image_bridge.cpp @@ -21,7 +21,7 @@ #include #include #include -#include +#include ////////////////////////////////////////////////// /// \brief Bridges one topic @@ -31,24 +31,24 @@ class Handler /// \brief Constructor /// \param[in] _topic Image base topic /// \param[in] _it_node Pointer to image transport node - /// \param[in] _ign_node Pointer to Ignition node + /// \param[in] _gz_node Pointer to Gazebo node Handler( const std::string & _topic, std::shared_ptr _it_node, - std::shared_ptr _ign_node) + std::shared_ptr _gz_node) { this->ros_pub = _it_node->advertise(_topic, 1); - _ign_node->Subscribe(_topic, &Handler::OnImage, this); + _gz_node->Subscribe(_topic, &Handler::OnImage, this); } private: - /// \brief Callback when Ignition image is received - /// \param[in] _ign_msg Ignition message - void OnImage(const ignition::msgs::Image & _ign_msg) + /// \brief Callback when Gazebo image is received + /// \param[in] _gz_msg Gazebo message + void OnImage(const ignition::msgs::Image & _gz_msg) { sensor_msgs::msg::Image ros_msg; - ros_ign_bridge::convert_ign_to_ros(_ign_msg, ros_msg); + ros_gz_bridge::convert_gz_to_ros(_gz_msg, ros_msg); this->ros_pub.publish(ros_msg); } @@ -59,7 +59,7 @@ class Handler ////////////////////////////////////////////////// void usage() { - std::cerr << "Bridge a collection of Ignition Transport image topics to ROS " << + std::cerr << "Bridge a collection of Gazebo Transport image topics to ROS " << "using image_transport.\n\n" << " image_bridge ..\n\n" << "E.g.: image_bridge /camera/front/image_raw" << std::endl; @@ -76,11 +76,11 @@ int main(int argc, char * argv[]) rclcpp::init(argc, argv); // ROS node - auto node_ = rclcpp::Node::make_shared("ros_ign_image"); + auto node_ = rclcpp::Node::make_shared("ros_gz_image"); auto it_node = std::make_shared(node_); - // Ignition node - auto ign_node = std::make_shared(); + // Gazebo node + auto gz_node = std::make_shared(); std::vector> handlers; @@ -88,10 +88,10 @@ int main(int argc, char * argv[]) // Create publishers and subscribers for (auto topic : args) { - handlers.push_back(std::make_shared(topic, it_node, ign_node)); + handlers.push_back(std::make_shared(topic, it_node, gz_node)); } - // Spin ROS and Ign until shutdown + // Spin ROS and Gz until shutdown rclcpp::spin(node_); ignition::transport::waitForShutdown(); diff --git a/ros_gz_image/test/launch/test_ros_subscriber.launch b/ros_gz_image/test/launch/test_ros_subscriber.launch index cbe8634b..e4e451a5 100644 --- a/ros_gz_image/test/launch/test_ros_subscriber.launch +++ b/ros_gz_image/test/launch/test_ros_subscriber.launch @@ -1,12 +1,12 @@ - - - + + diff --git a/ros_gz_image/test/publishers/gz_publisher.cpp b/ros_gz_image/test/publishers/gz_publisher.cpp index 2f5820ae..eb91256f 100644 --- a/ros_gz_image/test/publishers/gz_publisher.cpp +++ b/ros_gz_image/test/publishers/gz_publisher.cpp @@ -47,7 +47,7 @@ int main(int /*argc*/, char **/*argv*/) // ignition::msgs::Image. auto image_pub = node.Advertise("image"); ignition::msgs::Image image_msg; - ros_ign_image::testing::createTestMsg(image_msg); + ros_gz_image::testing::createTestMsg(image_msg); // Publish messages at 1Hz. while (!g_terminatePub) diff --git a/ros_gz_image/test/ros_subscriber.test b/ros_gz_image/test/ros_subscriber.test index a5fb11f3..192a2b39 100644 --- a/ros_gz_image/test/ros_subscriber.test +++ b/ros_gz_image/test/ros_subscriber.test @@ -1,9 +1,9 @@ - + - + diff --git a/ros_gz_image/test/subscribers/ros_subscriber.cpp b/ros_gz_image/test/subscribers/ros_subscriber.cpp index 78ab4438..6fb6b28c 100644 --- a/ros_gz_image/test/subscribers/ros_subscriber.cpp +++ b/ros_gz_image/test/subscribers/ros_subscriber.cpp @@ -35,7 +35,7 @@ class MyTestClass /// \brief Member function called each time a topic update is received. public: void Cb(const ROS_T& _msg) { - ros_ign_image::testing::compareTestMsg(_msg); + ros_gz_image::testing::compareTestMsg(_msg); this->callbackExecuted = true; }; @@ -55,7 +55,7 @@ TEST(ROSSubscriberTest, Image) MyTestClass client("image"); using namespace std::chrono_literals; - ros_ign_image::testing::waitUntilBoolVarAndSpin( + ros_gz_image::testing::waitUntilBoolVarAndSpin( client.callbackExecuted, 10ms, 200); EXPECT_TRUE(client.callbackExecuted); diff --git a/ros_gz_image/test/test_utils.h b/ros_gz_image/test/test_utils.h index 6ede3889..1f7ce264 100644 --- a/ros_gz_image/test/test_utils.h +++ b/ros_gz_image/test/test_utils.h @@ -15,8 +15,8 @@ * */ -#ifndef ROS_IGN_IMAGE__TEST_UTILS_H_ -#define ROS_IGN_IMAGE__TEST_UTILS_H_ +#ifndef ROS_GZ_IMAGE__TEST_UTILS_H_ +#define ROS_GZ_IMAGE__TEST_UTILS_H_ #include #include @@ -27,7 +27,7 @@ #include #include -namespace ros_ign_image +namespace ros_gz_image { namespace testing { @@ -137,7 +137,7 @@ namespace testing } ////////////////////////////////////////////////// - /// Ignition::msgs test utils + /// Gazebo::msgs test utils ////////////////////////////////////////////////// /// \brief Create a message used for testing. @@ -213,4 +213,4 @@ namespace testing } } -#endif // ROS_IGN_BRIDGE__TEST_UTILS_H_ +#endif // ROS_GZ_BRIDGE__TEST_UTILS_H_ diff --git a/ros_gz_interfaces/CHANGELOG.rst b/ros_gz_interfaces/CHANGELOG.rst index fbcad7d4..19994bdd 100644 --- a/ros_gz_interfaces/CHANGELOG.rst +++ b/ros_gz_interfaces/CHANGELOG.rst @@ -1,24 +1,24 @@ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package ros_ign_interfaces +Changelog for package ros_gz_interfaces ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 0.244.3 (2022-05-19) -------------------- -* [ros2] README updates (service bridge, Gazebo rename) (`#252 `_) +* [ros2] README updates (service bridge, Gazebo rename) (`#252 `_) * Contributors: Louise Poubel 0.244.2 (2022-04-25) -------------------- -* [ros_ign_interfaces] Add GuiCamera, StringVec, TrackVisual, VideoRecord (`#214 `_) - * [ros_ign_interfaces] Add more interface definitions. +* [ros_gz_interfaces] Add GuiCamera, StringVec, TrackVisual, VideoRecord (`#214 `_) + * [ros_gz_interfaces] Add more interface definitions. * Add converion functions for the added messages * Update the factory factory function with the new messages * Add new messages to docs * Add test cases for the new messages conversions -* Update maintainer for ros_ign_interfaces (`#204 `_) -* [ros2] new package ros_ign_interfaces, provide some Ignition-specific ROS messages. (`#152 `_) - * add new package ros_ign_interfaces,provide some Ignition-specific ros .msg and .srv files - * modify to match ign-msgs +* Update maintainer for ros_gz_interfaces (`#204 `_) +* [ros2] new package ros_gz_interfaces, provide some Gazebo-specific ROS messages. (`#152 `_) + * add new package ros_gz_interfaces,provide some Gazebo-specific ros .msg and .srv files + * modify to match gz-msgs * add author info * modify comments * update code and doc style @@ -29,15 +29,15 @@ Changelog for package ros_ign_interfaces 0.244.0 (2021-12-30) -------------------- -* New Light Message, also bridge Color (`#187 `_) -* Expose Contacts through ROS bridge (`#175 `_) +* New Light Message, also bridge Color (`#187 `_) +* Expose Contacts through ROS bridge (`#175 `_) * Contributors: Guillaume Doisy, Vatan Aksoy Tezer, William Lew 0.233.2 (2021-07-20) -------------------- -* [ros2] new package ros_ign_interfaces, provide some Ignition-specific ROS messages. (`#152 `_) - * add new package ros_ign_interfaces,provide some Ignition-specific ros .msg and .srv files - * modify to match ign-msgs +* [ros2] new package ros_gz_interfaces, provide some Gazebo-specific ROS messages. (`#152 `_) + * add new package ros_gz_interfaces,provide some Gazebo-specific ros .msg and .srv files + * modify to match gz-msgs * add author info * modify comments * update code and doc style diff --git a/ros_gz_interfaces/CMakeLists.txt b/ros_gz_interfaces/CMakeLists.txt index df877646..0353319c 100644 --- a/ros_gz_interfaces/CMakeLists.txt +++ b/ros_gz_interfaces/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.5) -project(ros_ign_interfaces) +project(ros_gz_interfaces) if(NOT CMAKE_CXX_STANDARD) set(CMAKE_CXX_STANDARD 14) diff --git a/ros_gz_interfaces/msg/Contact.msg b/ros_gz_interfaces/msg/Contact.msg index 90235356..98d2cef8 100644 --- a/ros_gz_interfaces/msg/Contact.msg +++ b/ros_gz_interfaces/msg/Contact.msg @@ -1,6 +1,6 @@ -ros_ign_interfaces/Entity collision1 # Contact collision1 -ros_ign_interfaces/Entity collision2 # Contact collision2 +ros_gz_interfaces/Entity collision1 # Contact collision1 +ros_gz_interfaces/Entity collision2 # Contact collision2 geometry_msgs/Vector3[] positions # List of contact position geometry_msgs/Vector3[] normals # List of contact normals float64[] depths # List of penetration depths -ros_ign_interfaces/JointWrench[] wrenches # List of joint wrenches including forces/torques +ros_gz_interfaces/JointWrench[] wrenches # List of joint wrenches including forces/torques diff --git a/ros_gz_interfaces/msg/Contacts.msg b/ros_gz_interfaces/msg/Contacts.msg index e709e178..40232e51 100644 --- a/ros_gz_interfaces/msg/Contacts.msg +++ b/ros_gz_interfaces/msg/Contacts.msg @@ -1,2 +1,2 @@ std_msgs/Header header # Time stamp -ros_ign_interfaces/Contact[] contacts # List of contacts +ros_gz_interfaces/Contact[] contacts # List of contacts diff --git a/ros_gz_interfaces/msg/WorldControl.msg b/ros_gz_interfaces/msg/WorldControl.msg index f08cb6f5..efa22fb9 100644 --- a/ros_gz_interfaces/msg/WorldControl.msg +++ b/ros_gz_interfaces/msg/WorldControl.msg @@ -1,7 +1,7 @@ bool pause # Paused state. bool step # uint32 multi_step 0 # Paused after stepping multi_step. -ros_ign_interfaces/WorldReset reset # +ros_gz_interfaces/WorldReset reset # uint32 seed # builtin_interfaces/Time run_to_sim_time # A simulation time in the future to run to and # then pause. diff --git a/ros_gz_interfaces/package.xml b/ros_gz_interfaces/package.xml index 9584c8b4..b9da959b 100644 --- a/ros_gz_interfaces/package.xml +++ b/ros_gz_interfaces/package.xml @@ -1,7 +1,7 @@ - ros_ign_interfaces + ros_gz_interfaces 0.244.3 - Message and service data structures for interacting with Ignition from ROS2. + Message and service data structures for interacting with Gazebo from ROS2. Apache 2.0 Louise Poubel Zhenpeng Ge diff --git a/ros_gz_interfaces/srv/ControlWorld.srv b/ros_gz_interfaces/srv/ControlWorld.srv index 92f7a712..d8e41f24 100644 --- a/ros_gz_interfaces/srv/ControlWorld.srv +++ b/ros_gz_interfaces/srv/ControlWorld.srv @@ -1,3 +1,3 @@ -ros_ign_interfaces/WorldControl world_control # Message to Control world in Ignition Gazebo +ros_gz_interfaces/WorldControl world_control # Message to Control world in Gazebo Sim --- bool success # Return true if control is successful. diff --git a/ros_gz_interfaces/srv/DeleteEntity.srv b/ros_gz_interfaces/srv/DeleteEntity.srv index d922e7f9..13b3e1fd 100644 --- a/ros_gz_interfaces/srv/DeleteEntity.srv +++ b/ros_gz_interfaces/srv/DeleteEntity.srv @@ -1,3 +1,3 @@ -ros_ign_interfaces/Entity entity # Ignition Gazebo entity to be deleted. +ros_gz_interfaces/Entity entity # Gazebo Sim entity to be deleted. --- bool success # Return true if deletion is successful. diff --git a/ros_gz_interfaces/srv/SetEntityPose.srv b/ros_gz_interfaces/srv/SetEntityPose.srv index f1fbec7e..b749488c 100644 --- a/ros_gz_interfaces/srv/SetEntityPose.srv +++ b/ros_gz_interfaces/srv/SetEntityPose.srv @@ -1,4 +1,4 @@ -ros_ign_interfaces/Entity entity # Ignition Gazebo entity. +ros_gz_interfaces/Entity entity # Gazebo Sim entity. geometry_msgs/Pose pose # Pose of entity. --- bool success # Return true if set successfully. diff --git a/ros_gz_interfaces/srv/SpawnEntity.srv b/ros_gz_interfaces/srv/SpawnEntity.srv index cb85e438..35d5df59 100644 --- a/ros_gz_interfaces/srv/SpawnEntity.srv +++ b/ros_gz_interfaces/srv/SpawnEntity.srv @@ -1,3 +1,3 @@ -ros_ign_interfaces/EntityFactory entity_factory # Message to create a new entity +ros_gz_interfaces/EntityFactory entity_factory # Message to create a new entity --- bool success # Return true if spawned successfully. diff --git a/ros_gz_point_cloud/CMakeLists.txt b/ros_gz_point_cloud/CMakeLists.txt index e8bcf251..afcce424 100644 --- a/ros_gz_point_cloud/CMakeLists.txt +++ b/ros_gz_point_cloud/CMakeLists.txt @@ -1,6 +1,6 @@ cmake_minimum_required(VERSION 3.5) -project(ros_ign_point_cloud) +project(ros_gz_point_cloud) # Default to C++17 if(NOT CMAKE_CXX_STANDARD) @@ -15,13 +15,13 @@ find_package(catkin REQUIRED COMPONENTS sensor_msgs) find_package(ignition-gazebo2 2.1 QUIET REQUIRED) -set(IGN_GAZEBO_VER ${ignition-gazebo2_VERSION_MAJOR}) +set(GZ_SIM_VER ${ignition-gazebo2_VERSION_MAJOR}) find_package(ignition-rendering2 QUIET REQUIRED) -set(IGN_RENDERING_VER ${ignition-rendering2_VERSION_MAJOR}) +set(GZ_RENDERING_VER ${ignition-rendering2_VERSION_MAJOR}) find_package(ignition-sensors2 QUIET REQUIRED) -set(IGN_SENSORS_VER ${ignition-sensors2_VERSION_MAJOR}) +set(GZ_SENSORS_VER ${ignition-sensors2_VERSION_MAJOR}) catkin_package() @@ -30,14 +30,14 @@ include_directories( ${catkin_INCLUDE_DIRS} ) -set(plugin_name RosIgnPointCloud) +set(plugin_name RosGzPointCloud) add_library(${plugin_name} SHARED src/point_cloud.cc ) target_link_libraries(${plugin_name} - ignition-gazebo${IGN_GAZEBO_VER}::core - ignition-rendering${IGN_RENDERING_VER}::core - ignition-sensors${IGN_SENSORS_VER}::core + ignition-gazebo${GZ_SIM_VER}::core + ignition-rendering${GZ_RENDERING_VER}::core + ignition-sensors${GZ_SENSORS_VER}::core ${catkin_LIBRARIES} ) install(TARGETS ${plugin_name} @@ -52,3 +52,16 @@ install( ${CATKIN_PACKAGE_SHARE_DESTINATION}/examples ) +# TODO(CH3): Install symlink to deprecated library name. Remove on tock. +string(REPLACE "RosGz" "RosIgn" plugin_name_ign ${plugin_name}) +if(WIN32) + # symlinks on Windows require admin priviledges, fallback to copy + ADD_CUSTOM_COMMAND(TARGET ${plugin_name} POST_BUILD + COMMAND "${CMAKE_COMMAND}" -E copy + "$" + "$/${plugin_name_ign}") +else() + file(MAKE_DIRECTORY "${PROJECT_BINARY_DIR}/lib") + EXECUTE_PROCESS(COMMAND ${CMAKE_COMMAND} -E create_symlink ${plugin_name} ${plugin_name_ign} WORKING_DIRECTORY "${PROJECT_BINARY_DIR}/lib") + INSTALL(FILES ${PROJECT_BINARY_DIR}/lib/${plugin_name_ign} DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) +endif() diff --git a/ros_gz_point_cloud/examples/depth_camera.sdf b/ros_gz_point_cloud/examples/depth_camera.sdf index 5c47528f..b29c124b 100644 --- a/ros_gz_point_cloud/examples/depth_camera.sdf +++ b/ros_gz_point_cloud/examples/depth_camera.sdf @@ -1,6 +1,6 @@ - + 0.001 1.0 ogre2 @@ -82,8 +83,8 @@ true true true - /world/ros_ign/control - /world/ros_ign/stats + /world/ros_gz/control + /world/ros_gz/stats @@ -108,7 +109,7 @@ true true true - /world/ros_ign/stats + /world/ros_gz/stats @@ -275,8 +276,8 @@ true depth_camera + filename="RosGzPointCloud" + name="ros_gz_point_cloud::PointCloud"> points map diff --git a/ros_gz_point_cloud/examples/gpu_lidar.sdf b/ros_gz_point_cloud/examples/gpu_lidar.sdf index f6a531d2..ac61cbbe 100644 --- a/ros_gz_point_cloud/examples/gpu_lidar.sdf +++ b/ros_gz_point_cloud/examples/gpu_lidar.sdf @@ -1,6 +1,6 @@ - + 0.001 1.0 ogre2 @@ -82,8 +83,8 @@ true true true - /world/ros_ign/control - /world/ros_ign/stats + /world/ros_gz/control + /world/ros_gz/stats @@ -108,7 +109,7 @@ true true true - /world/ros_ign/stats + /world/ros_gz/stats @@ -278,8 +279,8 @@ 1 true + filename="RosGzPointCloud" + name="ros_gz_point_cloud::PointCloud"> custom_params pc2 custom_params/link diff --git a/ros_gz_point_cloud/examples/rgbd_camera.sdf b/ros_gz_point_cloud/examples/rgbd_camera.sdf index dd1282ee..e969ffce 100644 --- a/ros_gz_point_cloud/examples/rgbd_camera.sdf +++ b/ros_gz_point_cloud/examples/rgbd_camera.sdf @@ -1,6 +1,6 @@ - + 0.001 1.0 ogre2 @@ -86,8 +87,8 @@ true true true - /world/ros_ign/control - /world/ros_ign/stats + /world/ros_gz/control + /world/ros_gz/stats @@ -112,7 +113,7 @@ true true true - /world/ros_ign/stats + /world/ros_gz/stats @@ -330,8 +331,8 @@ true custom_params + filename="RosGzPointCloud" + name="ros_gz_point_cloud::PointCloud"> custom_params pc2 map @@ -375,8 +376,8 @@ true rgbd_camera + filename="RosGzPointCloud" + name="ros_gz_point_cloud::PointCloud"> diff --git a/ros_gz_point_cloud/package.xml b/ros_gz_point_cloud/package.xml index 7a7b5add..b3d5717e 100644 --- a/ros_gz_point_cloud/package.xml +++ b/ros_gz_point_cloud/package.xml @@ -1,7 +1,7 @@ - ros_ign_point_cloud + ros_gz_point_cloud 0.7.0 - Point cloud utilities for Ignition simulation with ROS. + Point cloud utilities for Gazebo simulation with ROS. Apache 2.0 Louise Poubel diff --git a/ros_gz_point_cloud/src/point_cloud.cc b/ros_gz_point_cloud/src/point_cloud.cc index 7f6af6d6..2dd5cd66 100644 --- a/ros_gz_point_cloud/src/point_cloud.cc +++ b/ros_gz_point_cloud/src/point_cloud.cc @@ -33,13 +33,13 @@ #include #include -IGNITION_ADD_PLUGIN( - ros_ign_point_cloud::PointCloud, +GZ_ADD_PLUGIN( + ros_gz_point_cloud::PointCloud, ignition::gazebo::System, - ros_ign_point_cloud::PointCloud::ISystemConfigure, - ros_ign_point_cloud::PointCloud::ISystemPostUpdate) + ros_gz_point_cloud::PointCloud::ISystemConfigure, + ros_gz_point_cloud::PointCloud::ISystemPostUpdate) -using namespace ros_ign_point_cloud; +using namespace ros_gz_point_cloud; /// \brief Types of sensors supported by this plugin enum class SensorType { @@ -54,7 +54,7 @@ enum class SensorType { }; ////////////////////////////////////////////////// -class ros_ign_point_cloud::PointCloudPrivate +class ros_gz_point_cloud::PointCloudPrivate { /// \brief Callback when the depth camera generates a new frame. /// This is called in the rendering thread. @@ -156,7 +156,7 @@ void PointCloud::Configure(const ignition::gazebo::Entity &_entity, } else { - ROS_ERROR_NAMED("ros_ign_point_cloud", + ROS_ERROR_NAMED("ros_gz_point_cloud", "Point cloud plugin must be attached to an RGBD camera, depth camera or GPU lidar."); return; } @@ -167,7 +167,7 @@ void PointCloud::Configure(const ignition::gazebo::Entity &_entity, int argc = 0; char** argv = NULL; ros::init(argc, argv, "ignition", ros::init_options::NoSigintHandler); - ROS_INFO_NAMED("ros_ign_point_cloud", "Initialized ROS"); + ROS_INFO_NAMED("ros_gz_point_cloud", "Initialized ROS"); } // Sensor scoped name @@ -250,7 +250,7 @@ void PointCloudPrivate::LoadDepthCamera( std::dynamic_pointer_cast(sensor); if (!this->depth_camera_) { - ROS_ERROR_NAMED("ros_ign_point_cloud", + ROS_ERROR_NAMED("ros_gz_point_cloud", "Rendering sensor named [%s] is not a depth camera", sensor_name.c_str()); return; } @@ -280,7 +280,7 @@ void PointCloudPrivate::LoadRgbCamera( this->rgb_camera_ = std::dynamic_pointer_cast(sensor); if (!this->rgb_camera_) { - ROS_ERROR_NAMED("ros_ign_point_cloud", + ROS_ERROR_NAMED("ros_gz_point_cloud", "Rendering sensor named [%s] is not an RGB camera", sensor_name.c_str()); return; } @@ -308,7 +308,7 @@ void PointCloudPrivate::LoadGpuRays( std::dynamic_pointer_cast(sensor); if (!this->gpu_rays_) { - ROS_ERROR_NAMED("ros_ign_point_cloud", + ROS_ERROR_NAMED("ros_gz_point_cloud", "Rendering sensor named [%s] is not a depth camera", sensor_name.c_str()); return; } @@ -331,23 +331,23 @@ void PointCloudPrivate::OnNewDepthFrame(const float *_scan, // Just sanity check, but don't prevent publishing if (this->type_ == SensorType::RGBD_CAMERA && _channels != 1) { - ROS_WARN_NAMED("ros_ign_point_cloud", + ROS_WARN_NAMED("ros_gz_point_cloud", "Expected depth image to have 1 channel, but it has [%i]", _channels); } if (this->type_ == SensorType::GPU_LIDAR && _channels != 3) { - ROS_WARN_NAMED("ros_ign_point_cloud", + ROS_WARN_NAMED("ros_gz_point_cloud", "Expected GPU rays to have 3 channels, but it has [%i]", _channels); } if ((this->type_ == SensorType::RGBD_CAMERA || this->type_ == SensorType::DEPTH_CAMERA) && _format != "FLOAT32") { - ROS_WARN_NAMED("ros_ign_point_cloud", + ROS_WARN_NAMED("ros_gz_point_cloud", "Expected depth image to have [FLOAT32] format, but it has [%s]", _format.c_str()); } if (this->type_ == SensorType::GPU_LIDAR && _format != "PF_FLOAT32_RGB") { - ROS_WARN_NAMED("ros_ign_point_cloud", + ROS_WARN_NAMED("ros_gz_point_cloud", "Expected GPU rays to have [PF_FLOAT32_RGB] format, but it has [%s]", _format.c_str()); } @@ -496,4 +496,3 @@ void PointCloudPrivate::OnNewDepthFrame(const float *_scan, this->pc_pub_.publish(msg); } - diff --git a/ros_gz_point_cloud/src/point_cloud.hh b/ros_gz_point_cloud/src/point_cloud.hh index 3d9a2ff5..8d09c73e 100644 --- a/ros_gz_point_cloud/src/point_cloud.hh +++ b/ros_gz_point_cloud/src/point_cloud.hh @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef ROS_IGN_POINTCLOUD__POINTCLOUD_HPP_ -#define ROS_IGN_POINTCLOUD__POINTCLOUD_HPP_ +#ifndef ROS_GZ_POINTCLOUD__POINTCLOUD_HPP_ +#define ROS_GZ_POINTCLOUD__POINTCLOUD_HPP_ #include #include -namespace ros_ign_point_cloud +namespace ros_gz_point_cloud { // Forward declarations. class PointCloudPrivate; diff --git a/ros_gz_shims/README.md b/ros_gz_shims/README.md new file mode 100644 index 00000000..b653a6fc --- /dev/null +++ b/ros_gz_shims/README.md @@ -0,0 +1,13 @@ +# Description + +These are shim packages for `ros_gz` that redirect executable calls to the related `ros_gz` executable. +These require `ros_gz` to be installed though, but are set up to depend on `ros_gz`. + +This allows users to do either of these and get equivalent behavior: + +```bash +ros2 run ros_gz parameter_bridge [...] +ros2 run ros_ign parameter_bridge [...] # Will emit deprecation warning +``` + +Additionally, installed files like launchfiles, message interfaces etc. are **duplicated** versions of the ones in `ros_gz` (but renamed as appropriate), and point to `ros_gz` dependencies as well (e.g. launchfiles pointing to `ros_gz` nodes.) diff --git a/ros_gz_shims/ros_ign/CMakeLists.txt b/ros_gz_shims/ros_ign/CMakeLists.txt new file mode 100644 index 00000000..80524e92 --- /dev/null +++ b/ros_gz_shims/ros_ign/CMakeLists.txt @@ -0,0 +1,10 @@ +cmake_minimum_required(VERSION 3.5) +project(ros_ign) +find_package(ament_cmake REQUIRED) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + +ament_package() diff --git a/ros_gz_shims/ros_ign/README.md b/ros_gz_shims/ros_ign/README.md new file mode 100644 index 00000000..d6f36599 --- /dev/null +++ b/ros_gz_shims/ros_ign/README.md @@ -0,0 +1,2 @@ +# This is a shim meta-package +For [ros_gz](https://github.com/gazebosim/ros_gz) diff --git a/ros_gz_shims/ros_ign/package.xml b/ros_gz_shims/ros_ign/package.xml new file mode 100644 index 00000000..03e41bcb --- /dev/null +++ b/ros_gz_shims/ros_ign/package.xml @@ -0,0 +1,28 @@ + + + + + ros_ign + 0.0.1 + Shim meta-package to redirect to ros_gz. + Brandon Ong + Apache 2.0 + + ament_cmake + ros_gz + + ros_ign_bridge + ros_ign_gazebo + ros_ign_gazebo_demos + ros_ign_image + + + + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/ros_gz_shims/ros_ign_bridge/CMakeLists.txt b/ros_gz_shims/ros_ign_bridge/CMakeLists.txt new file mode 100644 index 00000000..7be505b0 --- /dev/null +++ b/ros_gz_shims/ros_ign_bridge/CMakeLists.txt @@ -0,0 +1,29 @@ +cmake_minimum_required(VERSION 3.5) +project(ros_ign_bridge) + +# Default to C++14 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra -Wpedantic") +endif() + +find_package(ament_cmake REQUIRED) +find_package(ament_index_cpp REQUIRED) + +add_executable(parameter_bridge src/parameter_bridge_shim.cpp) +ament_target_dependencies(parameter_bridge ament_index_cpp) + +add_executable(static_bridge src/static_bridge_shim.cpp) +ament_target_dependencies(static_bridge ament_index_cpp) + +ament_export_dependencies(ament_index_cpp ros_gz_bridge) + +install(TARGETS + parameter_bridge + static_bridge + DESTINATION lib/${PROJECT_NAME} +) + +ament_package() diff --git a/ros_gz_shims/ros_ign_bridge/README.md b/ros_gz_shims/ros_ign_bridge/README.md new file mode 100644 index 00000000..e93d8f26 --- /dev/null +++ b/ros_gz_shims/ros_ign_bridge/README.md @@ -0,0 +1,2 @@ +# This is a shim package +For [ros_gz_bridge](https://github.com/gazebosim/ros_gz/tree/ros2/ros_gz_bridge) diff --git a/ros_gz_shims/ros_ign_bridge/package.xml b/ros_gz_shims/ros_ign_bridge/package.xml new file mode 100644 index 00000000..c85b8c97 --- /dev/null +++ b/ros_gz_shims/ros_ign_bridge/package.xml @@ -0,0 +1,19 @@ + + + + ros_ign_bridge + 0.0.1 + Shim package to redirect to ros_gz_bridge. + Brandon Ong + + Apache 2.0 + + ament_cmake + ament_index_cpp + + ros_gz_bridge + + + ament_cmake + + diff --git a/ros_gz_shims/ros_ign_bridge/src/parameter_bridge_shim.cpp b/ros_gz_shims/ros_ign_bridge/src/parameter_bridge_shim.cpp new file mode 100644 index 00000000..b6b613e5 --- /dev/null +++ b/ros_gz_shims/ros_ign_bridge/src/parameter_bridge_shim.cpp @@ -0,0 +1,30 @@ +// Shim to redirect "ros_ign_bridge parameter_bridge" call to "ros_gz_bridge parameter_bridge" + +#include +#include +#include +#include + +#include + + +int main(int argc, char * argv[]) +{ + std::stringstream cli_call; + + cli_call << ament_index_cpp::get_package_prefix("ros_gz_bridge") + << "/lib/ros_gz_bridge/parameter_bridge"; + + if (argc > 1) + { + for (int i = 1; i < argc; i++) + cli_call << " " << argv[i]; + } + + std::cerr << "[ros_ign_bridge] is deprecated! " + << "Redirecting to use [ros_gz_bridge] instead!" + << std::endl << std::endl; + system(cli_call.str().c_str()); + + return 0; +} diff --git a/ros_gz_shims/ros_ign_bridge/src/static_bridge_shim.cpp b/ros_gz_shims/ros_ign_bridge/src/static_bridge_shim.cpp new file mode 100644 index 00000000..56c577b8 --- /dev/null +++ b/ros_gz_shims/ros_ign_bridge/src/static_bridge_shim.cpp @@ -0,0 +1,30 @@ +// Shim to redirect "ros_ign_bridge static_bridge" call to "ros_gz_bridge static_bridge" + +#include +#include +#include +#include + +#include + + +int main(int argc, char * argv[]) +{ + std::stringstream cli_call; + + cli_call << ament_index_cpp::get_package_prefix("ros_gz_bridge") + << "/lib/ros_gz_bridge/static_bridge"; + + if (argc > 1) + { + for (int i = 1; i < argc; i++) + cli_call << " " << argv[i]; + } + + std::cerr << "[ros_ign_bridge] is deprecated! " + << "Redirecting to use [ros_gz_bridge] instead!" + << std::endl << std::endl; + system(cli_call.str().c_str()); + + return 0; +} diff --git a/ros_gz_shims/ros_ign_gazebo/CMakeLists.txt b/ros_gz_shims/ros_ign_gazebo/CMakeLists.txt new file mode 100644 index 00000000..86974a76 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo/CMakeLists.txt @@ -0,0 +1,45 @@ +cmake_minimum_required(VERSION 3.5) +project(ros_ign_gazebo) + +# Default to C++14 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra -Wpedantic") +endif() + +find_package(ament_cmake REQUIRED) +find_package(ament_index_cpp REQUIRED) + +add_executable(create + src/create_shim.cpp +) +ament_target_dependencies(create ament_index_cpp) + +ament_export_dependencies( + ament_index_cpp + ros_gz_bridge +) + +configure_file( + launch/ign_gazebo.launch.py.in + launch/ign_gazebo.launch.py.configured + @ONLY +) +file(GENERATE + OUTPUT "${CMAKE_CURRENT_BINARY_DIR}/launch/ign_gazebo.launch.py" + INPUT "${CMAKE_CURRENT_BINARY_DIR}/launch/ign_gazebo.launch.py.configured" +) + +install(FILES + "${CMAKE_CURRENT_BINARY_DIR}/launch/ign_gazebo.launch.py" + DESTINATION share/${PROJECT_NAME}/launch +) + +install(TARGETS + create + DESTINATION lib/${PROJECT_NAME} +) + +ament_package() diff --git a/ros_gz_shims/ros_ign_gazebo/launch/ign_gazebo.launch.py.in b/ros_gz_shims/ros_ign_gazebo/launch/ign_gazebo.launch.py.in new file mode 100644 index 00000000..e8ff4909 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo/launch/ign_gazebo.launch.py.in @@ -0,0 +1,63 @@ +# Copyright 2020 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +"""Launch Gazebo Sim with command line arguments.""" + +from os import environ + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import ExecuteProcess +from launch.substitutions import LaunchConfiguration + + +def generate_launch_description(): + env = {'GZ_SIM_SYSTEM_PLUGIN_PATH': + ':'.join([environ.get('GZ_SIM_SYSTEM_PLUGIN_PATH', default=''), + environ.get('LD_LIBRARY_PATH', default='')]), + 'IGN_GAZEBO_SYSTEM_PLUGIN_PATH': # TODO(CH3): To support pre-garden. Deprecated. + ':'.join([environ.get('IGN_GAZEBO_SYSTEM_PLUGIN_PATH', default=''), + environ.get('LD_LIBRARY_PATH', default='')])} + + return LaunchDescription([ + DeclareLaunchArgument('gz_args', default_value='', + description='Arguments to be passed to Gazebo Sim'), + # Gazebo Sim's major version + DeclareLaunchArgument('gz_version', default_value='@GZ_SIM_VER@', + description='Gazebo Sim\'s major version'), + + # TODO(CH3): Deprecated. Remove on tock. + DeclareLaunchArgument( + 'ign_args', default_value='', + description='Deprecated: Arguments to be passed to Gazebo Sim' + ), + # Gazebo Sim's major version + DeclareLaunchArgument( + 'ign_version', default_value='@GZ_SIM_VER@', + description='Deprecated: Gazebo Sim\'s major version' + ), + + ExecuteProcess( + cmd=['gz sim', + LaunchConfiguration('gz_args'), + LaunchConfiguration('ign_args'), + '--force-version', + LaunchConfiguration('gz_version'), + LaunchConfiguration('ign_version'), + ], + output='screen', + additional_env=env, + shell=True + ) + ]) diff --git a/ros_gz_shims/ros_ign_gazebo/package.xml b/ros_gz_shims/ros_ign_gazebo/package.xml new file mode 100644 index 00000000..c0683a53 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo/package.xml @@ -0,0 +1,19 @@ + + + + ros_ign_gazebo + 0.0.1 + Shim package to redirect to ros_gz_sim. + Brandon Ong + + Apache 2.0 + + ament_cmake + ament_index_cpp + + ros_gz_sim + + + ament_cmake + + diff --git a/ros_gz_shims/ros_ign_gazebo/src/create_shim.cpp b/ros_gz_shims/ros_ign_gazebo/src/create_shim.cpp new file mode 100644 index 00000000..dbaa029e --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo/src/create_shim.cpp @@ -0,0 +1,30 @@ +// Shim to redirect "ros_ign_bridge parameter_bridge" call to "ros_gz_sim parameter_bridge" + +#include +#include +#include +#include + +#include + + +int main(int argc, char * argv[]) +{ + std::stringstream cli_call; + + cli_call << ament_index_cpp::get_package_prefix("ros_gz_sim") + << "/lib/ros_gz_sim/create"; + + if (argc > 1) + { + for (int i = 1; i < argc; i++) + cli_call << " " << argv[i]; + } + + std::cerr << "[ros_ign_gazebo] is deprecated! " + << "Redirecting to use [ros_gz_sim] instead!" + << std::endl << std::endl; + system(cli_call.str().c_str()); + + return 0; +} diff --git a/ros_gz_shims/ros_ign_gazebo_demos/CMakeLists.txt b/ros_gz_shims/ros_ign_gazebo_demos/CMakeLists.txt new file mode 100644 index 00000000..0a7ae4fe --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/CMakeLists.txt @@ -0,0 +1,29 @@ +cmake_minimum_required(VERSION 3.5) +project(ros_ign_gazebo_demos) + +find_package(ament_cmake REQUIRED) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + +install( + DIRECTORY + launch/ + DESTINATION share/${PROJECT_NAME}/launch +) + +install( + DIRECTORY + rviz/ + DESTINATION share/${PROJECT_NAME}/rviz +) + +install( + DIRECTORY + models/ + DESTINATION share/${PROJECT_NAME}/models +) + +ament_package() diff --git a/ros_gz_shims/ros_ign_gazebo_demos/README.md b/ros_gz_shims/ros_ign_gazebo_demos/README.md new file mode 100644 index 00000000..b2ce4368 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/README.md @@ -0,0 +1,2 @@ +# This is a shim package +For [ros_gz_sim_demos](https://github.com/gazebosim/ros_gz/tree/ros2/ros_ign_gazebo_demos) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/air_pressure.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/air_pressure.launch.py new file mode 100644 index 00000000..272d6eb1 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/air_pressure.launch.py @@ -0,0 +1,63 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +"""Launch Gazebo Sim with command line arguments.""" + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + # Bridge + bridge = Node( + package='ros_gz_bridge', + executable='parameter_bridge', + arguments=['/air_pressure@sensor_msgs/msg/FluidPressure@ignition.msgs.FluidPressure'], + parameters=[{'qos_overrides./air_pressure.publisher.reliability': 'best_effort'}], + output='screen' + ) + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={'gz_args': '-r sensors.sdf'}.items(), + ) + + # RQt + rqt = Node( + package='rqt_topic', + executable='rqt_topic', + arguments=['-t'], + condition=IfCondition(LaunchConfiguration('rqt')) + ) + return LaunchDescription([ + gz_sim, + DeclareLaunchArgument('rqt', default_value='true', + description='Open RQt.'), + bridge, + rqt + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/battery.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/battery.launch.py new file mode 100644 index 00000000..4e32322a --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/battery.launch.py @@ -0,0 +1,69 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + # RQt + rqt = Node( + package='rqt_plot', + executable='rqt_plot', + # FIXME: Why isn't the topic being populated on the UI? RQt issue? + arguments=['--force-discover', + '/model/vehicle_blue/battery/linear_battery/state/percentage'], + condition=IfCondition(LaunchConfiguration('rqt')) + ) + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={ + 'gz_args': '-r -z 1000000 linear_battery_demo.sdf' + }.items(), + ) + + # Bridge + bridge = Node( + package='ros_gz_bridge', + executable='parameter_bridge', + arguments=[ + '/model/vehicle_blue/cmd_vel@geometry_msgs/msg/Twist@ignition.msgs.Twist', + '/model/vehicle_blue/battery/linear_battery/state@sensor_msgs/msg/BatteryState@' + 'ignition.msgs.BatteryState' + ], + output='screen' + ) + + return LaunchDescription([ + gz_sim, + DeclareLaunchArgument('rqt', default_value='true', + description='Open RQt.'), + bridge, + rqt + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/camera.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/camera.launch.py new file mode 100644 index 00000000..1bd9a8a0 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/camera.launch.py @@ -0,0 +1,63 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={'gz_args': '-r camera_sensor.sdf'}.items(), + ) + + # RViz + rviz = Node( + package='rviz2', + executable='rviz2', + arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'camera.rviz')], + condition=IfCondition(LaunchConfiguration('rviz')) + ) + + # Bridge + bridge = Node( + package='ros_gz_bridge', + executable='parameter_bridge', + arguments=['/camera@sensor_msgs/msg/Image@ignition.msgs.Image', + '/camera_info@sensor_msgs/msg/CameraInfo@ignition.msgs.CameraInfo'], + output='screen' + ) + + return LaunchDescription([ + DeclareLaunchArgument('rviz', default_value='true', + description='Open RViz.'), + gz_sim, + bridge, + rviz + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/depth_camera.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/depth_camera.launch.py new file mode 100644 index 00000000..d42ce862 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/depth_camera.launch.py @@ -0,0 +1,77 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py') + ), + # launch_arguments={ + # 'gz_args': '-r depth_camera.sdf' + # }.items(), + ) + + # RQt + rqt = Node( + package='rqt_image_view', + executable='rqt_image_view', + arguments=['/camera'], + condition=IfCondition(LaunchConfiguration('rqt')) + ) + + # RViz + rviz = Node( + package='rviz2', + executable='rviz2', + # FIXME: Generate new RViz config once this demo is usable again + # arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'depth_camera.rviz')], + condition=IfCondition(LaunchConfiguration('rviz')) + ) + + # Bridge + bridge = Node( + package='ros_gz_bridge', + executable='parameter_bridge', + arguments=['/depth_camera@sensor_msgs/msg/Image@ignition.msgs.Image'], + output='screen' + ) + + # FIXME: need a SDF file (depth_camera.sdf) inside ros_gz_point_cloud + return LaunchDescription([ + gz_sim, + DeclareLaunchArgument('rviz', default_value='true', + description='Open RViz.'), + DeclareLaunchArgument('rqt', default_value='true', + description='Open RQt.'), + bridge, + rviz, + rqt + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/diff_drive.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/diff_drive.launch.py new file mode 100644 index 00000000..8a297567 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/diff_drive.launch.py @@ -0,0 +1,69 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={ + 'gz_args': '-r diff_drive.sdf' + }.items(), + ) + + # RViz + rviz = Node( + package='rviz2', + executable='rviz2', + arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'diff_drive.rviz')], + condition=IfCondition(LaunchConfiguration('rviz')) + ) + + # Bridge + bridge = Node( + package='ros_gz_bridge', + executable='parameter_bridge', + arguments=['/model/vehicle_blue/cmd_vel@geometry_msgs/msg/Twist@ignition.msgs.Twist', + '/model/vehicle_blue/odometry@nav_msgs/msg/Odometry@ignition.msgs.Odometry', + '/model/vehicle_green/cmd_vel@geometry_msgs/msg/Twist@ignition.msgs.Twist', + '/model/vehicle_green/odometry@nav_msgs/msg/Odometry@ignition.msgs.Odometry'], + parameters=[{'qos_overrides./model/vehicle_blue.subscriber.reliability': 'reliable', + 'qos_overrides./model/vehicle_green.subscriber.reliability': 'reliable'}], + output='screen' + ) + + return LaunchDescription([ + gz_sim, + DeclareLaunchArgument('rviz', default_value='true', + description='Open RViz.'), + bridge, + rviz + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/gpu_lidar.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/gpu_lidar.launch.py new file mode 100644 index 00000000..5cfdb08f --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/gpu_lidar.launch.py @@ -0,0 +1,65 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + # launch_arguments={ + # 'gz_args': '-r gpu_lidar.sdf' + # }.items(), + ) + + # RViz + rviz = Node( + package='rviz2', + executable='rviz2', + # FIXME: Generate new RViz config once this demo is usable again + # arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'gpu_lidar.rviz')], + condition=IfCondition(LaunchConfiguration('rviz')) + ) + + # Bridge + bridge = Node( + package='ros_gz_bridge', + executable='parameter_bridge', + arguments=['/lidar@sensor_msgs/msg/LaserScan@ignition.msgs.LaserScan/'], + output='screen' + ) + + # FIXME: need a SDF file (gpu_lidar.sdf) inside ros_gz_point_cloud/ + return LaunchDescription([ + gz_sim, + DeclareLaunchArgument('rviz', default_value='true', + description='Open RViz.'), + bridge, + rviz + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/gpu_lidar_bridge.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/gpu_lidar_bridge.launch.py new file mode 100644 index 00000000..26bd36b8 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/gpu_lidar_bridge.launch.py @@ -0,0 +1,65 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={ + 'gz_args': '-r gpu_lidar_sensor.sdf' + }.items(), + ) + + # RViz + rviz = Node( + package='rviz2', + executable='rviz2', + arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'gpu_lidar_bridge.rviz')], + condition=IfCondition(LaunchConfiguration('rviz')) + ) + + # Bridge + bridge = Node( + package='ros_gz_bridge', + executable='parameter_bridge', + arguments=['lidar@sensor_msgs/msg/LaserScan@ignition.msgs.LaserScan', + '/lidar/points@sensor_msgs/msg/PointCloud2@ignition.msgs.PointCloudPacked'], + output='screen' + ) + + return LaunchDescription([ + gz_sim, + DeclareLaunchArgument('rviz', default_value='true', + description='Open RViz.'), + bridge, + rviz, + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/image_bridge.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/image_bridge.launch.py new file mode 100644 index 00000000..91e81e33 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/image_bridge.launch.py @@ -0,0 +1,65 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={ + 'gz_args': '-r sensors_demo.sdf' + }.items(), + ) + + # RQt + rqt = Node( + package='rqt_image_view', + executable='rqt_image_view', + arguments=[LaunchConfiguration('image_topic')], + condition=IfCondition(LaunchConfiguration('rqt')) + ) + + # Bridge + bridge = Node( + package='ros_gz_image', + executable='image_bridge', + arguments=['camera', 'depth_camera', 'rgbd_camera/image', 'rgbd_camera/depth_image'], + output='screen' + ) + + return LaunchDescription([ + gz_sim, + DeclareLaunchArgument('rqt', default_value='true', + description='Open RQt.'), + DeclareLaunchArgument('image_topic', default_value='/camera', + description='Topic to start viewing in RQt.'), + bridge, + rqt + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/imu.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/imu.launch.py new file mode 100644 index 00000000..649ad359 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/imu.launch.py @@ -0,0 +1,78 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={ + 'gz_args': '-r sensors.sdf' + }.items(), + ) + + # RQt + rqt = Node( + package='rqt_topic', + executable='rqt_topic', + arguments=['-t'], + condition=IfCondition(LaunchConfiguration('rqt')) + ) + + # RViz + # FIXME: Add once there's an IMU display for RViz2 + # pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') + # rviz = Node( + # package='rviz2', + # executable='rviz2', + # # arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'imu.rviz')], + # condition=IfCondition(LaunchConfiguration('rviz')) + # ) + + # Bridge + bridge = Node( + package='ros_gz_bridge', + executable='parameter_bridge', + arguments=['/imu@sensor_msgs/msg/Imu@ignition.msgs.IMU'], + output='screen' + ) + + return LaunchDescription([ + gz_sim, + DeclareLaunchArgument( + 'rqt', default_value='true', description='Open RQt.' + ), + DeclareLaunchArgument( + 'rviz', default_value='true', description='Open RViz.' + ), + bridge, + rqt + # rviz + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/joint_states.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/joint_states.launch.py new file mode 100644 index 00000000..20b330ec --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/joint_states.launch.py @@ -0,0 +1,98 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import IncludeLaunchDescription +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch_ros.actions import Node +import xacro + + +def generate_launch_description(): + + # Package Directories + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') + + # Parse robot description from xacro + robot_description_file = os.path.join(pkg_ros_gz_sim_demos, 'models', 'rrbot.xacro') + robot_description_config = xacro.process_file( + robot_description_file + ) + robot_description = {'robot_description': robot_description_config.toxml()} + + # Robot state publisher + robot_state_publisher = Node( + package='robot_state_publisher', + executable='robot_state_publisher', + name='robot_state_publisher', + output='both', + parameters=[robot_description], + ) + + # Gazebo Sim + gazebo = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py') + ), + launch_arguments={'gz_args': '-r empty.sdf'}.items(), + ) + + # RViz + rviz = Node( + package='rviz2', + executable='rviz2', + arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'joint_states.rviz')], + ) + + # Spawn + spawn = Node( + package='ros_gz_sim', + executable='create', + arguments=[ + '-name', 'rrbot', + '-topic', 'robot_description', + ], + output='screen', + ) + + # Gz - ROS Bridge + bridge = Node( + package='ros_gz_bridge', + executable='parameter_bridge', + arguments=[ + # Clock (IGN -> ROS2) + '/clock@rosgraph_msgs/msg/Clock[ignition.msgs.Clock', + # Joint states (IGN -> ROS2) + '/world/empty/model/rrbot/joint_state@sensor_msgs/msg/JointState[ignition.msgs.Model', + ], + remappings=[ + ('/world/empty/model/rrbot/joint_state', 'joint_states'), + ], + output='screen' + ) + + return LaunchDescription( + [ + # Nodes and Launches + gazebo, + spawn, + bridge, + robot_state_publisher, + rviz, + ] + ) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/magnetometer.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/magnetometer.launch.py new file mode 100644 index 00000000..0e026676 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/magnetometer.launch.py @@ -0,0 +1,63 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={ + 'gz_args': '-r sensors.sdf' + }.items(), + ) + + # RQt + rqt = Node( + package='rqt_topic', + executable='rqt_topic', + arguments=['-t'], + condition=IfCondition(LaunchConfiguration('rqt')) + ) + + # Bridge + bridge = Node( + package='ros_gz_bridge', + executable='parameter_bridge', + arguments=['/magnetometer@sensor_msgs/msg/MagneticField@ignition.msgs.Magnetometer'], + output='screen' + ) + + return LaunchDescription([ + gz_sim, + DeclareLaunchArgument('rqt', default_value='true', + description='Open RQt.'), + bridge, + rqt + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/rgbd_camera.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/rgbd_camera.launch.py new file mode 100644 index 00000000..1ec8409b --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/rgbd_camera.launch.py @@ -0,0 +1,63 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.launch_description_sources import PythonLaunchDescriptionSource + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + # launch_arguments={ + # 'gz_args': '-r rgbd_camera.sdf' + # }.items(), + ) + + # FIXME: need rviz configuration migration + # rviz = Node( + # package='rviz2', + # executable='rviz2', + # arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'rgbd_camera.rviz')], + # condition=IfCondition(LaunchConfiguration('rviz')) + # ) + + # Bridge + bridge = Node( + package='ros_gz_bridge', + executable='parameter_bridge', + arguments=['/rgbd_camera/image@sensor_msgs/msg/Image@ignition.msgs.Image', + '/rgbd_camera/depth_image@sensor_msgs/msg/Image@ignition.msgs.Image'], + output='screen' + ) + + # FIXME: need a SDF file (depth_camera.sdf) inside ros_gz_point_cloud/ + return LaunchDescription([ + gz_sim, + DeclareLaunchArgument('rviz', default_value='true', + description='Open RViz.'), + bridge, + # rviz, + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/rgbd_camera_bridge.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/rgbd_camera_bridge.launch.py new file mode 100644 index 00000000..a318f682 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/rgbd_camera_bridge.launch.py @@ -0,0 +1,70 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={ + 'gz_args': '-r sensors_demo.sdf' + }.items(), + ) + + # RViz + rviz = Node( + package='rviz2', + executable='rviz2', + arguments=[ + '-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'rgbd_camera_bridge.rviz') + ], + condition=IfCondition(LaunchConfiguration('rviz')) + ) + + # Bridge + bridge = Node( + package='ros_gz_bridge', + executable='parameter_bridge', + arguments=[ + '/rgbd_camera/image@sensor_msgs/msg/Image@ignition.msgs.Image', + '/rgbd_camera/depth_image@sensor_msgs/msg/Image@ignition.msgs.Image', + '/rgbd_camera/points@sensor_msgs/msg/PointCloud2@ignition.msgs.PointCloudPacked' + ], + output='screen' + ) + + return LaunchDescription([ + gz_sim, + DeclareLaunchArgument('rviz', default_value='true', + description='Open RViz.'), + bridge, + rviz, + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/robot_description_publisher.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/robot_description_publisher.launch.py new file mode 100755 index 00000000..882cdee3 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/robot_description_publisher.launch.py @@ -0,0 +1,93 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import IncludeLaunchDescription +from launch.launch_description_sources import PythonLaunchDescriptionSource + +from launch_ros.actions import Node + + +def generate_launch_description(): + # Import the model urdf (load from file, xacro ...) + robot_desc = \ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + ''\ + '' + + # Robot state publisher + params = {'use_sim_time': True, 'robot_description': robot_desc} + robot_state_publisher = Node( + package='robot_state_publisher', + executable='robot_state_publisher', + name='robot_state_publisher', + output='screen', + parameters=[params], + arguments=[]) + + # Gazebo Sim + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + gazebo = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={'gz_args': '-r empty.sdf'}.items(), + ) + + # RViz + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') + rviz = Node( + package='rviz2', + executable='rviz2', + arguments=[ + '-d', + os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'robot_description_publisher.rviz') + ] + ) + + # Spawn + spawn = Node(package='ros_gz_sim', executable='create', + arguments=[ + '-name', 'my_custom_model', + '-x', '1.2', + '-z', '2.3', + '-Y', '3.4', + '-topic', '/robot_description'], + output='screen') + + return LaunchDescription([ + gazebo, + robot_state_publisher, + rviz, + spawn + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/tf_bridge.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/tf_bridge.launch.py new file mode 100644 index 00000000..3b2171d0 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/tf_bridge.launch.py @@ -0,0 +1,59 @@ +# Copyright 2022 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import ExecuteProcess +from launch_ros.actions import Node + + +def generate_launch_description(): + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') + return LaunchDescription([ + # Launch gazebo + ExecuteProcess( + cmd=[ + 'ign', 'gazebo', '-r', + os.path.join( + pkg_ros_gz_sim_demos, + 'models', + 'double_pendulum_model.sdf' + ) + ] + ), + # Launch a bridge to forward tf and joint states to ros2 + Node( + package='ros_gz_bridge', + executable='parameter_bridge', + arguments=[ + '/world/default/model/double_pendulum_with_base0/joint_state@' + 'sensor_msgs/msg/JointState[ignition.msgs.Model', + '/model/double_pendulum_with_base0/pose@' + 'tf2_msgs/msg/TFMessage[ignition.msgs.Pose_V' + ], + remappings=[ + ('/model/double_pendulum_with_base0/pose', '/tf'), + ('/world/default/model/double_pendulum_with_base0/joint_state', '/joint_states') + ] + ), + # Launch rviz + Node( + package='rviz2', + executable='rviz2', + arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'tf_bridge.rviz')] + ) + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/launch/triggered_camera.launch.py b/ros_gz_shims/ros_ign_gazebo_demos/launch/triggered_camera.launch.py new file mode 100644 index 00000000..9e6362a2 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/launch/triggered_camera.launch.py @@ -0,0 +1,64 @@ +# Copyright 2022 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import Node + + +def generate_launch_description(): + + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + + gz_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={'gz_args': '-r triggered_camera_sensor.sdf'}.items(), + ) + + # RViz + rviz = Node( + package='rviz2', + executable='rviz2', + arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'camera.rviz')], + condition=IfCondition(LaunchConfiguration('rviz')) + ) + + # Bridge + bridge = Node( + package='ros_gz_bridge', + executable='parameter_bridge', + arguments=['/camera@sensor_msgs/msg/Image@ignition.msgs.Image', + '/camera/trigger@std_msgs/msg/Bool@ignition.msgs.Boolean', + '/camera_info@sensor_msgs/msg/CameraInfo@ignition.msgs.CameraInfo'], + output='screen' + ) + + return LaunchDescription([ + DeclareLaunchArgument('rviz', default_value='true', + description='Open RViz.'), + gz_sim, + bridge, + rviz + ]) diff --git a/ros_gz_shims/ros_ign_gazebo_demos/models/double_pendulum_model.sdf b/ros_gz_shims/ros_ign_gazebo_demos/models/double_pendulum_model.sdf new file mode 100644 index 00000000..91e072e4 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/models/double_pendulum_model.sdf @@ -0,0 +1,266 @@ + + + + + 0.001 + 1 + + + + true + 0 0 10 0 0 0 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + + + true + + + + + 0 0 1 + 100 100 + + + + + + + 0 0 1 + 100 100 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + + + + 0 0 0 0 0 0 + + + + 100 + + + 0 0 0.01 0 0 0 + + + 0.8 + 0.02 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + -0.275 0 1.1 0 0 0 + + + 0.2 0.2 2.2 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + 0 0 0.01 0 0 0 + + + 0.8 + 0.02 + + + + + -0.275 0 1.1 0 0 0 + + + 0.2 0.2 2.2 + + + + + + + 0 0 2.1 -1.5708 0 0 + 0 + + 0 0 0.5 0 0 0 + + + -0.05 0 0 0 1.5708 0 + + + 0.1 + 0.3 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + 0 0 1.0 0 1.5708 0 + + + 0.1 + 0.2 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + 0 0 0.5 0 0 0 + + + 0.1 + 0.9 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + -0.05 0 0 0 1.5708 0 + + + 0.1 + 0.3 + + + + + 0 0 1.0 0 1.5708 0 + + + 0.1 + 0.2 + + + + + 0 0 0.5 0 0 0 + + + 0.1 + 0.9 + + + + + + + 0.25 1.0 2.1 -2 0 0 + 0 + + 0 0 0.5 0 0 0 + + + 0 0 0 0 1.5708 0 + + + 0.08 + 0.3 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + 0 0 0.5 0 0 0 + + + 0.1 + 0.9 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + 0 0 0 0 1.5708 0 + + + 0.08 + 0.3 + + + + + 0 0 0.5 0 0 0 + + + 0.1 + 0.9 + + + + + + + base + upper_link + + 1.0 0 0 + + + + + upper_link + lower_link + + 1.0 0 0 + + + + + + + + true + + true + + + + + + diff --git a/ros_gz_shims/ros_ign_gazebo_demos/models/rrbot.xacro b/ros_gz_shims/ros_ign_gazebo_demos/models/rrbot.xacro new file mode 100644 index 00000000..00680c14 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/models/rrbot.xacro @@ -0,0 +1,165 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1 0.423529412 0.039215686 1 + 1 0.423529412 0.039215686 1 + 1 0.423529412 0.039215686 1 + + + + + + 0.2 + 0.2 + + 0 0 0 1 + 0 0 0 1 + 0 0 0 1 + + + + + + 0.2 + 0.2 + + 1 0.423529412 0.039215686 1 + 1 0.423529412 0.039215686 1 + 1 0.423529412 0.039215686 1 + + + + + + + + + \ No newline at end of file diff --git a/ros_gz_shims/ros_ign_gazebo_demos/package.xml b/ros_gz_shims/ros_ign_gazebo_demos/package.xml new file mode 100644 index 00000000..55bf4a5c --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/package.xml @@ -0,0 +1,17 @@ + + ros_ign_gazebo_demos + 0.0.1 + Shim package to redirect to ros_gz_sim_demos. + Apache 2.0 + Brandon Ong + + ament_cmake + ros_gz_sim_demos + + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/camera.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/camera.rviz new file mode 100644 index 00000000..81398197 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/rviz/camera.rviz @@ -0,0 +1,137 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Camera1 + - /Camera1/Status1 + - /Image1 + Splitter Ratio: 0.5 + Tree Height: 557 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz_default_plugins/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Class: rviz_default_plugins/Camera + Enabled: true + Image Rendering: background and overlay + Name: Camera + Overlay Alpha: 0.5 + Queue Size: 10 + Topic: /camera + Unreliable: false + Value: true + Visibility: + Grid: true + Image: true + Value: true + Zoom Factor: 1 + - Class: rviz_default_plugins/Image + Enabled: true + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 10 + Topic: /camera + Unreliable: false + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: camera/link/camera + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Topic: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: /move_base_simple/goal + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 19.73822784423828 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0 + Y: 0 + Z: 0 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.7903980016708374 + Target Frame: + Value: Orbit (rviz) + Yaw: 0.785398006439209 + Saved: ~ +Window Geometry: + Camera: + collapsed: false + Displays: + collapsed: false + Height: 702 + Hide Left Dock: false + Hide Right Dock: false + Image: + collapsed: false + QMainWindow State: 000000ff00000000fd00000004000000000000015600000268fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b00000268000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c0000026100000001000001c700000268fc0200000005fb0000000c00430061006d006500720061010000003b0000011f0000002800fffffffb0000000a0049006d0061006700650100000160000001430000002800fffffffb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b000002f8000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d00650100000000000004500000000000000000000000320000026800000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 859 + X: 517 + Y: 361 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/depth_camera.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/depth_camera.rviz new file mode 100644 index 00000000..6957e15f --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/rviz/depth_camera.rviz @@ -0,0 +1,147 @@ +Panels: + - Class: rviz/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Image1 + - /PointCloud21 + Splitter Ratio: 0.5 + Tree Height: 423 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: Image +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Class: rviz/Image + Enabled: true + Image Topic: /depth_camera + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: RGB8 + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: PointCloud2 + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.019999999552965164 + Style: Flat Squares + Topic: /depth_camera/points + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + Enabled: true + Global Options: + Background Color: 255; 255; 255 + Default Light: true + Fixed Frame: map + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 6.307931423187256 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: -0.024829570204019547 + Y: -0.440496027469635 + Z: 1.0747597217559814 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: -1.3397971391677856 + Target Frame: + Value: Orbit (rviz) + Yaw: 4.723598957061768 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 568 + Hide Left Dock: false + Hide Right Dock: false + Image: + collapsed: false + QMainWindow State: 000000ff00000000fd000000040000000000000156000001e2fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000001e2000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d0065007200610000000272000000c1000000000000000000000001000001b8000001e2fc0200000006fb0000000a0049006d006100670065010000003b000001e20000001600fffffffb0000000c00430061006d00650072006100000001ae000001850000000000000000fb0000000c00430061006d00650072006101000001ba000001790000000000000000fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b000002f8000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b000000052fc0100000002fb0000000800540069006d006502000001a70000029a000004b000000052fb0000000800540069006d0065010000000000000450000000000000000000000196000001e200000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1200 + X: 405 + Y: 378 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/diff_drive.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/diff_drive.rviz new file mode 100644 index 00000000..e647f4c9 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/rviz/diff_drive.rviz @@ -0,0 +1,123 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Odometry1 + - /Odometry1/Status1 + Splitter Ratio: 0.5 + Tree Height: 701 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 +Visualization Manager: + Class: "" + Displays: + - Angle Tolerance: 0.10000000149011612 + Class: rviz_default_plugins/Odometry + Covariance: + Orientation: + Alpha: 0.5 + Color: 255; 255; 127 + Color Style: Unique + Frame: Local + Offset: 1 + Scale: 1 + Value: true + Position: + Alpha: 0.30000001192092896 + Color: 204; 51; 204 + Scale: 1 + Value: true + Value: true + Enabled: true + Keep: 1000 + Name: Odometry + Position Tolerance: 0.10000000149011612 + Shape: + Alpha: 1 + Axes Length: 1 + Axes Radius: 0.10000000149011612 + Color: 255; 25; 0 + Head Length: 0.30000001192092896 + Head Radius: 0.10000000149011612 + Shaft Length: 1 + Shaft Radius: 0.05000000074505806 + Value: Arrow + Topic: /model/vehicle_blue/odometry + Unreliable: false + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: vehicle_blue/odom + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Topic: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: /move_base_simple/goal + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 68.66040802001953 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: -1.2689772844314575 + Y: 10.203336715698242 + Z: -2.8907392024993896 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 1.5697963237762451 + Target Frame: + Value: Orbit (rviz) + Yaw: 0.8253979682922363 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 846 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd00000004000000000000023d000002f8fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000002f8000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002f8fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b000002f8000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d006501000000000000045000000000000000000000026d000002f800000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1200 + X: 325 + Y: 158 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/gpu_lidar.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/gpu_lidar.rviz new file mode 100644 index 00000000..9161d0c8 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/rviz/gpu_lidar.rviz @@ -0,0 +1,181 @@ +Panels: + - Class: rviz/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /LaserScan1 + - /PointCloud21 + Splitter Ratio: 0.5 + Tree Height: 366 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: LaserScan +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/LaserScan + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 0 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: LaserScan + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.029999999329447746 + Style: Flat Squares + Topic: /lidar + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: PointCloud2 + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.029999999329447746 + Style: Flat Squares + Topic: /custom_params/pc2 + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: custom_params/link + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 10.596034049987793 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 1.855783224105835 + Y: -0.6233639717102051 + Z: 0.7489486932754517 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.5402030348777771 + Target Frame: + Value: Orbit (rviz) + Yaw: 3.7535903453826904 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 511 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd000000040000000000000156000001a9fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000001a9000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c0000026100000001000001b8000002f8fc0200000006fb0000000a0049006d006100670065000000003b0000016d0000000000000000fb0000000c00430061006d006500720061000000003b000002f80000000000000000fb0000000c00430061006d00650072006101000001ba000001790000000000000000fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b000002f8000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b000000052fc0100000002fb0000000800540069006d006502000001a70000029a000004b000000052fb0000000800540069006d0065010000000000000450000000000000000000000161000001a900000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 701 + X: 352 + Y: 269 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/gpu_lidar_bridge.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/gpu_lidar_bridge.rviz new file mode 100644 index 00000000..42968c2b --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/rviz/gpu_lidar_bridge.rviz @@ -0,0 +1,167 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /LaserScan1/Status1 + - /PointCloud21/Status1 + Splitter Ratio: 0.504601240158081 + Tree Height: 701 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz_default_plugins/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/LaserScan + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 0 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: LaserScan + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.009999999776482582 + Style: Flat Squares + Topic: /lidar + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud2 + Color: 255; 255; 255 + Color Transformer: "" + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: PointCloud2 + Position Transformer: "" + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.009999999776482582 + Style: Flat Squares + Topic: /lidar + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: model_with_lidar/link/gpu_lidar + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Topic: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: /move_base_simple/goal + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 15.735194206237793 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 2.550645589828491 + Y: -0.290515273809433 + Z: -1.1467934846878052 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.7253980040550232 + Target Frame: + Value: Orbit (rviz) + Yaw: 3.7385823726654053 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 846 + Hide Left Dock: false + Hide Right Dock: true + QMainWindow State: 000000ff00000000fd0000000400000000000001ef000002f8fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000002ed00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000002f8000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002f8fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b000002f8000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d00650100000000000004500000000000000000000002bb000002f800000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: true + Width: 1200 + X: 338 + Y: 1176 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/imu.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/imu.rviz new file mode 100644 index 00000000..0169390a --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/rviz/imu.rviz @@ -0,0 +1,130 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Imu1 + - /Imu1/Status1 + Splitter Ratio: 0.5 + Tree Height: 352 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: "" +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 1 + Class: rviz_plugin_tutorials/Imu + Color: 204; 51; 204 + Enabled: true + History Length: 1 + Name: Imu + Topic: /imu + Unreliable: false + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: sensors/sensors_box/link/imu + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 33.22251510620117 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: -1.7206333875656128 + Y: -0.9246708154678345 + Z: 1.870512843132019 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.785398006439209 + Target Frame: + Value: Orbit (rviz) + Yaw: 0.785398006439209 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 575 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd000000040000000000000191000001e9fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000001e9000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002b4fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b000002b4000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000003d70000003efc0100000002fb0000000800540069006d00650000000000000003d70000024400fffffffb0000000800540069006d00650100000000000004500000000000000000000001a2000001e900000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 825 + X: 751 + Y: 92 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/joint_states.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/joint_states.rviz new file mode 100644 index 00000000..06920d70 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/rviz/joint_states.rviz @@ -0,0 +1,190 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + - /RobotModel1 + - /TF1 + Splitter Ratio: 0.5 + Tree Height: 802 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Goal Pose1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz_default_plugins/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 0.800000011920929 + Class: rviz_default_plugins/RobotModel + Collision Enabled: false + Description File: "" + Description Source: Topic + Description Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /robot_description + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + link1: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link2: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + link3: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Name: RobotModel + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + - Class: rviz_default_plugins/TF + Enabled: true + Frame Timeout: 15 + Frames: + All Enabled: true + link1: + Value: true + link2: + Value: true + link3: + Value: true + world: + Value: true + Marker Scale: 1 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: true + Tree: + link1: + link2: + link3: + {} + world: + {} + Update Interval: 0 + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: world + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/Interact + Hide Inactive Objects: true + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /goal_pose + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 6.524543762207031 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: -0.106326624751091 + Y: 0.5023337006568909 + Z: 1.1979976892471313 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.7303980588912964 + Target Frame: + Value: Orbit (rviz) + Yaw: 5.698581218719482 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1025 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd000000040000000000000156000003abfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000003ab000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000003abfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003b000003ab000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d00650100000000000004500000000000000000000004cc000003ab00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1853 + X: 67 + Y: 27 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/rgbd_camera.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/rgbd_camera.rviz new file mode 100644 index 00000000..d6933fc6 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/rviz/rgbd_camera.rviz @@ -0,0 +1,159 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /PointCloud21 + - /Image2 + Splitter Ratio: 0.5 + Tree Height: 317 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: Image +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Class: rviz/Image + Enabled: true + Image Topic: /rgbd_camera/depth_image + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: RGB8 + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: PointCloud2 + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.029999999329447746 + Style: Flat Squares + Topic: /default_params/points + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Class: rviz/Image + Enabled: true + Image Topic: /rgbd_camera/image + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: default_params + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 3.1044178009033203 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: -0.04919945076107979 + Y: -0.08779548853635788 + Z: 2.6499500274658203 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: -1.3547965288162231 + Target Frame: + Value: Orbit (rviz) + Yaw: 4.718593597412109 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 540 + Hide Left Dock: false + Hide Right Dock: false + Image: + collapsed: false + QMainWindow State: 000000ff00000000fd000000040000000000000156000001c6fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000001c6000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000012d000001c6fc0200000007fb0000000a0049006d006100670065010000003b000000d60000001600fffffffb0000000a0049006d0061006700650100000117000000ea0000001600fffffffc000001ce000001650000000000fffffffa000000000100000002fb0000000a0049006d0061006700650100000000ffffffff0000000000000000fb0000000c00430061006d006500720061000000044c000000640000000000000000fb0000000c00430061006d00650072006101000001ba000001790000000000000000fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b000002f8000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b000000052fc0100000002fb0000000800540069006d006502000001a70000029a000004b000000052fb0000000800540069006d006501000000000000045000000000000000000000011a000001c600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 937 + X: 147 + Y: 349 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/rgbd_camera_bridge.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/rgbd_camera_bridge.rviz new file mode 100644 index 00000000..58955045 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/rviz/rgbd_camera_bridge.rviz @@ -0,0 +1,142 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /PointCloud21/Status1 + Splitter Ratio: 0.3251533806324005 + Tree Height: 701 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 +Visualization Manager: + Class: "" + Displays: + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud2 + Color: 255; 255; 255 + Color Transformer: RGB8 + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: PointCloud2 + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.05000000074505806 + Style: Flat Squares + Topic: /rgbd_camera/points + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Class: rviz_default_plugins/Image + Enabled: true + Max Value: 10 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: false + Queue Size: 10 + Topic: /rgbd_camera/depth_image + Unreliable: false + Value: true + - Class: rviz_default_plugins/Image + Enabled: true + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 10 + Topic: /rgbd_camera/image + Unreliable: false + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: rgbd_camera/link/rgbd_camera + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Topic: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: /move_base_simple/goal + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 5.996953964233398 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0.10905617475509644 + Y: 0.08000272512435913 + Z: 0.346417099237442 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.29039809107780457 + Target Frame: + Value: Orbit (rviz) + Yaw: 3.0753986835479736 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 846 + Hide Left Dock: false + Hide Right Dock: false + Image: + collapsed: false + QMainWindow State: 000000ff00000000fd000000040000000000000174000002f8fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000002ed00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000002f8000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002f8fc0200000005fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0049006d006100670065010000003b000002020000002800fffffffb0000000a0049006d0061006700650100000243000000f00000002800fffffffb0000000a0056006900650077007300000000cf00000264000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d0065010000000000000450000000000000000000000221000002f800000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1200 + X: 375 + Y: 1116 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/robot_description_publisher.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/robot_description_publisher.rviz new file mode 100644 index 00000000..058a47f4 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/rviz/robot_description_publisher.rviz @@ -0,0 +1,148 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /RobotModel1/Description Topic1 + Splitter Ratio: 0.5 + Tree Height: 878 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz_default_plugins/Grid + Color: 77; 77; 79 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 50 + Reference Frame: + Value: true + - Alpha: 1 + Class: rviz_default_plugins/RobotModel + Collision Enabled: false + Description File: "" + Description Source: Topic + Description Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /robot_description + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Name: RobotModel + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + Enabled: true + Global Options: + Background Color: 207; 207; 207 + Fixed Frame: link + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /move_base_simple/goal + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 49.51093292236328 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0.8779783248901367 + Y: 0.15285056829452515 + Z: 0.762141764163971 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.6602023243904114 + Target Frame: + Value: Orbit (rviz) + Yaw: 4.142223358154297 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1023 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd000000040000000000000222000003a9fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003b000003a9000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002f8fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b000002f8000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d0065010000000000000450000000000000000000000198000003a900000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 960 + X: 898 + Y: 27 diff --git a/ros_gz_shims/ros_ign_gazebo_demos/rviz/tf_bridge.rviz b/ros_gz_shims/ros_ign_gazebo_demos/rviz/tf_bridge.rviz new file mode 100644 index 00000000..76c42557 --- /dev/null +++ b/ros_gz_shims/ros_ign_gazebo_demos/rviz/tf_bridge.rviz @@ -0,0 +1,163 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + - /TF1 + - /TF1/Frames1 + Splitter Ratio: 0.516339898109436 + Tree Height: 549 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Goal Pose1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz_common/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: "" +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz_default_plugins/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Class: rviz_default_plugins/TF + Enabled: true + Frame Timeout: 15 + Frames: + All Enabled: true + double_pendulum_with_base0: + Value: true + double_pendulum_with_base0/base: + Value: true + double_pendulum_with_base0/lower_link: + Value: true + double_pendulum_with_base0/upper_link: + Value: true + Marker Scale: 1 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: true + Tree: + double_pendulum_with_base0: + double_pendulum_with_base0/base: + {} + double_pendulum_with_base0/lower_link: + {} + double_pendulum_with_base0/upper_link: + {} + Update Interval: 0 + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: double_pendulum_with_base0 + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/Interact + Hide Inactive Objects: true + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Covariance x: 0.25 + Covariance y: 0.25 + Covariance yaw: 0.06853891909122467 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /goal_pose + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 8.114859580993652 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0 + Y: 0 + Z: 0 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.3453984260559082 + Target Frame: + Value: Orbit (rviz) + Yaw: 3.2535715103149414 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 846 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd0000000400000000000002ff000002b0fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000002b0000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002b0fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000002b0000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000066f0000003efc0100000002fb0000000800540069006d006501000000000000066f000002eb00fffffffb0000000800540069006d0065010000000000000450000000000000000000000255000002b000000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1647 + X: 251 + Y: 169 diff --git a/ros_gz_shims/ros_ign_image/CMakeLists.txt b/ros_gz_shims/ros_ign_image/CMakeLists.txt new file mode 100644 index 00000000..5fa4b91b --- /dev/null +++ b/ros_gz_shims/ros_ign_image/CMakeLists.txt @@ -0,0 +1,26 @@ +cmake_minimum_required(VERSION 3.5) + +project(ros_ign_image) + +# Default to C++14 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra -Wpedantic") +endif() + +find_package(ament_cmake REQUIRED) +find_package(ament_index_cpp REQUIRED) + +add_executable(image_bridge src/image_bridge_shim.cpp) +ament_target_dependencies(image_bridge ament_index_cpp) + +ament_export_dependencies(ament_index_cpp ros_gz_image) + +install(TARGETS + image_bridge + DESTINATION lib/${PROJECT_NAME} +) + +ament_package() diff --git a/ros_gz_shims/ros_ign_image/README.md b/ros_gz_shims/ros_ign_image/README.md new file mode 100644 index 00000000..517ccdd8 --- /dev/null +++ b/ros_gz_shims/ros_ign_image/README.md @@ -0,0 +1,2 @@ +# This is a shim package +For [ros_gz_image](https://github.com/gazebosim/ros_gz/tree/ros2/ros_gz_image) diff --git a/ros_gz_shims/ros_ign_image/package.xml b/ros_gz_shims/ros_ign_image/package.xml new file mode 100644 index 00000000..7b621801 --- /dev/null +++ b/ros_gz_shims/ros_ign_image/package.xml @@ -0,0 +1,19 @@ + + + + ros_ign_image + 0.0.1 + Shim package to redirect to ros_gz_image. + Brandon Ong + + Apache 2.0 + + ament_cmake + ament_index_cpp + + ros_gz_image + + + ament_cmake + + diff --git a/ros_gz_shims/ros_ign_image/src/image_bridge_shim.cpp b/ros_gz_shims/ros_ign_image/src/image_bridge_shim.cpp new file mode 100644 index 00000000..c004a7dc --- /dev/null +++ b/ros_gz_shims/ros_ign_image/src/image_bridge_shim.cpp @@ -0,0 +1,30 @@ +// Shim to redirect "ros_ign_image image_bridge" call to "ros_gz_image image_bridge" + +#include +#include +#include +#include + +#include + + +int main(int argc, char * argv[]) +{ + std::stringstream cli_call; + + cli_call << ament_index_cpp::get_package_prefix("ros_gz_image") + << "/lib/ros_gz_image/image_bridge"; + + if (argc > 1) + { + for (int i = 1; i < argc; i++) + cli_call << " " << argv[i]; + } + + std::cerr << "[ros_ign_bridge] is deprecated! " + << "Redirecting to use [ros_gz_image] instead!" + << std::endl << std::endl; + system(cli_call.str().c_str()); + + return 0; +} diff --git a/ros_gz_shims/ros_ign_interfaces/CMakeLists.txt b/ros_gz_shims/ros_ign_interfaces/CMakeLists.txt new file mode 100644 index 00000000..b397466b --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/CMakeLists.txt @@ -0,0 +1,49 @@ +cmake_minimum_required(VERSION 3.5) +project(ros_ign_interfaces) + +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +find_package(ament_cmake REQUIRED) +find_package(builtin_interfaces REQUIRED) +find_package(std_msgs REQUIRED) +find_package(geometry_msgs REQUIRED) +find_package(ros_gz_interfaces REQUIRED) +find_package(rosidl_default_generators REQUIRED) + +set(msg_files + "msg/Contact.msg" + "msg/Contacts.msg" + "msg/Entity.msg" + "msg/EntityFactory.msg" + "msg/GuiCamera.msg" + "msg/JointWrench.msg" + "msg/Light.msg" + "msg/StringVec.msg" + "msg/TrackVisual.msg" + "msg/VideoRecord.msg" + "msg/WorldControl.msg" + "msg/WorldReset.msg" +) + +set(srv_files + "srv/ControlWorld.srv" + "srv/DeleteEntity.srv" + "srv/SetEntityPose.srv" + "srv/SpawnEntity.srv" +) + +rosidl_generate_interfaces(${PROJECT_NAME} + ${msg_files} + ${srv_files} + DEPENDENCIES builtin_interfaces std_msgs geometry_msgs ros_gz_interfaces + ADD_LINTER_TESTS +) + +ament_export_dependencies(rosidl_default_runtime) +ament_package() diff --git a/ros_gz_shims/ros_ign_interfaces/README.md b/ros_gz_shims/ros_ign_interfaces/README.md new file mode 100644 index 00000000..b2ce4368 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/README.md @@ -0,0 +1,2 @@ +# This is a shim package +For [ros_gz_sim_demos](https://github.com/gazebosim/ros_gz/tree/ros2/ros_ign_gazebo_demos) diff --git a/ros_gz_shims/ros_ign_interfaces/msg/Contact.msg b/ros_gz_shims/ros_ign_interfaces/msg/Contact.msg new file mode 100644 index 00000000..98d2cef8 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/msg/Contact.msg @@ -0,0 +1,6 @@ +ros_gz_interfaces/Entity collision1 # Contact collision1 +ros_gz_interfaces/Entity collision2 # Contact collision2 +geometry_msgs/Vector3[] positions # List of contact position +geometry_msgs/Vector3[] normals # List of contact normals +float64[] depths # List of penetration depths +ros_gz_interfaces/JointWrench[] wrenches # List of joint wrenches including forces/torques diff --git a/ros_gz_shims/ros_ign_interfaces/msg/Contacts.msg b/ros_gz_shims/ros_ign_interfaces/msg/Contacts.msg new file mode 100644 index 00000000..40232e51 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/msg/Contacts.msg @@ -0,0 +1,2 @@ +std_msgs/Header header # Time stamp +ros_gz_interfaces/Contact[] contacts # List of contacts diff --git a/ros_gz_shims/ros_ign_interfaces/msg/Entity.msg b/ros_gz_shims/ros_ign_interfaces/msg/Entity.msg new file mode 100644 index 00000000..b785c7ed --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/msg/Entity.msg @@ -0,0 +1,13 @@ +# Entity type: constant definition +uint8 NONE = 0 +uint8 LIGHT = 1 +uint8 MODEL = 2 +uint8 LINK = 3 +uint8 VISUAL = 4 +uint8 COLLISION = 5 +uint8 SENSOR = 6 +uint8 JOINT = 7 + +uint64 id # Entity unique identifier accross all types. Defaults to 0 +string name # Entity name, which is not guaranteed to be unique. +uint8 type # Entity type. diff --git a/ros_gz_shims/ros_ign_interfaces/msg/EntityFactory.msg b/ros_gz_shims/ros_ign_interfaces/msg/EntityFactory.msg new file mode 100644 index 00000000..4576c003 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/msg/EntityFactory.msg @@ -0,0 +1,11 @@ +string name # New name for the entity, overrides the name on the SDF +bool allow_renaming false # Whether the server is allowed to rename the entity in case of + # overlap with existing entities. + +# Only one method is supported at a time (sdf,sdf_filename,clone_name) +string sdf # SDF description in string format +string sdf_filename # Full path to SDF file. +string clone_name # Name of entity to clone + +geometry_msgs/Pose pose # Pose where the entity will be spawned in the world. +string relative_to "world" # Pose is defined relative to the frame of this entity. diff --git a/ros_gz_shims/ros_ign_interfaces/msg/GuiCamera.msg b/ros_gz_shims/ros_ign_interfaces/msg/GuiCamera.msg new file mode 100644 index 00000000..d45fd9b8 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/msg/GuiCamera.msg @@ -0,0 +1,12 @@ +# Message for a GUI Camera. + +# Optional header data. +std_msgs/Header header + +string name +string view_controller +geometry_msgs/Pose pose +TrackVisual track + +# Type of projection: "perspective" or "orthographic". +string projection_type diff --git a/ros_gz_shims/ros_ign_interfaces/msg/JointWrench.msg b/ros_gz_shims/ros_ign_interfaces/msg/JointWrench.msg new file mode 100644 index 00000000..2da89094 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/msg/JointWrench.msg @@ -0,0 +1,8 @@ +std_msgs/Header header # Time stamp +std_msgs/String body_1_name # Body 1 name string +std_msgs/UInt32 body_1_id # Body 1 id +std_msgs/String body_2_name # Body 2 name string +std_msgs/UInt32 body_2_id # Body 2 id + +geometry_msgs/Wrench body_1_wrench # Body 1 wrench +geometry_msgs/Wrench body_2_wrench # Body 2 wrench diff --git a/ros_gz_shims/ros_ign_interfaces/msg/Light.msg b/ros_gz_shims/ros_ign_interfaces/msg/Light.msg new file mode 100644 index 00000000..911e20bd --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/msg/Light.msg @@ -0,0 +1,29 @@ +std_msgs/Header header # Optional header data + +string name # Light name + +# Light type: constant definition +uint8 POINT = 0 +uint8 SPOT = 1 +uint8 DIRECTIONAL = 2 + +uint8 type # Light type (from constant definitions) + +geometry_msgs/Pose pose # Light pose +std_msgs/ColorRGBA diffuse # Light diffuse emission +std_msgs/ColorRGBA specular # Light specular emission +float32 attenuation_constant # Constant variable in attenuation formula +float32 attenuation_linear # Linear variable in attenuation formula +float32 attenuation_quadratic # Quadratic variable in attenuation formula +geometry_msgs/Vector3 direction # Light direction +float32 range # Light range +bool cast_shadows # Enable/disable shadow casting +float32 spot_inner_angle # Spotlight inner cone angle +float32 spot_outer_angle # Spotlight outer cone angle +float32 spot_falloff # Falloff between inner and outer cone + +uint32 id # Unique id of the light + +uint32 parent_id # Unique id of the light's parent + +float32 intensity # Light intensity diff --git a/ros_gz_shims/ros_ign_interfaces/msg/StringVec.msg b/ros_gz_shims/ros_ign_interfaces/msg/StringVec.msg new file mode 100644 index 00000000..15a7dda9 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/msg/StringVec.msg @@ -0,0 +1,7 @@ +# A message for a vector of string data. + +# Optional header data. +std_msgs/Header header + +# The vector of strings. +string[] data diff --git a/ros_gz_shims/ros_ign_interfaces/msg/TrackVisual.msg b/ros_gz_shims/ros_ign_interfaces/msg/TrackVisual.msg new file mode 100644 index 00000000..c09f4785 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/msg/TrackVisual.msg @@ -0,0 +1,33 @@ +# Message for a tracking a rendering::Visual with a rendering::Camera. + +# Optional header data. +std_msgs/Header header + +# Name of the visual to track. +string name + +# Id of the visual to track. +uint32 id + +# True to have the tracking camera inherit the orientation of +# the tracked visual. +bool inherit_orientation + +# Minimum follow distance. +float64 min_dist + +# Maximum follow distance. +float64 max_dist + +# If set to true, the position of the camera is fixed. +bool is_static + +# If set to true, the position of the camera is relative to the. +# model reference frame. +bool use_model_frame + +# Position of the camera. +geometry_msgs/Vector3 xyz + +# If set to true, the camera inherits the yaw rotation of the model. +bool inherit_yaw diff --git a/ros_gz_shims/ros_ign_interfaces/msg/VideoRecord.msg b/ros_gz_shims/ros_ign_interfaces/msg/VideoRecord.msg new file mode 100644 index 00000000..02bafde0 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/msg/VideoRecord.msg @@ -0,0 +1,16 @@ +# A message that allows for control of video recording functions. + +# Optional header data. +std_msgs/Header header + +# True to start video recording. +bool start + +# True to stop video recording. +bool stop + +# Video encoding format, e.g. "mp4", "ogv". +string format + +# filename of the recorded video. +string save_filename diff --git a/ros_gz_shims/ros_ign_interfaces/msg/WorldControl.msg b/ros_gz_shims/ros_ign_interfaces/msg/WorldControl.msg new file mode 100644 index 00000000..efa22fb9 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/msg/WorldControl.msg @@ -0,0 +1,7 @@ +bool pause # Paused state. +bool step # +uint32 multi_step 0 # Paused after stepping multi_step. +ros_gz_interfaces/WorldReset reset # +uint32 seed # +builtin_interfaces/Time run_to_sim_time # A simulation time in the future to run to and + # then pause. diff --git a/ros_gz_shims/ros_ign_interfaces/msg/WorldReset.msg b/ros_gz_shims/ros_ign_interfaces/msg/WorldReset.msg new file mode 100644 index 00000000..46f5971f --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/msg/WorldReset.msg @@ -0,0 +1,3 @@ +bool all false # Reset time and model +bool time_only false # Reset time only +bool model_only false # Reset model only diff --git a/ros_gz_shims/ros_ign_interfaces/package.xml b/ros_gz_shims/ros_ign_interfaces/package.xml new file mode 100644 index 00000000..4c0909e1 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/package.xml @@ -0,0 +1,27 @@ + + ros_ign_interfaces + 0.0.1 + Shim package to redirect to ros_gz_interfaces. + Apache 2.0 + Brandon Ong + Zhenpeng Ge + ament_cmake + rosidl_default_generators + + builtin_interfaces + ros_gz_interfaces + std_msgs + geometry_msgs + + builtin_interfaces + ros_gz_interfaces + std_msgs + geometry_msgs + rosidl_default_runtime + + ament_lint_common + rosidl_interface_packages + + ament_cmake + + diff --git a/ros_gz_shims/ros_ign_interfaces/srv/ControlWorld.srv b/ros_gz_shims/ros_ign_interfaces/srv/ControlWorld.srv new file mode 100644 index 00000000..d8e41f24 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/srv/ControlWorld.srv @@ -0,0 +1,3 @@ +ros_gz_interfaces/WorldControl world_control # Message to Control world in Gazebo Sim +--- +bool success # Return true if control is successful. diff --git a/ros_gz_shims/ros_ign_interfaces/srv/DeleteEntity.srv b/ros_gz_shims/ros_ign_interfaces/srv/DeleteEntity.srv new file mode 100644 index 00000000..13b3e1fd --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/srv/DeleteEntity.srv @@ -0,0 +1,3 @@ +ros_gz_interfaces/Entity entity # Gazebo Sim entity to be deleted. +--- +bool success # Return true if deletion is successful. diff --git a/ros_gz_shims/ros_ign_interfaces/srv/SetEntityPose.srv b/ros_gz_shims/ros_ign_interfaces/srv/SetEntityPose.srv new file mode 100644 index 00000000..b749488c --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/srv/SetEntityPose.srv @@ -0,0 +1,4 @@ +ros_gz_interfaces/Entity entity # Gazebo Sim entity. +geometry_msgs/Pose pose # Pose of entity. +--- +bool success # Return true if set successfully. diff --git a/ros_gz_shims/ros_ign_interfaces/srv/SpawnEntity.srv b/ros_gz_shims/ros_ign_interfaces/srv/SpawnEntity.srv new file mode 100644 index 00000000..35d5df59 --- /dev/null +++ b/ros_gz_shims/ros_ign_interfaces/srv/SpawnEntity.srv @@ -0,0 +1,3 @@ +ros_gz_interfaces/EntityFactory entity_factory # Message to create a new entity +--- +bool success # Return true if spawned successfully. diff --git a/ros_gz_sim/CHANGELOG.rst b/ros_gz_sim/CHANGELOG.rst index 2840f732..2bbc0aa9 100644 --- a/ros_gz_sim/CHANGELOG.rst +++ b/ros_gz_sim/CHANGELOG.rst @@ -1,24 +1,24 @@ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package ros_ign_gazebo +Changelog for package ros_gz_sim ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 0.244.3 (2022-05-19) -------------------- -* [ros2] README updates (service bridge, Gazebo rename) (`#252 `_) -* Fix linter tests (`#251 `_) +* [ros2] README updates (service bridge, Gazebo rename) (`#252 `_) +* Fix linter tests (`#251 `_) Co-authored-by: Louise Poubel * Contributors: Daisuke Nishimatsu, Louise Poubel 0.244.2 (2022-04-25) -------------------- -* Support bridging services (`#211 `_) -* Add std_msgs as dependency of ros_ign_gazebo (`#242 `_) -* Fixed ros_ign_gazebo launch file install directory (`#229 `_) (`#230 `_) -* Added ign_version launch argument to set ignition gazebo version (`#226 `_) -* Bring ros2 branch up-to-date with Rolling (`#213 `_) -* create.cpp usage message fixed for ros2 branch (`#207 `_) -* Separate galactic branch from ros2 branch (`#201 `_) -* 🏁 Dome EOL (`#198 `_) +* Support bridging services (`#211 `_) +* Add std_msgs as dependency of ros_gz_sim (`#242 `_) +* Fixed ros_gz_sim launch file install directory (`#229 `_) (`#230 `_) +* Added ign_version launch argument to set ignition gazebo version (`#226 `_) +* Bring ros2 branch up-to-date with Rolling (`#213 `_) +* create.cpp usage message fixed for ros2 branch (`#207 `_) +* Separate galactic branch from ros2 branch (`#201 `_) +* 🏁 Dome EOL (`#198 `_) * Contributors: Alejandro Hernández Cordero, Aryaman Shardul, Ivan Santiago Paunovic, Kenji Brameld, Louise Poubel, Michael Carroll, ahcorde 0.244.1 (2022-01-04) @@ -26,48 +26,48 @@ Changelog for package ros_ign_gazebo 0.244.0 (2021-12-30) -------------------- -* Default to Fortress for Rolling (future Humble) (`#195 `_) -* [ros2] 🏁 Dome EOL (`#199 `_) +* Default to Fortress for Rolling (future Humble) (`#195 `_) +* [ros2] 🏁 Dome EOL (`#199 `_) * Contributors: Guillaume Doisy, Louise Poubel 0.233.2 (2021-07-20) -------------------- -* [ros2] Update version docs, add Galactic and Fortress (`#164 `_) +* [ros2] Update version docs, add Galactic and Fortress (`#164 `_) * Contributors: Louise Poubel 0.233.1 (2021-04-16) -------------------- -* Default to Edifice for Rolling (`#150 `_) -* Edifice support (`#140 `_) +* Default to Edifice for Rolling (`#150 `_) +* Edifice support (`#140 `_) Co-authored-by: Alejandro Hernández -* Add topic flag to create robot (`#128 `_) - Now it is possible to run ros_ign_gazebo create specifying a topic as +* Add topic flag to create robot (`#128 `_) + Now it is possible to run ros_gz_sim create specifying a topic as source of the robot description Add a launch file starting a ignition gazebo world and spawn a sphere in it. Additionally a rviz2 interface is loaded to show that also Rviz can load the robot description The newly created demo introduce a dependency on the robot_state_publisher package -* Add default value for plugin path in launch script (`#125 `_) -* Fix overwriting of plugin path in launch script (`#122 `_) - - IGN_GAZEBO_SYSTEM_PLUGIN_PATH was overwritten by LD_LIBRARY_PATH +* Add default value for plugin path in launch script (`#125 `_) +* Fix overwriting of plugin path in launch script (`#122 `_) + - GZ_SIM_SYSTEM_PLUGIN_PATH was overwritten by LD_LIBRARY_PATH - Now it is instead extended by LD_LIBRARY_PATH - - This allows use of ign_gazebo.launch.py with custom gazebo plugins -* Changed for loading xml from ROS param(`#119 `_) (`#120 `_) -* ros_ign_gazebo exec depend on ign-gazebo (`#110 `_) -* Update releases (`#108 `_) -* Add support for Dome (`#103 `_) + - This allows use of gz_sim.launch.py with custom gazebo plugins +* Changed for loading xml from ROS param(`#119 `_) (`#120 `_) +* ros_gz_sim exec depend on gz-sim (`#110 `_) +* Update releases (`#108 `_) +* Add support for Dome (`#103 `_) * Contributors: Andrej Orsula, Louise Poubel, Luca Della Vedova, Valerio Magnago, chama1176 0.221.1 (2020-08-19) -------------------- -* Add pkg-config as a buildtool dependency (`#102 `_) +* Add pkg-config as a buildtool dependency (`#102 `_) * Contributors: Louise Poubel 0.221.0 (2020-07-23) -------------------- -* [ros2] Fixed CI - Added Foxy (`#89 `_) +* [ros2] Fixed CI - Added Foxy (`#89 `_) Co-authored-by: Louise Poubel -* Added ros_ign_gazebo for ros2 (`#80 `_) +* Added ros_gz_sim for ros2 (`#80 `_) Co-authored-by: Louise Poubel -* Update Dashing docs (`#62 `_) +* Update Dashing docs (`#62 `_) * Contributors: Alejandro Hernández Cordero, Louise Poubel, chapulina diff --git a/ros_gz_sim/CMakeLists.txt b/ros_gz_sim/CMakeLists.txt index a98a5b59..71ba3d0f 100644 --- a/ros_gz_sim/CMakeLists.txt +++ b/ros_gz_sim/CMakeLists.txt @@ -1,6 +1,6 @@ cmake_minimum_required(VERSION 3.5) -project(ros_ign_gazebo) +project(ros_gz_sim) # Default to C++14 if(NOT CMAKE_CXX_STANDARD) @@ -14,36 +14,42 @@ find_package(ament_cmake REQUIRED) find_package(rclcpp REQUIRED) find_package(std_msgs REQUIRED) +# TODO(CH3): Deprecated. Remove on tock. +if("$ENV{GZ_VERSION}" STREQUAL "" AND NOT "$ENV{IGNITION_VERSION}" STREQUAL "") + message(DEPRECATION "Environment variable [IGNITION_VERSION] is deprecated. Use [GZ_VERSION] instead.") + set(ENV{GZ_VERSION} ENV{IGNITION_VERSION}) +endif() + # Edifice -if("$ENV{IGNITION_VERSION}" STREQUAL "edifice") +if("$ENV{GZ_VERSION}" STREQUAL "edifice") find_package(ignition-math6 REQUIRED) - set(IGN_MATH_VER ${ignition-math6_VERSION_MAJOR}) + set(GZ_MATH_VER ${ignition-math6_VERSION_MAJOR}) find_package(ignition-transport10 REQUIRED) - set(IGN_TRANSPORT_VER ${ignition-transport10_VERSION_MAJOR}) + set(GZ_TRANSPORT_VER ${ignition-transport10_VERSION_MAJOR}) find_package(ignition-msgs7 REQUIRED) - set(IGN_MSGS_VER ${ignition-msgs7_VERSION_MAJOR}) + set(GZ_MSGS_VER ${ignition-msgs7_VERSION_MAJOR}) find_package(ignition-gazebo5 REQUIRED) - set(IGN_GAZEBO_VER ${ignition-gazebo5_VERSION_MAJOR}) + set(GZ_SIM_VER ${ignition-gazebo5_VERSION_MAJOR}) set(GZ_TARGET_PREFIX ignition) - message(STATUS "Compiling against Ignition Edifice") + message(STATUS "Compiling against Gazebo Edifice") # Garden -elseif("$ENV{IGNITION_VERSION}" STREQUAL "garden") +elseif("$ENV{GZ_VERSION}" STREQUAL "garden") find_package(gz-math7 REQUIRED) - set(IGN_MATH_VER ${gz-math7_VERSION_MAJOR}) + set(GZ_MATH_VER ${gz-math7_VERSION_MAJOR}) find_package(gz-transport12 REQUIRED) - set(IGN_TRANSPORT_VER ${gz-transport12_VERSION_MAJOR}) + set(GZ_TRANSPORT_VER ${gz-transport12_VERSION_MAJOR}) find_package(gz-msgs9 REQUIRED) - set(IGN_MSGS_VER ${gz-msgs9_VERSION_MAJOR}) + set(GZ_MSGS_VER ${gz-msgs9_VERSION_MAJOR}) find_package(gz-sim7 REQUIRED) - set(IGN_GAZEBO_VER ${gz-sim7_VERSION_MAJOR}) + set(GZ_SIM_VER ${gz-sim7_VERSION_MAJOR}) set(GZ_TARGET_PREFIX gz) @@ -51,20 +57,20 @@ elseif("$ENV{IGNITION_VERSION}" STREQUAL "garden") # Default to Fortress else() find_package(ignition-math6 REQUIRED) - set(IGN_MATH_VER ${ignition-math6_VERSION_MAJOR}) + set(GZ_MATH_VER ${ignition-math6_VERSION_MAJOR}) find_package(ignition-transport11 REQUIRED) - set(IGN_TRANSPORT_VER ${ignition-transport11_VERSION_MAJOR}) + set(GZ_TRANSPORT_VER ${ignition-transport11_VERSION_MAJOR}) find_package(ignition-msgs8 REQUIRED) - set(IGN_MSGS_VER ${ignition-msgs8_VERSION_MAJOR}) + set(GZ_MSGS_VER ${ignition-msgs8_VERSION_MAJOR}) find_package(ignition-gazebo6 REQUIRED) - set(IGN_GAZEBO_VER ${ignition-gazebo6_VERSION_MAJOR}) + set(GZ_SIM_VER ${ignition-gazebo6_VERSION_MAJOR}) set(GZ_TARGET_PREFIX ignition) - message(STATUS "Compiling against Ignition Fortress") + message(STATUS "Compiling against Gazebo Fortress") endif() ign_find_package(gflags @@ -79,24 +85,24 @@ ament_target_dependencies(create ) target_link_libraries(create gflags - ${GZ_TARGET_PREFIX}-math${IGN_MATH_VER}::core - ${GZ_TARGET_PREFIX}-msgs${IGN_MSGS_VER}::core - ${GZ_TARGET_PREFIX}-transport${IGN_TRANSPORT_VER}::core + ${GZ_TARGET_PREFIX}-math${GZ_MATH_VER}::core + ${GZ_TARGET_PREFIX}-msgs${GZ_MSGS_VER}::core + ${GZ_TARGET_PREFIX}-transport${GZ_TRANSPORT_VER}::core ) ament_target_dependencies(create std_msgs) configure_file( - launch/ign_gazebo.launch.py.in - launch/ign_gazebo.launch.py.configured + launch/gz_sim.launch.py.in + launch/gz_sim.launch.py.configured @ONLY ) file(GENERATE - OUTPUT "${CMAKE_CURRENT_BINARY_DIR}/launch/ign_gazebo.launch.py" - INPUT "${CMAKE_CURRENT_BINARY_DIR}/launch/ign_gazebo.launch.py.configured" + OUTPUT "${CMAKE_CURRENT_BINARY_DIR}/launch/gz_sim.launch.py" + INPUT "${CMAKE_CURRENT_BINARY_DIR}/launch/gz_sim.launch.py.configured" ) install(FILES - "${CMAKE_CURRENT_BINARY_DIR}/launch/ign_gazebo.launch.py" + "${CMAKE_CURRENT_BINARY_DIR}/launch/gz_sim.launch.py" DESTINATION share/${PROJECT_NAME}/launch ) diff --git a/ros_gz_sim/README.md b/ros_gz_sim/README.md index 377c4080..c4561a5d 100644 --- a/ros_gz_sim/README.md +++ b/ros_gz_sim/README.md @@ -10,7 +10,7 @@ This package contains things that make it convenient to integrate ROS with Gazeb There's a convenient launch file, try for example: ```bash -ros2 launch ros_ign_gazebo ign_gazebo.launch.py ign_args:="shapes.sdf" +ros2 launch ros_gz_sim gz_sim.launch.py gz_args:="shapes.sdf" ``` ### Spawn entities @@ -23,17 +23,17 @@ The `create` executable can be used to spawn SDF or URDF entities from: For example, start Gazebo Sim: ``` -ros2 launch ros_ign_gazebo ign_gazebo.launch.py +ros2 launch ros_gz_sim gz_sim.launch.py ``` then spawn a model: ``` -ros2 run ros_ign_gazebo create -world default -file 'https://fuel.ignitionrobotics.org/1.0/openrobotics/models/Gazebo' +ros2 run ros_gz_sim create -world default -file 'https://fuel.ignitionrobotics.org/1.0/openrobotics/models/Gazebo' ``` See more options with: ``` -ros2 run ros_ign_gazebo create --helpshort +ros2 run ros_gz_sim create --helpshort ``` diff --git a/ros_gz_sim/launch/gz_sim.launch.py.in b/ros_gz_sim/launch/gz_sim.launch.py.in index 7adb02ce..e8ff4909 100644 --- a/ros_gz_sim/launch/gz_sim.launch.py.in +++ b/ros_gz_sim/launch/gz_sim.launch.py.in @@ -12,7 +12,7 @@ # See the License for the specific language governing permissions and # limitations under the License. -"""Launch Ignition Gazebo with command line arguments.""" +"""Launch Gazebo Sim with command line arguments.""" from os import environ @@ -23,20 +23,37 @@ from launch.substitutions import LaunchConfiguration def generate_launch_description(): - env = {'IGN_GAZEBO_SYSTEM_PLUGIN_PATH': - ':'.join([environ.get('IGN_GAZEBO_SYSTEM_PLUGIN_PATH', default=''), - environ.get('LD_LIBRARY_PATH', default='')])} + env = {'GZ_SIM_SYSTEM_PLUGIN_PATH': + ':'.join([environ.get('GZ_SIM_SYSTEM_PLUGIN_PATH', default=''), + environ.get('LD_LIBRARY_PATH', default='')]), + 'IGN_GAZEBO_SYSTEM_PLUGIN_PATH': # TODO(CH3): To support pre-garden. Deprecated. + ':'.join([environ.get('IGN_GAZEBO_SYSTEM_PLUGIN_PATH', default=''), + environ.get('LD_LIBRARY_PATH', default='')])} return LaunchDescription([ - DeclareLaunchArgument('ign_args', default_value='', - description='Arguments to be passed to Ignition Gazebo'), - # Ignition Gazebo's major version - DeclareLaunchArgument('ign_version', default_value='@IGN_GAZEBO_VER@', - description='Ignition Gazebo\'s major version'), + DeclareLaunchArgument('gz_args', default_value='', + description='Arguments to be passed to Gazebo Sim'), + # Gazebo Sim's major version + DeclareLaunchArgument('gz_version', default_value='@GZ_SIM_VER@', + description='Gazebo Sim\'s major version'), + + # TODO(CH3): Deprecated. Remove on tock. + DeclareLaunchArgument( + 'ign_args', default_value='', + description='Deprecated: Arguments to be passed to Gazebo Sim' + ), + # Gazebo Sim's major version + DeclareLaunchArgument( + 'ign_version', default_value='@GZ_SIM_VER@', + description='Deprecated: Gazebo Sim\'s major version' + ), + ExecuteProcess( - cmd=['ign gazebo', + cmd=['gz sim', + LaunchConfiguration('gz_args'), LaunchConfiguration('ign_args'), '--force-version', + LaunchConfiguration('gz_version'), LaunchConfiguration('ign_version'), ], output='screen', diff --git a/ros_gz_sim/package.xml b/ros_gz_sim/package.xml index e54b6b5a..1b3b2a42 100644 --- a/ros_gz_sim/package.xml +++ b/ros_gz_sim/package.xml @@ -1,9 +1,9 @@ - ros_ign_gazebo + ros_gz_sim 0.244.3 - Tools for using Ignition Gazebo simulation with ROS. + Tools for using Gazebo Sim simulation with ROS. Alejandro Hernandez Apache 2.0 @@ -18,16 +18,16 @@ std_msgs - gz-sim7 - gz-math7 + gz-sim7 + gz-math7 - ignition-gazebo6 - ignition-math6 - ignition-gazebo6 - ignition-math6 + ignition-gazebo6 + ignition-math6 + ignition-gazebo6 + ignition-math6 - ignition-gazebo5 - ignition-math6 + ignition-gazebo5 + ignition-math6 ament_lint_auto ament_lint_common diff --git a/ros_gz_sim/src/create.cpp b/ros_gz_sim/src/create.cpp index 6e1204a0..016f8b57 100644 --- a/ros_gz_sim/src/create.cpp +++ b/ros_gz_sim/src/create.cpp @@ -40,13 +40,13 @@ DEFINE_double(R, 0, "Roll component of initial orientation, in radians."); DEFINE_double(P, 0, "Pitch component of initial orientation, in radians."); DEFINE_double(Y, 0, "Yaw component of initial orientation, in radians."); -// ROS interface for spawning entities into Ignition. +// ROS interface for spawning entities into Gazebo. // Suggested for use with roslaunch and loading entities from ROS param. -// If these are not needed, just use the `ign service` command line instead. +// If these are not needed, just use the `gz service` command line instead. int main(int _argc, char ** _argv) { rclcpp::init(_argc, _argv); - auto ros2_node = rclcpp::Node::make_shared("ros_ign_gazebo"); + auto ros2_node = rclcpp::Node::make_shared("ros_gz_sim"); gflags::AllowCommandLineReparsing(); gflags::SetUsageMessage( @@ -58,7 +58,7 @@ int main(int _argc, char ** _argv) // World std::string world_name = FLAGS_world; if (world_name.empty()) { - // If caller doesn't provide a world name, get list of worlds from ign-gazebo server + // If caller doesn't provide a world name, get list of worlds from gz-sim server ignition::transport::Node node; bool executed{false}; diff --git a/ros_gz_sim_demos/CHANGELOG.rst b/ros_gz_sim_demos/CHANGELOG.rst index beca6e6e..f191cee7 100644 --- a/ros_gz_sim_demos/CHANGELOG.rst +++ b/ros_gz_sim_demos/CHANGELOG.rst @@ -1,23 +1,23 @@ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package ros1_ign_gazebo_demos +Changelog for package ros1_gz_sim_demos ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 0.244.3 (2022-05-19) -------------------- -* [ros2] README updates (service bridge, Gazebo rename) (`#252 `_) -* Fix linter tests (`#251 `_) +* [ros2] README updates (service bridge, Gazebo rename) (`#252 `_) +* Fix linter tests (`#251 `_) Co-authored-by: Louise Poubel -* Joint state publisher and tf bridging demo (`#244 `_) +* Joint state publisher and tf bridging demo (`#244 `_) * Added joint state publisher and tf bridge demo Co-authored-by: Louise Poubel * Contributors: Aditya Pande, Daisuke Nishimatsu, Louise Poubel 0.244.2 (2022-04-25) -------------------- -* Camera trigger demo (`#223 `_) -* Separate galactic branch from ros2 branch (`#201 `_) -* 🏁 Dome EOL (`#198 `_) -* Joint states tutorial (`#156 `_) +* Camera trigger demo (`#223 `_) +* Separate galactic branch from ros2 branch (`#201 `_) +* 🏁 Dome EOL (`#198 `_) +* Joint states tutorial (`#156 `_) Adds an rrbot model to demos and shows the usage of joint_states plugin. * Contributors: Louise Poubel, Michael Carroll, Vatan Aksoy Tezer, William Lew @@ -26,37 +26,37 @@ Changelog for package ros1_ign_gazebo_demos 0.244.0 (2021-12-30) -------------------- -* Default to Fortress for Rolling (future Humble) (`#195 `_) -* [ros2] 🏁 Dome EOL (`#199 `_) -* Enable QoS overrides (`#181 `_) +* Default to Fortress for Rolling (future Humble) (`#195 `_) +* [ros2] 🏁 Dome EOL (`#199 `_) +* Enable QoS overrides (`#181 `_) * Contributors: Guillaume Doisy, Louise Poubel 0.233.2 (2021-07-20) -------------------- -* [ros2] Add exec depend on xacro for demos (`#170 `_) -* [ros2] Update version docs, add Galactic and Fortress (`#164 `_) -* Joint states tutorial (`#156 `_) +* [ros2] Add exec depend on xacro for demos (`#170 `_) +* [ros2] Update version docs, add Galactic and Fortress (`#164 `_) +* Joint states tutorial (`#156 `_) Adds an rrbot model to demos and shows the usage of joint_states plugin. * Contributors: Louise Poubel, Vatan Aksoy Tezer 0.233.1 (2021-04-16) -------------------- -* Default to Edifice for Rolling (`#150 `_) -* Minor updates for demos (`#144 `_) +* Default to Edifice for Rolling (`#150 `_) +* Minor updates for demos (`#144 `_) * Re-enable air pressure demo - - Resolves https://github.com/ignitionrobotics/ros_ign/issues/78 + - Resolves https://github.com/gazebosim/ros_gz/issues/78 * Add RQt topic viewer to IMU demo * Add image_topic argument for image_bridge demo * Do not normalize depth image in RViz2 -* Edifice support (`#140 `_) -* Add topic flag to create robot (`#128 `_) - Now it is possible to run ros_ign_gazebo create specifying a topic as +* Edifice support (`#140 `_) +* Add topic flag to create robot (`#128 `_) + Now it is possible to run ros_gz_sim create specifying a topic as source of the robot description Add a launch file starting a ignition gazebo world and spawn a sphere in it. Additionally a rviz2 interface is loaded to show that also Rviz can load the robot description The newly created demo introduce a dependency on the robot_state_publisher package -* [ros2] Update releases (`#108 `_) +* [ros2] Update releases (`#108 `_) * Contributors: Andrej Orsula, Louise Poubel, Valerio Magnago 0.221.1 (2020-08-19) @@ -64,14 +64,14 @@ Changelog for package ros1_ign_gazebo_demos 0.221.0 (2020-07-23) -------------------- -* Updated launch file to use ros_ign_gazebo (`#82 `_) +* Updated launch file to use ros_gz_sim (`#82 `_) Co-authored-by: Louise Poubel -* Use new ros_ign_gazebo package on ROS 2 demos (`#85 `_) +* Use new ros_gz_sim package on ROS 2 demos (`#85 `_) Co-authored-by: Alejandro Hernández Cordero -* [WIP] Port ign_ros_gazebo_demos to ROS2 (`#58 `_) - Port ros_ign_image to ROS2 - Port ros_ign_gazebo_demos to ROS2 -* Enable ROS2 CI for Dashing branch (`#43 `_) +* [WIP] Port ign_ros_gazebo_demos to ROS2 (`#58 `_) + Port ros_gz_image to ROS2 + Port ros_gz_sim_demos to ROS2 +* Enable ROS2 CI for Dashing branch (`#43 `_) * Make all API and comments ROS-version agnostic * Rename packages and fix compilation + tests * Move files ros1 -> ros diff --git a/ros_gz_sim_demos/CMakeLists.txt b/ros_gz_sim_demos/CMakeLists.txt index bf6a7253..38754563 100644 --- a/ros_gz_sim_demos/CMakeLists.txt +++ b/ros_gz_sim_demos/CMakeLists.txt @@ -1,6 +1,6 @@ cmake_minimum_required(VERSION 3.5) -project(ros_ign_gazebo_demos) +project(ros_gz_sim_demos) find_package(ament_cmake REQUIRED) diff --git a/ros_gz_sim_demos/README.md b/ros_gz_sim_demos/README.md index 4ba9b4fb..46970592 100644 --- a/ros_gz_sim_demos/README.md +++ b/ros_gz_sim_demos/README.md @@ -6,7 +6,7 @@ This package contains demos showing how to use Gazebo Sim with ROS. There's a convenient launch file, try for example: - ros2 launch ros_ign_gazebo ign_gazebo.launch.py ign_args:="shapes.sdf" + ros2 launch ros_gz_sim gz_sim.launch.py gz_args:="shapes.sdf" ![](images/shapes_demo.png) @@ -14,7 +14,7 @@ There's a convenient launch file, try for example: Publishes fluid pressure readings. - ros2 launch ros_ign_gazebo_demos air_pressure.launch.py + ros2 launch ros_gz_sim_demos air_pressure.launch.py This demo also shows the use of custom QoS parameters. The sensor data is published as as "best-effort", so trying to subscribe to "reliable" data won't @@ -32,19 +32,19 @@ And Publishes RGB camera image and info. -Images can be exposed to ROS through `ros_ign_bridge` or `ros_ign_image`. +Images can be exposed to ROS through `ros_gz_bridge` or `ros_gz_image`. Using the image bridge (unidirectional, uses [image_transport](http://wiki.ros.org/image_transport)): - ros2 launch ros_ign_gazebo_demos image_bridge.launch.py + ros2 launch ros_gz_sim_demos image_bridge.launch.py Using the regular bridge: - ros2 launch ros_ign_gazebo_demos camera.launch.py + ros2 launch ros_gz_sim_demos camera.launch.py To use a camera that only publishes information when triggered: - ros2 launch ros_ign_gazebo_demos triggered_camera.launch.py + ros2 launch ros_gz_sim_demos triggered_camera.launch.py Trigger the camera: @@ -56,7 +56,7 @@ Trigger the camera: Send commands to a differential drive vehicle and listen to its odometry. - ros2 launch ros_ign_gazebo_demos diff_drive.launch.py + ros2 launch ros_gz_sim_demos diff_drive.launch.py Then unpause and send a command @@ -78,18 +78,18 @@ And Depth camera data can be obtained as: -* `sensor_msgs/msg/Image`, through `ros_ign_bridge` or `ros_ign_image` -* `sensor_msgs/msg/PointCloud2`, through `ros_ign_point_cloud` +* `sensor_msgs/msg/Image`, through `ros_gz_bridge` or `ros_gz_image` +* `sensor_msgs/msg/PointCloud2`, through `ros_gz_point_cloud` Using the image bridge (unidirectional, uses [image_transport](http://wiki.ros.org/image_transport)): - ros2 launch ros_ign_gazebo_demos image_bridge.launch.py image_topic:=/depth_camera + ros2 launch ros_gz_sim_demos image_bridge.launch.py image_topic:=/depth_camera -*TODO*: Blocked by `ros_ign_point_cloud` [issue](https://github.com/osrf/ros_ign/issues/40). +*TODO*: Blocked by `ros_gz_point_cloud` [issue](https://github.com/gazebosim/ros_gz/issues/40). Using Gazebo Sim plugin: - ros2 launch ros_ign_gazebo_demos depth_camera.launch.py + ros2 launch ros_gz_sim_demos depth_camera.launch.py ![](images/depth_camera_demo.png) @@ -97,18 +97,18 @@ Using Gazebo Sim plugin: GPU lidar data can be obtained as: -* `sensor_msgs/msg/LaserScan`, through the `ros_ign_bridge` -* `sensor_msgs/msg/PointCloud2`, through the `ros_ign_bridge` or `ros_ign_point_cloud` +* `sensor_msgs/msg/LaserScan`, through the `ros_gz_bridge` +* `sensor_msgs/msg/PointCloud2`, through the `ros_gz_bridge` or `ros_gz_point_cloud` Using the bridge: - ros2 launch ros_ign_gazebo_demos gpu_lidar_bridge.launch.py + ros2 launch ros_gz_sim_demos gpu_lidar_bridge.launch.py -*TODO*: Blocked by `ros_ign_point_cloud` [issue](https://github.com/osrf/ros_ign/issues/40). +*TODO*: Blocked by `ros_gz_point_cloud` [issue](https://github.com/gazebosim/ros_gz/issues/40). Using Gazebo Sim plugin: - ros2 launch ros_ign_gazebo_demos gpu_lidar.launch.py + ros2 launch ros_gz_sim_demos gpu_lidar.launch.py ![](images/gpu_lidar_demo.png) @@ -116,7 +116,7 @@ Using Gazebo Sim plugin: Publishes IMU readings. - ros2 launch ros_ign_gazebo_demos imu.launch.py + ros2 launch ros_gz_sim_demos imu.launch.py ![](images/imu_demo.png) @@ -126,7 +126,7 @@ Publishes IMU readings. Publishes magnetic field readings. - ros2 launch ros_ign_gazebo_demos magnetometer.launch.py + ros2 launch ros_gz_sim_demos magnetometer.launch.py ![](images/magnetometer_demo.png) @@ -134,25 +134,25 @@ Publishes magnetic field readings. RGBD camera data can be obtained as: -* `sensor_msgs/msg/Image`, through `ros_ign_bridge` or `ros_ign_image` -* `sensor_msgs/msg/PointCloud2`, through `ros_ign_bridge` or `ros_ign_point_cloud` +* `sensor_msgs/msg/Image`, through `ros_gz_bridge` or `ros_gz_image` +* `sensor_msgs/msg/PointCloud2`, through `ros_gz_bridge` or `ros_gz_point_cloud` Using the image bridge (unidirectional, uses [image_transport](http://wiki.ros.org/image_transport)): # RGB image - ros2 launch ros_ign_gazebo_demos image_bridge.launch.py image_topic:=/rgbd_camera/image + ros2 launch ros_gz_sim_demos image_bridge.launch.py image_topic:=/rgbd_camera/image # Depth image - ros2 launch ros_ign_gazebo_demos image_bridge.launch.py image_topic:=/rgbd_camera/depth_image + ros2 launch ros_gz_sim_demos image_bridge.launch.py image_topic:=/rgbd_camera/depth_image Using the regular bridge: - ros2 launch ros_ign_gazebo_demos rgbd_camera_bridge.launch.py + ros2 launch ros_gz_sim_demos rgbd_camera_bridge.launch.py -*TODO*: Blocked by `ros_ign_point_cloud` [issue](https://github.com/osrf/ros_ign/issues/40). +*TODO*: Blocked by `ros_gz_point_cloud` [issue](https://github.com/gazebosim/ros_gz/issues/40). Using Gazebo Sim plugin: - ros2 launch ros_ign_gazebo_demos rgbd_camera.launch.py + ros2 launch ros_gz_sim_demos rgbd_camera.launch.py ![](images/rgbd_camera_demo.png) @@ -160,7 +160,7 @@ Using Gazebo Sim plugin: Get the current state of a battery. - ros2 launch ros_ign_gazebo_demos battery.launch.py + ros2 launch ros_gz_sim_demos battery.launch.py Then send a command so the vehicle moves and drains the battery @@ -174,7 +174,7 @@ Leverage the robot description publisher to spawn a new urdf model in gazebo and show it in rviz2. To try the demo launch: - ros2 launch ros_ign_gazebo_demos robot_description_publisher.launch.py + ros2 launch ros_gz_sim_demos robot_description_publisher.launch.py ![](images/robot_state_publisher_demo.png) @@ -184,7 +184,7 @@ Publishes joint states of the robot. To try the demo launch: - ros2 launch ros_ign_gazebo_demos joint_states.launch.py + ros2 launch ros_gz_sim_demos joint_states.launch.py ![](images/joint_states.png) @@ -195,6 +195,6 @@ and transforms of a robot in rviz. To try the demo launch: - ros2 launch ros_ign_gazebo_demos tf_bridge.launch.py + ros2 launch ros_gz_sim_demos tf_bridge.launch.py ![](images/tf_bridge.gif) diff --git a/ros_gz_sim_demos/launch/air_pressure.launch.py b/ros_gz_sim_demos/launch/air_pressure.launch.py index ccaa7251..272d6eb1 100644 --- a/ros_gz_sim_demos/launch/air_pressure.launch.py +++ b/ros_gz_sim_demos/launch/air_pressure.launch.py @@ -12,7 +12,7 @@ # See the License for the specific language governing permissions and # limitations under the License. -"""Launch Ignition Gazebo with command line arguments.""" +"""Launch Gazebo Sim with command line arguments.""" import os @@ -30,21 +30,21 @@ def generate_launch_description(): - pkg_ros_ign_gazebo = get_package_share_directory('ros_ign_gazebo') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') # Bridge bridge = Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='parameter_bridge', arguments=['/air_pressure@sensor_msgs/msg/FluidPressure@ignition.msgs.FluidPressure'], parameters=[{'qos_overrides./air_pressure.publisher.reliability': 'best_effort'}], output='screen' ) - ign_gazebo = IncludeLaunchDescription( + gz_sim = IncludeLaunchDescription( PythonLaunchDescriptionSource( - os.path.join(pkg_ros_ign_gazebo, 'launch', 'ign_gazebo.launch.py')), - launch_arguments={'ign_args': '-r sensors.sdf'}.items(), + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={'gz_args': '-r sensors.sdf'}.items(), ) # RQt @@ -55,7 +55,7 @@ def generate_launch_description(): condition=IfCondition(LaunchConfiguration('rqt')) ) return LaunchDescription([ - ign_gazebo, + gz_sim, DeclareLaunchArgument('rqt', default_value='true', description='Open RQt.'), bridge, diff --git a/ros_gz_sim_demos/launch/battery.launch.py b/ros_gz_sim_demos/launch/battery.launch.py index 239e14a2..4e32322a 100644 --- a/ros_gz_sim_demos/launch/battery.launch.py +++ b/ros_gz_sim_demos/launch/battery.launch.py @@ -28,7 +28,7 @@ def generate_launch_description(): - pkg_ros_ign_gazebo = get_package_share_directory('ros_ign_gazebo') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') # RQt rqt = Node( @@ -40,17 +40,17 @@ def generate_launch_description(): condition=IfCondition(LaunchConfiguration('rqt')) ) - ign_gazebo = IncludeLaunchDescription( + gz_sim = IncludeLaunchDescription( PythonLaunchDescriptionSource( - os.path.join(pkg_ros_ign_gazebo, 'launch', 'ign_gazebo.launch.py')), + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), launch_arguments={ - 'ign_args': '-r -z 1000000 linear_battery_demo.sdf' + 'gz_args': '-r -z 1000000 linear_battery_demo.sdf' }.items(), ) # Bridge bridge = Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='parameter_bridge', arguments=[ '/model/vehicle_blue/cmd_vel@geometry_msgs/msg/Twist@ignition.msgs.Twist', @@ -61,7 +61,7 @@ def generate_launch_description(): ) return LaunchDescription([ - ign_gazebo, + gz_sim, DeclareLaunchArgument('rqt', default_value='true', description='Open RQt.'), bridge, diff --git a/ros_gz_sim_demos/launch/camera.launch.py b/ros_gz_sim_demos/launch/camera.launch.py index 903096e4..1bd9a8a0 100644 --- a/ros_gz_sim_demos/launch/camera.launch.py +++ b/ros_gz_sim_demos/launch/camera.launch.py @@ -28,26 +28,26 @@ def generate_launch_description(): - pkg_ros_ign_gazebo_demos = get_package_share_directory('ros_ign_gazebo_demos') - pkg_ros_ign_gazebo = get_package_share_directory('ros_ign_gazebo') + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') - ign_gazebo = IncludeLaunchDescription( + gz_sim = IncludeLaunchDescription( PythonLaunchDescriptionSource( - os.path.join(pkg_ros_ign_gazebo, 'launch', 'ign_gazebo.launch.py')), - launch_arguments={'ign_args': '-r camera_sensor.sdf'}.items(), + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={'gz_args': '-r camera_sensor.sdf'}.items(), ) # RViz rviz = Node( package='rviz2', executable='rviz2', - arguments=['-d', os.path.join(pkg_ros_ign_gazebo_demos, 'rviz', 'camera.rviz')], + arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'camera.rviz')], condition=IfCondition(LaunchConfiguration('rviz')) ) # Bridge bridge = Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='parameter_bridge', arguments=['/camera@sensor_msgs/msg/Image@ignition.msgs.Image', '/camera_info@sensor_msgs/msg/CameraInfo@ignition.msgs.CameraInfo'], @@ -57,7 +57,7 @@ def generate_launch_description(): return LaunchDescription([ DeclareLaunchArgument('rviz', default_value='true', description='Open RViz.'), - ign_gazebo, + gz_sim, bridge, rviz ]) diff --git a/ros_gz_sim_demos/launch/depth_camera.launch.py b/ros_gz_sim_demos/launch/depth_camera.launch.py index d025c695..d42ce862 100644 --- a/ros_gz_sim_demos/launch/depth_camera.launch.py +++ b/ros_gz_sim_demos/launch/depth_camera.launch.py @@ -28,14 +28,14 @@ def generate_launch_description(): - pkg_ros_ign_gazebo = get_package_share_directory('ros_ign_gazebo') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') - ign_gazebo = IncludeLaunchDescription( + gz_sim = IncludeLaunchDescription( PythonLaunchDescriptionSource( - os.path.join(pkg_ros_ign_gazebo, 'launch', 'ign_gazebo.launch.py') + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py') ), # launch_arguments={ - # 'ign_args': '-r depth_camera.sdf' + # 'gz_args': '-r depth_camera.sdf' # }.items(), ) @@ -52,21 +52,21 @@ def generate_launch_description(): package='rviz2', executable='rviz2', # FIXME: Generate new RViz config once this demo is usable again - # arguments=['-d', os.path.join(pkg_ros_ign_gazebo_demos, 'rviz', 'depth_camera.rviz')], + # arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'depth_camera.rviz')], condition=IfCondition(LaunchConfiguration('rviz')) ) # Bridge bridge = Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='parameter_bridge', arguments=['/depth_camera@sensor_msgs/msg/Image@ignition.msgs.Image'], output='screen' ) - # FIXME: need a SDF file (depth_camera.sdf) inside ros_ign_point_cloud + # FIXME: need a SDF file (depth_camera.sdf) inside ros_gz_point_cloud return LaunchDescription([ - ign_gazebo, + gz_sim, DeclareLaunchArgument('rviz', default_value='true', description='Open RViz.'), DeclareLaunchArgument('rqt', default_value='true', diff --git a/ros_gz_sim_demos/launch/diff_drive.launch.py b/ros_gz_sim_demos/launch/diff_drive.launch.py index 9cac29d1..8a297567 100644 --- a/ros_gz_sim_demos/launch/diff_drive.launch.py +++ b/ros_gz_sim_demos/launch/diff_drive.launch.py @@ -28,14 +28,14 @@ def generate_launch_description(): - pkg_ros_ign_gazebo_demos = get_package_share_directory('ros_ign_gazebo_demos') - pkg_ros_ign_gazebo = get_package_share_directory('ros_ign_gazebo') + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') - ign_gazebo = IncludeLaunchDescription( + gz_sim = IncludeLaunchDescription( PythonLaunchDescriptionSource( - os.path.join(pkg_ros_ign_gazebo, 'launch', 'ign_gazebo.launch.py')), + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), launch_arguments={ - 'ign_args': '-r diff_drive.sdf' + 'gz_args': '-r diff_drive.sdf' }.items(), ) @@ -43,13 +43,13 @@ def generate_launch_description(): rviz = Node( package='rviz2', executable='rviz2', - arguments=['-d', os.path.join(pkg_ros_ign_gazebo_demos, 'rviz', 'diff_drive.rviz')], + arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'diff_drive.rviz')], condition=IfCondition(LaunchConfiguration('rviz')) ) # Bridge bridge = Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='parameter_bridge', arguments=['/model/vehicle_blue/cmd_vel@geometry_msgs/msg/Twist@ignition.msgs.Twist', '/model/vehicle_blue/odometry@nav_msgs/msg/Odometry@ignition.msgs.Odometry', @@ -61,7 +61,7 @@ def generate_launch_description(): ) return LaunchDescription([ - ign_gazebo, + gz_sim, DeclareLaunchArgument('rviz', default_value='true', description='Open RViz.'), bridge, diff --git a/ros_gz_sim_demos/launch/gpu_lidar.launch.py b/ros_gz_sim_demos/launch/gpu_lidar.launch.py index 095a0a81..5cfdb08f 100644 --- a/ros_gz_sim_demos/launch/gpu_lidar.launch.py +++ b/ros_gz_sim_demos/launch/gpu_lidar.launch.py @@ -28,13 +28,13 @@ def generate_launch_description(): - pkg_ros_ign_gazebo = get_package_share_directory('ros_ign_gazebo') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') - ign_gazebo = IncludeLaunchDescription( + gz_sim = IncludeLaunchDescription( PythonLaunchDescriptionSource( - os.path.join(pkg_ros_ign_gazebo, 'launch', 'ign_gazebo.launch.py')), + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), # launch_arguments={ - # 'ign_args': '-r gpu_lidar.sdf' + # 'gz_args': '-r gpu_lidar.sdf' # }.items(), ) @@ -43,21 +43,21 @@ def generate_launch_description(): package='rviz2', executable='rviz2', # FIXME: Generate new RViz config once this demo is usable again - # arguments=['-d', os.path.join(pkg_ros_ign_gazebo_demos, 'rviz', 'gpu_lidar.rviz')], + # arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'gpu_lidar.rviz')], condition=IfCondition(LaunchConfiguration('rviz')) ) # Bridge bridge = Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='parameter_bridge', arguments=['/lidar@sensor_msgs/msg/LaserScan@ignition.msgs.LaserScan/'], output='screen' ) - # FIXME: need a SDF file (gpu_lidar.sdf) inside ros_ign_point_cloud/ + # FIXME: need a SDF file (gpu_lidar.sdf) inside ros_gz_point_cloud/ return LaunchDescription([ - ign_gazebo, + gz_sim, DeclareLaunchArgument('rviz', default_value='true', description='Open RViz.'), bridge, diff --git a/ros_gz_sim_demos/launch/gpu_lidar_bridge.launch.py b/ros_gz_sim_demos/launch/gpu_lidar_bridge.launch.py index d45381b0..26bd36b8 100644 --- a/ros_gz_sim_demos/launch/gpu_lidar_bridge.launch.py +++ b/ros_gz_sim_demos/launch/gpu_lidar_bridge.launch.py @@ -28,14 +28,14 @@ def generate_launch_description(): - pkg_ros_ign_gazebo_demos = get_package_share_directory('ros_ign_gazebo_demos') - pkg_ros_ign_gazebo = get_package_share_directory('ros_ign_gazebo') + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') - ign_gazebo = IncludeLaunchDescription( + gz_sim = IncludeLaunchDescription( PythonLaunchDescriptionSource( - os.path.join(pkg_ros_ign_gazebo, 'launch', 'ign_gazebo.launch.py')), + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), launch_arguments={ - 'ign_args': '-r gpu_lidar_sensor.sdf' + 'gz_args': '-r gpu_lidar_sensor.sdf' }.items(), ) @@ -43,13 +43,13 @@ def generate_launch_description(): rviz = Node( package='rviz2', executable='rviz2', - arguments=['-d', os.path.join(pkg_ros_ign_gazebo_demos, 'rviz', 'gpu_lidar_bridge.rviz')], + arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'gpu_lidar_bridge.rviz')], condition=IfCondition(LaunchConfiguration('rviz')) ) # Bridge bridge = Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='parameter_bridge', arguments=['lidar@sensor_msgs/msg/LaserScan@ignition.msgs.LaserScan', '/lidar/points@sensor_msgs/msg/PointCloud2@ignition.msgs.PointCloudPacked'], @@ -57,7 +57,7 @@ def generate_launch_description(): ) return LaunchDescription([ - ign_gazebo, + gz_sim, DeclareLaunchArgument('rviz', default_value='true', description='Open RViz.'), bridge, diff --git a/ros_gz_sim_demos/launch/image_bridge.launch.py b/ros_gz_sim_demos/launch/image_bridge.launch.py index 642deb70..91e81e33 100644 --- a/ros_gz_sim_demos/launch/image_bridge.launch.py +++ b/ros_gz_sim_demos/launch/image_bridge.launch.py @@ -28,13 +28,13 @@ def generate_launch_description(): - pkg_ros_ign_gazebo = get_package_share_directory('ros_ign_gazebo') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') - ign_gazebo = IncludeLaunchDescription( + gz_sim = IncludeLaunchDescription( PythonLaunchDescriptionSource( - os.path.join(pkg_ros_ign_gazebo, 'launch', 'ign_gazebo.launch.py')), + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), launch_arguments={ - 'ign_args': '-r sensors_demo.sdf' + 'gz_args': '-r sensors_demo.sdf' }.items(), ) @@ -48,14 +48,14 @@ def generate_launch_description(): # Bridge bridge = Node( - package='ros_ign_image', + package='ros_gz_image', executable='image_bridge', arguments=['camera', 'depth_camera', 'rgbd_camera/image', 'rgbd_camera/depth_image'], output='screen' ) return LaunchDescription([ - ign_gazebo, + gz_sim, DeclareLaunchArgument('rqt', default_value='true', description='Open RQt.'), DeclareLaunchArgument('image_topic', default_value='/camera', diff --git a/ros_gz_sim_demos/launch/imu.launch.py b/ros_gz_sim_demos/launch/imu.launch.py index 4d2d524f..649ad359 100644 --- a/ros_gz_sim_demos/launch/imu.launch.py +++ b/ros_gz_sim_demos/launch/imu.launch.py @@ -28,13 +28,13 @@ def generate_launch_description(): - pkg_ros_ign_gazebo = get_package_share_directory('ros_ign_gazebo') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') - ign_gazebo = IncludeLaunchDescription( + gz_sim = IncludeLaunchDescription( PythonLaunchDescriptionSource( - os.path.join(pkg_ros_ign_gazebo, 'launch', 'ign_gazebo.launch.py')), + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), launch_arguments={ - 'ign_args': '-r sensors.sdf' + 'gz_args': '-r sensors.sdf' }.items(), ) @@ -48,24 +48,24 @@ def generate_launch_description(): # RViz # FIXME: Add once there's an IMU display for RViz2 - # pkg_ros_ign_gazebo_demos = get_package_share_directory('ros_ign_gazebo_demos') + # pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') # rviz = Node( # package='rviz2', # executable='rviz2', - # # arguments=['-d', os.path.join(pkg_ros_ign_gazebo_demos, 'rviz', 'imu.rviz')], + # # arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'imu.rviz')], # condition=IfCondition(LaunchConfiguration('rviz')) # ) # Bridge bridge = Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='parameter_bridge', arguments=['/imu@sensor_msgs/msg/Imu@ignition.msgs.IMU'], output='screen' ) return LaunchDescription([ - ign_gazebo, + gz_sim, DeclareLaunchArgument( 'rqt', default_value='true', description='Open RQt.' ), diff --git a/ros_gz_sim_demos/launch/joint_states.launch.py b/ros_gz_sim_demos/launch/joint_states.launch.py index a9dbac82..20b330ec 100644 --- a/ros_gz_sim_demos/launch/joint_states.launch.py +++ b/ros_gz_sim_demos/launch/joint_states.launch.py @@ -25,11 +25,11 @@ def generate_launch_description(): # Package Directories - pkg_ros_ign_gazebo = get_package_share_directory('ros_ign_gazebo') - pkg_ros_ign_gazebo_demos = get_package_share_directory('ros_ign_gazebo_demos') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') # Parse robot description from xacro - robot_description_file = os.path.join(pkg_ros_ign_gazebo_demos, 'models', 'rrbot.xacro') + robot_description_file = os.path.join(pkg_ros_gz_sim_demos, 'models', 'rrbot.xacro') robot_description_config = xacro.process_file( robot_description_file ) @@ -44,24 +44,24 @@ def generate_launch_description(): parameters=[robot_description], ) - # Ignition gazebo + # Gazebo Sim gazebo = IncludeLaunchDescription( PythonLaunchDescriptionSource( - os.path.join(pkg_ros_ign_gazebo, 'launch', 'ign_gazebo.launch.py') + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py') ), - launch_arguments={'ign_args': '-r empty.sdf'}.items(), + launch_arguments={'gz_args': '-r empty.sdf'}.items(), ) # RViz rviz = Node( package='rviz2', executable='rviz2', - arguments=['-d', os.path.join(pkg_ros_ign_gazebo_demos, 'rviz', 'joint_states.rviz')], + arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'joint_states.rviz')], ) # Spawn spawn = Node( - package='ros_ign_gazebo', + package='ros_gz_sim', executable='create', arguments=[ '-name', 'rrbot', @@ -70,9 +70,9 @@ def generate_launch_description(): output='screen', ) - # Ign - ROS Bridge + # Gz - ROS Bridge bridge = Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='parameter_bridge', arguments=[ # Clock (IGN -> ROS2) diff --git a/ros_gz_sim_demos/launch/magnetometer.launch.py b/ros_gz_sim_demos/launch/magnetometer.launch.py index 15564347..0e026676 100644 --- a/ros_gz_sim_demos/launch/magnetometer.launch.py +++ b/ros_gz_sim_demos/launch/magnetometer.launch.py @@ -28,13 +28,13 @@ def generate_launch_description(): - pkg_ros_ign_gazebo = get_package_share_directory('ros_ign_gazebo') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') - ign_gazebo = IncludeLaunchDescription( + gz_sim = IncludeLaunchDescription( PythonLaunchDescriptionSource( - os.path.join(pkg_ros_ign_gazebo, 'launch', 'ign_gazebo.launch.py')), + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), launch_arguments={ - 'ign_args': '-r sensors.sdf' + 'gz_args': '-r sensors.sdf' }.items(), ) @@ -48,14 +48,14 @@ def generate_launch_description(): # Bridge bridge = Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='parameter_bridge', arguments=['/magnetometer@sensor_msgs/msg/MagneticField@ignition.msgs.Magnetometer'], output='screen' ) return LaunchDescription([ - ign_gazebo, + gz_sim, DeclareLaunchArgument('rqt', default_value='true', description='Open RQt.'), bridge, diff --git a/ros_gz_sim_demos/launch/rgbd_camera.launch.py b/ros_gz_sim_demos/launch/rgbd_camera.launch.py index 39453647..1ec8409b 100644 --- a/ros_gz_sim_demos/launch/rgbd_camera.launch.py +++ b/ros_gz_sim_demos/launch/rgbd_camera.launch.py @@ -26,13 +26,13 @@ def generate_launch_description(): - pkg_ros_ign_gazebo = get_package_share_directory('ros_ign_gazebo') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') - ign_gazebo = IncludeLaunchDescription( + gz_sim = IncludeLaunchDescription( PythonLaunchDescriptionSource( - os.path.join(pkg_ros_ign_gazebo, 'launch', 'ign_gazebo.launch.py')), + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), # launch_arguments={ - # 'ign_args': '-r rgbd_camera.sdf' + # 'gz_args': '-r rgbd_camera.sdf' # }.items(), ) @@ -40,22 +40,22 @@ def generate_launch_description(): # rviz = Node( # package='rviz2', # executable='rviz2', - # arguments=['-d', os.path.join(pkg_ros_ign_gazebo_demos, 'rviz', 'rgbd_camera.rviz')], + # arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'rgbd_camera.rviz')], # condition=IfCondition(LaunchConfiguration('rviz')) # ) # Bridge bridge = Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='parameter_bridge', arguments=['/rgbd_camera/image@sensor_msgs/msg/Image@ignition.msgs.Image', '/rgbd_camera/depth_image@sensor_msgs/msg/Image@ignition.msgs.Image'], output='screen' ) - # FIXME: need a SDF file (depth_camera.sdf) inside ros_ign_point_cloud/ + # FIXME: need a SDF file (depth_camera.sdf) inside ros_gz_point_cloud/ return LaunchDescription([ - ign_gazebo, + gz_sim, DeclareLaunchArgument('rviz', default_value='true', description='Open RViz.'), bridge, diff --git a/ros_gz_sim_demos/launch/rgbd_camera_bridge.launch.py b/ros_gz_sim_demos/launch/rgbd_camera_bridge.launch.py index 07faece8..a318f682 100644 --- a/ros_gz_sim_demos/launch/rgbd_camera_bridge.launch.py +++ b/ros_gz_sim_demos/launch/rgbd_camera_bridge.launch.py @@ -28,14 +28,14 @@ def generate_launch_description(): - pkg_ros_ign_gazebo_demos = get_package_share_directory('ros_ign_gazebo_demos') - pkg_ros_ign_gazebo = get_package_share_directory('ros_ign_gazebo') + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') - ign_gazebo = IncludeLaunchDescription( + gz_sim = IncludeLaunchDescription( PythonLaunchDescriptionSource( - os.path.join(pkg_ros_ign_gazebo, 'launch', 'ign_gazebo.launch.py')), + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), launch_arguments={ - 'ign_args': '-r sensors_demo.sdf' + 'gz_args': '-r sensors_demo.sdf' }.items(), ) @@ -44,14 +44,14 @@ def generate_launch_description(): package='rviz2', executable='rviz2', arguments=[ - '-d', os.path.join(pkg_ros_ign_gazebo_demos, 'rviz', 'rgbd_camera_bridge.rviz') + '-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'rgbd_camera_bridge.rviz') ], condition=IfCondition(LaunchConfiguration('rviz')) ) # Bridge bridge = Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='parameter_bridge', arguments=[ '/rgbd_camera/image@sensor_msgs/msg/Image@ignition.msgs.Image', @@ -62,7 +62,7 @@ def generate_launch_description(): ) return LaunchDescription([ - ign_gazebo, + gz_sim, DeclareLaunchArgument('rviz', default_value='true', description='Open RViz.'), bridge, diff --git a/ros_gz_sim_demos/launch/robot_description_publisher.launch.py b/ros_gz_sim_demos/launch/robot_description_publisher.launch.py index 4f9d94e3..882cdee3 100755 --- a/ros_gz_sim_demos/launch/robot_description_publisher.launch.py +++ b/ros_gz_sim_demos/launch/robot_description_publisher.launch.py @@ -56,27 +56,27 @@ def generate_launch_description(): parameters=[params], arguments=[]) - # Ignition gazebo - pkg_ros_ign_gazebo = get_package_share_directory('ros_ign_gazebo') + # Gazebo Sim + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') gazebo = IncludeLaunchDescription( PythonLaunchDescriptionSource( - os.path.join(pkg_ros_ign_gazebo, 'launch', 'ign_gazebo.launch.py')), - launch_arguments={'ign_args': '-r empty.sdf'}.items(), + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={'gz_args': '-r empty.sdf'}.items(), ) # RViz - pkg_ros_ign_gazebo_demos = get_package_share_directory('ros_ign_gazebo_demos') + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') rviz = Node( package='rviz2', executable='rviz2', arguments=[ '-d', - os.path.join(pkg_ros_ign_gazebo_demos, 'rviz', 'robot_description_publisher.rviz') + os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'robot_description_publisher.rviz') ] ) # Spawn - spawn = Node(package='ros_ign_gazebo', executable='create', + spawn = Node(package='ros_gz_sim', executable='create', arguments=[ '-name', 'my_custom_model', '-x', '1.2', diff --git a/ros_gz_sim_demos/launch/tf_bridge.launch.py b/ros_gz_sim_demos/launch/tf_bridge.launch.py index ae995704..3b2171d0 100644 --- a/ros_gz_sim_demos/launch/tf_bridge.launch.py +++ b/ros_gz_sim_demos/launch/tf_bridge.launch.py @@ -22,14 +22,14 @@ def generate_launch_description(): - pkg_ros_ign_gazebo_demos = get_package_share_directory('ros_ign_gazebo_demos') + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') return LaunchDescription([ # Launch gazebo ExecuteProcess( cmd=[ 'ign', 'gazebo', '-r', os.path.join( - pkg_ros_ign_gazebo_demos, + pkg_ros_gz_sim_demos, 'models', 'double_pendulum_model.sdf' ) @@ -37,7 +37,7 @@ def generate_launch_description(): ), # Launch a bridge to forward tf and joint states to ros2 Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='parameter_bridge', arguments=[ '/world/default/model/double_pendulum_with_base0/joint_state@' @@ -54,6 +54,6 @@ def generate_launch_description(): Node( package='rviz2', executable='rviz2', - arguments=['-d', os.path.join(pkg_ros_ign_gazebo_demos, 'rviz', 'tf_bridge.rviz')] + arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'tf_bridge.rviz')] ) ]) diff --git a/ros_gz_sim_demos/launch/triggered_camera.launch.py b/ros_gz_sim_demos/launch/triggered_camera.launch.py index 4f3d7a85..9e6362a2 100644 --- a/ros_gz_sim_demos/launch/triggered_camera.launch.py +++ b/ros_gz_sim_demos/launch/triggered_camera.launch.py @@ -28,26 +28,26 @@ def generate_launch_description(): - pkg_ros_ign_gazebo_demos = get_package_share_directory('ros_ign_gazebo_demos') - pkg_ros_ign_gazebo = get_package_share_directory('ros_ign_gazebo') + pkg_ros_gz_sim_demos = get_package_share_directory('ros_gz_sim_demos') + pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim') - ign_gazebo = IncludeLaunchDescription( + gz_sim = IncludeLaunchDescription( PythonLaunchDescriptionSource( - os.path.join(pkg_ros_ign_gazebo, 'launch', 'ign_gazebo.launch.py')), - launch_arguments={'ign_args': '-r triggered_camera_sensor.sdf'}.items(), + os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), + launch_arguments={'gz_args': '-r triggered_camera_sensor.sdf'}.items(), ) # RViz rviz = Node( package='rviz2', executable='rviz2', - arguments=['-d', os.path.join(pkg_ros_ign_gazebo_demos, 'rviz', 'camera.rviz')], + arguments=['-d', os.path.join(pkg_ros_gz_sim_demos, 'rviz', 'camera.rviz')], condition=IfCondition(LaunchConfiguration('rviz')) ) # Bridge bridge = Node( - package='ros_ign_bridge', + package='ros_gz_bridge', executable='parameter_bridge', arguments=['/camera@sensor_msgs/msg/Image@ignition.msgs.Image', '/camera/trigger@std_msgs/msg/Bool@ignition.msgs.Boolean', @@ -58,7 +58,7 @@ def generate_launch_description(): return LaunchDescription([ DeclareLaunchArgument('rviz', default_value='true', description='Open RViz.'), - ign_gazebo, + gz_sim, bridge, rviz ]) diff --git a/ros_gz_sim_demos/models/rrbot.xacro b/ros_gz_sim_demos/models/rrbot.xacro index 782154e3..00680c14 100644 --- a/ros_gz_sim_demos/models/rrbot.xacro +++ b/ros_gz_sim_demos/models/rrbot.xacro @@ -159,7 +159,7 @@ - + \ No newline at end of file diff --git a/ros_gz_sim_demos/package.xml b/ros_gz_sim_demos/package.xml index a2ba4628..36b27b32 100644 --- a/ros_gz_sim_demos/package.xml +++ b/ros_gz_sim_demos/package.xml @@ -1,25 +1,25 @@ - ros_ign_gazebo_demos + ros_gz_sim_demos 0.244.3 - Demos using Ignition Gazebo simulation with ROS. + Demos using Gazebo Sim simulation with ROS. Apache 2.0 Louise Poubel ament_cmake - ignition-gazebo6 - ignition-gazebo6 + ignition-gazebo6 + ignition-gazebo6 - ignition-gazebo5 + ignition-gazebo5 image_transport_plugins robot_state_publisher - ros_ign_bridge - ros_ign_gazebo - ros_ign_image - - + ros_gz_bridge + ros_gz_sim + ros_gz_image + + rqt_image_view rqt_plot rqt_topic