The basic idea of ROS2 composition is to have a unified API in place of ROS1 nodes and nodelets. Nodelets in ROS1 are compiled into shared libraries and can be loaded into one process during runtime through the tool chain. This way, nodelets can achieve zero copy in communication. The ROS2 composition mechanism is to achieve that too.
For example, in a SLAM system, we can have two component FrontEnd and BackEnd. We can dynamically load them into the same SLAM process and achieve zero-copy IPC (on the RMW/DDS middleware layer)
These two components are built into shared libraries.
They subclass rclcpp::Node, and can launch their own topics, timers, etc.
Then, they are registered using a macro (from the package rclcpp_components) so they are discoverable for runtime-loading.
#include<rclcpp/rclcpp.hpp>namespacecomposition{classTalker:publicrclcpp::Node{public:explicitTalker(constrclcpp::NodeOptions&options):Node("talker",options){publisher_=this->create_publisher<std_msgs::msg::String>("chatter",10);timer_=this->create_wall_timer(std::chrono::milliseconds(500),[this](){automsg=std_msgs::msg::String();msg.data="hello from composable talker";publisher_->publish(msg);});}private:rclcpp::Publisher<std_msgs::msg::String>::SharedPtrpublisher_;rclcpp::TimerBase::SharedPtrtimer_;};}// namespace composition// register with class loader — makes “composition::Talker” discoverable#include<rclcpp_components/register_node_macro.hpp>RCLCPP_COMPONENTS_REGISTER_NODE(composition::Talker)
cmake_minimum_required(VERSION 3.5)project(my_package)find_package(ament_cmake REQUIRED)find_package(rclcpp REQUIRED)find_package(rclcpp_components REQUIRED)find_package(std_msgs REQUIRED)add_library(talker_component SHARED
src/talker_component.cpp
)# link in ROS 2 dependenciesament_target_dependencies(talker_component
rclcpp
rclcpp_components
std_msgs
)# register the component (this expands to RCLCPP_COMPONENTS_REGISTER_NODE)rclcpp_components_register_nodes(talker_component
"composition::Talker")# install rulesinstall(
TARGETS talker_component
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
)ament_package()
1
2
- `rclcpp_components_register_nodes` must appear after add_library and ament_target_dependencies.
- You only register each class once, even if you have multiple RCLCPP_COMPONENTS_REGISTER_NODE lines (one per class).
// src/SLAM.cpp#include<rclcpp/rclcpp.hpp>
#include<rclcpp_components/component_manager.hpp>intmain(intargc,char**argv){rclcpp::init(argc,argv);// In-process container that will hold all your componentsautocontainer=std::make_shared<rclcpp_components::ComponentManager>(rclcpp::NodeOptions{});// Load FrontEnd (talker) into the containercontainer->load_component("my_package",// library name (package name by default)"composition::Talker"// fully-qualified class name);// (Optionally) load more components here:// container->load_component("my_package", "composition::Listener");// container->load_component("other_pkg", "other_namespace::BackEnd");rclcpp::executors::StaticSingleThreadedExecutorexec;exec.add_node(container);exec.spin();rclcpp::shutdown();return0;}
CMakeLists.txt
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
add_executable(slam_containersrc/SLAM.cpp)ament_target_dependencies(slam_containerrclcpprclcpp_components)# Ensure the container links against all component libraries
# so the symbols are available at load time.
target_link_libraries(slam_containertalker_component#ifinsamepackage# other_component_lib # list any other component libs you intend to load
)install(TARGETSslam_containerRUNTIMEDESTINATIONlib/${PROJECT_NAME})