Skip to content

Commit

Permalink
Parametrization of parameter_bridge quality of service [Port of the…
Browse files Browse the repository at this point in the history
… commits (ec44770) and (86b4245) to foxy branch] (#401)

* Port of the commit (ec44770) to foxy branch

Just reproduces the changes made in #331 in ros foxy.

Parametrize Quality of Service in `parameter_bridge`

Signed-off-by: Lucyanno Frota <lucyannofrota@gmail.com>

* Port of the commit (86b4245) to foxy branch

Reproduces the changes made in #371 in ros foxy.

Move xmlrpcpp find_package so it only searches if ROS 1 is found

Signed-off-by: Lucyanno Frota <lucyannofrota@gmail.com>

* CI fix

White spaces removed
Signed-off-by: Lucyanno Frota <lucyannofrota@gmail.com>

---------

Signed-off-by: Lucyanno Frota <lucyannofrota@gmail.com>
  • Loading branch information
lucyannofrota authored May 24, 2023
1 parent 3209bc7 commit 2c24a8d
Show file tree
Hide file tree
Showing 7 changed files with 366 additions and 3 deletions.
4 changes: 4 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,10 @@ endif()

find_ros1_package(std_msgs REQUIRED)

# Dependency that we should only look for if ROS 1 is installed (it's not present on a ROS 2
# system; see https://github.com/ros2/ros1_bridge/pull/331#issuecomment-1188111510)
find_package(xmlrpcpp REQUIRED)

# find ROS 1 packages with messages / services
include(cmake/find_ros1_interface_packages.cmake)
find_ros1_interface_packages(ros1_message_packages)
Expand Down
117 changes: 117 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -346,3 +346,120 @@ Launch AddTwoInts client:
. <ros2-install-dir>/setup.bash
ros2 run demo_nodes_cpp add_two_ints_client
```

## Example 4: bridge only selected topics and services
This example expands on example 3 by selecting a subset of topics and services to be bridged.
This is handy when, for example, you have a system that runs most of it's stuff in either ROS 1 or ROS 2 but needs a few nodes from the 'opposite' version of ROS.
Where the `dynamic_bridge` bridges all topics and service, the `parameter_bridge` uses the ROS 1 parameter server to choose which topics and services are bridged.
For example, to bridge only eg. the `/chatter` topic and the `/add_two_ints service` from ROS1 to ROS2, create this configuration file, `bridge.yaml`:

```yaml
topics:
-
topic: /chatter # ROS1 topic name
type: std_msgs/msg/String # ROS2 type name
queue_size: 1 # For the publisher back to ROS1
services_1_to_2:
-
service: /add_two_ints # ROS1 service name
type: example_interfaces/srv/AddTwoInts # The ROS2 type name
```
Start a ROS 1 roscore:
```bash
# Shell A (ROS 1 only):
. /opt/ros/melodic/setup.bash
# Or, on OSX, something like:
# . ~/ros_catkin_ws/install_isolated/setup.bash
roscore
```

Then load the bridge.yaml config file and start the talker to publish on the `/chatter` topic:

```bash
Shell B: (ROS1 only):
. /opt/ros/melodic/setup.bash
# Or, on OSX, something like:
# . ~/ros_catkin_ws/install_isolated/setup.bash
rosparam load bridge.yaml

rosrun rospy_tutorials talker
```

```bash
Shell C: (ROS1 only):
. /opt/ros/melodic/setup.bash
# Or, on OSX, something like:
# . ~/ros_catkin_ws/install_isolated/setup.bash

rosrun roscpp_tutorials add_two_ints_server
```

Then, in a few ROS 2 terminals:

```bash
# Shell D:
. <install-space-with-ros2>/setup.bash
ros2 run ros1_bridge parameter_bridge
```

If all is well, the logging shows it is creating bridges for the topic and service and you should be able to call the service and listen to the ROS 1 talker from ROS 2:

```bash
# Shell E:
. <install-space-with-ros2>/setup.bash
ros2 run demo_nodes_cpp listener
```
This should start printing text like `I heard: [hello world ...]` with a timestamp.

```bash
# Shell F:
. <install-space-with-ros2>/setup.bash
ros2 service call /add_two_ints example_interfaces/srv/AddTwoInts "{a: 1, b: 2}"
```
If all is well, the output should contain `example_interfaces.srv.AddTwoInts_Response(sum=3)`

### Parametrizing Quality of Service
An advantage of ROS 2 over ROS 1 is the possibility to define different Quality of Service settings per topic.
The parameter bridge optionally allows for this as well.
For some topics, like `/tf_static` this is actually required, as this is a latching topic in ROS 1.
In ROS 2 with the `parameter_bridge`, this requires that topic to be configured as such:

```yaml
topics:
-
topic: /tf_static
type: tf2_msgs/msg/TFMessage
queue_size: 1
qos:
history: keep_all
durability: transient_local
```
All other QoS options (as documented here in https://docs.ros.org/en/foxy/Concepts/About-Quality-of-Service-Settings.html) are available:
```yaml
topics:
-
topic: /some_ros1_topic
type: std_msgs/msg/String
queue_size: 1
qos:
history: keep_last # OR keep_all, then you can omit `depth` parameter below
depth: 10 # Only required when history == keep_last
reliability: reliable # OR best_effort
durability: transient_local # OR volatile
deadline:
secs: 10
nsecs: 2345
lifespan:
secs: 20
nsecs: 3456
liveliness: liveliness_system_default # Values from https://design.ros2.org/articles/qos_deadline_liveliness_lifespan.html, eg. LIVELINESS_AUTOMATIC
liveliness_lease_duration:
secs: 40
nsecs: 5678
```
Note that the `qos` section can be omitted entirely and options not set are left default.
Empty file modified bin/ros1_bridge_generate_factories
100755 → 100644
Empty file.
10 changes: 10 additions & 0 deletions include/ros1_bridge/bridge.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -127,6 +127,16 @@ create_bidirectional_bridge(
const std::string & topic_name,
size_t queue_size = 10);

BridgeHandles
create_bidirectional_bridge(
ros::NodeHandle ros1_node,
rclcpp::Node::SharedPtr ros2_node,
const std::string & ros1_type_name,
const std::string & ros2_type_name,
const std::string & topic_name,
size_t queue_size,
const rclcpp::QoS & publisher_qos);

} // namespace ros1_bridge

#endif // ROS1_BRIDGE__BRIDGE_HPP_
1 change: 1 addition & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
<build_depend>rcutils</build_depend>
<build_depend>rmw_implementation_cmake</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>xmlrpcpp</build_depend>

<buildtool_export_depend>pkg-config</buildtool_export_depend>

Expand Down
24 changes: 24 additions & 0 deletions src/bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -137,4 +137,28 @@ create_bidirectional_bridge(
return handles;
}

BridgeHandles
create_bidirectional_bridge(
ros::NodeHandle ros1_node,
rclcpp::Node::SharedPtr ros2_node,
const std::string & ros1_type_name,
const std::string & ros2_type_name,
const std::string & topic_name,
size_t queue_size,
const rclcpp::QoS & publisher_qos)
{
RCLCPP_INFO(
ros2_node->get_logger(), "create bidirectional bridge for topic %s",
topic_name.c_str());
BridgeHandles handles;
handles.bridge1to2 = create_bridge_from_1_to_2(
ros1_node, ros2_node,
ros1_type_name, topic_name, queue_size, ros2_type_name, topic_name, publisher_qos);
handles.bridge2to1 = create_bridge_from_2_to_1(
ros2_node, ros1_node,
ros2_type_name, topic_name, queue_size, ros1_type_name, topic_name, queue_size,
handles.bridge1to2.ros2_publisher);
return handles;
}

} // namespace ros1_bridge
Loading

0 comments on commit 2c24a8d

Please sign in to comment.