Skip to content

Commit

Permalink
Add support for gz.msgs.EntityWrench (base branch: ros2) (backport #573
Browse files Browse the repository at this point in the history
…) (#576)

* Add support for gz.msgs.EntityWrench (base branch: ros2) (#573)

Signed-off-by: Victor T. N. <[email protected]>
(cherry picked from commit f9afb69)

# Conflicts:
#	ros_gz_bridge/README.md
#	ros_gz_bridge/test/utils/gz_test_msg.hpp

* Fixed merge

Signed-off-by: Alejandro Hernández Cordero <[email protected]>

---------

Signed-off-by: Alejandro Hernández Cordero <[email protected]>
Co-authored-by: Victor T. Noppeney <[email protected]>
Co-authored-by: Alejandro Hernández Cordero <[email protected]>
  • Loading branch information
3 people authored Jul 1, 2024
1 parent 02ea7f6 commit 152b691
Show file tree
Hide file tree
Showing 11 changed files with 102 additions and 0 deletions.
1 change: 1 addition & 0 deletions ros_gz_bridge/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@ The following message types can be bridged for topics:
| ros_gz_interfaces/msg/Contacts | ignition::msgs::Contacts |
| ros_gz_interfaces/msg/Dataframe | ignition::msgs::Dataframe |
| ros_gz_interfaces/msg/Entity | ignition::msgs::Entity |
| ros_gz_interfaces/msg/EntityWrench | ignition.msgs.EntityWrench |
| ros_gz_interfaces/msg/Float32Array | ignition::msgs::Float_V |
| ros_gz_interfaces/msg/GuiCamera | ignition::msgs::GUICamera |
| ros_gz_interfaces/msg/JointWrench | ignition::msgs::JointWrench |
Expand Down
14 changes: 14 additions & 0 deletions ros_gz_bridge/include/ros_gz_bridge/convert/ros_gz_interfaces.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
// Gazebo Msgs
#include <gz/msgs/altimeter.pb.h>
#include <gz/msgs/entity.pb.h>
#include <gz/msgs/entity_wrench.pb.h>
#include <gz/msgs/joint_wrench.pb.h>
#include <gz/msgs/contact.pb.h>
#include <gz/msgs/contacts.pb.h>
Expand All @@ -35,6 +36,7 @@
// ROS 2 messages
#include <ros_gz_interfaces/msg/altimeter.hpp>
#include <ros_gz_interfaces/msg/entity.hpp>
#include <ros_gz_interfaces/msg/entity_wrench.hpp>
#include <ros_gz_interfaces/msg/joint_wrench.hpp>
#include <ros_gz_interfaces/msg/contact.hpp>
#include <ros_gz_interfaces/msg/contacts.hpp>
Expand Down Expand Up @@ -102,6 +104,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(
Expand Down
1 change: 1 addition & 0 deletions ros_gz_bridge/ros_gz_bridge/mappings.py
Original file line number Diff line number Diff line change
Expand Up @@ -62,6 +62,7 @@
Mapping('Contact', 'Contact'),
Mapping('Contacts', 'Contacts'),
Mapping('Entity', 'Entity'),
Mapping('EntityWrench', 'EntityWrench'),
Mapping('Float32Array', 'Float_V'),
Mapping('GuiCamera', 'GUICamera'),
Mapping('JointWrench', 'JointWrench'),
Expand Down
22 changes: 22 additions & 0 deletions ros_gz_bridge/src/convert/ros_gz_interfaces.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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(
Expand Down
24 changes: 24 additions & 0 deletions ros_gz_bridge/test/utils/gz_test_msg.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -525,6 +525,30 @@ void compareTestMsg(const std::shared_ptr<gz::msgs::Entity> & _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<gz::msgs::EntityWrench> & _msg)
{
gz::msgs::EntityWrench expected_msg;
createTestMsg(expected_msg);
compareTestMsg(std::make_shared<gz::msgs::Header>(_msg->header()));
compareTestMsg(std::make_shared<gz::msgs::Entity>(_msg->entity()));
compareTestMsg(std::make_shared<gz::msgs::Wrench>(_msg->wrench()));
}

void createTestMsg(gz::msgs::Contact & _msg)
{
gz::msgs::Entity collision1;
Expand Down
9 changes: 9 additions & 0 deletions ros_gz_bridge/test/utils/gz_test_msg.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@
#include <gz/msgs/double.pb.h>
#include <gz/msgs/empty.pb.h>
#include <gz/msgs/entity.pb.h>
#include <gz/msgs/entity_wrench.pb.h>
#include <gz/msgs/float.pb.h>
#include <gz/msgs/float_v.pb.h>
#include <gz/msgs/fluid_pressure.pb.h>
Expand Down Expand Up @@ -298,6 +299,14 @@ void createTestMsg(gz::msgs::Entity & _msg);
/// \param[in] _msg The message to compare.
void compareTestMsg(const std::shared_ptr<gz::msgs::Entity> & _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<gz::msgs::EntityWrench> & _msg);

/// \brief Create a message used for testing.
/// \param[out] _msg The message populated.
void createTestMsg(gz::msgs::Contact & _msg);
Expand Down
17 changes: 17 additions & 0 deletions ros_gz_bridge/test/utils/ros_test_msg.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -857,6 +857,23 @@ void compareTestMsg(const std::shared_ptr<ros_gz_interfaces::msg::Entity> & _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<ros_gz_interfaces::msg::EntityWrench> & _msg)
{
ros_gz_interfaces::msg::EntityWrench expected_msg;
createTestMsg(expected_msg);

compareTestMsg(std::make_shared<std_msgs::msg::Header>(_msg->header));
compareTestMsg(std::make_shared<ros_gz_interfaces::msg::Entity>(_msg->entity));
compareTestMsg(std::make_shared<geometry_msgs::msg::Wrench>(_msg->wrench));
}

void createTestMsg(ros_gz_interfaces::msg::Contact & _msg)
{
createTestMsg(_msg.collision1);
Expand Down
9 changes: 9 additions & 0 deletions ros_gz_bridge/test/utils/ros_test_msg.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,7 @@
#include <nav_msgs/msg/odometry.hpp>
#include <ros_gz_interfaces/msg/altimeter.hpp>
#include <ros_gz_interfaces/msg/entity.hpp>
#include <ros_gz_interfaces/msg/entity_wrench.hpp>
#include <ros_gz_interfaces/msg/gui_camera.hpp>
#include <ros_gz_interfaces/msg/joint_wrench.hpp>
#include <ros_gz_interfaces/msg/contact.hpp>
Expand Down Expand Up @@ -418,6 +419,14 @@ void createTestMsg(ros_gz_interfaces::msg::Entity & _msg);
/// \param[in] _msg The message to compare.
void compareTestMsg(const std::shared_ptr<ros_gz_interfaces::msg::Entity> & _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<ros_gz_interfaces::msg::EntityWrench> & _msg);

/// \brief Create a message used for testing.
/// \param[out] _msg The message populated.
void createTestMsg(ros_gz_interfaces::msg::Contact & _msg);
Expand Down
1 change: 1 addition & 0 deletions ros_gz_interfaces/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand Down
1 change: 1 addition & 0 deletions ros_gz_interfaces/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down
3 changes: 3 additions & 0 deletions ros_gz_interfaces/msg/EntityWrench.msg
Original file line number Diff line number Diff line change
@@ -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

0 comments on commit 152b691

Please sign in to comment.