Skip to content

Commit

Permalink
refactor Python module to compile only the relevant packages. Add ONL…
Browse files Browse the repository at this point in the history
…Y and IGNORE options at compile time

Signed-off-by: Olivier Kermorgant <olivier_kermorgant@yahoo.fr>
  • Loading branch information
oKermorgant committed Jul 27, 2023
1 parent 609451a commit d73388d
Show file tree
Hide file tree
Showing 5 changed files with 221 additions and 40 deletions.
68 changes: 46 additions & 22 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,10 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra)
endif()

find_package(rmw REQUIRED)
set(ROS1_BRIDGE_ONLY "none" CACHE STRING "Compile only these packages and their dependencies. Use semi colon to separate.")
set(ROS1_BRIDGE_IGNORE "none" CACHE STRING "Ignore these packages and the ones that depend on them. Use semi colon to separate.")

find_package(rmw REQUIRED)
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rmw_implementation_cmake REQUIRED)
Expand Down Expand Up @@ -48,20 +50,6 @@ find_ros1_package(std_msgs REQUIRED)
# 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)

set(prefixed_ros1_message_packages "")
foreach(ros1_message_package ${ros1_message_packages})
# TODO(karsten1987): This is currently a workaround to work with ROS 2 classloader
# rather than ROS 1 classloader.
if(NOT "${ros1_message_package}" STREQUAL "nodelet")
find_ros1_package(${ros1_message_package} REQUIRED)
list(APPEND prefixed_ros1_message_packages "ros1_${ros1_message_package}")
endif()
endforeach()

set(TEST_ROS1_BRIDGE FALSE)
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
Expand Down Expand Up @@ -131,18 +119,53 @@ set(generated_path "${CMAKE_BINARY_DIR}/generated")
set(generated_files "${generated_path}/get_factory.cpp")
list(APPEND generated_files "${generated_path}/get_mappings.cpp")


find_package(Python3 REQUIRED COMPONENTS Interpreter)

# get useful ROS 2 packages to FIND and paths to ROS 1 message headers
execute_process(
COMMAND bin/ros1_bridge_common_interfaces --only "${ROS1_BRIDGE_ONLY}" --ignore "${ROS1_BRIDGE_IGNORE}"
OUTPUT_VARIABLE all_interfaces
WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}
)

# parse output to get 2 lists: ROS 1 packages and ROS 2 per-package interfaces
list(GET all_interfaces 0 ros1_packages)
string(REPLACE ":" ";" ros1_packages ${ros1_packages})
list(GET all_interfaces 1 ros2_interfaces)
string(REPLACE ":" ";" ros2_interfaces ${ros2_interfaces})

# find ROS 1 packages with messages / services
# deprecated as Python now returns these depending on the only / ignores
#include(cmake/find_ros1_interface_packages.cmake)
#find_ros1_interface_packages(ros1_message_packages)

set(prefixed_ros1_message_packages "")
foreach(ros1_message_package ${ros1_packages})
# TODO(karsten1987): This is currently a workaround to work with ROS 2 classloader
# rather than ROS 1 classloader.
if(NOT "${ros1_message_package}" STREQUAL "nodelet")
find_ros1_package(${ros1_message_package} REQUIRED)
list(APPEND prefixed_ros1_message_packages "ros1_${ros1_message_package}")
endif()
endforeach()

# generate per interface compilation units to keep the memory usage low
ament_index_get_resources(ros2_interface_packages "rosidl_interfaces")
# actionlib_msgs is deprecated, but we will quiet the warning until the bridge has support for
# ROS actions: https://github.com/ros2/design/issues/195
set(actionlib_msgs_DEPRECATED_QUIET TRUE)
foreach(package_name ${ros2_interface_packages})
foreach(package_interfaces ${ros2_interfaces})

# get interfaces for this package
string(REPLACE "+" ";" package_interfaces ${package_interfaces})

# extract package name for dependencies
list(POP_FRONT package_interfaces package_name)
list(APPEND ros2_interface_packages ${package_name})

find_package(${package_name} QUIET REQUIRED)
message(STATUS "Found ${package_name}: ${${package_name}_VERSION} (${${package_name}_DIR})")
if(NOT "${package_name}" STREQUAL "builtin_interfaces")
list(APPEND generated_files "${generated_path}/${package_name}_factories.cpp")
list(APPEND generated_files "${generated_path}/${package_name}_factories.hpp")
foreach(interface_file ${${package_name}_IDL_FILES})
foreach(interface_file ${package_interfaces})
file(TO_CMAKE_PATH "${interface_file}" interface_name)
get_filename_component(interface_basename "${interface_name}" NAME_WE)
# skipping actions and request and response messages of services
Expand Down Expand Up @@ -172,6 +195,7 @@ add_custom_command(
COMMAND Python3::Interpreter
ARGS bin/ros1_bridge_generate_factories
--output-path "${generated_path}" --template-dir resource
--only "${ROS1_BRIDGE_ONLY}" --ignore "${ROS1_BRIDGE_IGNORE}"
DEPENDS ${target_dependencies}
WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}
COMMENT "Generating factories for interface types")
Expand All @@ -182,7 +206,7 @@ if(NOT WIN32)
PROPERTIES COMPILE_FLAGS "-Wno-unused-parameter")
endif()

include_directories(include ${generated_path})
include_directories(include ${generated_path} ${ros1_includes})

function(custom_executable target)
cmake_parse_arguments(
Expand Down
10 changes: 10 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -125,6 +125,16 @@ colcon build --symlink-install --packages-select ros1_bridge --cmake-force-confi

*Note:* If you are building on a memory constrained system you might want to limit the number of parallel jobs by setting e.g. the environment variable `MAKEFLAGS=-j1`.

#### Compilation options

The bridge can be compiled to consider only some ROS 2 packages, or to ignore some. This is set through two CMake variables:

- -DROS1_BRIDGE_ONLY='std_msgs;geometry_msgs'
- -DROS1_BRIDGE_IGNORE='my_disfunctionning_pkg_msgs;another_undesired_pkg'





## Example 1: run the bridge and the example talker and listener

Expand Down
55 changes: 55 additions & 0 deletions bin/ros1_bridge_common_interfaces
Original file line number Diff line number Diff line change
@@ -0,0 +1,55 @@
#!/usr/bin/env python3

import os
import sys
import argparse

# add ros1_bridge to the Python path
ros1_bridge_root = os.path.join(os.path.dirname(__file__), '..')
sys.path.insert(0, os.path.abspath(ros1_bridge_root))

from ros1_bridge import generate_bridged_pairs


def get_include_path(msg):
tail = f'/share/{msg.package_name}/msg'
return msg.prefix_path[:-len(tail)] + '/include'


def main(argv=sys.argv[1:]):

parser = argparse.ArgumentParser(description='Get relevant ROS 1 and ROS 2 messages to generate.',
formatter_class=argparse.ArgumentDefaultsHelpFormatter)
parser.add_argument('--only', type=str, help='Compile only these packages', default='')
parser.add_argument('--ignore', type=str, help='Skip these packages', default='')
args = parser.parse_args(argv)

try:
pairs = generate_bridged_pairs(args.only, args.ignore)

# isolate useful ROS 2 idls amongst these packages, to tell CMake what will be generated
ros2_pkgs = {pkg: pkg for pkg in pairs['ros2_package_names']}
for pkg in ros2_pkgs:
for interface in ('msg', 'srv'):
interfaces = [f'{interface}/{m.message_name}' for m in pairs[f'all_ros2_{interface}s'] if m.package_name == pkg]
if interfaces:
ros2_pkgs[pkg] += '+'+'+'.join(interfaces)
ros2_interfaces = ':'.join(ros2_pkgs.values())

# ROS 1 packages
ros1_interfaces = set(m.ros1_msg for m in pairs['mappings'])
ros1_srv_pkgs = set(srv['ros1_package'] for srv in pairs['services'])
ros1_interfaces.update(srv for srv in pairs['all_ros1_srvs'] if srv.package_name in ros1_srv_pkgs)
ros1_pkgs = ':'.join(set(msg.package_name for msg in ros1_interfaces))

# return as nested list for CMake, no linebreak to avoid passing it to CMake
print(f'{ros1_pkgs};{ros2_interfaces}', end='')

return 0
except RuntimeError as e:
print(str(e), file=sys.stderr)
return 1


if __name__ == '__main__':
sys.exit(main())
6 changes: 5 additions & 1 deletion bin/ros1_bridge_generate_factories
Original file line number Diff line number Diff line change
Expand Up @@ -23,13 +23,17 @@ def main(argv=sys.argv[1:]):
'--template-dir',
required=True,
help='The location of the template files')
parser.add_argument('--only', type=str, help='Compile only these packages', default='')
parser.add_argument('--ignore', type=str, help='Skip these packages', default='')

args = parser.parse_args(argv)

try:
return generate_cpp(
args.output_path,
args.template_dir,
)
args.only, args.ignore)

except RuntimeError as e:
print(str(e), file=sys.stderr)
return 1
Expand Down
Loading

0 comments on commit d73388d

Please sign in to comment.