Skip to content

Commit

Permalink
Merge branch 'ros2' into arjo/feat/log_environment_vars
Browse files Browse the repository at this point in the history
  • Loading branch information
arjo129 authored Jan 24, 2025
2 parents 9431af1 + 6156b3e commit eea766f
Show file tree
Hide file tree
Showing 18 changed files with 196 additions and 50 deletions.
3 changes: 3 additions & 0 deletions ros_gz/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package ros_gz
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.1.3 (2025-01-14)
------------------

2.1.2 (2024-10-31)
------------------

Expand Down
2 changes: 1 addition & 1 deletion ros_gz/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
<!-- TODO: Make this a metapackage, see
https://github.com/ros2/ros2/issues/408 -->
<name>ros_gz</name>
<version>2.1.2</version>
<version>2.1.3</version>
<description>Meta-package containing interfaces for using ROS 2 with <a href="https://gazebosim.org">Gazebo</a> simulation.</description>
<maintainer email="[email protected]">Aditya Pande</maintainer>
<maintainer email="[email protected]">Alejandro Hernandez</maintainer>
Expand Down
29 changes: 29 additions & 0 deletions ros_gz_bridge/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -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 <https://github.com/gazebosim/ros_gz/issues/656>`_)
Co-authored-by: Addisu Z. Taddese <[email protected]>
* Merge pull request `#664 <https://github.com/gazebosim/ros_gz/issues/664>`_ from azeey/improve_parameter_handling
Co-authored-by: Alejandro Hernández Cordero <[email protected]>
* Merge pull request `#663 <https://github.com/gazebosim/ros_gz/issues/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 <https://github.com/gazebosim/ros_gz/issues/651>`_)
* Add a way to pass extra parameters to ros_gz_bridge (`#628 <https://github.com/gazebosim/ros_gz/issues/628>`_)
* Add bridge_params argument to ros_gz_bridge
Co-authored-by: Alejandro Hernández Cordero <[email protected]>
Co-authored-by: Wiktor Bajor <[email protected]>
* Contributors: Aarav Gupta, Addisu Z. Taddese, Alejandro Hernández Cordero, Øystein Sture

2.1.2 (2024-10-31)
------------------

Expand Down
2 changes: 1 addition & 1 deletion ros_gz_bridge/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>ros_gz_bridge</name>
<version>2.1.2</version>
<version>2.1.3</version>
<description>Bridge communication between ROS and Gazebo Transport</description>
<maintainer email="[email protected]">Aditya Pande</maintainer>
<maintainer email="[email protected]">Alejandro Hernandez</maintainer>
Expand Down
3 changes: 2 additions & 1 deletion ros_gz_bridge/ros_gz_bridge/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -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):
Expand Down
3 changes: 3 additions & 0 deletions ros_gz_image/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package ros1_ign_image
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.1.3 (2025-01-14)
------------------

2.1.2 (2024-10-31)
------------------

Expand Down
2 changes: 1 addition & 1 deletion ros_gz_image/package.xml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<package format="3">
<name>ros_gz_image</name>
<version>2.1.2</version>
<version>2.1.3</version>
<description>Image utilities for Gazebo simulation with ROS.</description>
<license>Apache 2.0</license>
<maintainer email="[email protected]">Aditya Pande</maintainer>
Expand Down
3 changes: 3 additions & 0 deletions ros_gz_interfaces/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package ros_gz_interfaces
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.1.3 (2025-01-14)
------------------

2.1.2 (2024-10-31)
------------------

Expand Down
2 changes: 1 addition & 1 deletion ros_gz_interfaces/package.xml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<package format="3">
<name>ros_gz_interfaces</name>
<version>2.1.2</version>
<version>2.1.3</version>
<description>Message and service data structures for interacting with Gazebo from ROS2.</description>
<license>Apache 2.0</license>
<author>Louise Poubel</author>
Expand Down
28 changes: 28 additions & 0 deletions ros_gz_sim/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,34 @@
Changelog for package ros_gz_sim
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.1.3 (2025-01-14)
------------------
* Shutdown explicitly while existing (`#623 <https://github.com/gazebosim/ros_gz/issues/623>`_)
* Merge pull request `#663 <https://github.com/gazebosim/ros_gz/issues/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 <https://github.com/gazebosim/ros_gz/issues/659>`_)
* Use member variables instead. (`#653 <https://github.com/gazebosim/ros_gz/issues/653>`_)
* Move gzserver logic to its action (`#646 <https://github.com/gazebosim/ros_gz/issues/646>`_)
* Add a way to pass extra parameters to ros_gz_bridge (`#628 <https://github.com/gazebosim/ros_gz/issues/628>`_)
* Add bridge_params argument to ros_gz_bridge
Co-authored-by: Alejandro Hernández Cordero <[email protected]>
Co-authored-by: Wiktor Bajor <[email protected]>
* Add remove entity node (`#629 <https://github.com/gazebosim/ros_gz/issues/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 <https://github.com/gazebosim/ros_gz/issues/604>`_)
Expand Down
5 changes: 5 additions & 0 deletions ros_gz_sim/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -93,6 +93,11 @@ rclcpp_components_register_node(
EXECUTABLE gzserver
)

target_include_directories(gzserver_component PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>
)

configure_file(
launch/gz_sim.launch.py.in
launch/gz_sim.launch.py.configured
Expand Down
45 changes: 45 additions & 0 deletions ros_gz_sim/include/ros_gz_sim/gzserver.hpp
Original file line number Diff line number Diff line change
@@ -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 <gz/utils/ImplPtr.hh>
#include <rclcpp/node.hpp>

// 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_
2 changes: 1 addition & 1 deletion ros_gz_sim/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>ros_gz_sim</name>
<version>2.1.2</version>
<version>2.1.3</version>
<description>Tools for using Gazebo Sim simulation with ROS.</description>
<maintainer email="[email protected]">Alejandro Hernandez</maintainer>
<maintainer email="[email protected]">Aditya Pande</maintainer>
Expand Down
83 changes: 41 additions & 42 deletions ros_gz_sim/src/gzserver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 <functional>
#include <thread>
#include <gz/common/Console.hh>
Expand All @@ -21,60 +23,57 @@
#include <rclcpp/rclcpp.hpp>
#include <rclcpp_components/register_node_macro.hpp>

// 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<Implementation>())
{
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)
27 changes: 27 additions & 0 deletions ros_gz_sim_demos/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,33 @@
Changelog for package ros1_gz_sim_demos
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.1.3 (2025-01-14)
------------------
* Refactor triggered_camera demo (`#645 <https://github.com/gazebosim/ros_gz/issues/645>`_)
Co-authored-by: Alejandro Hernández Cordero <[email protected]>
* Refactor rgbd_camera_bridge demo (`#643 <https://github.com/gazebosim/ros_gz/issues/643>`_)
Co-authored-by: Alejandro Hernández Cordero <[email protected]>
* Refactor diff_drive demo (`#635 <https://github.com/gazebosim/ros_gz/issues/635>`_)
Co-authored-by: Alejandro Hernández Cordero <[email protected]>
* Refactor gpu_lidar_bridge demo (`#636 <https://github.com/gazebosim/ros_gz/issues/636>`_)
* Refactor gpu_lidar_bridge demo
* Refactor camera demo (`#634 <https://github.com/gazebosim/ros_gz/issues/634>`_)
Co-authored-by: Alejandro Hernández Cordero <[email protected]>
* Refactor battery demo (`#633 <https://github.com/gazebosim/ros_gz/issues/633>`_)
* Refactor tf_bridge demo (`#644 <https://github.com/gazebosim/ros_gz/issues/644>`_)
* Refactor magnetometer demo (`#638 <https://github.com/gazebosim/ros_gz/issues/638>`_)
* Refactor imu demo (`#637 <https://github.com/gazebosim/ros_gz/issues/637>`_)
* Refactor imu demo
* Refactor navsat_gpxfix demo (`#642 <https://github.com/gazebosim/ros_gz/issues/642>`_)
* Refactor navsat_gpxfix demo
* Refactor navsat demo (`#639 <https://github.com/gazebosim/ros_gz/issues/639>`_)
* Refactor navsat demo
* Refactor air pressure demo (`#632 <https://github.com/gazebosim/ros_gz/issues/632>`_)
* Refactor air pressure demo
Co-authored-by: Addisu Z. Taddese <[email protected]>
Co-authored-by: Alejandro Hernández Cordero <[email protected]>
* Contributors: Carlos Agüero

2.1.2 (2024-10-31)
------------------

Expand Down
2 changes: 1 addition & 1 deletion ros_gz_sim_demos/package.xml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<package format="3">
<name>ros_gz_sim_demos</name>
<version>2.1.2</version>
<version>2.1.3</version>
<description>Demos using Gazebo Sim simulation with ROS.</description>
<license>Apache 2.0</license>
<maintainer email="[email protected]">Aditya Pande</maintainer>
Expand Down
3 changes: 3 additions & 0 deletions test_ros_gz_bridge/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package test_ros_gz_bridge
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

2.1.3 (2025-01-14)
------------------

2.1.2 (2024-10-31)
------------------

Expand Down
2 changes: 1 addition & 1 deletion test_ros_gz_bridge/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>test_ros_gz_bridge</name>
<version>2.1.2</version>
<version>2.1.3</version>
<description>Bridge communication between ROS and Gazebo Transport</description>
<maintainer email="[email protected]">Aditya Pande</maintainer>
<maintainer email="[email protected]">Alejandro Hernandez</maintainer>
Expand Down

0 comments on commit eea766f

Please sign in to comment.