diff --git a/README.md b/README.md index eb9d726e..48fb930a 100644 --- a/README.md +++ b/README.md @@ -59,7 +59,7 @@ This repository holds packages that provide integration between ## Install -This branch supports ROS Rolling. See above for other ROS versions. +This branch supports ROS Jazzy. See above for other ROS versions. ### Binaries @@ -74,24 +74,24 @@ They are hosted at https://packages.ros.org. 1. Install `ros_gz` - sudo apt install ros-rolling-ros-gz + sudo apt install ros-jazzy-ros-gz ### From source #### ROS Be sure you've installed -[ROS Rolling](https://index.ros.org/doc/ros2/Installation/) +[ROS Jazzy](https://docs.ros.org/en/jazzy/Installation.html) (at least ROS-Base). More ROS dependencies will be installed below. #### Gazebo -Install either [Edifice, Fortress, or Garden](https://gazebosim.org/docs). +Install either [Garden or Harmonic](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 # IMPORTANT: Replace with correct version + export GZ_VERSION=harmonic # IMPORTANT: Replace with correct version > You only need to set this variable when compiling, not when running. @@ -107,14 +107,14 @@ 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 jazzy ``` 1. Install dependencies (this may also install Gazebo): ``` cd ~/ws - rosdep install -r --from-paths src -i -y --rosdistro humble + rosdep install -r --from-paths src -i -y --rosdistro jazzy ``` > If `rosdep` fails to install Gazebo libraries and you have not installed them before, please follow [Gazebo installation instructions](https://gazebosim.org/docs/latest/install). diff --git a/ros_gz/CHANGELOG.rst b/ros_gz/CHANGELOG.rst index a90bbf5d..800dfb64 100644 --- a/ros_gz/CHANGELOG.rst +++ b/ros_gz/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package ros_gz ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.0.4 (2024-08-29) +------------------ + +1.0.3 (2024-07-22) +------------------ + 1.0.2 (2024-07-03) ------------------ * Prepare for 1.0.0 Release (`#495 `_) diff --git a/ros_gz/package.xml b/ros_gz/package.xml index 370af439..3ecbec2d 100644 --- a/ros_gz/package.xml +++ b/ros_gz/package.xml @@ -4,7 +4,7 @@ ros_gz - 1.0.0 + 1.0.4 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 a95d609c..db2f49c6 100644 --- a/ros_gz_bridge/CHANGELOG.rst +++ b/ros_gz_bridge/CHANGELOG.rst @@ -2,6 +2,25 @@ Changelog for package ros_gz_bridge ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.0.4 (2024-08-29) +------------------ +* feat: `override_timestamps_with_wall_time` parameter (backport `#562 `_) (`#584 `_) + Co-authored-by: Rein Appeldoorn +* Use memcpy instead of std::copy when bridging images (`#565 `_) (`#585 `_) + While testing ros <-> gz communication using the bridge I noticed that the bridge was talking quite a bit of time copying images from Gazebo to ROS. I found that the std::copy operation that we're doing is substantially slower than the memcpy alternative. I think that in principle this shouldn't happen but the numbers are quite clear. Perhaps std::copy is doing something that doesn't use cache effectively + --------- + Co-authored-by: Jose Luis Rivero + (cherry picked from commit a781b78852112246245c05481db6335388d4f736) + Co-authored-by: Carlos Agüero +* Contributors: mergify[bot] + +1.0.3 (2024-07-22) +------------------ +* Add support for gz.msgs.EntityWrench (base branch: ros2) (`#573 `_) (`#574 `_) + (cherry picked from commit f9afb69d1163633dd978024bb7271a28cf7b551a) + Co-authored-by: Victor T. Noppeney +* Contributors: mergify[bot] + 1.0.2 (2024-07-03) ------------------ * Merge pull request `#569 `_ from azeey/iron_to_jazzy diff --git a/ros_gz_bridge/README.md b/ros_gz_bridge/README.md index 98792d92..2a53c08c 100644 --- a/ros_gz_bridge/README.md +++ b/ros_gz_bridge/README.md @@ -34,6 +34,7 @@ The following message types can be bridged for topics: | ros_gz_interfaces/msg/Contacts | gz.msgs.Contacts | | ros_gz_interfaces/msg/Dataframe | gz.msgs.Dataframe | | ros_gz_interfaces/msg/Entity | gz.msgs.Entity | +| ros_gz_interfaces/msg/EntityWrench | gz.msgs.EntityWrench | | ros_gz_interfaces/msg/Float32Array | gz.msgs.Float_V | | ros_gz_interfaces/msg/GuiCamera | gz.msgs.GUICamera | | ros_gz_interfaces/msg/JointWrench | gz.msgs.JointWrench | @@ -89,6 +90,9 @@ You should create an unidirectional `/clock` bridge: ros2 run ros_gz_bridge parameter_bridge /clock@rosgraph_msgs/msg/Clock[gz.msgs.Clock ``` +An alternative set-up can be using the bridge with the `override_timestamps_with_wall_time` ros parameter set to `true` (default=`false`). In this set-up, +all header timestamps of the outgoing messages will be stamped with the wall time. This can be useful when the simulator has to communicate with an external system that requires wall times. + ## Example 1a: Gazebo Transport talker and ROS 2 listener Start the parameter bridge which will watch the specified topics. 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 9b17d0cf..b49f02d7 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 @@ -18,6 +18,7 @@ // Gazebo Msgs #include #include +#include #include #include #include @@ -37,6 +38,7 @@ // ROS 2 messages #include #include +#include #include #include #include @@ -95,6 +97,18 @@ convert_gz_to_ros( const gz::msgs::Entity & gz_msg, ros_gz_interfaces::msg::Entity & ros_msg); +template<> +void +convert_ros_to_gz( + const ros_gz_interfaces::msg::EntityWrench & ros_msg, + gz::msgs::EntityWrench & gz_msg); + +template<> +void +convert_gz_to_ros( + const gz::msgs::EntityWrench & gz_msg, + ros_gz_interfaces::msg::EntityWrench & ros_msg); + template<> void convert_ros_to_gz( diff --git a/ros_gz_bridge/package.xml b/ros_gz_bridge/package.xml index fe402448..87898a96 100644 --- a/ros_gz_bridge/package.xml +++ b/ros_gz_bridge/package.xml @@ -2,7 +2,7 @@ ros_gz_bridge - 1.0.0 + 1.0.4 Bridge communication between ROS and Gazebo Transport Aditya Pande Alejandro Hernandez diff --git a/ros_gz_bridge/ros_gz_bridge/mappings.py b/ros_gz_bridge/ros_gz_bridge/mappings.py index 2414586f..203e33d1 100644 --- a/ros_gz_bridge/ros_gz_bridge/mappings.py +++ b/ros_gz_bridge/ros_gz_bridge/mappings.py @@ -64,6 +64,7 @@ Mapping('Contacts', 'Contacts'), Mapping('Dataframe', 'Dataframe'), Mapping('Entity', 'Entity'), + Mapping('EntityWrench', 'EntityWrench'), Mapping('Float32Array', 'Float_V'), Mapping('GuiCamera', 'GUICamera'), Mapping('JointWrench', 'JointWrench'), diff --git a/ros_gz_bridge/src/bridge_handle.cpp b/ros_gz_bridge/src/bridge_handle.cpp index c7851503..eb8b1f90 100644 --- a/ros_gz_bridge/src/bridge_handle.cpp +++ b/ros_gz_bridge/src/bridge_handle.cpp @@ -30,6 +30,8 @@ BridgeHandle::BridgeHandle( config_(config), factory_(get_factory(config.ros_type_name, config.gz_type_name)) { + ros_node_->get_parameter("override_timestamps_with_wall_time", + override_timestamps_with_wall_time_); } BridgeHandle::~BridgeHandle() = default; diff --git a/ros_gz_bridge/src/bridge_handle.hpp b/ros_gz_bridge/src/bridge_handle.hpp index d1751fb9..777496ac 100644 --- a/ros_gz_bridge/src/bridge_handle.hpp +++ b/ros_gz_bridge/src/bridge_handle.hpp @@ -101,6 +101,9 @@ class BridgeHandle /// \brief Typed factory used to create publishers/subscribers std::shared_ptr factory_; + + /// \brief Override the header.stamp field of the outgoing messages with the wall time + bool override_timestamps_with_wall_time_ = false; }; } // namespace ros_gz_bridge diff --git a/ros_gz_bridge/src/bridge_handle_gz_to_ros.cpp b/ros_gz_bridge/src/bridge_handle_gz_to_ros.cpp index ddc292f8..ce90c875 100644 --- a/ros_gz_bridge/src/bridge_handle_gz_to_ros.cpp +++ b/ros_gz_bridge/src/bridge_handle_gz_to_ros.cpp @@ -70,7 +70,8 @@ void BridgeHandleGzToRos::StartSubscriber() this->gz_node_, this->config_.gz_topic_name, this->config_.subscriber_queue_size, - this->ros_publisher_); + this->ros_publisher_, + override_timestamps_with_wall_time_); this->gz_subscriber_ = this->gz_node_; } diff --git a/ros_gz_bridge/src/convert/ros_gz_interfaces.cpp b/ros_gz_bridge/src/convert/ros_gz_interfaces.cpp index ae4665e5..eb923b34 100644 --- a/ros_gz_bridge/src/convert/ros_gz_interfaces.cpp +++ b/ros_gz_bridge/src/convert/ros_gz_interfaces.cpp @@ -139,6 +139,28 @@ convert_gz_to_ros( } } +template<> +void +convert_ros_to_gz( + const ros_gz_interfaces::msg::EntityWrench & ros_msg, + gz::msgs::EntityWrench & gz_msg) +{ + convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header())); + convert_ros_to_gz(ros_msg.entity, (*gz_msg.mutable_entity())); + convert_ros_to_gz(ros_msg.wrench, (*gz_msg.mutable_wrench())); +} + +template<> +void +convert_gz_to_ros( + const gz::msgs::EntityWrench & gz_msg, + ros_gz_interfaces::msg::EntityWrench & ros_msg) +{ + convert_gz_to_ros(gz_msg.header(), ros_msg.header); + convert_gz_to_ros(gz_msg.entity(), ros_msg.entity); + convert_gz_to_ros(gz_msg.wrench(), ros_msg.wrench); +} + template<> void convert_ros_to_gz( diff --git a/ros_gz_bridge/src/convert/sensor_msgs.cpp b/ros_gz_bridge/src/convert/sensor_msgs.cpp index 691b823c..f537f908 100644 --- a/ros_gz_bridge/src/convert/sensor_msgs.cpp +++ b/ros_gz_bridge/src/convert/sensor_msgs.cpp @@ -166,13 +166,11 @@ convert_gz_to_ros( ros_msg.is_bigendian = false; ros_msg.step = ros_msg.width * num_channels * octets_per_channel; - - auto count = ros_msg.step * ros_msg.height; ros_msg.data.resize(ros_msg.step * ros_msg.height); - std::copy( - gz_msg.data().begin(), - gz_msg.data().begin() + count, - ros_msg.data.begin()); + + // Prefer memcpy over std::copy for performance reasons, + // see https://github.com/gazebosim/ros_gz/pull/565 + memcpy(ros_msg.data.data(), gz_msg.data().c_str(), gz_msg.data().size()); } template<> diff --git a/ros_gz_bridge/src/factory.hpp b/ros_gz_bridge/src/factory.hpp index ec00af7b..656f38d9 100644 --- a/ros_gz_bridge/src/factory.hpp +++ b/ros_gz_bridge/src/factory.hpp @@ -15,9 +15,11 @@ #ifndef FACTORY_HPP_ #define FACTORY_HPP_ +#include #include #include #include +#include #include @@ -27,6 +29,16 @@ #include "factory_interface.hpp" +template +struct has_header : std::false_type +{ +}; + +template +struct has_header>: std::true_type +{ +}; + namespace ros_gz_bridge { @@ -52,9 +64,11 @@ class Factory : public FactoryInterface auto options = rclcpp::PublisherOptions(); options.qos_overriding_options = rclcpp::QosOverridingOptions { { + rclcpp::QosPolicyKind::Deadline, rclcpp::QosPolicyKind::Depth, rclcpp::QosPolicyKind::Durability, rclcpp::QosPolicyKind::History, + rclcpp::QosPolicyKind::Liveliness, rclcpp::QosPolicyKind::Reliability }, }; @@ -103,15 +117,17 @@ class Factory : public FactoryInterface std::shared_ptr node, const std::string & topic_name, size_t /*queue_size*/, - rclcpp::PublisherBase::SharedPtr ros_pub) + rclcpp::PublisherBase::SharedPtr ros_pub, + bool override_timestamps_with_wall_time) { std::function subCb = - [this, ros_pub](const GZ_T & _msg, const gz::transport::MessageInfo & _info) + [this, ros_pub, override_timestamps_with_wall_time](const GZ_T & _msg, + const gz::transport::MessageInfo & _info) { // Ignore messages that are published from this bridge. if (!_info.IntraProcess()) { - this->gz_callback(_msg, ros_pub); + this->gz_callback(_msg, ros_pub, override_timestamps_with_wall_time); } }; @@ -139,10 +155,20 @@ class Factory : public FactoryInterface static void gz_callback( const GZ_T & gz_msg, - rclcpp::PublisherBase::SharedPtr ros_pub) + rclcpp::PublisherBase::SharedPtr ros_pub, + bool override_timestamps_with_wall_time) { ROS_T ros_msg; convert_gz_to_ros(gz_msg, ros_msg); + if constexpr (has_header::value) { + if (override_timestamps_with_wall_time) { + auto now = std::chrono::system_clock::now().time_since_epoch(); + auto ns = + std::chrono::duration_cast(now).count(); + ros_msg.header.stamp.sec = ns / 1e9; + ros_msg.header.stamp.nanosec = ns - ros_msg.header.stamp.sec * 1e9; + } + } std::shared_ptr> pub = std::dynamic_pointer_cast>(ros_pub); if (pub != nullptr) { diff --git a/ros_gz_bridge/src/factory_interface.hpp b/ros_gz_bridge/src/factory_interface.hpp index b760bcd8..3ea64ee8 100644 --- a/ros_gz_bridge/src/factory_interface.hpp +++ b/ros_gz_bridge/src/factory_interface.hpp @@ -60,7 +60,8 @@ class FactoryInterface std::shared_ptr node, const std::string & topic_name, size_t queue_size, - rclcpp::PublisherBase::SharedPtr ros_pub) = 0; + rclcpp::PublisherBase::SharedPtr ros_pub, + bool override_timestamps_with_wall_time) = 0; }; } // namespace ros_gz_bridge diff --git a/ros_gz_bridge/src/ros_gz_bridge.cpp b/ros_gz_bridge/src/ros_gz_bridge.cpp index 46a86d98..c3752d95 100644 --- a/ros_gz_bridge/src/ros_gz_bridge.cpp +++ b/ros_gz_bridge/src/ros_gz_bridge.cpp @@ -33,6 +33,7 @@ RosGzBridge::RosGzBridge(const rclcpp::NodeOptions & options) this->declare_parameter("subscription_heartbeat", 1000); this->declare_parameter("config_file", ""); this->declare_parameter("expand_gz_topic_names", false); + this->declare_parameter("override_timestamps_with_wall_time", false); int heartbeat; this->get_parameter("subscription_heartbeat", heartbeat); diff --git a/ros_gz_bridge/test/utils/gz_test_msg.cpp b/ros_gz_bridge/test/utils/gz_test_msg.cpp index cbaff583..b13a06b1 100644 --- a/ros_gz_bridge/test/utils/gz_test_msg.cpp +++ b/ros_gz_bridge/test/utils/gz_test_msg.cpp @@ -526,6 +526,30 @@ void compareTestMsg(const std::shared_ptr & _msg) EXPECT_EQ(expected_msg.type(), _msg->type()); } +void createTestMsg(gz::msgs::EntityWrench & _msg) +{ + gz::msgs::Header header_msg; + gz::msgs::Entity entity_msg; + gz::msgs::Wrench wrench_msg; + + createTestMsg(header_msg); + createTestMsg(entity_msg); + createTestMsg(wrench_msg); + + _msg.mutable_header()->CopyFrom(header_msg); + _msg.mutable_entity()->CopyFrom(entity_msg); + _msg.mutable_wrench()->CopyFrom(wrench_msg); +} + +void compareTestMsg(const std::shared_ptr & _msg) +{ + gz::msgs::EntityWrench expected_msg; + createTestMsg(expected_msg); + compareTestMsg(std::make_shared(_msg->header())); + compareTestMsg(std::make_shared(_msg->entity())); + compareTestMsg(std::make_shared(_msg->wrench())); +} + void createTestMsg(gz::msgs::Contact & _msg) { gz::msgs::Entity collision1; diff --git a/ros_gz_bridge/test/utils/gz_test_msg.hpp b/ros_gz_bridge/test/utils/gz_test_msg.hpp index 0f9b712a..cff1a0af 100644 --- a/ros_gz_bridge/test/utils/gz_test_msg.hpp +++ b/ros_gz_bridge/test/utils/gz_test_msg.hpp @@ -29,6 +29,7 @@ #include #include #include +#include #include #include #include @@ -292,6 +293,14 @@ void createTestMsg(gz::msgs::Entity & _msg); /// \param[in] _msg The message to compare. void compareTestMsg(const std::shared_ptr & _msg); +/// \brief Create a message used for testing. +/// \param[out] _msg The message populated. +void createTestMsg(gz::msgs::EntityWrench & _msg); + +/// \brief Compare a message with the populated for testing. +/// \param[in] _msg The message to compare. +void compareTestMsg(const std::shared_ptr & _msg); + /// \brief Create a message used for testing. /// \param[out] _msg The message populated. void createTestMsg(gz::msgs::Contact & _msg); diff --git a/ros_gz_bridge/test/utils/ros_test_msg.cpp b/ros_gz_bridge/test/utils/ros_test_msg.cpp index 42afcb25..42f9b90b 100644 --- a/ros_gz_bridge/test/utils/ros_test_msg.cpp +++ b/ros_gz_bridge/test/utils/ros_test_msg.cpp @@ -867,6 +867,23 @@ void compareTestMsg(const std::shared_ptr & _msg EXPECT_EQ(expected_msg.type, _msg->type); } +void createTestMsg(ros_gz_interfaces::msg::EntityWrench & _msg) +{ + createTestMsg(_msg.header); + createTestMsg(_msg.entity); + createTestMsg(_msg.wrench); +} + +void compareTestMsg(const std::shared_ptr & _msg) +{ + ros_gz_interfaces::msg::EntityWrench expected_msg; + createTestMsg(expected_msg); + + compareTestMsg(std::make_shared(_msg->header)); + compareTestMsg(std::make_shared(_msg->entity)); + compareTestMsg(std::make_shared(_msg->wrench)); +} + void createTestMsg(ros_gz_interfaces::msg::Contact & _msg) { createTestMsg(_msg.collision1); diff --git a/ros_gz_bridge/test/utils/ros_test_msg.hpp b/ros_gz_bridge/test/utils/ros_test_msg.hpp index 43c127e9..68211305 100644 --- a/ros_gz_bridge/test/utils/ros_test_msg.hpp +++ b/ros_gz_bridge/test/utils/ros_test_msg.hpp @@ -50,6 +50,7 @@ #include #include #include +#include #include #include #include @@ -425,6 +426,14 @@ void createTestMsg(ros_gz_interfaces::msg::Entity & _msg); /// \param[in] _msg The message to compare. void compareTestMsg(const std::shared_ptr & _msg); +/// \brief Create a message used for testing. +/// \param[out] _msg The message populated. +void createTestMsg(ros_gz_interfaces::msg::EntityWrench & _msg); + +/// \brief Compare a message with the populated for testing. +/// \param[in] _msg The message to compare. +void compareTestMsg(const std::shared_ptr & _msg); + /// \brief Create a message used for testing. /// \param[out] _msg The message populated. void createTestMsg(ros_gz_interfaces::msg::Contact & _msg); diff --git a/ros_gz_image/CHANGELOG.rst b/ros_gz_image/CHANGELOG.rst index a9a8317c..6982025b 100644 --- a/ros_gz_image/CHANGELOG.rst +++ b/ros_gz_image/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package ros1_ign_image ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.0.4 (2024-08-29) +------------------ + +1.0.3 (2024-07-22) +------------------ + 1.0.2 (2024-07-03) ------------------ * Merge pull request `#569 `_ from azeey/iron_to_jazzy diff --git a/ros_gz_image/package.xml b/ros_gz_image/package.xml index b6ca0048..96d9047d 100644 --- a/ros_gz_image/package.xml +++ b/ros_gz_image/package.xml @@ -1,6 +1,6 @@ ros_gz_image - 1.0.0 + 1.0.4 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 786f54d0..ba5eee13 100644 --- a/ros_gz_interfaces/CHANGELOG.rst +++ b/ros_gz_interfaces/CHANGELOG.rst @@ -2,6 +2,16 @@ Changelog for package ros_gz_interfaces ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.0.4 (2024-08-29) +------------------ + +1.0.3 (2024-07-22) +------------------ +* Add support for gz.msgs.EntityWrench (base branch: ros2) (`#573 `_) (`#574 `_) + (cherry picked from commit f9afb69d1163633dd978024bb7271a28cf7b551a) + Co-authored-by: Victor T. Noppeney +* Contributors: mergify[bot] + 1.0.2 (2024-07-03) ------------------ * Add option to change material color from ROS. (`#521 `_) diff --git a/ros_gz_interfaces/CMakeLists.txt b/ros_gz_interfaces/CMakeLists.txt index 5f3b312e..9f3d7a1f 100644 --- a/ros_gz_interfaces/CMakeLists.txt +++ b/ros_gz_interfaces/CMakeLists.txt @@ -23,6 +23,7 @@ set(msg_files "msg/Dataframe.msg" "msg/Entity.msg" "msg/EntityFactory.msg" + "msg/EntityWrench.msg" "msg/Float32Array.msg" "msg/GuiCamera.msg" "msg/JointWrench.msg" diff --git a/ros_gz_interfaces/README.md b/ros_gz_interfaces/README.md index 88ed27d7..610cb7e3 100644 --- a/ros_gz_interfaces/README.md +++ b/ros_gz_interfaces/README.md @@ -8,6 +8,7 @@ This package currently contains some Gazebo-specific ROS message and service dat * [Contacts](msg/Contacts.msg): related to [ignition::msgs::Contacts](https://github.com/gazebosim/gz-msgs/blob/ign-msgs7/proto/ignition/msgs/contacts.proto). A list of contacts. * [Entity](msg/Entity.msg): related to [ignition::msgs::Entity](https://github.com/gazebosim/gz-msgs/blob/ign-msgs7/proto/ignition/msgs/entity.proto). Entity of Gazebo Sim. * [EntityFactory](msg/EntityFactory.msg): related to [ignition::msgs::EntityFactory](https://github.com/gazebosim/gz-msgs/blob/ign-msgs7/proto/ignition/msgs/entity_factory.proto). Message to create a new entity. +* [EntityWrench](msg/EntityWrench.msg): related to [ignition::msgs::EntityWrench](https://github.com/gazebosim/gz-msgs/blob/ign-msgs7/proto/gz/msgs/entity_wrench.proto). Wrench to be applied to a specified Entity of Gazebo Sim. * [Light](msg/Light.msg): related to [ignition::msgs::Light](https://github.com/gazebosim/gz-msgs/blob/ign-msgs7/proto/ignition/msgs/light.proto). Light info in Gazebo Sim. * [WorldControl](msg/WorldControl.msg): related to [ignition::msgs::WorldControl](https://github.com/gazebosim/gz-msgs/blob/ign-msgs7/proto/ignition/msgs/world_control.proto). Message to control world of Gazebo Sim. * [WorldReset](msg/WorldReset.msg): related to [ignition::msgs::WorldReset](https://github.com/gazebosim/gz-msgs/blob/ign-msgs7/proto/ignition/msgs/world_reset.proto). Reset time and model of simulation. diff --git a/ros_gz_interfaces/msg/EntityWrench.msg b/ros_gz_interfaces/msg/EntityWrench.msg new file mode 100644 index 00000000..c1a03987 --- /dev/null +++ b/ros_gz_interfaces/msg/EntityWrench.msg @@ -0,0 +1,3 @@ +std_msgs/Header header # Time stamp +ros_gz_interfaces/Entity entity # Entity +geometry_msgs/Wrench wrench # Wrench to be applied to entity \ No newline at end of file diff --git a/ros_gz_interfaces/package.xml b/ros_gz_interfaces/package.xml index f236eaa4..54739c91 100644 --- a/ros_gz_interfaces/package.xml +++ b/ros_gz_interfaces/package.xml @@ -1,6 +1,6 @@ ros_gz_interfaces - 1.0.0 + 1.0.4 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 9c1484b8..31d721b4 100644 --- a/ros_gz_sim/CHANGELOG.rst +++ b/ros_gz_sim/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package ros_gz_sim ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.0.4 (2024-08-29) +------------------ + +1.0.3 (2024-07-22) +------------------ + 1.0.2 (2024-07-03) ------------------ * Merge pull request `#569 `_ from azeey/iron_to_jazzy diff --git a/ros_gz_sim/launch/gz_sim.launch.py.in b/ros_gz_sim/launch/gz_sim.launch.py.in index d41bede6..ba8244a9 100644 --- a/ros_gz_sim/launch/gz_sim.launch.py.in +++ b/ros_gz_sim/launch/gz_sim.launch.py.in @@ -128,6 +128,7 @@ def launch_gz(context, *args, **kwargs): return [ExecuteProcess( cmd=[exec, exec_args, '--force-version', gz_version], + name='gazebo', output='screen', additional_env=env, shell=True, diff --git a/ros_gz_sim/package.xml b/ros_gz_sim/package.xml index 1047196d..9df162a5 100644 --- a/ros_gz_sim/package.xml +++ b/ros_gz_sim/package.xml @@ -2,7 +2,7 @@ ros_gz_sim - 1.0.0 + 1.0.4 Tools for using Gazebo Sim simulation with ROS. Alejandro Hernandez Aditya Pande diff --git a/ros_gz_sim_demos/CHANGELOG.rst b/ros_gz_sim_demos/CHANGELOG.rst index 64a4b6dc..700b4c51 100644 --- a/ros_gz_sim_demos/CHANGELOG.rst +++ b/ros_gz_sim_demos/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package ros1_gz_sim_demos ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.0.4 (2024-08-29) +------------------ + +1.0.3 (2024-07-22) +------------------ + 1.0.2 (2024-07-03) ------------------ * Prepare for 1.0.0 Release (`#495 `_) diff --git a/ros_gz_sim_demos/package.xml b/ros_gz_sim_demos/package.xml index cb65108c..a177d3e4 100644 --- a/ros_gz_sim_demos/package.xml +++ b/ros_gz_sim_demos/package.xml @@ -1,6 +1,6 @@ ros_gz_sim_demos - 1.0.0 + 1.0.4 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 6ba6ec6f..8cbe4bc2 100644 --- a/test_ros_gz_bridge/CHANGELOG.rst +++ b/test_ros_gz_bridge/CHANGELOG.rst @@ -2,6 +2,12 @@ Changelog for package test_ros_gz_bridge ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.0.4 (2024-08-29) +------------------ + +1.0.3 (2024-07-22) +------------------ + 1.0.2 (2024-07-03) ------------------ * Prepare for 1.0.0 Release (`#495 `_) diff --git a/test_ros_gz_bridge/package.xml b/test_ros_gz_bridge/package.xml index 659c820b..01d8cb26 100644 --- a/test_ros_gz_bridge/package.xml +++ b/test_ros_gz_bridge/package.xml @@ -2,7 +2,7 @@ test_ros_gz_bridge - 1.0.0 + 1.0.4 Bridge communication between ROS and Gazebo Transport Aditya Pande Alejandro Hernandez