diff --git a/ros_gz/CHANGELOG.rst b/ros_gz/CHANGELOG.rst
index 9effb7fc..1354e9c3 100644
--- a/ros_gz/CHANGELOG.rst
+++ b/ros_gz/CHANGELOG.rst
@@ -2,6 +2,9 @@
Changelog for package ros_gz
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+2.1.3 (2025-01-14)
+------------------
+
2.1.2 (2024-10-31)
------------------
diff --git a/ros_gz/package.xml b/ros_gz/package.xml
index 585a4754..0bf0d67b 100644
--- a/ros_gz/package.xml
+++ b/ros_gz/package.xml
@@ -4,7 +4,7 @@
ros_gz
- 2.1.2
+ 2.1.3
Meta-package containing interfaces for using ROS 2 with Gazebo simulation.
Aditya Pande
Alejandro Hernandez
diff --git a/ros_gz_bridge/CHANGELOG.rst b/ros_gz_bridge/CHANGELOG.rst
index 81ce3d08..177c228e 100644
--- a/ros_gz_bridge/CHANGELOG.rst
+++ b/ros_gz_bridge/CHANGELOG.rst
@@ -2,6 +2,35 @@
Changelog for package ros_gz_bridge
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+2.1.3 (2025-01-14)
+------------------
+* Use both ROS package and message name for unique mappings (`#656 `_)
+ Co-authored-by: Addisu Z. Taddese
+* Merge pull request `#664 `_ from azeey/improve_parameter_handling
+ Co-authored-by: Alejandro Hernández Cordero
+* Merge pull request `#663 `_ from azeey/improve_arg_parsing
+ The `RosGzBridge` and `GzServer` now support different spellings for
+ boolean arguments (`True`, `true`). This also simplifies how
+ conditionals are used to create composable nodes by evaluating the
+ conditionals and using them as regular Python booleans instead of
+ relying on `PythonExpression`. It was actually the `PythonExpression`
+ that was preventing support of boolean arguments spelled `true`/`false`.
+* Improve parameter handling for RosGzBridge
+* Fix linter errors
+* Improve argument parsing in Actions
+ The `RosGzBridge` and `GzServer` now support different spellings for
+ boolean arguments (`True`, `true`). This also simplifies how
+ conditionals are used to create composable nodes by evaluating the
+ conditionals and using them as regular Python booleans instead of
+ relying on `PythonExpression`. It was actually the `PythonExpression`
+ that was preventing support of boolean arguments spelled `true`/`false`.
+* Fix use_respawn argument causing errors (`#651 `_)
+* Add a way to pass extra parameters to ros_gz_bridge (`#628 `_)
+ * Add bridge_params argument to ros_gz_bridge
+ Co-authored-by: Alejandro Hernández Cordero
+ Co-authored-by: Wiktor Bajor <69388767+Wiktor-99@users.noreply.github.com>
+* Contributors: Aarav Gupta, Addisu Z. Taddese, Alejandro Hernández Cordero, Øystein Sture
+
2.1.2 (2024-10-31)
------------------
diff --git a/ros_gz_bridge/package.xml b/ros_gz_bridge/package.xml
index b43b0cd7..a695e6e6 100644
--- a/ros_gz_bridge/package.xml
+++ b/ros_gz_bridge/package.xml
@@ -2,7 +2,7 @@
ros_gz_bridge
- 2.1.2
+ 2.1.3
Bridge communication between ROS and Gazebo Transport
Aditya Pande
Alejandro Hernandez
diff --git a/ros_gz_bridge/ros_gz_bridge/__init__.py b/ros_gz_bridge/ros_gz_bridge/__init__.py
index f6ea05ee..31640eaa 100644
--- a/ros_gz_bridge/ros_gz_bridge/__init__.py
+++ b/ros_gz_bridge/ros_gz_bridge/__init__.py
@@ -59,7 +59,8 @@ def gz_type(self):
return f'gz::msgs::{self.gz_message_name}'
def unique(self):
- return f'{self.gz_message_name.lower()}_{self.ros2_message_name.lower()}'
+ return f'{self.gz_message_name.lower()}_' \
+ f'{self.ros2_package_name}_{self.ros2_message_name.lower()}'
def mappings(gz_msgs_ver):
diff --git a/ros_gz_image/CHANGELOG.rst b/ros_gz_image/CHANGELOG.rst
index 1504e16c..efdba8f9 100644
--- a/ros_gz_image/CHANGELOG.rst
+++ b/ros_gz_image/CHANGELOG.rst
@@ -2,6 +2,9 @@
Changelog for package ros1_ign_image
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+2.1.3 (2025-01-14)
+------------------
+
2.1.2 (2024-10-31)
------------------
diff --git a/ros_gz_image/package.xml b/ros_gz_image/package.xml
index e6961941..1ab51cac 100644
--- a/ros_gz_image/package.xml
+++ b/ros_gz_image/package.xml
@@ -1,6 +1,6 @@
ros_gz_image
- 2.1.2
+ 2.1.3
Image utilities for Gazebo simulation with ROS.
Apache 2.0
Aditya Pande
diff --git a/ros_gz_interfaces/CHANGELOG.rst b/ros_gz_interfaces/CHANGELOG.rst
index db0253ff..cd44d222 100644
--- a/ros_gz_interfaces/CHANGELOG.rst
+++ b/ros_gz_interfaces/CHANGELOG.rst
@@ -2,6 +2,9 @@
Changelog for package ros_gz_interfaces
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+2.1.3 (2025-01-14)
+------------------
+
2.1.2 (2024-10-31)
------------------
diff --git a/ros_gz_interfaces/package.xml b/ros_gz_interfaces/package.xml
index c6aeb753..ff1dd782 100644
--- a/ros_gz_interfaces/package.xml
+++ b/ros_gz_interfaces/package.xml
@@ -1,6 +1,6 @@
ros_gz_interfaces
- 2.1.2
+ 2.1.3
Message and service data structures for interacting with Gazebo from ROS2.
Apache 2.0
Louise Poubel
diff --git a/ros_gz_sim/CHANGELOG.rst b/ros_gz_sim/CHANGELOG.rst
index 4ad7fd41..88314c4d 100644
--- a/ros_gz_sim/CHANGELOG.rst
+++ b/ros_gz_sim/CHANGELOG.rst
@@ -2,6 +2,34 @@
Changelog for package ros_gz_sim
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+2.1.3 (2025-01-14)
+------------------
+* Shutdown explicitly while existing (`#623 `_)
+* Merge pull request `#663 `_ from azeey/improve_arg_parsing
+ The `RosGzBridge` and `GzServer` now support different spellings for
+ boolean arguments (`True`, `true`). This also simplifies how
+ conditionals are used to create composable nodes by evaluating the
+ conditionals and using them as regular Python booleans instead of
+ relying on `PythonExpression`. It was actually the `PythonExpression`
+ that was preventing support of boolean arguments spelled `true`/`false`.
+* Fix linter errors
+* Improve argument parsing in Actions
+ The `RosGzBridge` and `GzServer` now support different spellings for
+ boolean arguments (`True`, `true`). This also simplifies how
+ conditionals are used to create composable nodes by evaluating the
+ conditionals and using them as regular Python booleans instead of
+ relying on `PythonExpression`. It was actually the `PythonExpression`
+ that was preventing support of boolean arguments spelled `true`/`false`.
+* Set env path (`#659 `_)
+* Use member variables instead. (`#653 `_)
+* Move gzserver logic to its action (`#646 `_)
+* Add a way to pass extra parameters to ros_gz_bridge (`#628 `_)
+ * Add bridge_params argument to ros_gz_bridge
+ Co-authored-by: Alejandro Hernández Cordero
+ Co-authored-by: Wiktor Bajor <69388767+Wiktor-99@users.noreply.github.com>
+* Add remove entity node (`#629 `_)
+* Contributors: Aarav Gupta, Addisu Z. Taddese, Alejandro Hernández Cordero, Carlos Agüero, ChenYing Kuo (CY), Tatsuro Sakaguchi, Wiktor Bajor
+
2.1.2 (2024-10-31)
------------------
* Create ros_gz_spawn_model.launch (`#604 `_)
diff --git a/ros_gz_sim/CMakeLists.txt b/ros_gz_sim/CMakeLists.txt
index dc8deb03..34f34454 100644
--- a/ros_gz_sim/CMakeLists.txt
+++ b/ros_gz_sim/CMakeLists.txt
@@ -93,6 +93,11 @@ rclcpp_components_register_node(
EXECUTABLE gzserver
)
+target_include_directories(gzserver_component PUBLIC
+ $
+ $
+)
+
configure_file(
launch/gz_sim.launch.py.in
launch/gz_sim.launch.py.configured
diff --git a/ros_gz_sim/include/ros_gz_sim/gzserver.hpp b/ros_gz_sim/include/ros_gz_sim/gzserver.hpp
new file mode 100644
index 00000000..ac6ded0d
--- /dev/null
+++ b/ros_gz_sim/include/ros_gz_sim/gzserver.hpp
@@ -0,0 +1,45 @@
+// Copyright 2025 Open Source Robotics Foundation
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#ifndef ROS_GZ_SIM__GZSERVER_HPP_
+#define ROS_GZ_SIM__GZSERVER_HPP_
+
+#include
+#include
+
+// ROS node that executes a gz-sim Server given a world SDF file or string.
+namespace ros_gz_sim
+{
+class GzServer : public rclcpp::Node
+{
+public:
+ // Class constructor.
+ explicit GzServer(const rclcpp::NodeOptions & options);
+
+public:
+ // Class destructor.
+ ~GzServer();
+
+public:
+ /// \brief Run the gz sim server.
+ void OnStart();
+
+private:
+ /// \internal
+ /// \brief Private data pointer.
+ GZ_UTILS_UNIQUE_IMPL_PTR(dataPtr)
+};
+} // namespace ros_gz_sim
+
+#endif // ROS_GZ_SIM__GZSERVER_HPP_
diff --git a/ros_gz_sim/package.xml b/ros_gz_sim/package.xml
index 14be978f..a1f4f9f1 100644
--- a/ros_gz_sim/package.xml
+++ b/ros_gz_sim/package.xml
@@ -2,7 +2,7 @@
ros_gz_sim
- 2.1.2
+ 2.1.3
Tools for using Gazebo Sim simulation with ROS.
Alejandro Hernandez
Aditya Pande
diff --git a/ros_gz_sim/src/gzserver.cpp b/ros_gz_sim/src/gzserver.cpp
index aa4361f5..d485971b 100644
--- a/ros_gz_sim/src/gzserver.cpp
+++ b/ros_gz_sim/src/gzserver.cpp
@@ -12,6 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.
+#include "ros_gz_sim/gzserver.hpp"
+
#include
#include
#include
@@ -21,60 +23,57 @@
#include
#include
-// ROS node that executes a gz-sim Server given a world SDF file or string.
+
namespace ros_gz_sim
{
-class GzServer : public rclcpp::Node
+
+class GzServer::Implementation
{
-public:
- // Class constructor.
- explicit GzServer(const rclcpp::NodeOptions & options)
- : Node("gzserver", options)
- {
- thread_ = std::thread(std::bind(&GzServer::OnStart, this));
- }
+ /// \brief We don't want to block the ROS thread.
public:
- // Class destructor.
- ~GzServer()
- {
- // Make sure to join the thread on shutdown.
- if (thread_.joinable()) {
- thread_.join();
- }
- }
+ std::thread thread;
+};
-public:
- /// \brief Run the gz sim server.
- void OnStart()
- {
- auto world_sdf_file = this->declare_parameter("world_sdf_file", "");
- auto world_sdf_string = this->declare_parameter("world_sdf_string", "");
+GzServer::GzServer(const rclcpp::NodeOptions & options)
+: Node("gzserver", options), dataPtr(gz::utils::MakeUniqueImpl())
+{
+ this->dataPtr->thread = std::thread(std::bind(&GzServer::OnStart, this));
+}
+
+GzServer::~GzServer()
+{
+ // Make sure to join the thread on shutdown.
+ if (this->dataPtr->thread.joinable()) {
+ this->dataPtr->thread.join();
+ }
+}
- gz::common::Console::SetVerbosity(4);
- gz::sim::ServerConfig server_config;
+void GzServer::OnStart()
+{
+ auto world_sdf_file = this->declare_parameter("world_sdf_file", "");
+ auto world_sdf_string = this->declare_parameter("world_sdf_string", "");
- if (!world_sdf_file.empty()) {
- server_config.SetSdfFile(world_sdf_file);
- } else if (!world_sdf_string.empty()) {
- server_config.SetSdfString(world_sdf_string);
- } else {
- RCLCPP_ERROR(
- this->get_logger(),
- "Must specify either 'world_sdf_file' or 'world_sdf_string'");
- rclcpp::shutdown();
- return;
- }
+ gz::common::Console::SetVerbosity(4);
+ gz::sim::ServerConfig server_config;
- gz::sim::Server server(server_config);
- server.Run(true /*blocking*/, 0, false /*paused*/);
+ if (!world_sdf_file.empty()) {
+ server_config.SetSdfFile(world_sdf_file);
+ } else if (!world_sdf_string.empty()) {
+ server_config.SetSdfString(world_sdf_string);
+ } else {
+ RCLCPP_ERROR(
+ this->get_logger(),
+ "Must specify either 'world_sdf_file' or 'world_sdf_string'");
rclcpp::shutdown();
+ return;
}
-private:
- /// \brief We don't want to block the ROS thread.
- std::thread thread_;
-};
+ gz::sim::Server server(server_config);
+ server.Run(true /*blocking*/, 0, false /*paused*/);
+ rclcpp::shutdown();
+}
+
} // namespace ros_gz_sim
RCLCPP_COMPONENTS_REGISTER_NODE(ros_gz_sim::GzServer)
diff --git a/ros_gz_sim_demos/CHANGELOG.rst b/ros_gz_sim_demos/CHANGELOG.rst
index 89dc117c..ec77329c 100644
--- a/ros_gz_sim_demos/CHANGELOG.rst
+++ b/ros_gz_sim_demos/CHANGELOG.rst
@@ -2,6 +2,33 @@
Changelog for package ros1_gz_sim_demos
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+2.1.3 (2025-01-14)
+------------------
+* Refactor triggered_camera demo (`#645 `_)
+ Co-authored-by: Alejandro Hernández Cordero
+* Refactor rgbd_camera_bridge demo (`#643 `_)
+ Co-authored-by: Alejandro Hernández Cordero
+* Refactor diff_drive demo (`#635 `_)
+ Co-authored-by: Alejandro Hernández Cordero
+* Refactor gpu_lidar_bridge demo (`#636 `_)
+ * Refactor gpu_lidar_bridge demo
+* Refactor camera demo (`#634 `_)
+ Co-authored-by: Alejandro Hernández Cordero
+* Refactor battery demo (`#633 `_)
+* Refactor tf_bridge demo (`#644 `_)
+* Refactor magnetometer demo (`#638 `_)
+* Refactor imu demo (`#637 `_)
+ * Refactor imu demo
+* Refactor navsat_gpxfix demo (`#642 `_)
+ * Refactor navsat_gpxfix demo
+* Refactor navsat demo (`#639 `_)
+ * Refactor navsat demo
+* Refactor air pressure demo (`#632 `_)
+ * Refactor air pressure demo
+ Co-authored-by: Addisu Z. Taddese
+ Co-authored-by: Alejandro Hernández Cordero
+* Contributors: Carlos Agüero
+
2.1.2 (2024-10-31)
------------------
diff --git a/ros_gz_sim_demos/package.xml b/ros_gz_sim_demos/package.xml
index 433f3f23..9c7cc0a7 100644
--- a/ros_gz_sim_demos/package.xml
+++ b/ros_gz_sim_demos/package.xml
@@ -1,6 +1,6 @@
ros_gz_sim_demos
- 2.1.2
+ 2.1.3
Demos using Gazebo Sim simulation with ROS.
Apache 2.0
Aditya Pande
diff --git a/test_ros_gz_bridge/CHANGELOG.rst b/test_ros_gz_bridge/CHANGELOG.rst
index b4f1e3b6..43f47d3c 100644
--- a/test_ros_gz_bridge/CHANGELOG.rst
+++ b/test_ros_gz_bridge/CHANGELOG.rst
@@ -2,6 +2,9 @@
Changelog for package test_ros_gz_bridge
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
+2.1.3 (2025-01-14)
+------------------
+
2.1.2 (2024-10-31)
------------------
diff --git a/test_ros_gz_bridge/package.xml b/test_ros_gz_bridge/package.xml
index 95da57f1..610e76e4 100644
--- a/test_ros_gz_bridge/package.xml
+++ b/test_ros_gz_bridge/package.xml
@@ -2,7 +2,7 @@
test_ros_gz_bridge
- 2.1.2
+ 2.1.3
Bridge communication between ROS and Gazebo Transport
Aditya Pande
Alejandro Hernandez