Skip to content

Commit

Permalink
Revert "humble to ros2 (#311)"
Browse files Browse the repository at this point in the history
This reverts commit 39cdcf8.
  • Loading branch information
ahcorde committed Oct 12, 2022
1 parent 39cdcf8 commit 49ab767
Show file tree
Hide file tree
Showing 30 changed files with 93 additions and 339 deletions.
5 changes: 0 additions & 5 deletions ros_gz/CHANGELOG.rst
Expand Up @@ -2,11 +2,6 @@
Changelog for package ros_gz
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

0.244.7 (2022-10-12)
--------------------
* Merge branch 'ros2' into ports/galactic_to_ros2
* Contributors: Michael Carroll

0.244.6 (2022-09-14)
--------------------

Expand Down
2 changes: 1 addition & 1 deletion ros_gz/package.xml
Expand Up @@ -4,7 +4,7 @@
<!-- TODO: Make this a metapackage, see
https://github.com/ros2/ros2/issues/408 -->
<name>ros_gz</name>
<version>0.244.7</version>
<version>0.244.6</version>
<description>Meta-package containing interfaces for using ROS 2 with <a href="https://gazebosim.org">Gazebo</a> simulation.</description>
<maintainer email="louise@openrobotics.org">Louise Poubel</maintainer>
<license>Apache 2.0</license>
Expand Down
14 changes: 0 additions & 14 deletions ros_gz_bridge/CHANGELOG.rst
Expand Up @@ -2,20 +2,6 @@
Changelog for package ros_gz_bridge
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

0.244.7 (2022-10-12)
--------------------
* Make sure that ign\_* yaml configs work as well (`#310 <https://github.com/gazebosim/ros_gz/issues/310>`_)
* Bridge between msgs::Float_V and ros_gz_interfaces/Float32Array msg types (`#306 <https://github.com/gazebosim/ros_gz/issues/306>`_)
* bridge float_v and float32_multi_array msg type
Co-authored-by: Ian Chen <ichen@openrobotics.org>
* Bridge between msgs::Pose_V and geometry_msgs/PoseArray msg types (`#305 <https://github.com/gazebosim/ros_gz/issues/305>`_)
* replace ign with gz in ros_gz_bridge README (`#303 <https://github.com/gazebosim/ros_gz/issues/303>`_)
* Merge pull request `#275 <https://github.com/gazebosim/ros_gz/issues/275>`_ (Galactic to Humble)
Galactic to Humble
* Fix merge
* Merge branch 'ros2' into ports/galactic_to_ros2
* Contributors: Ian Chen, Michael Carroll, Olivier Kermorgant

0.244.6 (2022-09-14)
--------------------

Expand Down
26 changes: 12 additions & 14 deletions ros_gz_bridge/README.md
Expand Up @@ -10,7 +10,6 @@ The following message types can be bridged for topics:
| builtin_interfaces/Time | gz.msgs.Time |
| geometry_msgs/Point | gz.msgs.Vector3d |
| geometry_msgs/Pose | gz.msgs.Pose |
| geometry_msgs/msg/PoseArray | gz.msgs.Pose_V |
| geometry_msgs/PoseStamped | gz.msgs.Pose |
| geometry_msgs/PoseWithCovariance | gz.msgs.PoseWithCovariance |
| geometry_msgs/Quaternion | gz.msgs.Quaternion |
Expand All @@ -27,7 +26,6 @@ The following message types can be bridged for topics:
| ros_gz_interfaces/Contacts | gz.msgs.Contacts |
| ros_gz_interfaces/Dataframe | gz.msgs.Dataframe |
| ros_gz_interfaces/Entity | gz.msgs.Entity |
| ros_gz_interfaces/msg/Float32Array | gz.msgs.Float_V |
| ros_gz_interfaces/GuiCamera | gz.msgs.GUICamera |
| ros_gz_interfaces/JointWrench | gz.msgs.JointWrench |
| ros_gz_interfaces/Light | gz.msgs.Light |
Expand Down Expand Up @@ -233,40 +231,40 @@ bridge may be specified:
# Set just topic name, applies to both
- topic_name: "chatter"
ros_type_name: "std_msgs/msg/String"
gz_type_name: "ignition.msgs.StringMsg"
ign_type_name: "ignition.msgs.StringMsg"

# Set just ROS topic name, applies to both
- ros_topic_name: "chatter_ros"
ros_type_name: "std_msgs/msg/String"
gz_type_name: "ignition.msgs.StringMsg"
ign_type_name: "ignition.msgs.StringMsg"

# Set just GZ topic name, applies to both
- gz_topic_name: "chatter_ign"
# Set just IGN topic name, applies to both
- ign_topic_name: "chatter_ign"
ros_type_name: "std_msgs/msg/String"
gz_type_name: "ignition.msgs.StringMsg"
ign_type_name: "ignition.msgs.StringMsg"

# Set each topic name explicitly
- ros_topic_name: "chatter_both_ros"
gz_topic_name: "chatter_both_ign"
ign_topic_name: "chatter_both_ign"
ros_type_name: "std_msgs/msg/String"
gz_type_name: "ignition.msgs.StringMsg"
ign_type_name: "ignition.msgs.StringMsg"

# Full set of configurations
- ros_topic_name: "ros_chatter"
gz_topic_name: "ign_chatter"
ign_topic_name: "ign_chatter"
ros_type_name: "std_msgs/msg/String"
gz_type_name: "ignition.msgs.StringMsg"
ign_type_name: "ignition.msgs.StringMsg"
subscriber_queue: 5 # Default 10
publisher_queue: 6 # Default 10
lazy: true # Default "false"
direction: BIDIRECTIONAL # Default "BIDIRECTIONAL" - Bridge both directions
# "GZ_TO_ROS" - Bridge Ignition topic to ROS
# "ROS_TO_GZ" - Bridge ROS topic to Ignition
# "IGN_TO_ROS" - Bridge Ignition topic to ROS
# "ROS_TO_IGN" - Bridge ROS topic to Ignition
```

To run the bridge node with the above configuration:
```bash
ros2 run ros_gz_bridge parameter_bridge --ros-args -p config_file:=$WORKSPACE/ros_gz/ros_gz_bridge/test/config/full.yaml
ros2 run ros_gz_bridge bridge_node --ros-args -p config_file:=$WORKSPACE/ros_gz/ros_gz_bridge/test/config/full.yaml
```

## API
Expand Down
13 changes: 0 additions & 13 deletions ros_gz_bridge/include/ros_gz_bridge/convert/geometry_msgs.hpp
Expand Up @@ -28,7 +28,6 @@
// ROS 2 messages
#include <geometry_msgs/msg/point.hpp>
#include <geometry_msgs/msg/pose.hpp>
#include <geometry_msgs/msg/pose_array.hpp>
#include <geometry_msgs/msg/pose_with_covariance.hpp>
#include <geometry_msgs/msg/pose_stamped.hpp>
#include <geometry_msgs/msg/quaternion.hpp>
Expand Down Expand Up @@ -91,18 +90,6 @@ convert_gz_to_ros(
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,
gz::msgs::Pose_V & gz_msg);

template<>
void
convert_gz_to_ros(
const gz::msgs::Pose_V & gz_msg,
geometry_msgs::msg::PoseArray & ros_msg);

template<>
void
convert_ros_to_gz(
Expand Down
Expand Up @@ -15,7 +15,7 @@
#ifndef ROS_GZ_BRIDGE__CONVERT__RCL_INTERFACES_HPP_
#define ROS_GZ_BRIDGE__CONVERT__RCL_INTERFACES_HPP_

// GZ messages
// Ignition messages
#include <gz/msgs/any.pb.h>

// ROS 2 messages
Expand Down
14 changes: 0 additions & 14 deletions ros_gz_bridge/include/ros_gz_bridge/convert/ros_gz_interfaces.hpp
Expand Up @@ -21,7 +21,6 @@
#include <gz/msgs/contact.pb.h>
#include <gz/msgs/contacts.pb.h>
#include <gz/msgs/dataframe.pb.h>
#include <gz/msgs/float_v.pb.h>
#include <gz/msgs/gui_camera.pb.h>
#include <gz/msgs/light.pb.h>
#include <gz/msgs/param.pb.h>
Expand All @@ -37,7 +36,6 @@
#include <ros_gz_interfaces/msg/contact.hpp>
#include <ros_gz_interfaces/msg/contacts.hpp>
#include <ros_gz_interfaces/msg/dataframe.hpp>
#include <ros_gz_interfaces/msg/float32_array.hpp>
#include <ros_gz_interfaces/msg/gui_camera.hpp>
#include <ros_gz_interfaces/msg/light.hpp>
#include <ros_gz_interfaces/msg/param_vec.hpp>
Expand Down Expand Up @@ -220,18 +218,6 @@ void
convert_gz_to_ros(
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,
gz::msgs::Float_V & gz_msg);

template<>
void
convert_gz_to_ros(
const gz::msgs::Float_V & gz_msg,
ros_gz_interfaces::msg::Float32Array & ros_msg);
} // namespace ros_gz_bridge

#endif // ROS_GZ_BRIDGE__CONVERT__ROS_GZ_INTERFACES_HPP_
2 changes: 1 addition & 1 deletion ros_gz_bridge/package.xml
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>0.244.7</version>
<version>0.244.6</version>
<description>Bridge communication between ROS and Gazebo Transport</description>
<maintainer email="louise@openrobotics.org">Louise Poubel</maintainer>

Expand Down
2 changes: 0 additions & 2 deletions ros_gz_bridge/ros_gz_bridge/mappings.py
Expand Up @@ -30,7 +30,6 @@
'geometry_msgs': [
Mapping('Point', 'Vector3d'),
Mapping('Pose', 'Pose'),
Mapping('PoseArray', 'Pose_V'),
Mapping('PoseStamped', 'Pose'),
Mapping('PoseWithCovariance', 'PoseWithCovariance'),
Mapping('Quaternion', 'Quaternion'),
Expand All @@ -53,7 +52,6 @@
Mapping('Contacts', 'Contacts'),
Mapping('Dataframe', 'Dataframe'),
Mapping('Entity', 'Entity'),
Mapping('Float32Array', 'Float_V'),
Mapping('GuiCamera', 'GUICamera'),
Mapping('JointWrench', 'JointWrench'),
Mapping('Light', 'Light'),
Expand Down
59 changes: 23 additions & 36 deletions ros_gz_bridge/src/bridge_config.cpp
Expand Up @@ -54,37 +54,21 @@ std::optional<BridgeConfig> parseEntry(const YAML::Node & yaml_node)
return {};
}

auto getValue = [yaml_node](const char * key) -> std::string
{
if (yaml_node[key]) {
return yaml_node[key].as<std::string>();
} else {
return "";
}
};

const auto topic_name = getValue(kTopicName);
const auto ros_topic_name = getValue(kRosTopicName);
const auto ros_type_name = getValue(kRosTypeName);
const auto gz_topic_name = getValue(kGzTopicName);
const auto gz_type_name = getValue(kGzTypeName);
const auto direction = getValue(kDirection);

if (!topic_name.empty() && !ros_topic_name.empty()) {
if (yaml_node[kTopicName] && yaml_node[kRosTopicName]) {
RCLCPP_ERROR(
logger,
"Could not parse entry: %s and %s are mutually exclusive", kTopicName, kRosTopicName);
return {};
}

if (!topic_name.empty() && !gz_topic_name.empty()) {
if (yaml_node[kTopicName] && yaml_node[kGzTopicName]) {
RCLCPP_ERROR(
logger,
"Could not parse entry: %s and %s are mutually exclusive", kTopicName, kGzTopicName);
return {};
}

if (ros_type_name.empty() || gz_type_name.empty()) {
if (!yaml_node[kRosTypeName] || !yaml_node[kGzTypeName]) {
RCLCPP_ERROR(
logger,
"Could not parse entry: both %s and %s must be set", kRosTypeName, kGzTypeName);
Expand All @@ -96,40 +80,43 @@ std::optional<BridgeConfig> parseEntry(const YAML::Node & yaml_node)
ret.direction = BridgeDirection::BIDIRECTIONAL;

if (yaml_node[kDirection]) {
if (direction == kBidirectional) {
auto dirStr = yaml_node[kDirection].as<std::string>();

if (dirStr == kBidirectional) {
ret.direction = BridgeDirection::BIDIRECTIONAL;
} else if (direction == kGzToRos) {
} else if (dirStr == kGzToRos) {
ret.direction = BridgeDirection::GZ_TO_ROS;
} else if (direction == kRosToGz) {
} else if (dirStr == kRosToGz) {
ret.direction = BridgeDirection::ROS_TO_GZ;
} else {
RCLCPP_ERROR(
logger,
"Could not parse entry: invalid direction [%s]", direction.c_str());
"Could not parse entry: invalid direction [%s]", dirStr.c_str());
return {};
}
}

if (!topic_name.empty()) {

if (yaml_node[kTopicName]) {
// Only "topic_name" is set
ret.gz_topic_name = topic_name;
ret.ros_topic_name = topic_name;
} else if (!ros_topic_name.empty() && gz_topic_name.empty()) {
ret.gz_topic_name = yaml_node[kTopicName].as<std::string>();
ret.ros_topic_name = yaml_node[kTopicName].as<std::string>();
} else if (yaml_node[kRosTopicName] && !yaml_node[kGzTopicName]) {
// Only "ros_topic_name" is set
ret.gz_topic_name = ros_topic_name;
ret.ros_topic_name = ros_topic_name;
} else if (!gz_topic_name.empty() && ros_topic_name.empty()) {
ret.gz_topic_name = yaml_node[kRosTopicName].as<std::string>();
ret.ros_topic_name = yaml_node[kRosTopicName].as<std::string>();
} else if (yaml_node[kGzTopicName] && !yaml_node[kRosTopicName]) {
// Only kGzTopicName is set
ret.gz_topic_name = gz_topic_name;
ret.ros_topic_name = gz_topic_name;
ret.gz_topic_name = yaml_node[kGzTopicName].as<std::string>();
ret.ros_topic_name = yaml_node[kGzTopicName].as<std::string>();
} else {
// Both are set
ret.gz_topic_name = gz_topic_name;
ret.ros_topic_name = ros_topic_name;
ret.gz_topic_name = yaml_node[kGzTopicName].as<std::string>();
ret.ros_topic_name = yaml_node[kRosTopicName].as<std::string>();
}

ret.gz_type_name = gz_type_name;
ret.ros_type_name = ros_type_name;
ret.gz_type_name = yaml_node[kGzTypeName].as<std::string>();
ret.ros_type_name = yaml_node[kRosTypeName].as<std::string>();

if (yaml_node[kPublisherQueue]) {
ret.publisher_queue_size = yaml_node[kPublisherQueue].as<size_t>();
Expand Down
29 changes: 0 additions & 29 deletions ros_gz_bridge/src/convert/geometry_msgs.cpp
Expand Up @@ -106,35 +106,6 @@ convert_gz_to_ros(
convert_gz_to_ros(gz_msg.orientation(), ros_msg.orientation);
}

template<>
void
convert_ros_to_gz(
const geometry_msgs::msg::PoseArray & ros_msg,
gz::msgs::Pose_V & gz_msg)
{
convert_ros_to_gz(ros_msg.header, (*gz_msg.mutable_header()));
gz_msg.clear_pose();
for (auto const & t : ros_msg.poses) {
auto p = gz_msg.add_pose();
convert_ros_to_gz(t, *p);
}
}

template<>
void
convert_gz_to_ros(
const gz::msgs::Pose_V & gz_msg,
geometry_msgs::msg::PoseArray & ros_msg)
{
convert_gz_to_ros(gz_msg.header(), ros_msg.header);
ros_msg.poses.clear();
for (auto const & p : gz_msg.pose()) {
geometry_msgs::msg::Pose pose;
convert_gz_to_ros(p, pose);
ros_msg.poses.push_back(pose);
}
}

template<>
void
convert_ros_to_gz(
Expand Down
24 changes: 0 additions & 24 deletions ros_gz_bridge/src/convert/ros_gz_interfaces.cpp
Expand Up @@ -574,28 +574,4 @@ convert_gz_to_ros(
ros_msg.time_only = gz_msg.time_only();
ros_msg.model_only = gz_msg.model_only();
}

template<>
void
convert_ros_to_gz(
const ros_gz_interfaces::msg::Float32Array & ros_msg,
gz::msgs::Float_V & gz_msg)
{
gz_msg.clear_data();
for (auto const & t : ros_msg.data) {
gz_msg.add_data(t);
}
}

template<>
void
convert_gz_to_ros(
const gz::msgs::Float_V & gz_msg,
ros_gz_interfaces::msg::Float32Array & ros_msg)
{
ros_msg.data.clear();
for (auto const & p : gz_msg.data()) {
ros_msg.data.push_back(p);
}
}
} // namespace ros_gz_bridge

0 comments on commit 49ab767

Please sign in to comment.