Skip to content

Commit

Permalink
RST-6618 fixes for action bridge (#2)
Browse files Browse the repository at this point in the history
Fixed action_bridge changes to work with newer ros2 releases and added support for skipping previously built generated factories to speed up recompiling.
  • Loading branch information
abencz committed Feb 7, 2024
1 parent a2c6441 commit 3a35ce4
Show file tree
Hide file tree
Showing 4 changed files with 63 additions and 22 deletions.
10 changes: 5 additions & 5 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -532,14 +532,14 @@ Note that the `qos` section can be omitted entirely and options not set are left

This bridge extends the `ros1_bridge` to support actions. The bridge works in both directions, meaning an action goal can be sent from ROS 1 client to ROS 2 server, or from ROS 2 client to ROS 1 server.

The arguments for the `action_bridge` node are:
The arguments for the `action_bridge` node are:
`direction`: from client (`ros1` or `ros2`)
e.g.:
- `ROS1` client to `ROS2` server --> `direction` = `ros1`
- `ROS2` client to `ROS1` server --> `direction` = `ros2`
- `ROS1` client to `ROS2` server --> `direction` = `ros2`
- `ROS2` client to `ROS1` server --> `direction` = `ros1`

`package`: package of the `ROS1` server node
`type`: action interface type of `ROS1`
`package`: package of the `ROS1` server node
`type`: action interface type of `ROS1`
`name`: action name

For sending goals from a ROS 2 action client to a ROS 1 action server
Expand Down
2 changes: 1 addition & 1 deletion include/ros1_bridge/action_factory.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -146,7 +146,7 @@ class ActionFactory_1_2 : public ActionFactoryInterface
std::shared_future<ROS2ClientGoalHandle> gh2_future;
auto send_goal_ops = ROS2SendGoalOptions();
send_goal_ops.goal_response_callback =
[this, &gh2_future](std::shared_future<ROS2GoalHandle> gh2) mutable {
[this, &gh2_future](ROS2GoalHandle gh2) mutable {
auto goal_handle = gh2_future.get();
if (!goal_handle) {
gh1_.setRejected(); // goal was not accepted by remote server
Expand Down
22 changes: 11 additions & 11 deletions resource/interface_factories.cpp.em
Original file line number Diff line number Diff line change
Expand Up @@ -405,27 +405,27 @@ void ActionFactory_@(frm_)_@(to_)<
@(action["ros2_package"])::action::@(action["ros2_name"])
>::translate_@(type.lower())_@(frm)_to_@(to)(
@[ if type == "Goal"]@
@(const_1)ROS@(frm)@(type) &@(type.lower())@(frm),
@(const_2)ROS@(to)@(type) &@(type.lower())@(to))
@(const_1)ROS@(frm)@(type) &@(type.lower())_msg@(frm),
@(const_2)ROS@(to)@(type) &@(type.lower())_msg@(to))
@[ else]@
@(const_1)ROS@(to)@(type) &@(type.lower())@(to),
@(const_2)ROS@(frm)@(type) &@(type.lower())@(frm))
@(const_1)ROS@(to)@(type) &@(type.lower())_msg@(to),
@(const_2)ROS@(frm)@(type) &@(type.lower())_msg@(frm))
@[ end if]@
{
@[ for field in action["fields"][type.lower()]]@
@[ if field["array"]]@
@(type.lower())@(to).@(field["ros" + to]["name"]).resize(@(type.lower())@(frm).@(field["ros" + frm]["name"]).size());
auto @(field["ros" + frm]["name"])@(frm)_it = @(type.lower())@(frm).@(field["ros" + frm]["name"]).begin();
auto @(field["ros" + to]["name"])@(to)_it = @(type.lower())@(to).@(field["ros" + to]["name"]).begin();
@(type.lower())_msg@(to).@(field["ros" + to]["name"]).resize(@(type.lower())_msg@(frm).@(field["ros" + frm]["name"]).size());
auto @(field["ros" + frm]["name"])@(frm)_it = @(type.lower())_msg@(frm).@(field["ros" + frm]["name"]).begin();
auto @(field["ros" + to]["name"])@(to)_it = @(type.lower())_msg@(to).@(field["ros" + to]["name"]).begin();
while (
@(field["ros" + frm]["name"])@(frm)_it != @(type.lower())@(frm).@(field["ros" + frm]["name"]).end() &&
@(field["ros" + to]["name"])@(to)_it != @(type.lower())@(to).@(field["ros" + to]["name"]).end()
@(field["ros" + frm]["name"])@(frm)_it != @(type.lower())_msg@(frm).@(field["ros" + frm]["name"]).end() &&
@(field["ros" + to]["name"])@(to)_it != @(type.lower())_msg@(to).@(field["ros" + to]["name"]).end()
) {
auto & @(field["ros" + frm]["name"])@(frm) = *(@(field["ros" + frm]["name"])@(frm)_it++);
auto & @(field["ros" + to]["name"])@(to) = *(@(field["ros" + to]["name"])@(to)_it++);
@[ else]@
auto & @(field["ros" + frm]["name"])@(frm) = @(type.lower())@(frm).@(field["ros" + frm]["name"]);
auto & @(field["ros" + to]["name"])@(to) = @(type.lower())@(to).@(field["ros" + to]["name"]);
auto & @(field["ros" + frm]["name"])@(frm) = @(type.lower())_msg@(frm).@(field["ros" + frm]["name"]);
auto & @(field["ros" + to]["name"])@(to) = @(type.lower())_msg@(to).@(field["ros" + to]["name"]);
@[ end if]@
@[ if field["basic"]]@
@[ if field["ros2"]["type"].startswith("builtin_interfaces") ]@
Expand Down
51 changes: 46 additions & 5 deletions ros1_bridge/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,10 @@
from collections import OrderedDict
import os
import re
import shutil
import sys
import tempfile
import filecmp

import ament_index_python
from catkin_pkg.package import parse_package
Expand Down Expand Up @@ -72,6 +75,15 @@


def generate_cpp(output_path, template_dir):
# Temporary directory is used to hold generated files, which are only
# copied into place if they differ from previously generated files. This
# ensures that timestamps on files that have not changed are not updated
# and saves a ton of compile time.
with tempfile.TemporaryDirectory() as tempdir:
_generate_cpp(output_path, template_dir, tempdir)


def _generate_cpp(output_path, template_dir, temporary_dir):
rospack = rospkg.RosPack()
data = generate_messages(rospack)
message_string_pairs = {
Expand All @@ -84,11 +96,17 @@ def generate_cpp(output_path, template_dir):
data.update(generate_actions(
rospack, message_string_pairs=message_string_pairs))

# create output folder if it doesn't exist
if not os.path.exists(output_path):
os.makedirs(output_path)

template_file = os.path.join(template_dir, 'get_mappings.cpp.em')
temporary_file = os.path.join(temporary_dir, 'get_mappings.cpp')
output_file = os.path.join(output_path, 'get_mappings.cpp')
data_for_template = {
'mappings': data['mappings'], 'services': data['services'], 'actions': data['actions']}
expand_template(template_file, data_for_template, output_file)
expand_template(template_file, data_for_template, temporary_file)
update_output_file(temporary_file, output_file)

unique_package_names = set(
data['ros2_package_names_msg'] + data['ros2_package_names_srv'])
Expand All @@ -97,8 +115,10 @@ def generate_cpp(output_path, template_dir):
data['ros2_package_names'] = list(unique_package_names)

template_file = os.path.join(template_dir, 'get_factory.cpp.em')
temporary_file = os.path.join(temporary_dir, 'get_factory.cpp')
output_file = os.path.join(output_path, 'get_factory.cpp')
expand_template(template_file, data, output_file)
expand_template(template_file, data, temporary_file)
update_output_file(temporary_file, output_file)

for ros2_package_name in data['ros2_package_names']:
data_pkg_hpp = {
Expand Down Expand Up @@ -126,9 +146,12 @@ def generate_cpp(output_path, template_dir):
if m.ros2_msg.package_name == ros2_package_name],
}
template_file = os.path.join(template_dir, 'pkg_factories.hpp.em')
temporary_file = os.path.join(
temporary_dir, '%s_factories.hpp' % ros2_package_name)
output_file = os.path.join(
output_path, '%s_factories.hpp' % ros2_package_name)
expand_template(template_file, data_pkg_hpp, output_file)
expand_template(template_file, data_pkg_hpp, temporary_file)
update_output_file(temporary_file, output_file)

data_pkg_cpp = {
'ros2_package_name': ros2_package_name,
Expand All @@ -138,9 +161,12 @@ def generate_cpp(output_path, template_dir):
'ros2_action_types': data_pkg_hpp['ros2_action_types'],
}
template_file = os.path.join(template_dir, 'pkg_factories.cpp.em')
temporary_file = os.path.join(
temporary_dir, '%s_factories.cpp' % ros2_package_name)
output_file = os.path.join(
output_path, '%s_factories.cpp' % ros2_package_name)
expand_template(template_file, data_pkg_cpp, output_file)
expand_template(template_file, data_pkg_cpp, temporary_file)
update_output_file(temporary_file, output_file)

for interface_type, interfaces in zip(
['msg', 'srv', 'action'], [data['all_ros2_msgs'],
Expand Down Expand Up @@ -175,10 +201,25 @@ def generate_cpp(output_path, template_dir):

template_file = os.path.join(
template_dir, 'interface_factories.cpp.em')
temporary_file = os.path.join(
temporary_dir, '%s__%s__%s__factories.cpp' %
(ros2_package_name, interface_type, interface.message_name))
output_file = os.path.join(
output_path, '%s__%s__%s__factories.cpp' %
(ros2_package_name, interface_type, interface.message_name))
expand_template(template_file, data_idl_cpp, output_file)
expand_template(template_file, data_idl_cpp, temporary_file)
update_output_file(temporary_file, output_file)


def update_output_file(temporary_file, output_file):
"""Copy temporary file to output file if the two differ"""
try:
files_same = filecmp.cmp(temporary_file, output_file)
except FileNotFoundError:
files_same = False

if not files_same:
shutil.copyfile(temporary_file, output_file)


def generate_messages(rospack=None):
Expand Down

0 comments on commit 3a35ce4

Please sign in to comment.