diff --git a/.github/workflows/build-and-test.sh b/.github/workflows/build-and-test.sh
index aa516d174..86b2fd8ba 100755
--- a/.github/workflows/build-and-test.sh
+++ b/.github/workflows/build-and-test.sh
@@ -10,14 +10,19 @@ export ROS_PYTHON_VERSION=3
apt update -qq
apt install -qq -y lsb-release wget curl build-essential
-# Garden only has nightlies for now
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 -
GZ_DEPS="libgz-sim7-dev"
+ ROSDEP_ARGS="--skip-keys='sdformat-urdf'"
+elif [ "$GZ_VERSION" == "harmonic" ]; then
+ echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-stable.list
+ wget https://packages.osrfoundation.org/gazebo.key -O - | apt-key add -
+
+ GZ_DEPS="libgz-sim8-dev"
+
ROSDEP_ARGS="--skip-keys='sdformat-urdf'"
fi
diff --git a/.github/workflows/ros2-ci.yml b/.github/workflows/ros2-ci.yml
index 83e1c7f4f..a97e228cc 100644
--- a/.github/workflows/ros2-ci.yml
+++ b/.github/workflows/ros2-ci.yml
@@ -16,6 +16,9 @@ jobs:
- docker-image: "ubuntu:22.04"
gz-version: "garden"
ros-distro: "iron"
+ - docker-image: "ubuntu:22.04"
+ gz-version: "harmonic"
+ ros-distro: "iron"
container:
image: ${{ matrix.docker-image }}
steps:
diff --git a/README.md b/README.md
index b0483900b..b61a4405d 100644
--- a/README.md
+++ b/README.md
@@ -7,12 +7,17 @@ Foxy | Edifice | [foxy](https://github.com/gazebosim/ros_gz/tree/foxy) | only fr
Galactic | Edifice | [galactic](https://github.com/gazebosim/ros_gz/tree/galactic) | https://packages.ros.org
Galactic | Fortress | [galactic](https://github.com/gazebosim/ros_gz/tree/galactic) | only from source
Humble | Fortress | [humble](https://github.com/gazebosim/ros_gz/tree/humble) | https://packages.ros.org
-Humble | Garden | [humble](https://github.com/gazebosim/ros_gz/tree/humble) | only from source
+Humble | Garden | [humble](https://github.com/gazebosim/ros_gz/tree/humble) | [gazebo packages](https://gazebosim.org/docs/latest/ros_installation#gazebo-garden-with-ros-2-humble-iron-or-rolling-use-with-caution-)[^1]
+Humble | Harmonic | [humble](https://github.com/gazebosim/ros_gz/tree/humble) | only from source
Iron | Fortress | [humble](https://github.com/gazebosim/ros_gz/tree/iron) | https://packages.ros.org
Iron | Garden | [humble](https://github.com/gazebosim/ros_gz/tree/iron) | only from source
+Iron | Harmonic | [humble](https://github.com/gazebosim/ros_gz/tree/iron) | only from source
Rolling | Edifice | [ros2](https://github.com/gazebosim/ros_gz/tree/ros2) | only from source
Rolling | Fortress | [ros2](https://github.com/gazebosim/ros_gz/tree/ros2) | https://packages.ros.org
Rolling | Garden | [ros2](https://github.com/gazebosim/ros_gz/tree/ros2) | only from source
+Rolling | Harmonic | [ros2](https://github.com/gazebosim/ros_gz/tree/ros2) | only from source
+
+[^1]: Binaries for these pairings are provided from a the packages.osrfoundation.org repository. Refer to https://gazebosim.org/docs/latest/ros_installation for installation instructions.
For information on ROS 2 and Gazebo compatibility, refer to the [melodic branch README](https://github.com/gazebosim/ros_gz/tree/melodic)
@@ -85,7 +90,7 @@ Install either [Edifice, Fortress, or Garden](https://gazebosim.org/docs).
Set the `GZ_VERSION` environment variable to the Gazebo version you'd
like to compile against. For example:
- export GZ_VERSION=edifice
+ export GZ_VERSION=edifice # IMPORTANT: Replace with correct version
> You only need to set this variable when compiling, not when running.
@@ -101,7 +106,7 @@ The following steps are for Linux and OSX.
cd ~/ws/src
# Download needed software
- git clone https://github.com/gazebosim/ros_gz.git -b ros2
+ git clone https://github.com/gazebosim/ros_gz.git -b humble
```
1. Install dependencies (this may also install Gazebo):
diff --git a/ros_gz/CHANGELOG.rst b/ros_gz/CHANGELOG.rst
index 12875b00f..60541f530 100644
--- a/ros_gz/CHANGELOG.rst
+++ b/ros_gz/CHANGELOG.rst
@@ -2,9 +2,6 @@
Changelog for package ros_gz
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
-0.247.0 (2023-11-02)
---------------------
-
0.245.0 (2023-05-23)
--------------------
diff --git a/ros_gz/package.xml b/ros_gz/package.xml
index f7c4d786e..323c8e857 100644
--- a/ros_gz/package.xml
+++ b/ros_gz/package.xml
@@ -4,7 +4,7 @@
ros_gz
- 0.247.0
+ 0.245.0
Meta-package containing interfaces for using ROS 2 with Gazebo simulation.
Louise Poubel
Apache 2.0
diff --git a/ros_gz_bridge/CHANGELOG.rst b/ros_gz_bridge/CHANGELOG.rst
index 158ce6ce1..4a086e268 100644
--- a/ros_gz_bridge/CHANGELOG.rst
+++ b/ros_gz_bridge/CHANGELOG.rst
@@ -2,21 +2,6 @@
Changelog for package ros_gz_bridge
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
-0.247.0 (2023-11-02)
---------------------
-* Fix double wait in ros_gz_bridge (`#347 `_) (`#449 `_)
- Co-authored-by: ymd-stella <7959916+ymd-stella@users.noreply.github.com>
-* [backport iron] SensorNoise msg bridging (`#417 `_) (`#425 `_)
- Co-authored-by: Aditya Pande
-* Merge pull request `#420 `_ from gazebosim/ahcorde/iron/backport/411
- [backport iron] Update README.md (`#411 `_)
-* Merge branch 'iron' into ahcorde/iron/backport/411
-* [backport Iron] Added Altimeter msg bridging (`#413 `_) (`#414 `_)
- Co-authored-by: Aditya Pande
-* Update README.md (`#411 `_)
- The ROS type for gz.msgs.NavSat messages should be **sensor_msgs/msg/NavSatFix** instead of **sensor_msgs/msg/NavSatFixed**
-* Contributors: Alejandro Hernández Cordero, Arjun K Haridas
-
0.245.0 (2023-05-23)
--------------------
* Backport: Add missing rosidl_cmake dep to ros_gz_bridge (`#391 `_) (`#396 `_)
diff --git a/ros_gz_bridge/CMakeLists.txt b/ros_gz_bridge/CMakeLists.txt
index d8192d9a3..4d0e4057f 100644
--- a/ros_gz_bridge/CMakeLists.txt
+++ b/ros_gz_bridge/CMakeLists.txt
@@ -41,6 +41,15 @@ elseif("$ENV{GZ_VERSION}" STREQUAL "garden")
set(GZ_TRANSPORT_VER ${gz-transport12_VERSION_MAJOR})
message(STATUS "Compiling against Gazebo Garden")
+elseif("$ENV{GZ_VERSION}" STREQUAL "harmonic")
+ find_package(gz-transport13 REQUIRED)
+ find_package(gz-msgs10 REQUIRED)
+
+ set(GZ_TARGET_PREFIX gz)
+ set(GZ_MSGS_VER ${gz-msgs10_VERSION_MAJOR})
+ set(GZ_TRANSPORT_VER ${gz-transport13_VERSION_MAJOR})
+
+ message(STATUS "Compiling against Gazebo Harmonic")
# Default to Fortress
else()
find_package(ignition-transport11 REQUIRED)
diff --git a/ros_gz_bridge/include/ros_gz_bridge/convert/actuator_msgs.hpp b/ros_gz_bridge/include/ros_gz_bridge/convert/actuator_msgs.hpp
index 74f0a0707..ea4055b01 100644
--- a/ros_gz_bridge/include/ros_gz_bridge/convert/actuator_msgs.hpp
+++ b/ros_gz_bridge/include/ros_gz_bridge/convert/actuator_msgs.hpp
@@ -16,7 +16,7 @@
#define ROS_GZ_BRIDGE__CONVERT__ACTUATOR_MSGS_HPP_
// Gazebo Msgs
-#include
+#include
// ROS 2 messages
#include
@@ -30,12 +30,12 @@ template<>
void
convert_ros_to_gz(
const actuator_msgs::msg::Actuators & ros_msg,
- ignition::msgs::Actuators & gz_msg);
+ gz::msgs::Actuators & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Actuators & gz_msg,
+ const gz::msgs::Actuators & gz_msg,
actuator_msgs::msg::Actuators & ros_msg);
} // namespace ros_gz_bridge
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 a2b1999ee..04c47ba93 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
@@ -15,7 +15,7 @@
#ifndef ROS_GZ_BRIDGE__CONVERT__BUILTIN_INTERFACES_HPP_
#define ROS_GZ_BRIDGE__CONVERT__BUILTIN_INTERFACES_HPP_
-#include
+#include
#include
@@ -28,12 +28,12 @@ template<>
void
convert_ros_to_gz(
const builtin_interfaces::msg::Time & ros_msg,
- ignition::msgs::Time & gz_msg);
+ gz::msgs::Time & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Time & gz_msg,
+ const gz::msgs::Time & gz_msg,
builtin_interfaces::msg::Time & ros_msg);
} // namespace ros_gz_bridge
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 edee9b442..3256f68e1 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
@@ -16,14 +16,14 @@
#define ROS_GZ_BRIDGE__CONVERT__GEOMETRY_MSGS_HPP_
// Gazebo Msgs
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
// ROS 2 messages
#include
@@ -48,156 +48,156 @@ template<>
void
convert_ros_to_gz(
const geometry_msgs::msg::Quaternion & ros_msg,
- ignition::msgs::Quaternion & gz_msg);
+ gz::msgs::Quaternion & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Quaternion & gz_msg,
+ const gz::msgs::Quaternion & gz_msg,
geometry_msgs::msg::Quaternion & ros_msg);
template<>
void
convert_ros_to_gz(
const geometry_msgs::msg::Vector3 & ros_msg,
- ignition::msgs::Vector3d & gz_msg);
+ gz::msgs::Vector3d & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Vector3d & gz_msg,
+ const gz::msgs::Vector3d & gz_msg,
geometry_msgs::msg::Vector3 & ros_msg);
template<>
void
convert_ros_to_gz(
const geometry_msgs::msg::Point & ros_msg,
- ignition::msgs::Vector3d & gz_msg);
+ gz::msgs::Vector3d & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Vector3d & gz_msg,
+ const gz::msgs::Vector3d & gz_msg,
geometry_msgs::msg::Point & ros_msg);
template<>
void
convert_ros_to_gz(
const geometry_msgs::msg::Pose & ros_msg,
- ignition::msgs::Pose & gz_msg);
+ gz::msgs::Pose & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Pose & gz_msg,
+ const gz::msgs::Pose & gz_msg,
geometry_msgs::msg::Pose & ros_msg);
template<>
void
convert_ros_to_gz(
const geometry_msgs::msg::PoseArray & ros_msg,
- ignition::msgs::Pose_V & gz_msg);
+ gz::msgs::Pose_V & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Pose_V & gz_msg,
+ const gz::msgs::Pose_V & gz_msg,
geometry_msgs::msg::PoseArray & ros_msg);
template<>
void
convert_ros_to_gz(
const geometry_msgs::msg::PoseWithCovariance & ros_msg,
- ignition::msgs::PoseWithCovariance & gz_msg);
+ gz::msgs::PoseWithCovariance & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::PoseWithCovariance & gz_msg,
+ const gz::msgs::PoseWithCovariance & gz_msg,
geometry_msgs::msg::PoseWithCovariance & ros_msg);
template<>
void
convert_ros_to_gz(
const geometry_msgs::msg::PoseStamped & ros_msg,
- ignition::msgs::Pose & gz_msg);
+ gz::msgs::Pose & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Pose & gz_msg,
+ const gz::msgs::Pose & gz_msg,
geometry_msgs::msg::PoseStamped & ros_msg);
template<>
void
convert_ros_to_gz(
const geometry_msgs::msg::Transform & ros_msg,
- ignition::msgs::Pose & gz_msg);
+ gz::msgs::Pose & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Pose & gz_msg,
+ const gz::msgs::Pose & gz_msg,
geometry_msgs::msg::Transform & ros_msg);
template<>
void
convert_ros_to_gz(
const geometry_msgs::msg::TransformStamped & ros_msg,
- ignition::msgs::Pose & gz_msg);
+ gz::msgs::Pose & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Pose & gz_msg,
+ const gz::msgs::Pose & gz_msg,
geometry_msgs::msg::TransformStamped & ros_msg);
template<>
void
convert_ros_to_gz(
const geometry_msgs::msg::Twist & ros_msg,
- ignition::msgs::Twist & gz_msg);
+ gz::msgs::Twist & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Twist & gz_msg,
+ const gz::msgs::Twist & gz_msg,
geometry_msgs::msg::Twist & ros_msg);
template<>
void
convert_ros_to_gz(
const geometry_msgs::msg::TwistWithCovariance & ros_msg,
- ignition::msgs::TwistWithCovariance & gz_msg);
+ gz::msgs::TwistWithCovariance & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::TwistWithCovariance & gz_msg,
+ const gz::msgs::TwistWithCovariance & gz_msg,
geometry_msgs::msg::TwistWithCovariance & ros_msg);
template<>
void
convert_ros_to_gz(
const geometry_msgs::msg::Wrench & ros_msg,
- ignition::msgs::Wrench & gz_msg);
+ gz::msgs::Wrench & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Wrench & gz_msg,
+ const gz::msgs::Wrench & gz_msg,
geometry_msgs::msg::Wrench & ros_msg);
template<>
void
convert_ros_to_gz(
const geometry_msgs::msg::WrenchStamped & ros_msg,
- ignition::msgs::Wrench & gz_msg);
+ gz::msgs::Wrench & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Wrench & gz_msg,
+ const gz::msgs::Wrench & gz_msg,
geometry_msgs::msg::WrenchStamped & ros_msg);
} // namespace ros_gz_bridge
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 4c52c5b98..91c0f1a53 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
@@ -16,8 +16,8 @@
#define ROS_GZ_BRIDGE__CONVERT__NAV_MSGS_HPP_
// Gazebo Msgs
-#include
-#include
+#include
+#include
// ROS 2 messages
#include
@@ -31,24 +31,24 @@ template<>
void
convert_ros_to_gz(
const nav_msgs::msg::Odometry & ros_msg,
- ignition::msgs::Odometry & gz_msg);
+ gz::msgs::Odometry & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Odometry & gz_msg,
+ const gz::msgs::Odometry & gz_msg,
nav_msgs::msg::Odometry & ros_msg);
template<>
void
convert_ros_to_gz(
const nav_msgs::msg::Odometry & ros_msg,
- ignition::msgs::OdometryWithCovariance & gz_msg);
+ gz::msgs::OdometryWithCovariance & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::OdometryWithCovariance & gz_msg,
+ const gz::msgs::OdometryWithCovariance & gz_msg,
nav_msgs::msg::Odometry & ros_msg);
} // namespace ros_gz_bridge
diff --git a/ros_gz_bridge/include/ros_gz_bridge/convert/rcl_interfaces.hpp b/ros_gz_bridge/include/ros_gz_bridge/convert/rcl_interfaces.hpp
index 1788facdb..261849c5f 100644
--- a/ros_gz_bridge/include/ros_gz_bridge/convert/rcl_interfaces.hpp
+++ b/ros_gz_bridge/include/ros_gz_bridge/convert/rcl_interfaces.hpp
@@ -16,7 +16,7 @@
#define ROS_GZ_BRIDGE__CONVERT__RCL_INTERFACES_HPP_
// Ignition messages
-#include
+#include
// ROS 2 messages
#include
@@ -32,12 +32,12 @@ template<>
void
convert_ros_to_gz(
const rcl_interfaces::msg::ParameterValue & ros_msg,
- ignition::msgs::Any & ign_msg);
+ gz::msgs::Any & ign_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Any & ign_msg,
+ const gz::msgs::Any & ign_msg,
rcl_interfaces::msg::ParameterValue & ros_msg);
} // namespace ros_gz_bridge
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 9b0f5c10d..c7e671d48 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
@@ -16,21 +16,21 @@
#define ROS_GZ_BRIDGE__CONVERT__ROS_GZ_INTERFACES_HPP_
// Gazebo Msgs
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
// ROS 2 messages
#include
@@ -52,7 +52,7 @@
#include
#if HAVE_DATAFRAME
-#include
+#include
#include
#endif // HAVE_DATAFRAME
@@ -65,60 +65,60 @@ template<>
void
convert_ros_to_gz(
const ros_gz_interfaces::msg::JointWrench & ros_msg,
- ignition::msgs::JointWrench & gz_msg);
+ gz::msgs::JointWrench & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::JointWrench & gz_msg,
+ const gz::msgs::JointWrench & gz_msg,
ros_gz_interfaces::msg::JointWrench & ros_msg);
template<>
void
convert_ros_to_gz(
const ros_gz_interfaces::msg::Altimeter & ros_msg,
- ignition::msgs::Altimeter & gz_msg);
+ gz::msgs::Altimeter & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Altimeter & gz_msg,
+ const gz::msgs::Altimeter & gz_msg,
ros_gz_interfaces::msg::Altimeter & ros_msg);
template<>
void
convert_ros_to_gz(
const ros_gz_interfaces::msg::Entity & ros_msg,
- ignition::msgs::Entity & gz_msg);
+ gz::msgs::Entity & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Entity & gz_msg,
+ const gz::msgs::Entity & gz_msg,
ros_gz_interfaces::msg::Entity & ros_msg);
template<>
void
convert_ros_to_gz(
const ros_gz_interfaces::msg::Contact & ros_msg,
- ignition::msgs::Contact & gz_msg);
+ gz::msgs::Contact & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Contact & gz_msg,
+ const gz::msgs::Contact & gz_msg,
ros_gz_interfaces::msg::Contact & ros_msg);
template<>
void
convert_ros_to_gz(
const ros_gz_interfaces::msg::Contacts & ros_msg,
- ignition::msgs::Contacts & gz_msg);
+ gz::msgs::Contacts & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Contacts & gz_msg,
+ const gz::msgs::Contacts & gz_msg,
ros_gz_interfaces::msg::Contacts & ros_msg);
#if HAVE_DATAFRAME
@@ -126,12 +126,12 @@ template<>
void
convert_ros_to_gz(
const ros_gz_interfaces::msg::Dataframe & ros_msg,
- ignition::msgs::Dataframe & ign_msg);
+ gz::msgs::Dataframe & ign_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Dataframe & ign_msg,
+ const gz::msgs::Dataframe & ign_msg,
ros_gz_interfaces::msg::Dataframe & ros_msg);
#endif // HAVE_DATAFRAME
@@ -139,132 +139,132 @@ template<>
void
convert_ros_to_gz(
const ros_gz_interfaces::msg::GuiCamera & ros_msg,
- ignition::msgs::GUICamera & gz_msg);
+ gz::msgs::GUICamera & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::GUICamera & gz_msg,
+ const gz::msgs::GUICamera & gz_msg,
ros_gz_interfaces::msg::GuiCamera & ros_msg);
template<>
void
convert_ros_to_gz(
const ros_gz_interfaces::msg::Light & ros_msg,
- ignition::msgs::Light & gz_msg);
+ gz::msgs::Light & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Light & gz_msg,
+ const gz::msgs::Light & gz_msg,
ros_gz_interfaces::msg::Light & ros_msg);
template<>
void
convert_ros_to_gz(
const ros_gz_interfaces::msg::SensorNoise & ros_msg,
- ignition::msgs::SensorNoise & gz_msg);
+ gz::msgs::SensorNoise & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::SensorNoise & gz_msg,
+ const gz::msgs::SensorNoise & gz_msg,
ros_gz_interfaces::msg::SensorNoise & ros_msg);
template<>
void
convert_ros_to_gz(
const ros_gz_interfaces::msg::StringVec & ros_msg,
- ignition::msgs::StringMsg_V & gz_msg);
+ gz::msgs::StringMsg_V & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::StringMsg_V & gz_msg,
+ const gz::msgs::StringMsg_V & gz_msg,
ros_gz_interfaces::msg::StringVec & ros_msg);
template<>
void
convert_ros_to_gz(
const ros_gz_interfaces::msg::ParamVec & ros_msg,
- ignition::msgs::Param & gz_msg);
+ gz::msgs::Param & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Param & gz_msg,
+ const gz::msgs::Param & gz_msg,
ros_gz_interfaces::msg::ParamVec & ros_msg);
template<>
void
convert_ros_to_gz(
const ros_gz_interfaces::msg::ParamVec & ros_msg,
- ignition::msgs::Param_V & gz_msg);
+ gz::msgs::Param_V & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Param_V & gz_msg,
+ const gz::msgs::Param_V & gz_msg,
ros_gz_interfaces::msg::ParamVec & ros_msg);
template<>
void
convert_ros_to_gz(
const ros_gz_interfaces::msg::TrackVisual & ros_msg,
- ignition::msgs::TrackVisual & gz_msg);
+ gz::msgs::TrackVisual & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::TrackVisual & gz_msg,
+ const gz::msgs::TrackVisual & gz_msg,
ros_gz_interfaces::msg::TrackVisual & ros_msg);
template<>
void
convert_ros_to_gz(
const ros_gz_interfaces::msg::VideoRecord & ros_msg,
- ignition::msgs::VideoRecord & gz_msg);
+ gz::msgs::VideoRecord & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::VideoRecord & gz_msg,
+ const gz::msgs::VideoRecord & gz_msg,
ros_gz_interfaces::msg::VideoRecord & ros_msg);
template<>
void
convert_ros_to_gz(
const ros_gz_interfaces::msg::WorldControl & ros_msg,
- ignition::msgs::WorldControl & gz_msg);
+ gz::msgs::WorldControl & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::WorldControl & gz_msg,
+ const gz::msgs::WorldControl & gz_msg,
ros_gz_interfaces::msg::WorldControl & ros_msg);
template<>
void
convert_ros_to_gz(
const ros_gz_interfaces::msg::WorldReset & ros_msg,
- ignition::msgs::WorldReset & gz_msg);
+ gz::msgs::WorldReset & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::WorldReset & gz_msg,
+ const gz::msgs::WorldReset & gz_msg,
ros_gz_interfaces::msg::WorldReset & ros_msg);
template<>
void
convert_ros_to_gz(
const ros_gz_interfaces::msg::Float32Array & ros_msg,
- ignition::msgs::Float_V & gz_msg);
+ gz::msgs::Float_V & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Float_V & gz_msg,
+ const gz::msgs::Float_V & gz_msg,
ros_gz_interfaces::msg::Float32Array & ros_msg);
} // namespace ros_gz_bridge
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 c67073bbd..7916aaa73 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
@@ -16,7 +16,7 @@
#define ROS_GZ_BRIDGE__CONVERT__ROSGRAPH_MSGS_HPP_
// Gazebo Msgs
-#include
+#include
// ROS 2 messages
#include
@@ -29,14 +29,14 @@ namespace ros_gz_bridge
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Clock & gz_msg,
+ const gz::msgs::Clock & gz_msg,
rosgraph_msgs::msg::Clock & ros_msg);
template<>
void
convert_ros_to_gz(
const rosgraph_msgs::msg::Clock & ros_msg,
- ignition::msgs::Clock & gz_msg);
+ gz::msgs::Clock & gz_msg);
} // namespace ros_gz_bridge
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 c9abb904f..ab0d314a4 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
@@ -16,17 +16,17 @@
#define ROS_GZ_BRIDGE__CONVERT__SENSOR_MSGS_HPP_
// Gazebo Msgs
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
// ROS 2 messages
#include
@@ -51,132 +51,132 @@ template<>
void
convert_ros_to_gz(
const sensor_msgs::msg::Joy & ros_msg,
- ignition::msgs::Joy & gz_msg);
+ gz::msgs::Joy & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Joy & gz_msg,
+ const gz::msgs::Joy & gz_msg,
sensor_msgs::msg::Joy & ros_msg);
template<>
void
convert_ros_to_gz(
const sensor_msgs::msg::FluidPressure & ros_msg,
- ignition::msgs::FluidPressure & gz_msg);
+ gz::msgs::FluidPressure & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::FluidPressure & gz_msg,
+ const gz::msgs::FluidPressure & gz_msg,
sensor_msgs::msg::FluidPressure & ros_msg);
template<>
void
convert_ros_to_gz(
const sensor_msgs::msg::Image & ros_msg,
- ignition::msgs::Image & gz_msg);
+ gz::msgs::Image & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Image & gz_msg,
+ const gz::msgs::Image & gz_msg,
sensor_msgs::msg::Image & ros_msg);
template<>
void
convert_ros_to_gz(
const sensor_msgs::msg::CameraInfo & ros_msg,
- ignition::msgs::CameraInfo & gz_msg);
+ gz::msgs::CameraInfo & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::CameraInfo & gz_msg,
+ const gz::msgs::CameraInfo & gz_msg,
sensor_msgs::msg::CameraInfo & ros_msg);
template<>
void
convert_ros_to_gz(
const sensor_msgs::msg::Imu & ros_msg,
- ignition::msgs::IMU & gz_msg);
+ gz::msgs::IMU & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::IMU & gz_msg,
+ const gz::msgs::IMU & gz_msg,
sensor_msgs::msg::Imu & ros_msg);
template<>
void
convert_ros_to_gz(
const sensor_msgs::msg::JointState & ros_msg,
- ignition::msgs::Model & gz_msg);
+ gz::msgs::Model & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Model & gz_msg,
+ const gz::msgs::Model & gz_msg,
sensor_msgs::msg::JointState & ros_msg);
template<>
void
convert_ros_to_gz(
const sensor_msgs::msg::LaserScan & ros_msg,
- ignition::msgs::LaserScan & gz_msg);
+ gz::msgs::LaserScan & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::LaserScan & gz_msg,
+ const gz::msgs::LaserScan & gz_msg,
sensor_msgs::msg::LaserScan & ros_msg);
template<>
void
convert_ros_to_gz(
const sensor_msgs::msg::MagneticField & ros_msg,
- ignition::msgs::Magnetometer & gz_msg);
+ gz::msgs::Magnetometer & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Magnetometer & gz_msg,
+ const gz::msgs::Magnetometer & gz_msg,
sensor_msgs::msg::MagneticField & ros_msg);
template<>
void
convert_ros_to_gz(
const sensor_msgs::msg::NavSatFix & ros_msg,
- ignition::msgs::NavSat & gz_msg);
+ gz::msgs::NavSat & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::NavSat & gz_msg,
+ const gz::msgs::NavSat & gz_msg,
sensor_msgs::msg::NavSatFix & ros_msg);
template<>
void
convert_ros_to_gz(
const sensor_msgs::msg::PointCloud2 & ros_msg,
- ignition::msgs::PointCloudPacked & gz_msg);
+ gz::msgs::PointCloudPacked & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::PointCloudPacked & gz_msg,
+ const gz::msgs::PointCloudPacked & gz_msg,
sensor_msgs::msg::PointCloud2 & ros_msg);
template<>
void
convert_ros_to_gz(
const sensor_msgs::msg::BatteryState & ros_msg,
- ignition::msgs::BatteryState & gz_msg);
+ gz::msgs::BatteryState & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::BatteryState & gz_msg,
+ const gz::msgs::BatteryState & gz_msg,
sensor_msgs::msg::BatteryState & ros_msg);
} // namespace ros_gz_bridge
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 155a7cdd1..78d3f1197 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
@@ -16,15 +16,15 @@
#define ROS_GZ_BRIDGE__CONVERT__STD_MSGS_HPP_
// Gazebo Msgs
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
// ROS 2 messages
#include
@@ -46,108 +46,108 @@ template<>
void
convert_ros_to_gz(
const std_msgs::msg::Bool & ros_msg,
- ignition::msgs::Boolean & gz_msg);
+ gz::msgs::Boolean & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Boolean & gz_msg,
+ const gz::msgs::Boolean & gz_msg,
std_msgs::msg::Bool & ros_msg);
template<>
void
convert_ros_to_gz(
const std_msgs::msg::ColorRGBA & ros_msg,
- ignition::msgs::Color & gz_msg);
+ gz::msgs::Color & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Color & gz_msg,
+ const gz::msgs::Color & gz_msg,
std_msgs::msg::ColorRGBA & ros_msg);
template<>
void
convert_ros_to_gz(
const std_msgs::msg::Empty & ros_msg,
- ignition::msgs::Empty & gz_msg);
+ gz::msgs::Empty & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Empty & gz_msg,
+ const gz::msgs::Empty & gz_msg,
std_msgs::msg::Empty & ros_msg);
template<>
void
convert_ros_to_gz(
const std_msgs::msg::UInt32 & ros_msg,
- ignition::msgs::UInt32 & gz_msg);
+ gz::msgs::UInt32 & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::UInt32 & gz_msg,
+ const gz::msgs::UInt32 & gz_msg,
std_msgs::msg::UInt32 & ros_msg);
template<>
void
convert_ros_to_gz(
const std_msgs::msg::Float32 & ros_msg,
- ignition::msgs::Float & gz_msg);
+ gz::msgs::Float & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Float & gz_msg,
+ const gz::msgs::Float & gz_msg,
std_msgs::msg::Float32 & ros_msg);
template<>
void
convert_ros_to_gz(
const std_msgs::msg::Float64 & ros_msg,
- ignition::msgs::Double & gz_msg);
+ gz::msgs::Double & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Double & gz_msg,
+ const gz::msgs::Double & gz_msg,
std_msgs::msg::Float64 & ros_msg);
template<>
void
convert_ros_to_gz(
const std_msgs::msg::Header & ros_msg,
- ignition::msgs::Header & gz_msg);
+ gz::msgs::Header & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Header & gz_msg,
+ const gz::msgs::Header & gz_msg,
std_msgs::msg::Header & ros_msg);
template<>
void
convert_ros_to_gz(
const std_msgs::msg::Int32 & ros_msg,
- ignition::msgs::Int32 & gz_msg);
+ gz::msgs::Int32 & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Int32 & gz_msg,
+ const gz::msgs::Int32 & gz_msg,
std_msgs::msg::Int32 & ros_msg);
template<>
void
convert_ros_to_gz(
const std_msgs::msg::String & ros_msg,
- ignition::msgs::StringMsg & gz_msg);
+ gz::msgs::StringMsg & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::StringMsg & gz_msg,
+ const gz::msgs::StringMsg & gz_msg,
std_msgs::msg::String & ros_msg);
} // namespace ros_gz_bridge
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 a254df5c6..a7df9e066 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
@@ -16,7 +16,7 @@
#define ROS_GZ_BRIDGE__CONVERT__TF2_MSGS_HPP_
// Gazebo Msgs
-#include
+#include
// ROS 2 messages
#include
@@ -30,12 +30,12 @@ template<>
void
convert_ros_to_gz(
const tf2_msgs::msg::TFMessage & ros_msg,
- ignition::msgs::Pose_V & gz_msg);
+ gz::msgs::Pose_V & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Pose_V & gz_msg,
+ const gz::msgs::Pose_V & gz_msg,
tf2_msgs::msg::TFMessage & ros_msg);
} // namespace ros_gz_bridge
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 f3efbbe21..d2120db2e 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
@@ -16,7 +16,7 @@
#define ROS_GZ_BRIDGE__CONVERT__TRAJECTORY_MSGS_HPP_
// Gazebo Msgs
-#include
+#include
// ROS 2 messages
#include
@@ -30,24 +30,24 @@ template<>
void
convert_ros_to_gz(
const trajectory_msgs::msg::JointTrajectoryPoint & ros_msg,
- ignition::msgs::JointTrajectoryPoint & gz_msg);
+ gz::msgs::JointTrajectoryPoint & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::JointTrajectoryPoint & gz_msg,
+ const gz::msgs::JointTrajectoryPoint & gz_msg,
trajectory_msgs::msg::JointTrajectoryPoint & ros_msg);
template<>
void
convert_ros_to_gz(
const trajectory_msgs::msg::JointTrajectory & ros_msg,
- ignition::msgs::JointTrajectory & gz_msg);
+ gz::msgs::JointTrajectory & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::JointTrajectory & gz_msg,
+ const gz::msgs::JointTrajectory & gz_msg,
trajectory_msgs::msg::JointTrajectory & ros_msg);
diff --git a/ros_gz_bridge/include/ros_gz_bridge/convert/vision_msgs.hpp b/ros_gz_bridge/include/ros_gz_bridge/convert/vision_msgs.hpp
index e5a718177..f370144fe 100644
--- a/ros_gz_bridge/include/ros_gz_bridge/convert/vision_msgs.hpp
+++ b/ros_gz_bridge/include/ros_gz_bridge/convert/vision_msgs.hpp
@@ -16,7 +16,7 @@
#define ROS_GZ_BRIDGE__CONVERT__VISION_MSGS_HPP_
// Gazebo Msgs
-#include
+#include
// ROS 2 messages
#include "vision_msgs/msg/detection2_d_array.hpp"
@@ -28,24 +28,24 @@ template<>
void
convert_ros_to_gz(
const vision_msgs::msg::Detection2D & ros_msg,
- ignition::msgs::AnnotatedAxisAligned2DBox & gz_msg);
+ gz::msgs::AnnotatedAxisAligned2DBox & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::AnnotatedAxisAligned2DBox & gz_msg,
+ const gz::msgs::AnnotatedAxisAligned2DBox & gz_msg,
vision_msgs::msg::Detection2D & ros_msg);
template<>
void
convert_ros_to_gz(
const vision_msgs::msg::Detection2DArray & ros_msg,
- ignition::msgs::AnnotatedAxisAligned2DBox_V & gz_msg);
+ gz::msgs::AnnotatedAxisAligned2DBox_V & gz_msg);
template<>
void
convert_gz_to_ros(
- const ignition::msgs::AnnotatedAxisAligned2DBox_V & gz_msg,
+ const gz::msgs::AnnotatedAxisAligned2DBox_V & gz_msg,
vision_msgs::msg::Detection2DArray & ros_msg);
} // namespace ros_gz_bridge
diff --git a/ros_gz_bridge/include/ros_gz_bridge/ros_gz_bridge.hpp b/ros_gz_bridge/include/ros_gz_bridge/ros_gz_bridge.hpp
index 4db02e4a9..8d9ff631c 100644
--- a/ros_gz_bridge/include/ros_gz_bridge/ros_gz_bridge.hpp
+++ b/ros_gz_bridge/include/ros_gz_bridge/ros_gz_bridge.hpp
@@ -19,8 +19,8 @@
#include
#include
-#include
-#include
+#include
+#include
#include
#include "ros_gz_bridge/bridge_config.hpp"
@@ -70,7 +70,7 @@ class RosGzBridge : public rclcpp::Node
protected:
/// \brief Pointer to Gazebo node used to create publishers/subscribers
- std::shared_ptr gz_node_;
+ std::shared_ptr gz_node_;
/// \brief List of bridge handles
std::vector> handles_;
diff --git a/ros_gz_bridge/package.xml b/ros_gz_bridge/package.xml
index 71818828f..58f947169 100644
--- a/ros_gz_bridge/package.xml
+++ b/ros_gz_bridge/package.xml
@@ -2,7 +2,7 @@
ros_gz_bridge
- 0.247.0
+ 0.245.0
Bridge communication between ROS and Gazebo Transport
Louise Poubel
@@ -28,6 +28,9 @@
yaml_cpp_vendor
vision_msgs
+
+ gz-msgs10
+ gz-transport13
gz-msgs9
gz-transport12
diff --git a/ros_gz_bridge/ros_gz_bridge/__init__.py b/ros_gz_bridge/ros_gz_bridge/__init__.py
index 01b3aa787..c0aaa4847 100644
--- a/ros_gz_bridge/ros_gz_bridge/__init__.py
+++ b/ros_gz_bridge/ros_gz_bridge/__init__.py
@@ -41,15 +41,15 @@ def ign_string(self):
return f'ignition.msgs.{self.gz_message_name}'
def ign_type(self):
- # Return GZ type of a message (eg ignition::msgs::Bool)
- return f'ignition::msgs::{self.gz_message_name}'
+ # Return GZ type of a message (eg gz::msgs::Bool)
+ return f'gz::msgs::{self.gz_message_name}'
def gz_string(self):
# Return GZ string version of a message (eg ignition.msgs.Bool)
return f'gz.msgs.{self.gz_message_name}'
def gz_type(self):
- # Return GZ type of a message (eg ignition::msgs::Bool)
+ # Return GZ type of a message (eg gz::msgs::Bool)
return f'gz::msgs::{self.gz_message_name}'
def unique(self):
diff --git a/ros_gz_bridge/src/bridge_handle.cpp b/ros_gz_bridge/src/bridge_handle.cpp
index 6fd1cc1f4..c7851503d 100644
--- a/ros_gz_bridge/src/bridge_handle.cpp
+++ b/ros_gz_bridge/src/bridge_handle.cpp
@@ -23,7 +23,7 @@ namespace ros_gz_bridge
{
BridgeHandle::BridgeHandle(
rclcpp::Node::SharedPtr ros_node,
- std::shared_ptr gz_node,
+ std::shared_ptr gz_node,
const BridgeConfig & config)
: ros_node_(ros_node),
gz_node_(gz_node),
diff --git a/ros_gz_bridge/src/bridge_handle.hpp b/ros_gz_bridge/src/bridge_handle.hpp
index 11712f011..d1751fb9e 100644
--- a/ros_gz_bridge/src/bridge_handle.hpp
+++ b/ros_gz_bridge/src/bridge_handle.hpp
@@ -18,7 +18,7 @@
#include
#include
-#include
+#include
#include
#include "get_factory.hpp"
@@ -40,7 +40,7 @@ class BridgeHandle
/// \param[in] config Configuration parameters for this handle
BridgeHandle(
rclcpp::Node::SharedPtr ros_node,
- std::shared_ptr gz_node,
+ std::shared_ptr gz_node,
const BridgeConfig & config);
/// \brief Destructor
@@ -94,7 +94,7 @@ class BridgeHandle
rclcpp::Node::SharedPtr ros_node_;
/// \brief The Gazebo node used to create publishers/subscriptions
- std::shared_ptr gz_node_;
+ std::shared_ptr gz_node_;
/// \brief The configuration parameters of this bridge
BridgeConfig config_;
diff --git a/ros_gz_bridge/src/bridge_handle_gz_to_ros.hpp b/ros_gz_bridge/src/bridge_handle_gz_to_ros.hpp
index 0fce7f78b..f8f4a02c5 100644
--- a/ros_gz_bridge/src/bridge_handle_gz_to_ros.hpp
+++ b/ros_gz_bridge/src/bridge_handle_gz_to_ros.hpp
@@ -17,7 +17,7 @@
#include
-#include
+#include
#include
#include "bridge_handle.hpp"
@@ -58,7 +58,7 @@ class BridgeHandleGzToRos : public BridgeHandle
protected:
/// \brief Gazebo subscriber, populated when subscriber active
- std::shared_ptr gz_subscriber_ = {nullptr};
+ std::shared_ptr gz_subscriber_ = {nullptr};
/// \brief ROS publisher, populated when publisher active
rclcpp::PublisherBase::SharedPtr ros_publisher_ = {nullptr};
diff --git a/ros_gz_bridge/src/bridge_handle_ros_to_gz.cpp b/ros_gz_bridge/src/bridge_handle_ros_to_gz.cpp
index a101ed69f..6253ce486 100644
--- a/ros_gz_bridge/src/bridge_handle_ros_to_gz.cpp
+++ b/ros_gz_bridge/src/bridge_handle_ros_to_gz.cpp
@@ -14,7 +14,7 @@
#include "bridge_handle_ros_to_gz.hpp"
-#include
+#include
namespace ros_gz_bridge
{
diff --git a/ros_gz_bridge/src/bridge_handle_ros_to_gz.hpp b/ros_gz_bridge/src/bridge_handle_ros_to_gz.hpp
index 5526ed46d..edf050dfe 100644
--- a/ros_gz_bridge/src/bridge_handle_ros_to_gz.hpp
+++ b/ros_gz_bridge/src/bridge_handle_ros_to_gz.hpp
@@ -15,7 +15,7 @@
#ifndef BRIDGE_HANDLE_ROS_TO_GZ_HPP_
#define BRIDGE_HANDLE_ROS_TO_GZ_HPP_
-#include
+#include
#include
#include "bridge_handle.hpp"
@@ -59,7 +59,7 @@ class BridgeHandleRosToGz : public BridgeHandle
rclcpp::SubscriptionBase::SharedPtr ros_subscriber_ = {nullptr};
/// \brief Gazebo publisher, populated when publisher active
- ignition::transport::Node::Publisher gz_publisher_;
+ gz::transport::Node::Publisher gz_publisher_;
};
} // namespace ros_gz_bridge
diff --git a/ros_gz_bridge/src/convert/actuator_msgs.cpp b/ros_gz_bridge/src/convert/actuator_msgs.cpp
index 7f321531b..0c9bcde34 100644
--- a/ros_gz_bridge/src/convert/actuator_msgs.cpp
+++ b/ros_gz_bridge/src/convert/actuator_msgs.cpp
@@ -22,7 +22,7 @@ template<>
void
convert_ros_to_gz(
const actuator_msgs::msg::Actuators & ros_msg,
- ignition::msgs::Actuators & gz_msg)
+ gz::msgs::Actuators & gz_msg)
{
convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header()));
@@ -41,7 +41,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Actuators & gz_msg,
+ const gz::msgs::Actuators & gz_msg,
actuator_msgs::msg::Actuators & ros_msg)
{
convert_gz_to_ros(gz_msg.header(), ros_msg.header);
diff --git a/ros_gz_bridge/src/convert/builtin_interfaces.cpp b/ros_gz_bridge/src/convert/builtin_interfaces.cpp
index fa5548eba..04451dd92 100644
--- a/ros_gz_bridge/src/convert/builtin_interfaces.cpp
+++ b/ros_gz_bridge/src/convert/builtin_interfaces.cpp
@@ -20,7 +20,7 @@ template<>
void
convert_ros_to_gz(
const builtin_interfaces::msg::Time & ros_msg,
- ignition::msgs::Time & gz_msg)
+ gz::msgs::Time & gz_msg)
{
gz_msg.set_sec(ros_msg.sec);
gz_msg.set_nsec(ros_msg.nanosec);
@@ -29,7 +29,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Time & gz_msg,
+ const gz::msgs::Time & gz_msg,
builtin_interfaces::msg::Time & ros_msg)
{
ros_msg.sec = gz_msg.sec();
diff --git a/ros_gz_bridge/src/convert/geometry_msgs.cpp b/ros_gz_bridge/src/convert/geometry_msgs.cpp
index fd2ad3d3a..be5f755c5 100644
--- a/ros_gz_bridge/src/convert/geometry_msgs.cpp
+++ b/ros_gz_bridge/src/convert/geometry_msgs.cpp
@@ -22,7 +22,7 @@ template<>
void
convert_ros_to_gz(
const geometry_msgs::msg::Quaternion & ros_msg,
- ignition::msgs::Quaternion & gz_msg)
+ gz::msgs::Quaternion & gz_msg)
{
gz_msg.set_x(ros_msg.x);
gz_msg.set_y(ros_msg.y);
@@ -33,7 +33,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Quaternion & gz_msg,
+ const gz::msgs::Quaternion & gz_msg,
geometry_msgs::msg::Quaternion & ros_msg)
{
ros_msg.x = gz_msg.x();
@@ -46,7 +46,7 @@ template<>
void
convert_ros_to_gz(
const geometry_msgs::msg::Vector3 & ros_msg,
- ignition::msgs::Vector3d & gz_msg)
+ gz::msgs::Vector3d & gz_msg)
{
gz_msg.set_x(ros_msg.x);
gz_msg.set_y(ros_msg.y);
@@ -56,7 +56,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Vector3d & gz_msg,
+ const gz::msgs::Vector3d & gz_msg,
geometry_msgs::msg::Vector3 & ros_msg)
{
ros_msg.x = gz_msg.x();
@@ -68,7 +68,7 @@ template<>
void
convert_ros_to_gz(
const geometry_msgs::msg::Point & ros_msg,
- ignition::msgs::Vector3d & gz_msg)
+ gz::msgs::Vector3d & gz_msg)
{
gz_msg.set_x(ros_msg.x);
gz_msg.set_y(ros_msg.y);
@@ -78,7 +78,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Vector3d & gz_msg,
+ const gz::msgs::Vector3d & gz_msg,
geometry_msgs::msg::Point & ros_msg)
{
ros_msg.x = gz_msg.x();
@@ -90,7 +90,7 @@ template<>
void
convert_ros_to_gz(
const geometry_msgs::msg::Pose & ros_msg,
- ignition::msgs::Pose & gz_msg)
+ gz::msgs::Pose & gz_msg)
{
convert_ros_to_gz(ros_msg.position, *gz_msg.mutable_position());
convert_ros_to_gz(ros_msg.orientation, *gz_msg.mutable_orientation());
@@ -99,7 +99,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Pose & gz_msg,
+ const gz::msgs::Pose & gz_msg,
geometry_msgs::msg::Pose & ros_msg)
{
convert_gz_to_ros(gz_msg.position(), ros_msg.position);
@@ -110,7 +110,7 @@ template<>
void
convert_ros_to_gz(
const geometry_msgs::msg::PoseArray & ros_msg,
- ignition::msgs::Pose_V & gz_msg)
+ gz::msgs::Pose_V & gz_msg)
{
convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header()));
gz_msg.clear_pose();
@@ -123,7 +123,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Pose_V & gz_msg,
+ const gz::msgs::Pose_V & gz_msg,
geometry_msgs::msg::PoseArray & ros_msg)
{
convert_gz_to_ros(gz_msg.header(), ros_msg.header);
@@ -139,7 +139,7 @@ template<>
void
convert_ros_to_gz(
const geometry_msgs::msg::PoseWithCovariance & ros_msg,
- ignition::msgs::PoseWithCovariance & gz_msg)
+ gz::msgs::PoseWithCovariance & gz_msg)
{
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());
@@ -151,7 +151,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::PoseWithCovariance & gz_msg,
+ const gz::msgs::PoseWithCovariance & gz_msg,
geometry_msgs::msg::PoseWithCovariance & ros_msg)
{
convert_gz_to_ros(gz_msg.pose().position(), ros_msg.pose.position);
@@ -169,7 +169,7 @@ template<>
void
convert_ros_to_gz(
const geometry_msgs::msg::PoseStamped & ros_msg,
- ignition::msgs::Pose & gz_msg)
+ gz::msgs::Pose & gz_msg)
{
convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header()));
convert_ros_to_gz(ros_msg.pose, gz_msg);
@@ -178,7 +178,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Pose & gz_msg,
+ const gz::msgs::Pose & gz_msg,
geometry_msgs::msg::PoseStamped & ros_msg)
{
convert_gz_to_ros(gz_msg.header(), ros_msg.header);
@@ -189,7 +189,7 @@ template<>
void
convert_ros_to_gz(
const geometry_msgs::msg::Transform & ros_msg,
- ignition::msgs::Pose & gz_msg)
+ gz::msgs::Pose & gz_msg)
{
convert_ros_to_gz(ros_msg.translation, *gz_msg.mutable_position());
convert_ros_to_gz(ros_msg.rotation, *gz_msg.mutable_orientation());
@@ -198,7 +198,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Pose & gz_msg,
+ const gz::msgs::Pose & gz_msg,
geometry_msgs::msg::Transform & ros_msg)
{
convert_gz_to_ros(gz_msg.position(), ros_msg.translation);
@@ -209,7 +209,7 @@ template<>
void
convert_ros_to_gz(
const geometry_msgs::msg::TransformStamped & ros_msg,
- ignition::msgs::Pose & gz_msg)
+ gz::msgs::Pose & gz_msg)
{
convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header()));
convert_ros_to_gz(ros_msg.transform, gz_msg);
@@ -222,7 +222,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Pose & gz_msg,
+ const gz::msgs::Pose & gz_msg,
geometry_msgs::msg::TransformStamped & ros_msg)
{
convert_gz_to_ros(gz_msg.header(), ros_msg.header);
@@ -240,7 +240,7 @@ template<>
void
convert_ros_to_gz(
const geometry_msgs::msg::Twist & ros_msg,
- ignition::msgs::Twist & gz_msg)
+ gz::msgs::Twist & gz_msg)
{
convert_ros_to_gz(ros_msg.linear, (*gz_msg.mutable_linear()));
convert_ros_to_gz(ros_msg.angular, (*gz_msg.mutable_angular()));
@@ -249,7 +249,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Twist & gz_msg,
+ const gz::msgs::Twist & gz_msg,
geometry_msgs::msg::Twist & ros_msg)
{
convert_gz_to_ros(gz_msg.linear(), ros_msg.linear);
@@ -260,7 +260,7 @@ template<>
void
convert_ros_to_gz(
const geometry_msgs::msg::TwistWithCovariance & ros_msg,
- ignition::msgs::TwistWithCovariance & gz_msg)
+ gz::msgs::TwistWithCovariance & gz_msg)
{
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()));
@@ -272,7 +272,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::TwistWithCovariance & gz_msg,
+ const gz::msgs::TwistWithCovariance & gz_msg,
geometry_msgs::msg::TwistWithCovariance & ros_msg)
{
convert_gz_to_ros(gz_msg.twist().linear(), ros_msg.twist.linear);
@@ -290,7 +290,7 @@ template<>
void
convert_ros_to_gz(
const geometry_msgs::msg::Wrench & ros_msg,
- ignition::msgs::Wrench & gz_msg)
+ gz::msgs::Wrench & gz_msg)
{
convert_ros_to_gz(ros_msg.force, (*gz_msg.mutable_force()));
convert_ros_to_gz(ros_msg.torque, (*gz_msg.mutable_torque()));
@@ -299,7 +299,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Wrench & gz_msg,
+ const gz::msgs::Wrench & gz_msg,
geometry_msgs::msg::Wrench & ros_msg)
{
convert_gz_to_ros(gz_msg.force(), ros_msg.force);
@@ -310,7 +310,7 @@ template<>
void
convert_ros_to_gz(
const geometry_msgs::msg::WrenchStamped & ros_msg,
- ignition::msgs::Wrench & gz_msg)
+ gz::msgs::Wrench & gz_msg)
{
convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header()));
convert_ros_to_gz(ros_msg.wrench.force, (*gz_msg.mutable_force()));
@@ -320,7 +320,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Wrench & gz_msg,
+ const gz::msgs::Wrench & gz_msg,
geometry_msgs::msg::WrenchStamped & ros_msg)
{
convert_gz_to_ros(gz_msg.header(), ros_msg.header);
diff --git a/ros_gz_bridge/src/convert/nav_msgs.cpp b/ros_gz_bridge/src/convert/nav_msgs.cpp
index 092ac3f19..816f1823a 100644
--- a/ros_gz_bridge/src/convert/nav_msgs.cpp
+++ b/ros_gz_bridge/src/convert/nav_msgs.cpp
@@ -22,7 +22,7 @@ template<>
void
convert_ros_to_gz(
const nav_msgs::msg::Odometry & ros_msg,
- ignition::msgs::Odometry & gz_msg)
+ gz::msgs::Odometry & gz_msg)
{
convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header()));
convert_ros_to_gz(ros_msg.pose.pose, (*gz_msg.mutable_pose()));
@@ -36,7 +36,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Odometry & gz_msg,
+ const gz::msgs::Odometry & gz_msg,
nav_msgs::msg::Odometry & ros_msg)
{
convert_gz_to_ros(gz_msg.header(), ros_msg.header);
@@ -56,7 +56,7 @@ template<>
void
convert_ros_to_gz(
const nav_msgs::msg::Odometry & ros_msg,
- ignition::msgs::OdometryWithCovariance & gz_msg)
+ gz::msgs::OdometryWithCovariance & gz_msg)
{
convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header()));
convert_ros_to_gz(ros_msg.pose, (*gz_msg.mutable_pose_with_covariance()));
@@ -70,7 +70,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::OdometryWithCovariance & gz_msg,
+ const gz::msgs::OdometryWithCovariance & gz_msg,
nav_msgs::msg::Odometry & ros_msg)
{
convert_gz_to_ros(gz_msg.header(), ros_msg.header);
diff --git a/ros_gz_bridge/src/convert/rcl_interfaces.cpp b/ros_gz_bridge/src/convert/rcl_interfaces.cpp
index 5673adf5b..d44441de6 100644
--- a/ros_gz_bridge/src/convert/rcl_interfaces.cpp
+++ b/ros_gz_bridge/src/convert/rcl_interfaces.cpp
@@ -27,10 +27,10 @@ template<>
void
convert_ros_to_gz(
const rcl_interfaces::msg::ParameterValue & ros_msg,
- ignition::msgs::Any & gz_msg)
+ gz::msgs::Any & gz_msg)
{
using ParameterType = rcl_interfaces::msg::ParameterType;
- using Any_ValueType = ignition::msgs::Any_ValueType;
+ using Any_ValueType = gz::msgs::Any_ValueType;
std::string unsupported_type;
gz_msg.set_type(Any_ValueType::Any_ValueType_NONE);
@@ -92,11 +92,11 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Any & gz_msg,
+ const gz::msgs::Any & gz_msg,
rcl_interfaces::msg::ParameterValue & ros_msg)
{
using ParameterType = rcl_interfaces::msg::ParameterType;
- using Any_ValueType = ignition::msgs::Any_ValueType;
+ using Any_ValueType = gz::msgs::Any_ValueType;
ros_msg.type = ParameterType::PARAMETER_NOT_SET;
diff --git a/ros_gz_bridge/src/convert/rcl_interfaces_TEST.cpp b/ros_gz_bridge/src/convert/rcl_interfaces_TEST.cpp
index ef5777975..a74631dad 100644
--- a/ros_gz_bridge/src/convert/rcl_interfaces_TEST.cpp
+++ b/ros_gz_bridge/src/convert/rcl_interfaces_TEST.cpp
@@ -19,15 +19,15 @@
#include
// A more specific set of tests for the rcl_interfaces/msg/ParamValue to
-// ignition::msgs::Any to verify behaviors that couldn't easily be captured
+// gz::msgs::Any to verify behaviors that couldn't easily be captured
// by the generic test framework
struct RosToGzTest : public ::testing::Test
{
using ParameterValue = rcl_interfaces::msg::ParameterValue;
using ParameterType = rcl_interfaces::msg::ParameterType;
- using Any = ignition::msgs::Any;
- using Any_ValueType = ignition::msgs::Any_ValueType;
+ using Any = gz::msgs::Any;
+ using Any_ValueType = gz::msgs::Any_ValueType;
Any gz_msg;
ParameterValue ros_msg;
diff --git a/ros_gz_bridge/src/convert/ros_gz_interfaces.cpp b/ros_gz_bridge/src/convert/ros_gz_interfaces.cpp
index 844c9c376..fceb296a8 100644
--- a/ros_gz_bridge/src/convert/ros_gz_interfaces.cpp
+++ b/ros_gz_bridge/src/convert/ros_gz_interfaces.cpp
@@ -21,7 +21,7 @@ template<>
void
convert_ros_to_gz(
const ros_gz_interfaces::msg::JointWrench & ros_msg,
- ignition::msgs::JointWrench & gz_msg)
+ gz::msgs::JointWrench & gz_msg)
{
convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header()));
gz_msg.set_body_1_name(ros_msg.body_1_name.data);
@@ -35,7 +35,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::JointWrench & gz_msg,
+ const gz::msgs::JointWrench & gz_msg,
ros_gz_interfaces::msg::JointWrench & ros_msg)
{
convert_gz_to_ros(gz_msg.header(), ros_msg.header);
@@ -51,7 +51,7 @@ template<>
void
convert_ros_to_gz(
const ros_gz_interfaces::msg::Altimeter & ros_msg,
- ignition::msgs::Altimeter & gz_msg)
+ gz::msgs::Altimeter & gz_msg)
{
convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header()));
gz_msg.set_vertical_position(ros_msg.vertical_position);
@@ -62,7 +62,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Altimeter & gz_msg,
+ const gz::msgs::Altimeter & gz_msg,
ros_gz_interfaces::msg::Altimeter & ros_msg)
{
convert_gz_to_ros(gz_msg.header(), ros_msg.header);
@@ -75,34 +75,34 @@ template<>
void
convert_ros_to_gz(
const ros_gz_interfaces::msg::Entity & ros_msg,
- ignition::msgs::Entity & gz_msg)
+ gz::msgs::Entity & gz_msg)
{
gz_msg.set_id(ros_msg.id);
gz_msg.set_name(ros_msg.name);
switch (ros_msg.type) {
case ros_gz_interfaces::msg::Entity::NONE:
- gz_msg.set_type(ignition::msgs::Entity::NONE);
+ gz_msg.set_type(gz::msgs::Entity::NONE);
break;
case ros_gz_interfaces::msg::Entity::LIGHT:
- gz_msg.set_type(ignition::msgs::Entity::LIGHT);
+ gz_msg.set_type(gz::msgs::Entity::LIGHT);
break;
case ros_gz_interfaces::msg::Entity::MODEL:
- gz_msg.set_type(ignition::msgs::Entity::MODEL);
+ gz_msg.set_type(gz::msgs::Entity::MODEL);
break;
case ros_gz_interfaces::msg::Entity::LINK:
- gz_msg.set_type(ignition::msgs::Entity::LINK);
+ gz_msg.set_type(gz::msgs::Entity::LINK);
break;
case ros_gz_interfaces::msg::Entity::VISUAL:
- gz_msg.set_type(ignition::msgs::Entity::VISUAL);
+ gz_msg.set_type(gz::msgs::Entity::VISUAL);
break;
case ros_gz_interfaces::msg::Entity::COLLISION:
- gz_msg.set_type(ignition::msgs::Entity::COLLISION);
+ gz_msg.set_type(gz::msgs::Entity::COLLISION);
break;
case ros_gz_interfaces::msg::Entity::SENSOR:
- gz_msg.set_type(ignition::msgs::Entity::SENSOR);
+ gz_msg.set_type(gz::msgs::Entity::SENSOR);
break;
case ros_gz_interfaces::msg::Entity::JOINT:
- gz_msg.set_type(ignition::msgs::Entity::JOINT);
+ gz_msg.set_type(gz::msgs::Entity::JOINT);
break;
default:
std::cerr << "Unsupported entity type [" << ros_msg.type << "]\n";
@@ -112,26 +112,26 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Entity & gz_msg,
+ const gz::msgs::Entity & gz_msg,
ros_gz_interfaces::msg::Entity & ros_msg)
{
ros_msg.id = gz_msg.id();
ros_msg.name = gz_msg.name();
- if (gz_msg.type() == ignition::msgs::Entity::Type::Entity_Type_NONE) {
+ if (gz_msg.type() == gz::msgs::Entity::Type::Entity_Type_NONE) {
ros_msg.type = ros_gz_interfaces::msg::Entity::NONE;
- } else if (gz_msg.type() == ignition::msgs::Entity::LIGHT) {
+ } else if (gz_msg.type() == gz::msgs::Entity::LIGHT) {
ros_msg.type = ros_gz_interfaces::msg::Entity::LIGHT;
- } else if (gz_msg.type() == ignition::msgs::Entity::MODEL) {
+ } else if (gz_msg.type() == gz::msgs::Entity::MODEL) {
ros_msg.type = ros_gz_interfaces::msg::Entity::MODEL;
- } else if (gz_msg.type() == ignition::msgs::Entity::LINK) {
+ } else if (gz_msg.type() == gz::msgs::Entity::LINK) {
ros_msg.type = ros_gz_interfaces::msg::Entity::LINK;
- } else if (gz_msg.type() == ignition::msgs::Entity::VISUAL) {
+ } else if (gz_msg.type() == gz::msgs::Entity::VISUAL) {
ros_msg.type = ros_gz_interfaces::msg::Entity::VISUAL;
- } else if (gz_msg.type() == ignition::msgs::Entity::COLLISION) {
+ } else if (gz_msg.type() == gz::msgs::Entity::COLLISION) {
ros_msg.type = ros_gz_interfaces::msg::Entity::COLLISION;
- } else if (gz_msg.type() == ignition::msgs::Entity::SENSOR) {
+ } else if (gz_msg.type() == gz::msgs::Entity::SENSOR) {
ros_msg.type = ros_gz_interfaces::msg::Entity::SENSOR;
- } else if (gz_msg.type() == ignition::msgs::Entity::JOINT) {
+ } else if (gz_msg.type() == gz::msgs::Entity::JOINT) {
ros_msg.type = ros_gz_interfaces::msg::Entity::JOINT;
} else {
std::cerr << "Unsupported Entity [" <<
@@ -143,7 +143,7 @@ template<>
void
convert_ros_to_gz(
const ros_gz_interfaces::msg::Contact & ros_msg,
- ignition::msgs::Contact & gz_msg)
+ gz::msgs::Contact & gz_msg)
{
convert_ros_to_gz(ros_msg.collision1, (*gz_msg.mutable_collision1()));
convert_ros_to_gz(ros_msg.collision1, (*gz_msg.mutable_collision2()));
@@ -170,7 +170,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Contact & gz_msg,
+ const gz::msgs::Contact & gz_msg,
ros_gz_interfaces::msg::Contact & ros_msg)
{
convert_gz_to_ros(gz_msg.collision1(), ros_msg.collision1);
@@ -199,7 +199,7 @@ template<>
void
convert_ros_to_gz(
const ros_gz_interfaces::msg::Contacts & ros_msg,
- ignition::msgs::Contacts & gz_msg)
+ gz::msgs::Contacts & gz_msg)
{
convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header()));
gz_msg.clear_contact();
@@ -212,7 +212,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Contacts & gz_msg,
+ const gz::msgs::Contacts & gz_msg,
ros_gz_interfaces::msg::Contacts & ros_msg)
{
convert_gz_to_ros(gz_msg.header(), ros_msg.header);
@@ -228,7 +228,7 @@ template<>
void
convert_ros_to_gz(
const ros_gz_interfaces::msg::Dataframe & ros_msg,
- ignition::msgs::Dataframe & gz_msg)
+ gz::msgs::Dataframe & gz_msg)
{
convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header()));
auto * rssiPtr = gz_msg.mutable_header()->add_data();
@@ -244,7 +244,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Dataframe & gz_msg,
+ const gz::msgs::Dataframe & gz_msg,
ros_gz_interfaces::msg::Dataframe & ros_msg)
{
convert_gz_to_ros(gz_msg.header(), ros_msg.header);
@@ -279,7 +279,7 @@ template<>
void
convert_ros_to_gz(
const ros_gz_interfaces::msg::GuiCamera & ros_msg,
- ignition::msgs::GUICamera & gz_msg)
+ gz::msgs::GUICamera & gz_msg)
{
convert_ros_to_gz(ros_msg.header, *gz_msg.mutable_header());
gz_msg.set_name(ros_msg.name);
@@ -292,7 +292,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::GUICamera & gz_msg,
+ const gz::msgs::GUICamera & gz_msg,
ros_gz_interfaces::msg::GuiCamera & ros_msg)
{
convert_gz_to_ros(gz_msg.header(), ros_msg.header);
@@ -307,18 +307,18 @@ template<>
void
convert_ros_to_gz(
const ros_gz_interfaces::msg::Light & ros_msg,
- ignition::msgs::Light & gz_msg)
+ gz::msgs::Light & gz_msg)
{
convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header()));
gz_msg.set_name(ros_msg.name);
if (ros_msg.type == 0) {
- gz_msg.set_type(ignition::msgs::Light_LightType::Light_LightType_POINT);
+ gz_msg.set_type(gz::msgs::Light_LightType::Light_LightType_POINT);
} else if (ros_msg.type == 1) {
- gz_msg.set_type(ignition::msgs::Light_LightType::Light_LightType_SPOT);
+ gz_msg.set_type(gz::msgs::Light_LightType::Light_LightType_SPOT);
} else if (ros_msg.type == 2) {
gz_msg.set_type(
- ignition::msgs::Light_LightType::Light_LightType_DIRECTIONAL);
+ gz::msgs::Light_LightType::Light_LightType_DIRECTIONAL);
}
convert_ros_to_gz(ros_msg.pose, *gz_msg.mutable_pose());
@@ -344,19 +344,19 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Light & gz_msg,
+ const gz::msgs::Light & gz_msg,
ros_gz_interfaces::msg::Light & ros_msg)
{
convert_gz_to_ros(gz_msg.header(), ros_msg.header);
ros_msg.name = gz_msg.name();
if (gz_msg.type() ==
- ignition::msgs::Light_LightType::Light_LightType_POINT)
+ gz::msgs::Light_LightType::Light_LightType_POINT)
{
ros_msg.type = 0;
- } else if (gz_msg.type() == ignition::msgs::Light_LightType::Light_LightType_SPOT) {
+ } else if (gz_msg.type() == gz::msgs::Light_LightType::Light_LightType_SPOT) {
ros_msg.type = 1;
- } else if (gz_msg.type() == ignition::msgs::Light_LightType::Light_LightType_DIRECTIONAL) {
+ } else if (gz_msg.type() == gz::msgs::Light_LightType::Light_LightType_DIRECTIONAL) {
ros_msg.type = 2;
}
@@ -384,15 +384,15 @@ template<>
void
convert_ros_to_gz(
const ros_gz_interfaces::msg::SensorNoise & ros_msg,
- ignition::msgs::SensorNoise & gz_msg)
+ gz::msgs::SensorNoise & gz_msg)
{
convert_ros_to_gz(ros_msg.header, *gz_msg.mutable_header());
if (ros_msg.type == 0) {
- gz_msg.set_type(ignition::msgs::SensorNoise_Type::SensorNoise_Type_NONE);
+ gz_msg.set_type(gz::msgs::SensorNoise_Type::SensorNoise_Type_NONE);
} else if (ros_msg.type == 2) {
- gz_msg.set_type(ignition::msgs::SensorNoise_Type::SensorNoise_Type_GAUSSIAN);
+ gz_msg.set_type(gz::msgs::SensorNoise_Type::SensorNoise_Type_GAUSSIAN);
} else if (ros_msg.type == 3) {
- gz_msg.set_type(ignition::msgs::SensorNoise_Type::SensorNoise_Type_GAUSSIAN_QUANTIZED);
+ gz_msg.set_type(gz::msgs::SensorNoise_Type::SensorNoise_Type_GAUSSIAN_QUANTIZED);
}
gz_msg.set_mean(ros_msg.mean);
@@ -406,17 +406,17 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::SensorNoise & gz_msg,
+ const gz::msgs::SensorNoise & gz_msg,
ros_gz_interfaces::msg::SensorNoise & ros_msg)
{
convert_gz_to_ros(gz_msg.header(), ros_msg.header);
- if (gz_msg.type() == ignition::msgs::SensorNoise_Type::SensorNoise_Type_NONE) {
+ if (gz_msg.type() == gz::msgs::SensorNoise_Type::SensorNoise_Type_NONE) {
ros_msg.type = 0;
- } else if (gz_msg.type() == ignition::msgs::SensorNoise_Type::SensorNoise_Type_GAUSSIAN) {
+ } else if (gz_msg.type() == gz::msgs::SensorNoise_Type::SensorNoise_Type_GAUSSIAN) {
ros_msg.type = 2;
} else if (gz_msg.type() == // NOLINT
- ignition::msgs::SensorNoise_Type::SensorNoise_Type_GAUSSIAN_QUANTIZED) // NOLINT
+ gz::msgs::SensorNoise_Type::SensorNoise_Type_GAUSSIAN_QUANTIZED) // NOLINT
{ // NOLINT
ros_msg.type = 3;
}
@@ -433,7 +433,7 @@ template<>
void
convert_ros_to_gz(
const ros_gz_interfaces::msg::StringVec & ros_msg,
- ignition::msgs::StringMsg_V & gz_msg)
+ gz::msgs::StringMsg_V & gz_msg)
{
convert_ros_to_gz(ros_msg.header, *gz_msg.mutable_header());
for (const auto & elem : ros_msg.data) {
@@ -445,7 +445,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::StringMsg_V & gz_msg,
+ const gz::msgs::StringMsg_V & gz_msg,
ros_gz_interfaces::msg::StringVec & ros_msg)
{
convert_gz_to_ros(gz_msg.header(), ros_msg.header);
@@ -458,12 +458,12 @@ template<>
void
convert_ros_to_gz(
const ros_gz_interfaces::msg::ParamVec & ros_msg,
- ignition::msgs::Param & gz_msg)
+ gz::msgs::Param & gz_msg)
{
convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header()));
for (auto param : ros_msg.params) {
- ignition::msgs::Any anyValue;
+ gz::msgs::Any anyValue;
convert_ros_to_gz(param.value, anyValue);
auto new_param = gz_msg.mutable_params();
(*new_param)[param.name] = anyValue;
@@ -473,7 +473,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Param & gz_msg,
+ const gz::msgs::Param & gz_msg,
ros_gz_interfaces::msg::ParamVec & ros_msg)
{
convert_gz_to_ros(gz_msg.header(), ros_msg.header);
@@ -502,7 +502,7 @@ template<>
void
convert_ros_to_gz(
const ros_gz_interfaces::msg::ParamVec & ros_msg,
- ignition::msgs::Param_V & gz_msg)
+ gz::msgs::Param_V & gz_msg)
{
convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header()));
@@ -519,7 +519,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Param_V & gz_msg,
+ const gz::msgs::Param_V & gz_msg,
ros_gz_interfaces::msg::ParamVec & ros_msg)
{
convert_gz_to_ros(gz_msg.header(), ros_msg.header);
@@ -542,7 +542,7 @@ template<>
void
convert_ros_to_gz(
const ros_gz_interfaces::msg::TrackVisual & ros_msg,
- ignition::msgs::TrackVisual & gz_msg)
+ gz::msgs::TrackVisual & gz_msg)
{
convert_ros_to_gz(ros_msg.header, *gz_msg.mutable_header());
gz_msg.set_name(ros_msg.name);
@@ -559,7 +559,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::TrackVisual & gz_msg,
+ const gz::msgs::TrackVisual & gz_msg,
ros_gz_interfaces::msg::TrackVisual & ros_msg)
{
convert_gz_to_ros(gz_msg.header(), ros_msg.header);
@@ -578,7 +578,7 @@ template<>
void
convert_ros_to_gz(
const ros_gz_interfaces::msg::VideoRecord & ros_msg,
- ignition::msgs::VideoRecord & gz_msg)
+ gz::msgs::VideoRecord & gz_msg)
{
convert_ros_to_gz(ros_msg.header, *gz_msg.mutable_header());
gz_msg.set_start(ros_msg.start);
@@ -590,7 +590,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::VideoRecord & gz_msg,
+ const gz::msgs::VideoRecord & gz_msg,
ros_gz_interfaces::msg::VideoRecord & ros_msg)
{
convert_gz_to_ros(gz_msg.header(), ros_msg.header);
@@ -604,7 +604,7 @@ template<>
void
convert_ros_to_gz(
const ros_gz_interfaces::msg::WorldControl & ros_msg,
- ignition::msgs::WorldControl & gz_msg)
+ gz::msgs::WorldControl & gz_msg)
{
gz_msg.set_pause(ros_msg.pause);
gz_msg.set_step(ros_msg.step);
@@ -617,7 +617,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::WorldControl & gz_msg,
+ const gz::msgs::WorldControl & gz_msg,
ros_gz_interfaces::msg::WorldControl & ros_msg)
{
ros_msg.pause = gz_msg.pause();
@@ -632,7 +632,7 @@ template<>
void
convert_ros_to_gz(
const ros_gz_interfaces::msg::WorldReset & ros_msg,
- ignition::msgs::WorldReset & gz_msg)
+ gz::msgs::WorldReset & gz_msg)
{
gz_msg.set_all(ros_msg.all);
gz_msg.set_time_only(ros_msg.time_only);
@@ -642,7 +642,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::WorldReset & gz_msg,
+ const gz::msgs::WorldReset & gz_msg,
ros_gz_interfaces::msg::WorldReset & ros_msg)
{
ros_msg.all = gz_msg.all();
@@ -654,7 +654,7 @@ template<>
void
convert_ros_to_gz(
const ros_gz_interfaces::msg::Float32Array & ros_msg,
- ignition::msgs::Float_V & gz_msg)
+ gz::msgs::Float_V & gz_msg)
{
gz_msg.clear_data();
for (auto const & t : ros_msg.data) {
@@ -665,7 +665,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Float_V & gz_msg,
+ const gz::msgs::Float_V & gz_msg,
ros_gz_interfaces::msg::Float32Array & ros_msg)
{
ros_msg.data.clear();
diff --git a/ros_gz_bridge/src/convert/ros_gz_interfaces_TEST.cpp b/ros_gz_bridge/src/convert/ros_gz_interfaces_TEST.cpp
index 160685b31..a4d0e105b 100644
--- a/ros_gz_bridge/src/convert/ros_gz_interfaces_TEST.cpp
+++ b/ros_gz_bridge/src/convert/ros_gz_interfaces_TEST.cpp
@@ -23,11 +23,11 @@ struct RosToGzTest : public ::testing::Test
using ParameterValue = rcl_interfaces::msg::ParameterValue;
using ParameterType = rcl_interfaces::msg::ParameterType;
- using Any = ignition::msgs::Any;
- using Any_ValueType = ignition::msgs::Any_ValueType;
+ using Any = gz::msgs::Any;
+ using Any_ValueType = gz::msgs::Any_ValueType;
using ParamVec = ros_gz_interfaces::msg::ParamVec;
- using Param = ignition::msgs::Param;
+ using Param = gz::msgs::Param;
Param gz_msg;
ParamVec ros_msg;
diff --git a/ros_gz_bridge/src/convert/rosgraph_msgs.cpp b/ros_gz_bridge/src/convert/rosgraph_msgs.cpp
index c6da7fc9b..26bab385d 100644
--- a/ros_gz_bridge/src/convert/rosgraph_msgs.cpp
+++ b/ros_gz_bridge/src/convert/rosgraph_msgs.cpp
@@ -23,7 +23,7 @@ namespace ros_gz_bridge
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Clock & gz_msg,
+ const gz::msgs::Clock & gz_msg,
rosgraph_msgs::msg::Clock & ros_msg)
{
ros_msg.clock = rclcpp::Time(gz_msg.sim().sec(), gz_msg.sim().nsec());
@@ -33,7 +33,7 @@ template<>
void
convert_ros_to_gz(
const rosgraph_msgs::msg::Clock & ros_msg,
- ignition::msgs::Clock & gz_msg)
+ gz::msgs::Clock & gz_msg)
{
gz_msg.mutable_sim()->set_sec(ros_msg.clock.sec);
gz_msg.mutable_sim()->set_nsec(ros_msg.clock.nanosec);
diff --git a/ros_gz_bridge/src/convert/sensor_msgs.cpp b/ros_gz_bridge/src/convert/sensor_msgs.cpp
index 2942bc675..cddc4f004 100644
--- a/ros_gz_bridge/src/convert/sensor_msgs.cpp
+++ b/ros_gz_bridge/src/convert/sensor_msgs.cpp
@@ -24,7 +24,7 @@ template<>
void
convert_ros_to_gz(
const sensor_msgs::msg::FluidPressure & ros_msg,
- ignition::msgs::FluidPressure & gz_msg)
+ gz::msgs::FluidPressure & gz_msg)
{
convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header()));
gz_msg.set_pressure(ros_msg.fluid_pressure);
@@ -34,7 +34,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::FluidPressure & gz_msg,
+ const gz::msgs::FluidPressure & gz_msg,
sensor_msgs::msg::FluidPressure & ros_msg)
{
convert_gz_to_ros(gz_msg.header(), ros_msg.header);
@@ -46,7 +46,7 @@ template<>
void
convert_ros_to_gz(
const sensor_msgs::msg::Image & ros_msg,
- ignition::msgs::Image & gz_msg)
+ gz::msgs::Image & gz_msg)
{
convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header()));
@@ -57,43 +57,43 @@ convert_ros_to_gz(
unsigned int octets_per_channel;
if (ros_msg.encoding == "mono8") {
- gz_msg.set_pixel_format_type(ignition::msgs::PixelFormatType::L_INT8);
+ gz_msg.set_pixel_format_type(gz::msgs::PixelFormatType::L_INT8);
num_channels = 1;
octets_per_channel = 1u;
} else if (ros_msg.encoding == "mono16") {
- gz_msg.set_pixel_format_type(ignition::msgs::PixelFormatType::L_INT16);
+ gz_msg.set_pixel_format_type(gz::msgs::PixelFormatType::L_INT16);
num_channels = 1;
octets_per_channel = 2u;
} else if (ros_msg.encoding == "rgb8") {
- gz_msg.set_pixel_format_type(ignition::msgs::PixelFormatType::RGB_INT8);
+ gz_msg.set_pixel_format_type(gz::msgs::PixelFormatType::RGB_INT8);
num_channels = 3;
octets_per_channel = 1u;
} else if (ros_msg.encoding == "rgba8") {
- gz_msg.set_pixel_format_type(ignition::msgs::PixelFormatType::RGBA_INT8);
+ gz_msg.set_pixel_format_type(gz::msgs::PixelFormatType::RGBA_INT8);
num_channels = 4;
octets_per_channel = 1u;
} else if (ros_msg.encoding == "bgra8") {
- gz_msg.set_pixel_format_type(ignition::msgs::PixelFormatType::BGRA_INT8);
+ gz_msg.set_pixel_format_type(gz::msgs::PixelFormatType::BGRA_INT8);
num_channels = 4;
octets_per_channel = 1u;
} else if (ros_msg.encoding == "rgb16") {
- gz_msg.set_pixel_format_type(ignition::msgs::PixelFormatType::RGB_INT16);
+ gz_msg.set_pixel_format_type(gz::msgs::PixelFormatType::RGB_INT16);
num_channels = 3;
octets_per_channel = 2u;
} else if (ros_msg.encoding == "bgr8") {
- gz_msg.set_pixel_format_type(ignition::msgs::PixelFormatType::BGR_INT8);
+ gz_msg.set_pixel_format_type(gz::msgs::PixelFormatType::BGR_INT8);
num_channels = 3;
octets_per_channel = 1u;
} else if (ros_msg.encoding == "bgr16") {
- gz_msg.set_pixel_format_type(ignition::msgs::PixelFormatType::BGR_INT16);
+ gz_msg.set_pixel_format_type(gz::msgs::PixelFormatType::BGR_INT16);
num_channels = 3;
octets_per_channel = 2u;
} else if (ros_msg.encoding == "32FC1") {
- gz_msg.set_pixel_format_type(ignition::msgs::PixelFormatType::R_FLOAT32);
+ gz_msg.set_pixel_format_type(gz::msgs::PixelFormatType::R_FLOAT32);
num_channels = 1;
octets_per_channel = 4u;
} else {
- gz_msg.set_pixel_format_type(ignition::msgs::PixelFormatType::UNKNOWN_PIXEL_FORMAT);
+ gz_msg.set_pixel_format_type(gz::msgs::PixelFormatType::UNKNOWN_PIXEL_FORMAT);
std::cerr << "Unsupported pixel format [" << ros_msg.encoding << "]" << std::endl;
return;
}
@@ -106,7 +106,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Image & gz_msg,
+ const gz::msgs::Image & gz_msg,
sensor_msgs::msg::Image & ros_msg)
{
convert_gz_to_ros(gz_msg.header(), ros_msg.header);
@@ -117,39 +117,39 @@ convert_gz_to_ros(
unsigned int num_channels;
unsigned int octets_per_channel;
- if (gz_msg.pixel_format_type() == ignition::msgs::PixelFormatType::L_INT8) {
+ if (gz_msg.pixel_format_type() == gz::msgs::PixelFormatType::L_INT8) {
ros_msg.encoding = "mono8";
num_channels = 1;
octets_per_channel = 1u;
- } else if (gz_msg.pixel_format_type() == ignition::msgs::PixelFormatType::L_INT16) {
+ } else if (gz_msg.pixel_format_type() == gz::msgs::PixelFormatType::L_INT16) {
ros_msg.encoding = "mono16";
num_channels = 1;
octets_per_channel = 2u;
- } else if (gz_msg.pixel_format_type() == ignition::msgs::PixelFormatType::RGB_INT8) {
+ } else if (gz_msg.pixel_format_type() == gz::msgs::PixelFormatType::RGB_INT8) {
ros_msg.encoding = "rgb8";
num_channels = 3;
octets_per_channel = 1u;
- } else if (gz_msg.pixel_format_type() == ignition::msgs::PixelFormatType::RGBA_INT8) {
+ } else if (gz_msg.pixel_format_type() == gz::msgs::PixelFormatType::RGBA_INT8) {
ros_msg.encoding = "rgba8";
num_channels = 4;
octets_per_channel = 1u;
- } else if (gz_msg.pixel_format_type() == ignition::msgs::PixelFormatType::BGRA_INT8) {
+ } else if (gz_msg.pixel_format_type() == gz::msgs::PixelFormatType::BGRA_INT8) {
ros_msg.encoding = "bgra8";
num_channels = 4;
octets_per_channel = 1u;
- } else if (gz_msg.pixel_format_type() == ignition::msgs::PixelFormatType::RGB_INT16) {
+ } else if (gz_msg.pixel_format_type() == gz::msgs::PixelFormatType::RGB_INT16) {
ros_msg.encoding = "rgb16";
num_channels = 3;
octets_per_channel = 2u;
- } else if (gz_msg.pixel_format_type() == ignition::msgs::PixelFormatType::BGR_INT8) {
+ } else if (gz_msg.pixel_format_type() == gz::msgs::PixelFormatType::BGR_INT8) {
ros_msg.encoding = "bgr8";
num_channels = 3;
octets_per_channel = 1u;
- } else if (gz_msg.pixel_format_type() == ignition::msgs::PixelFormatType::BGR_INT16) {
+ } else if (gz_msg.pixel_format_type() == gz::msgs::PixelFormatType::BGR_INT16) {
ros_msg.encoding = "bgr16";
num_channels = 3;
octets_per_channel = 2u;
- } else if (gz_msg.pixel_format_type() == ignition::msgs::PixelFormatType::R_FLOAT32) {
+ } else if (gz_msg.pixel_format_type() == gz::msgs::PixelFormatType::R_FLOAT32) {
ros_msg.encoding = "32FC1";
num_channels = 1;
octets_per_channel = 4u;
@@ -173,7 +173,7 @@ template<>
void
convert_ros_to_gz(
const sensor_msgs::msg::CameraInfo & ros_msg,
- ignition::msgs::CameraInfo & gz_msg)
+ gz::msgs::CameraInfo & gz_msg)
{
convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header()));
@@ -182,11 +182,11 @@ convert_ros_to_gz(
auto distortion = gz_msg.mutable_distortion();
if (ros_msg.distortion_model == "plumb_bob") {
- distortion->set_model(ignition::msgs::CameraInfo::Distortion::PLUMB_BOB);
+ distortion->set_model(gz::msgs::CameraInfo::Distortion::PLUMB_BOB);
} else if (ros_msg.distortion_model == "rational_polynomial") {
- distortion->set_model(ignition::msgs::CameraInfo::Distortion::RATIONAL_POLYNOMIAL);
+ distortion->set_model(gz::msgs::CameraInfo::Distortion::RATIONAL_POLYNOMIAL);
} else if (ros_msg.distortion_model == "equidistant") {
- distortion->set_model(ignition::msgs::CameraInfo::Distortion::EQUIDISTANT);
+ distortion->set_model(gz::msgs::CameraInfo::Distortion::EQUIDISTANT);
} else {
std::cerr << "Unsupported distortion model [" << ros_msg.distortion_model << "]" << std::endl;
}
@@ -213,7 +213,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::CameraInfo & gz_msg,
+ const gz::msgs::CameraInfo & gz_msg,
sensor_msgs::msg::CameraInfo & ros_msg)
{
convert_gz_to_ros(gz_msg.header(), ros_msg.header);
@@ -223,11 +223,11 @@ convert_gz_to_ros(
if (gz_msg.has_distortion()) {
const auto & distortion = gz_msg.distortion();
- if (distortion.model() == ignition::msgs::CameraInfo::Distortion::PLUMB_BOB) {
+ if (distortion.model() == gz::msgs::CameraInfo::Distortion::PLUMB_BOB) {
ros_msg.distortion_model = "plumb_bob";
- } else if (distortion.model() == ignition::msgs::CameraInfo::Distortion::RATIONAL_POLYNOMIAL) {
+ } else if (distortion.model() == gz::msgs::CameraInfo::Distortion::RATIONAL_POLYNOMIAL) {
ros_msg.distortion_model = "rational_polynomial";
- } else if (distortion.model() == ignition::msgs::CameraInfo::Distortion::EQUIDISTANT) {
+ } else if (distortion.model() == gz::msgs::CameraInfo::Distortion::EQUIDISTANT) {
ros_msg.distortion_model = "equidistant";
} else {
std::cerr << "Unsupported distortion model [" << distortion.model() << "]" << std::endl;
@@ -264,7 +264,7 @@ template<>
void
convert_ros_to_gz(
const sensor_msgs::msg::Imu & ros_msg,
- ignition::msgs::IMU & gz_msg)
+ gz::msgs::IMU & gz_msg)
{
convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header()));
@@ -279,7 +279,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::IMU & gz_msg,
+ const gz::msgs::IMU & gz_msg,
sensor_msgs::msg::Imu & ros_msg)
{
convert_gz_to_ros(gz_msg.header(), ros_msg.header);
@@ -294,7 +294,7 @@ template<>
void
convert_ros_to_gz(
const sensor_msgs::msg::JointState & ros_msg,
- ignition::msgs::Model & gz_msg)
+ gz::msgs::Model & gz_msg)
{
convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header()));
@@ -310,7 +310,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Model & gz_msg,
+ const gz::msgs::Model & gz_msg,
sensor_msgs::msg::JointState & ros_msg)
{
convert_gz_to_ros(gz_msg.header(), ros_msg.header);
@@ -327,7 +327,7 @@ template<>
void
convert_ros_to_gz(
const sensor_msgs::msg::Joy & ros_msg,
- ignition::msgs::Joy & gz_msg)
+ gz::msgs::Joy & gz_msg)
{
convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header()));
@@ -343,7 +343,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Joy & gz_msg,
+ const gz::msgs::Joy & gz_msg,
sensor_msgs::msg::Joy & ros_msg)
{
convert_gz_to_ros(gz_msg.header(), ros_msg.header);
@@ -361,7 +361,7 @@ template<>
void
convert_ros_to_gz(
const sensor_msgs::msg::LaserScan & ros_msg,
- ignition::msgs::LaserScan & gz_msg)
+ gz::msgs::LaserScan & gz_msg)
{
const unsigned int num_readings =
(ros_msg.angle_max - ros_msg.angle_min) / ros_msg.angle_increment;
@@ -390,7 +390,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::LaserScan & gz_msg,
+ const gz::msgs::LaserScan & gz_msg,
sensor_msgs::msg::LaserScan & ros_msg)
{
convert_gz_to_ros(gz_msg.header(), ros_msg.header);
@@ -432,7 +432,7 @@ template<>
void
convert_ros_to_gz(
const sensor_msgs::msg::MagneticField & ros_msg,
- ignition::msgs::Magnetometer & gz_msg)
+ gz::msgs::Magnetometer & gz_msg)
{
convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header()));
convert_ros_to_gz(ros_msg.magnetic_field, (*gz_msg.mutable_field_tesla()));
@@ -441,7 +441,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Magnetometer & gz_msg,
+ const gz::msgs::Magnetometer & gz_msg,
sensor_msgs::msg::MagneticField & ros_msg)
{
convert_gz_to_ros(gz_msg.header(), ros_msg.header);
@@ -454,7 +454,7 @@ template<>
void
convert_ros_to_gz(
const sensor_msgs::msg::NavSatFix & ros_msg,
- ignition::msgs::NavSat & gz_msg)
+ gz::msgs::NavSat & gz_msg)
{
convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header()));
gz_msg.set_latitude_deg(ros_msg.latitude);
@@ -471,7 +471,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::NavSat & gz_msg,
+ const gz::msgs::NavSat & gz_msg,
sensor_msgs::msg::NavSatFix & ros_msg)
{
convert_gz_to_ros(gz_msg.header(), ros_msg.header);
@@ -489,7 +489,7 @@ template<>
void
convert_ros_to_gz(
const sensor_msgs::msg::PointCloud2 & ros_msg,
- ignition::msgs::PointCloudPacked & gz_msg)
+ gz::msgs::PointCloudPacked & gz_msg)
{
convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header()));
@@ -503,35 +503,35 @@ convert_ros_to_gz(
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 = gz_msg.add_field();
+ gz::msgs::PointCloudPacked::Field * pf = gz_msg.add_field();
pf->set_name(field.name);
pf->set_count(field.count);
pf->set_offset(field.offset);
switch (field.datatype) {
default:
case sensor_msgs::msg::PointField::INT8:
- pf->set_datatype(ignition::msgs::PointCloudPacked::Field::INT8);
+ pf->set_datatype(gz::msgs::PointCloudPacked::Field::INT8);
break;
case sensor_msgs::msg::PointField::UINT8:
- pf->set_datatype(ignition::msgs::PointCloudPacked::Field::UINT8);
+ pf->set_datatype(gz::msgs::PointCloudPacked::Field::UINT8);
break;
case sensor_msgs::msg::PointField::INT16:
- pf->set_datatype(ignition::msgs::PointCloudPacked::Field::INT16);
+ pf->set_datatype(gz::msgs::PointCloudPacked::Field::INT16);
break;
case sensor_msgs::msg::PointField::UINT16:
- pf->set_datatype(ignition::msgs::PointCloudPacked::Field::UINT16);
+ pf->set_datatype(gz::msgs::PointCloudPacked::Field::UINT16);
break;
case sensor_msgs::msg::PointField::INT32:
- pf->set_datatype(ignition::msgs::PointCloudPacked::Field::INT32);
+ pf->set_datatype(gz::msgs::PointCloudPacked::Field::INT32);
break;
case sensor_msgs::msg::PointField::UINT32:
- pf->set_datatype(ignition::msgs::PointCloudPacked::Field::UINT32);
+ pf->set_datatype(gz::msgs::PointCloudPacked::Field::UINT32);
break;
case sensor_msgs::msg::PointField::FLOAT32:
- pf->set_datatype(ignition::msgs::PointCloudPacked::Field::FLOAT32);
+ pf->set_datatype(gz::msgs::PointCloudPacked::Field::FLOAT32);
break;
case sensor_msgs::msg::PointField::FLOAT64:
- pf->set_datatype(ignition::msgs::PointCloudPacked::Field::FLOAT64);
+ pf->set_datatype(gz::msgs::PointCloudPacked::Field::FLOAT64);
break;
}
}
@@ -540,7 +540,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::PointCloudPacked & gz_msg,
+ const gz::msgs::PointCloudPacked & gz_msg,
sensor_msgs::msg::PointCloud2 & ros_msg)
{
convert_gz_to_ros(gz_msg.header(), ros_msg.header);
@@ -561,28 +561,28 @@ convert_gz_to_ros(
pf.offset = gz_msg.field(i).offset();
switch (gz_msg.field(i).datatype()) {
default:
- case ignition::msgs::PointCloudPacked::Field::INT8:
+ case gz::msgs::PointCloudPacked::Field::INT8:
pf.datatype = sensor_msgs::msg::PointField::INT8;
break;
- case ignition::msgs::PointCloudPacked::Field::UINT8:
+ case gz::msgs::PointCloudPacked::Field::UINT8:
pf.datatype = sensor_msgs::msg::PointField::UINT8;
break;
- case ignition::msgs::PointCloudPacked::Field::INT16:
+ case gz::msgs::PointCloudPacked::Field::INT16:
pf.datatype = sensor_msgs::msg::PointField::INT16;
break;
- case ignition::msgs::PointCloudPacked::Field::UINT16:
+ case gz::msgs::PointCloudPacked::Field::UINT16:
pf.datatype = sensor_msgs::msg::PointField::UINT16;
break;
- case ignition::msgs::PointCloudPacked::Field::INT32:
+ case gz::msgs::PointCloudPacked::Field::INT32:
pf.datatype = sensor_msgs::msg::PointField::INT32;
break;
- case ignition::msgs::PointCloudPacked::Field::UINT32:
+ case gz::msgs::PointCloudPacked::Field::UINT32:
pf.datatype = sensor_msgs::msg::PointField::UINT32;
break;
- case ignition::msgs::PointCloudPacked::Field::FLOAT32:
+ case gz::msgs::PointCloudPacked::Field::FLOAT32:
pf.datatype = sensor_msgs::msg::PointField::FLOAT32;
break;
- case ignition::msgs::PointCloudPacked::Field::FLOAT64:
+ case gz::msgs::PointCloudPacked::Field::FLOAT64:
pf.datatype = sensor_msgs::msg::PointField::FLOAT64;
break;
}
@@ -594,7 +594,7 @@ template<>
void
convert_ros_to_gz(
const sensor_msgs::msg::BatteryState & ros_msg,
- ignition::msgs::BatteryState & gz_msg)
+ gz::msgs::BatteryState & gz_msg)
{
convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header()));
@@ -606,19 +606,19 @@ convert_ros_to_gz(
switch (ros_msg.power_supply_status) {
case sensor_msgs::msg::BatteryState::POWER_SUPPLY_STATUS_UNKNOWN:
- gz_msg.set_power_supply_status(ignition::msgs::BatteryState::UNKNOWN);
+ gz_msg.set_power_supply_status(gz::msgs::BatteryState::UNKNOWN);
break;
case sensor_msgs::msg::BatteryState::POWER_SUPPLY_STATUS_CHARGING:
- gz_msg.set_power_supply_status(ignition::msgs::BatteryState::CHARGING);
+ gz_msg.set_power_supply_status(gz::msgs::BatteryState::CHARGING);
break;
case sensor_msgs::msg::BatteryState::POWER_SUPPLY_STATUS_DISCHARGING:
- gz_msg.set_power_supply_status(ignition::msgs::BatteryState::DISCHARGING);
+ gz_msg.set_power_supply_status(gz::msgs::BatteryState::DISCHARGING);
break;
case sensor_msgs::msg::BatteryState::POWER_SUPPLY_STATUS_NOT_CHARGING:
- gz_msg.set_power_supply_status(ignition::msgs::BatteryState::NOT_CHARGING);
+ gz_msg.set_power_supply_status(gz::msgs::BatteryState::NOT_CHARGING);
break;
case sensor_msgs::msg::BatteryState::POWER_SUPPLY_STATUS_FULL:
- gz_msg.set_power_supply_status(ignition::msgs::BatteryState::FULL);
+ gz_msg.set_power_supply_status(gz::msgs::BatteryState::FULL);
break;
default:
std::cerr << "Unsupported power supply status [" << ros_msg.power_supply_status << "]\n";
@@ -628,7 +628,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::BatteryState & gz_msg,
+ const gz::msgs::BatteryState & gz_msg,
sensor_msgs::msg::BatteryState & ros_msg)
{
convert_gz_to_ros(gz_msg.header(), ros_msg.header);
@@ -640,15 +640,15 @@ convert_gz_to_ros(
ros_msg.design_capacity = std::numeric_limits::quiet_NaN();
ros_msg.percentage = gz_msg.percentage();
- if (gz_msg.power_supply_status() == ignition::msgs::BatteryState::UNKNOWN) {
+ if (gz_msg.power_supply_status() == gz::msgs::BatteryState::UNKNOWN) {
ros_msg.power_supply_status = sensor_msgs::msg::BatteryState::POWER_SUPPLY_STATUS_UNKNOWN;
- } else if (gz_msg.power_supply_status() == ignition::msgs::BatteryState::CHARGING) {
+ } else if (gz_msg.power_supply_status() == gz::msgs::BatteryState::CHARGING) {
ros_msg.power_supply_status = sensor_msgs::msg::BatteryState::POWER_SUPPLY_STATUS_CHARGING;
- } else if (gz_msg.power_supply_status() == ignition::msgs::BatteryState::DISCHARGING) {
+ } else if (gz_msg.power_supply_status() == gz::msgs::BatteryState::DISCHARGING) {
ros_msg.power_supply_status = sensor_msgs::msg::BatteryState::POWER_SUPPLY_STATUS_DISCHARGING;
- } else if (gz_msg.power_supply_status() == ignition::msgs::BatteryState::NOT_CHARGING) {
+ } else if (gz_msg.power_supply_status() == gz::msgs::BatteryState::NOT_CHARGING) {
ros_msg.power_supply_status = sensor_msgs::msg::BatteryState::POWER_SUPPLY_STATUS_NOT_CHARGING;
- } else if (gz_msg.power_supply_status() == ignition::msgs::BatteryState::FULL) {
+ } else if (gz_msg.power_supply_status() == gz::msgs::BatteryState::FULL) {
ros_msg.power_supply_status = sensor_msgs::msg::BatteryState::POWER_SUPPLY_STATUS_FULL;
} else {
std::cerr << "Unsupported power supply status [" <<
diff --git a/ros_gz_bridge/src/convert/std_msgs.cpp b/ros_gz_bridge/src/convert/std_msgs.cpp
index dcde74b32..1607bbaa3 100644
--- a/ros_gz_bridge/src/convert/std_msgs.cpp
+++ b/ros_gz_bridge/src/convert/std_msgs.cpp
@@ -23,7 +23,7 @@ template<>
void
convert_ros_to_gz(
const std_msgs::msg::Bool & ros_msg,
- ignition::msgs::Boolean & gz_msg)
+ gz::msgs::Boolean & gz_msg)
{
gz_msg.set_data(ros_msg.data);
}
@@ -31,7 +31,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Boolean & gz_msg,
+ const gz::msgs::Boolean & gz_msg,
std_msgs::msg::Bool & ros_msg)
{
ros_msg.data = gz_msg.data();
@@ -41,7 +41,7 @@ template<>
void
convert_ros_to_gz(
const std_msgs::msg::ColorRGBA & ros_msg,
- ignition::msgs::Color & gz_msg)
+ gz::msgs::Color & gz_msg)
{
gz_msg.set_r(ros_msg.r);
gz_msg.set_g(ros_msg.g);
@@ -52,7 +52,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Color & gz_msg,
+ const gz::msgs::Color & gz_msg,
std_msgs::msg::ColorRGBA & ros_msg)
{
ros_msg.r = gz_msg.r();
@@ -65,14 +65,14 @@ template<>
void
convert_ros_to_gz(
const std_msgs::msg::Empty &,
- ignition::msgs::Empty &)
+ gz::msgs::Empty &)
{
}
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Empty &,
+ const gz::msgs::Empty &,
std_msgs::msg::Empty &)
{
}
@@ -81,7 +81,7 @@ template<>
void
convert_ros_to_gz(
const std_msgs::msg::UInt32 & ros_msg,
- ignition::msgs::UInt32 & gz_msg)
+ gz::msgs::UInt32 & gz_msg)
{
gz_msg.set_data(ros_msg.data);
}
@@ -89,7 +89,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::UInt32 & gz_msg,
+ const gz::msgs::UInt32 & gz_msg,
std_msgs::msg::UInt32 & ros_msg)
{
ros_msg.data = gz_msg.data();
@@ -99,7 +99,7 @@ template<>
void
convert_ros_to_gz(
const std_msgs::msg::Float32 & ros_msg,
- ignition::msgs::Float & gz_msg)
+ gz::msgs::Float & gz_msg)
{
gz_msg.set_data(ros_msg.data);
}
@@ -107,7 +107,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Float & gz_msg,
+ const gz::msgs::Float & gz_msg,
std_msgs::msg::Float32 & ros_msg)
{
ros_msg.data = gz_msg.data();
@@ -117,7 +117,7 @@ template<>
void
convert_ros_to_gz(
const std_msgs::msg::Float64 & ros_msg,
- ignition::msgs::Double & gz_msg)
+ gz::msgs::Double & gz_msg)
{
gz_msg.set_data(ros_msg.data);
}
@@ -125,7 +125,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Double & gz_msg,
+ const gz::msgs::Double & gz_msg,
std_msgs::msg::Float64 & ros_msg)
{
ros_msg.data = gz_msg.data();
@@ -135,7 +135,7 @@ template<>
void
convert_ros_to_gz(
const std_msgs::msg::Header & ros_msg,
- ignition::msgs::Header & gz_msg)
+ gz::msgs::Header & gz_msg)
{
convert_ros_to_gz(ros_msg.stamp, *gz_msg.mutable_stamp());
auto newPair = gz_msg.add_data();
@@ -147,7 +147,7 @@ template<>
void
convert_ros_to_gz(
const std_msgs::msg::Int32 & ros_msg,
- ignition::msgs::Int32 & gz_msg)
+ gz::msgs::Int32 & gz_msg)
{
gz_msg.set_data(ros_msg.data);
}
@@ -155,7 +155,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Int32 & gz_msg,
+ const gz::msgs::Int32 & gz_msg,
std_msgs::msg::Int32 & ros_msg)
{
ros_msg.data = gz_msg.data();
@@ -164,7 +164,7 @@ convert_gz_to_ros(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Header & gz_msg,
+ const gz::msgs::Header & gz_msg,
std_msgs::msg::Header & ros_msg)
{
convert_gz_to_ros(gz_msg.stamp(), ros_msg.stamp);
@@ -180,7 +180,7 @@ template<>
void
convert_ros_to_gz(
const std_msgs::msg::String & ros_msg,
- ignition::msgs::StringMsg & gz_msg)
+ gz::msgs::StringMsg & gz_msg)
{
gz_msg.set_data(ros_msg.data);
}
@@ -188,7 +188,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::StringMsg & gz_msg,
+ const gz::msgs::StringMsg & gz_msg,
std_msgs::msg::String & ros_msg)
{
ros_msg.data = gz_msg.data();
diff --git a/ros_gz_bridge/src/convert/tf2_msgs.cpp b/ros_gz_bridge/src/convert/tf2_msgs.cpp
index 2a1b21425..b3d6f8775 100644
--- a/ros_gz_bridge/src/convert/tf2_msgs.cpp
+++ b/ros_gz_bridge/src/convert/tf2_msgs.cpp
@@ -22,7 +22,7 @@ template<>
void
convert_ros_to_gz(
const tf2_msgs::msg::TFMessage & ros_msg,
- ignition::msgs::Pose_V & gz_msg)
+ gz::msgs::Pose_V & gz_msg)
{
gz_msg.clear_pose();
for (auto const & t : ros_msg.transforms) {
@@ -40,7 +40,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Pose_V & gz_msg,
+ const gz::msgs::Pose_V & gz_msg,
tf2_msgs::msg::TFMessage & ros_msg)
{
ros_msg.transforms.clear();
diff --git a/ros_gz_bridge/src/convert/trajectory_msgs.cpp b/ros_gz_bridge/src/convert/trajectory_msgs.cpp
index db877c2ec..270309c77 100644
--- a/ros_gz_bridge/src/convert/trajectory_msgs.cpp
+++ b/ros_gz_bridge/src/convert/trajectory_msgs.cpp
@@ -24,7 +24,7 @@ template<>
void
convert_ros_to_gz(
const trajectory_msgs::msg::JointTrajectoryPoint & ros_msg,
- ignition::msgs::JointTrajectoryPoint & gz_msg)
+ gz::msgs::JointTrajectoryPoint & gz_msg)
{
for (const auto & ros_position : ros_msg.positions) {
gz_msg.add_positions(ros_position);
@@ -39,7 +39,7 @@ convert_ros_to_gz(
gz_msg.add_effort(ros_effort);
}
- ignition::msgs::Duration * gz_duration = gz_msg.mutable_time_from_start();
+ gz::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);
}
@@ -47,7 +47,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::JointTrajectoryPoint & gz_msg,
+ const gz::msgs::JointTrajectoryPoint & gz_msg,
trajectory_msgs::msg::JointTrajectoryPoint & ros_msg)
{
for (auto i = 0; i < gz_msg.positions_size(); ++i) {
@@ -72,7 +72,7 @@ template<>
void
convert_ros_to_gz(
const trajectory_msgs::msg::JointTrajectory & ros_msg,
- ignition::msgs::JointTrajectory & gz_msg)
+ gz::msgs::JointTrajectory & gz_msg)
{
convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header()));
@@ -81,7 +81,7 @@ convert_ros_to_gz(
}
for (const auto & ros_point : ros_msg.points) {
- ignition::msgs::JointTrajectoryPoint * gz_point = gz_msg.add_points();
+ gz::msgs::JointTrajectoryPoint * gz_point = gz_msg.add_points();
convert_ros_to_gz(ros_point, (*gz_point));
}
}
@@ -89,7 +89,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::JointTrajectory & gz_msg,
+ const gz::msgs::JointTrajectory & gz_msg,
trajectory_msgs::msg::JointTrajectory & ros_msg)
{
convert_gz_to_ros(gz_msg.header(), ros_msg.header);
diff --git a/ros_gz_bridge/src/convert/vision_msgs.cpp b/ros_gz_bridge/src/convert/vision_msgs.cpp
index 86a562a32..057426c77 100644
--- a/ros_gz_bridge/src/convert/vision_msgs.cpp
+++ b/ros_gz_bridge/src/convert/vision_msgs.cpp
@@ -23,13 +23,13 @@ template<>
void
convert_ros_to_gz(
const vision_msgs::msg::Detection2D & ros_msg,
- ignition::msgs::AnnotatedAxisAligned2DBox & gz_msg)
+ gz::msgs::AnnotatedAxisAligned2DBox & gz_msg)
{
convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header()));
- ignition::msgs::AxisAligned2DBox * box = new ignition::msgs::AxisAligned2DBox();
- ignition::msgs::Vector2d * min_corner = new ignition::msgs::Vector2d();
- ignition::msgs::Vector2d * max_corner = new ignition::msgs::Vector2d();
+ gz::msgs::AxisAligned2DBox * box = new gz::msgs::AxisAligned2DBox();
+ gz::msgs::Vector2d * min_corner = new gz::msgs::Vector2d();
+ gz::msgs::Vector2d * max_corner = new gz::msgs::Vector2d();
if (ros_msg.results.size() != 0) {
auto id = ros_msg.results.at(0).hypothesis.class_id;
@@ -48,7 +48,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::AnnotatedAxisAligned2DBox & gz_msg,
+ const gz::msgs::AnnotatedAxisAligned2DBox & gz_msg,
vision_msgs::msg::Detection2D & ros_msg)
{
convert_gz_to_ros(gz_msg.header(), ros_msg.header);
@@ -71,11 +71,11 @@ template<>
void
convert_ros_to_gz(
const vision_msgs::msg::Detection2DArray & ros_msg,
- ignition::msgs::AnnotatedAxisAligned2DBox_V & gz_msg)
+ gz::msgs::AnnotatedAxisAligned2DBox_V & gz_msg)
{
convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header()));
for (const auto & ros_box : ros_msg.detections) {
- ignition::msgs::AnnotatedAxisAligned2DBox * gz_box = gz_msg.add_annotated_box();
+ gz::msgs::AnnotatedAxisAligned2DBox * gz_box = gz_msg.add_annotated_box();
convert_ros_to_gz(ros_box, *gz_box);
}
}
@@ -83,7 +83,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::AnnotatedAxisAligned2DBox_V & gz_msg,
+ const gz::msgs::AnnotatedAxisAligned2DBox_V & gz_msg,
vision_msgs::msg::Detection2DArray & ros_msg)
{
convert_gz_to_ros(gz_msg.header(), ros_msg.header);
diff --git a/ros_gz_bridge/src/factory.hpp b/ros_gz_bridge/src/factory.hpp
index 607d97617..35daf4162 100644
--- a/ros_gz_bridge/src/factory.hpp
+++ b/ros_gz_bridge/src/factory.hpp
@@ -19,7 +19,7 @@
#include
#include
-#include
+#include
// include ROS 2
#include
@@ -65,9 +65,9 @@ class Factory : public FactoryInterface
return publisher;
}
- ignition::transport::Node::Publisher
+ gz::transport::Node::Publisher
create_gz_publisher(
- std::shared_ptr gz_node,
+ std::shared_ptr gz_node,
const std::string & topic_name,
size_t /*queue_size*/)
{
@@ -79,7 +79,7 @@ class Factory : public FactoryInterface
rclcpp::Node::SharedPtr ros_node,
const std::string & topic_name,
size_t queue_size,
- ignition::transport::Node::Publisher & gz_pub)
+ gz::transport::Node::Publisher & gz_pub)
{
std::function)> fn = std::bind(
&Factory::ros_callback,
@@ -100,15 +100,15 @@ class Factory : public FactoryInterface
void
create_gz_subscriber(
- std::shared_ptr node,
+ std::shared_ptr node,
const std::string & topic_name,
size_t /*queue_size*/,
rclcpp::PublisherBase::SharedPtr ros_pub)
{
std::function subCb =
+ const gz::transport::MessageInfo &)> subCb =
[this, ros_pub](const GZ_T & _msg,
- const ignition::transport::MessageInfo & _info)
+ const gz::transport::MessageInfo & _info)
{
// Ignore messages that are published from this bridge.
if (!_info.IntraProcess()) {
@@ -123,7 +123,7 @@ class Factory : public FactoryInterface
static
void ros_callback(
std::shared_ptr ros_msg,
- ignition::transport::Node::Publisher & gz_pub,
+ gz::transport::Node::Publisher & gz_pub,
const std::string & ros_type_name,
const std::string & gz_type_name,
rclcpp::Node::SharedPtr ros_node)
diff --git a/ros_gz_bridge/src/factory_interface.hpp b/ros_gz_bridge/src/factory_interface.hpp
index 181a191f5..b760bcd87 100644
--- a/ros_gz_bridge/src/factory_interface.hpp
+++ b/ros_gz_bridge/src/factory_interface.hpp
@@ -19,7 +19,7 @@
#include
// include Gazebo Transport
-#include
+#include
// include ROS 2
#include
@@ -40,9 +40,9 @@ class FactoryInterface
size_t queue_size) = 0;
virtual
- ignition::transport::Node::Publisher
+ gz::transport::Node::Publisher
create_gz_publisher(
- std::shared_ptr gz_node,
+ std::shared_ptr gz_node,
const std::string & topic_name,
size_t queue_size) = 0;
@@ -52,12 +52,12 @@ class FactoryInterface
rclcpp::Node::SharedPtr ros_node,
const std::string & topic_name,
size_t queue_size,
- ignition::transport::Node::Publisher & gz_pub) = 0;
+ gz::transport::Node::Publisher & gz_pub) = 0;
virtual
void
create_gz_subscriber(
- std::shared_ptr node,
+ std::shared_ptr node,
const std::string & topic_name,
size_t queue_size,
rclcpp::PublisherBase::SharedPtr ros_pub) = 0;
diff --git a/ros_gz_bridge/src/ros_gz_bridge.cpp b/ros_gz_bridge/src/ros_gz_bridge.cpp
index 423a2d3a2..f542ee90c 100644
--- a/ros_gz_bridge/src/ros_gz_bridge.cpp
+++ b/ros_gz_bridge/src/ros_gz_bridge.cpp
@@ -26,7 +26,7 @@ namespace ros_gz_bridge
RosGzBridge::RosGzBridge(const rclcpp::NodeOptions & options)
: rclcpp::Node("ros_gz_bridge", options)
{
- gz_node_ = std::make_shared();
+ gz_node_ = std::make_shared();
this->declare_parameter("subscription_heartbeat", 1000);
this->declare_parameter("config_file", "");
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 d5b464de7..17fb52898 100644
--- a/ros_gz_bridge/src/service_factories/ros_gz_interfaces.cpp
+++ b/ros_gz_bridge/src/service_factories/ros_gz_interfaces.cpp
@@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-#include
-#include
+#include
+#include
#include
#include
@@ -41,8 +41,8 @@ get_service_factory__ros_gz_interfaces(
return std::make_shared<
ServiceFactory<
ros_gz_interfaces::srv::ControlWorld,
- ignition::msgs::WorldControl,
- ignition::msgs::Boolean>
+ gz::msgs::WorldControl,
+ gz::msgs::Boolean>
>(ros_type_name, "ignition.msgs.WorldControl", "ignition.msgs.Boolean");
}
@@ -53,7 +53,7 @@ template<>
void
convert_ros_to_gz(
const ros_gz_interfaces::srv::ControlWorld::Request & ros_req,
- ignition::msgs::WorldControl & gz_req)
+ gz::msgs::WorldControl & gz_req)
{
convert_ros_to_gz(ros_req.world_control, gz_req);
}
@@ -61,7 +61,7 @@ convert_ros_to_gz(
template<>
void
convert_gz_to_ros(
- const ignition::msgs::Boolean & gz_rep,
+ const gz::msgs::Boolean & gz_rep,
ros_gz_interfaces::srv::ControlWorld::Response & ros_res)
{
ros_res.success = gz_rep.data();
diff --git a/ros_gz_bridge/src/service_factory.hpp b/ros_gz_bridge/src/service_factory.hpp
index d4a44d74a..f771d6180 100644
--- a/ros_gz_bridge/src/service_factory.hpp
+++ b/ros_gz_bridge/src/service_factory.hpp
@@ -20,7 +20,7 @@
#include
#include
-#include
+#include
#include
@@ -50,7 +50,7 @@ class ServiceFactory : public ServiceFactoryInterface
rclcpp::ServiceBase::SharedPtr
create_ros_service(
rclcpp::Node::SharedPtr ros_node,
- std::shared_ptr gz_node,
+ std::shared_ptr gz_node,
const std::string & service_name) override
{
return ros_node->create_service(
diff --git a/ros_gz_bridge/src/service_factory_interface.hpp b/ros_gz_bridge/src/service_factory_interface.hpp
index 4905994ef..9d4f73348 100644
--- a/ros_gz_bridge/src/service_factory_interface.hpp
+++ b/ros_gz_bridge/src/service_factory_interface.hpp
@@ -18,7 +18,7 @@
#include
#include
-#include
+#include
#include
#include
@@ -33,7 +33,7 @@ class ServiceFactoryInterface
rclcpp::ServiceBase::SharedPtr
create_ros_service(
rclcpp::Node::SharedPtr ros_node,
- std::shared_ptr gz_node,
+ std::shared_ptr gz_node,
const std::string & service_name) = 0;
};
diff --git a/ros_gz_bridge/test/resource/gz_publisher.cpp.em b/ros_gz_bridge/test/resource/gz_publisher.cpp.em
index 25bc59f45..9cccbfe0f 100644
--- a/ros_gz_bridge/test/resource/gz_publisher.cpp.em
+++ b/ros_gz_bridge/test/resource/gz_publisher.cpp.em
@@ -14,8 +14,8 @@
// This file is generated from test/resource/gz_publisher.cpp.em
-#include
-#include
+#include
+#include
#include
#include
@@ -50,7 +50,7 @@ int main(int /*argc*/, char **/*argv*/)
std::signal(SIGTERM, signal_handler);
// Create a transport node and advertise a topic.
- ignition::transport::Node node;
+ gz::transport::Node node;
@[for m in mappings]@
// @(m.gz_string()).
diff --git a/ros_gz_bridge/test/resource/gz_subscriber.cpp.em b/ros_gz_bridge/test/resource/gz_subscriber.cpp.em
index 9c55f3de4..6edae074c 100644
--- a/ros_gz_bridge/test/resource/gz_subscriber.cpp.em
+++ b/ros_gz_bridge/test/resource/gz_subscriber.cpp.em
@@ -14,7 +14,7 @@
#include
-#include
+#include
#include
#include
@@ -47,7 +47,7 @@ public: void Cb(const GZ_T & _msg)
public: bool callbackExecuted = false;
/// \brief Transport node;
-private: ignition::transport::Node node;
+private: gz::transport::Node node;
};
@[for m in mappings]@
diff --git a/ros_gz_bridge/test/serverclient/gz_server.cpp b/ros_gz_bridge/test/serverclient/gz_server.cpp
index c8f10e3ed..10fa33444 100644
--- a/ros_gz_bridge/test/serverclient/gz_server.cpp
+++ b/ros_gz_bridge/test/serverclient/gz_server.cpp
@@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-#include
-#include
+#include
+#include
#include
#include
@@ -21,7 +21,7 @@
#include
#include
-#include
+#include
#include "utils/test_utils.hpp"
#include "utils/gz_test_msg.hpp"
@@ -42,8 +42,8 @@ void signal_handler(int _signal)
//////////////////////////////////////////////////
bool control_world(
- const ignition::msgs::WorldControl &,
- ignition::msgs::Boolean & _res)
+ const gz::msgs::WorldControl &,
+ gz::msgs::Boolean & _res)
{
_res.set_data(true);
return true;
@@ -58,7 +58,7 @@ int main(int /*argc*/, char **/*argv*/)
std::signal(SIGTERM, signal_handler);
// Create a transport node and advertise a topic.
- ignition::transport::Node node;
+ gz::transport::Node node;
// gz::msgs::WorldControl.
node.Advertise(
diff --git a/ros_gz_bridge/test/utils/gz_test_msg.cpp b/ros_gz_bridge/test/utils/gz_test_msg.cpp
index f824b847b..52d076ab6 100644
--- a/ros_gz_bridge/test/utils/gz_test_msg.cpp
+++ b/ros_gz_bridge/test/utils/gz_test_msg.cpp
@@ -24,35 +24,35 @@ namespace ros_gz_bridge
namespace testing
{
-void createTestMsg(ignition::msgs::Any & _msg)
+void createTestMsg(gz::msgs::Any & _msg)
{
- _msg.set_type(ignition::msgs::Any_ValueType::Any_ValueType_STRING);
+ _msg.set_type(gz::msgs::Any_ValueType::Any_ValueType_STRING);
_msg.set_string_value("foobar");
}
-void compareTestMsg(const std::shared_ptr & _msg)
+void compareTestMsg(const std::shared_ptr & _msg)
{
- ignition::msgs::Any expected_msg;
+ gz::msgs::Any expected_msg;
createTestMsg(expected_msg);
EXPECT_EQ(expected_msg.type(), _msg->type());
EXPECT_EQ(expected_msg.string_value(), _msg->string_value());
}
-void createTestMsg(ignition::msgs::Boolean & _msg)
+void createTestMsg(gz::msgs::Boolean & _msg)
{
_msg.set_data(true);
}
-void compareTestMsg(const std::shared_ptr & _msg)
+void compareTestMsg(const std::shared_ptr & _msg)
{
- ignition::msgs::Boolean expected_msg;
+ gz::msgs::Boolean expected_msg;
createTestMsg(expected_msg);
EXPECT_EQ(expected_msg.data(), _msg->data());
}
-void createTestMsg(ignition::msgs::Color & _msg)
+void createTestMsg(gz::msgs::Color & _msg)
{
_msg.set_r(0.2);
_msg.set_g(0.4);
@@ -60,9 +60,9 @@ void createTestMsg(ignition::msgs::Color & _msg)
_msg.set_a(0.8);
}
-void compareTestMsg(const std::shared_ptr & _msg)
+void compareTestMsg(const std::shared_ptr & _msg)
{
- ignition::msgs::Color expected_msg;
+ gz::msgs::Color expected_msg;
createTestMsg(expected_msg);
EXPECT_EQ(expected_msg.r(), _msg->r());
@@ -71,37 +71,37 @@ void compareTestMsg(const std::shared_ptr & _msg)
EXPECT_EQ(expected_msg.a(), _msg->a());
}
-void createTestMsg(ignition::msgs::Empty &)
+void createTestMsg(gz::msgs::Empty &)
{
}
-void compareTestMsg(const std::shared_ptr &)
+void compareTestMsg(const std::shared_ptr &)
{
}
-void createTestMsg(ignition::msgs::Float & _msg)
+void createTestMsg(gz::msgs::Float & _msg)
{
_msg.set_data(1.5);
}
-void compareTestMsg(const std::shared_ptr & _msg)
+void compareTestMsg(const std::shared_ptr & _msg)
{
- ignition::msgs::Float expected_msg;
+ gz::msgs::Float expected_msg;
createTestMsg(expected_msg);
EXPECT_FLOAT_EQ(expected_msg.data(), _msg->data());
}
-void createTestMsg(ignition::msgs::Float_V & _msg)
+void createTestMsg(gz::msgs::Float_V & _msg)
{
- ignition::msgs::Float msg;
+ gz::msgs::Float msg;
createTestMsg(msg);
_msg.add_data(msg.data());
}
-void compareTestMsg(const std::shared_ptr & _msg)
+void compareTestMsg(const std::shared_ptr & _msg)
{
- ignition::msgs::Float_V expected_msg;
+ gz::msgs::Float_V expected_msg;
createTestMsg(expected_msg);
EXPECT_EQ(expected_msg.data().size(), _msg->data().size());
@@ -109,46 +109,46 @@ void compareTestMsg(const std::shared_ptr & _msg)
EXPECT_FLOAT_EQ(expected_msg.data()[0], _msg->data()[0]);
}
-void createTestMsg(ignition::msgs::Double & _msg)
+void createTestMsg(gz::msgs::Double & _msg)
{
_msg.set_data(1.5);
}
-void compareTestMsg(const std::shared_ptr & _msg)
+void compareTestMsg(const std::shared_ptr & _msg)
{
- ignition::msgs::Double expected_msg;
+ gz::msgs::Double expected_msg;
createTestMsg(expected_msg);
EXPECT_DOUBLE_EQ(expected_msg.data(), _msg->data());
}
-void createTestMsg(ignition::msgs::Int32 & _msg)
+void createTestMsg(gz::msgs::Int32 & _msg)
{
_msg.set_data(-10);
}
-void compareTestMsg(const std::shared_ptr & _msg)
+void compareTestMsg(const std::shared_ptr & _msg)
{
- ignition::msgs::Int32 expected_msg;
+ gz::msgs::Int32 expected_msg;
createTestMsg(expected_msg);
EXPECT_DOUBLE_EQ(expected_msg.data(), _msg->data());
}
-void createTestMsg(ignition::msgs::UInt32 & _msg)
+void createTestMsg(gz::msgs::UInt32 & _msg)
{
_msg.set_data(1);
}
-void compareTestMsg(const std::shared_ptr & _msg)
+void compareTestMsg(const std::shared_ptr