The ComponentContainer and Executor that assign a dedicated thread for each callback group.
$ git clone https://github.com/sykwer/callback_isolated_executor.git
$ cd callback_isolated_executor
$ source /opt/ros/humble/setup.bash
$ colcon build
$ source install/setup.bash
Set capability for the configurator executable to issue the syscalls like sched_setscheduler(2)
.
$ sudo setcap cap_sys_nice+ep ./build/ros2_thread_configurator/thread_configurator_node
After elevating the priviridge level, part of dynamic linking functionality gets disabled for the security reason.
To deal with it, add a file with the following content under the /etc/ld.so.conf.d/
directory.
The file name has to be *.conf
.
/opt/ros/humble/lib
/opt/ros/humble/lib/x86_64-linux-gnu
/path/to/callback_isolated_executor/install/thread_config_msgs/lib
To enable the configuration, type the command below.
$ sudo ldconfig
Why ldconfig changed?
When specific permissions are granted to an ELF binary using setcap, for security reasons, environment variables like LD_PRELOAD
and LD_LIBRARY_PATH
are ignored.
While setting RUNPATH
on the binary comes to mind as a solution, RUNPATH
does not easily handle recursive dynamic linking.
In such cases, modifying /etc/ld.so.conf.d/
is the only option.
According to the Linux Kernel documentation, setting the affinity for SCHED_DEADLINE
tasks requires the use of cgroup v1 features.
To use cgroup v1, it is necessary to disable cgroup v2 by specifying systemd.unified_cgroup_hierarchy=0
in the kernel boot parameters.
To change the kernel boot parameters, edit /etc/default/grub
and add the parameter to GRUB_CMDLINE_LINUX_DEFAULT
:
GRUB_CMDLINE_LINUX_DEFAULT="... systemd.unified_cgroup_hierarchy=0 ..."
To apply these changes, run the following commands. After rebooting, the features of cgroup v1 will be available:
$ sudo update-grub
$ sudo reboot
When running a node within ComponentContainerCallbackIsolated
, you don't need to modify the node's implementation.
However, if starting the node directly from the main function without using ComponentContainer, you need to modify the node's implementation as shown below and rebuild it.
Refer to the source code in the sample_app_callback_isolated package to understand how to modify your app.
If you are launching a node directly from the main function without using a ComponentContainer, change the name of the Executor.
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
...
<depend>rclcpp_component_container_callback_isolated</depend>
...
</package>
...
find_package(rclcpp_component_container_callback_isolated REQUIRED)
...
ament_target_dependencies(your_executable ... rclcpp_component_container_callback_isolated)
...
#include "static_callback_isolated_executor.hpp"
int main(int argc, char * argv[]) {
rclcpp::init(argc, argv);
auto node = std::make_shared<SampleNode>();
auto executor = std::make_shared<StaticCallbackIsolatedExecutor>();
executor->add_node(node);
executor->spin();
rclcpp::shutdown();
return 0;
}
Or, if you want to using realtime policy setting function without callback function level executors, all you need to do is changing spin()
to spin_node()
.
Why named "Static"CallbackIsolatedExecutor ?
For performance reasons, we were using StaticSingleThreadedExecutor
internally. Currently, we are temporarily using SingleThreadedExecutor
internally because CARET does not yet support StaticSingleThreadedExecutor
.
If you are launching a node within ComponentContainerCallbackIsolated
, all you have to do is modify the launch file as below.
<launch>
<node_container pkg="rclcpp_component_container_callback_isolated" exec="component_container_callback_isolated" name="sample_container" namespace="">
<composable_node pkg="rclcpp_component_container_callback_isolated" plugin="SampleNode" name="sample_node" namespace="">
...
</composable_node>
</node_container>
</launch>
Or, you can load the node to the existing component container.
<launch>
<load_composable_node target="sample_container">
<composable_node pkg="rclcpp_component_container_callback_isolated" plugin="SampleNode" name="sample_node" namespace="">
</composable_node>
</load_composable_node>
</launch>
If you want to launching a composite container with realtime setting function without overnumber executors, just using component_container_node
instead of component_container_callback_isolated
<launch>
<node_container pkg="rclcpp_component_container_callback_isolated" exec="component_container_node" name="sample_container" namespace="">
<composable_node pkg="rclcpp_component_container_callback_isolated" plugin="SampleNode" name="sample_node" namespace="">
...
</composable_node>
</node_container>
</launch>
Moreover, if you want to have something like component_container
, which only have one singleThreadedExecutor
in one container
, component_container_rt
is the answer.
<launch>
<node_container pkg="rclcpp_component_container_callback_isolated" exec="component_container_rt" name="sample_container" namespace="">
<composable_node pkg="rclcpp_component_container_callback_isolated" plugin="SampleNode" name="sample_node" namespace="">
...
</composable_node>
</node_container>
</launch>
If you modify the application's source code, a rebuild is necessary.
Open two terminal windows.
In one, launch a ROS 2 node to create a template for the YAML configuration file (prerun
node), and in the other, launch the target ROS 2 application.
After launching the prerun
node, launch your ROS 2 application.
To launch the prerun
node, type the command below.
$ ros2 run ros2_thread_configurator thread_configurator_node --prerun
Then launch your ROS 2 application in another terminal window, after which you can see log messages like shown below in the prerun
node window.
Each entry corresponds to the callback group ID and its OS thread ID.
Once all the nodes of the target application are up and the logs in the prerun node window have stopped, press Control+C in the prerun node window.
Then, in the current directory, a template for the YAML configuration file template.yaml
will be created in the format like below.
callback_groups:
- id: /sample_node@Subscription(/parameter_events)@Service(/sample_node/get_parameters)@Service(/sample_node/get_parameter_types)@Service(/sample_node/set_parameters)@Service(/sample_node/set_parameters_atomically)@Service(/sample_node/describe_parameters)@Service(/sample_node/list_parameters)@Waitable@Waitable@Waitable@Waitable
affinity: ~
policy: SCHED_OTHER
priority: 0
- id: /sample_node@Subscription(/topic_in)@Waitable
affinity: ~
policy: SCHED_OTHER
priority: 0
- id: /sample_node@Timer(1333000000)
affinity: ~
policy: SCHED_OTHER
priority: 0
- id: /sample_node@Timer(3000000000)
affinity: ~
policy: SCHED_OTHER
priority: 0
Once the creation of template.yaml is complete, please also terminate the target ROS 2 application.
Change the file name and edit to configure each callback group.
$ mv template.yaml your_config.yaml
$ vim your_config.yaml
For callback groups that do not require configuration, you can either delete the entry entirely or leave it as is because the default values in template.yaml
are set with default nice values and no affinity settings on the CFS scheduler.
For the detailed specifications of the configuration file, please refer to https://github.com/sykwer/callback_isolated_executor/tree/main/ros2_thread_configurator#yaml-configuration-file-format.
To launch the target ROS 2 application with the scheduler settings applied from the your_config.yaml you created, first start the configurator node with the following command.
$ ros2 run ros2_thread_configurator thread_configurator_node --config-file your_config.yaml
If there is a callback group with the SCHED_DEADLINE
scheduling policy specified, running the configurator node requires root privileges.
This is because it is not possible to set threads to SCHED_DEADLINE within the permissions that can be granted through capability.
Note that if the target ROS 2 application is operating with a specific ROS_DOMAIN_ID, the configurator node must also be operated with the same ROS_DOMAIN_ID.
$ sudo bash -c "export ROS_DOMAIN_ID=[app domain id]; source /path/to/callback_isolated_executor/install/setup.bash; ros2 run ros2_thread_configurator thread_configurator_node --config-file your_config.yaml"
Immediately after launching the configurator node, it will print the settings and then wait for the target ROS 2 application to start running as follows.
In this state, when you launch the target ROS 2 application, the configurator node's window will display the message Apply sched deadline?
and wait as below.
The entries above the waiting message each show the callback group ID and OS thread ID information received from the ROS 2 application.
At this stage, settings with policies other than SCHED_DEADLINE
have already been applied, while the application of settings including the SCHED_DEADLINE
policy is postponed.
To apply settings that include the SCHED_DEADLINE
policy, press the enter key in the window where Apply sched deadline?
is displayed.
Why delayed configuration of the SCHED_DEADLINE policy?
We delay the applying of settings with the SCHED_DEADLINE
policy because Autoware (main application area for this tool) contains nodes that implicitly create new threads immediately after startup, such as the EKF Localizer.
Threads specified with the SCHED_DEADLINE
policy are prohibited from creating new child tasks.
Generally, real-time scheduling policies fail with an EAGAIN
error when clone(2)
is issued without the SCHED_FLAG_RESET_ON_FORK
flag set.
However, setting this flag for SCHED_DEADLINE
threads is impossible due to the following facts:
- According to the Linux documentation for sched_setattr(2), the
flags
argument is currently required to be set to0
, indicating thatSCHED_FLAG_RESET_ON_FORK
can only be set viasched_setscheduler(2)
. - According to the Linux documentation for sched_setscheduler(2), the
SCHED_DEADLINE
policy can only be set viasched_setattr(2)
and not throughsched_setscheduler(2)
.
Thus, we adopt a workaround where we delay only the settings that include the SCHED_DEADLINE
policy.
Autoware's EKF Localizer creates child threads immediately after starting and does not create more afterwards (these child threads are likely deleted soon after).
Therefore, applying the SCHED_DEADLINE
policy after the system has started, such as after starting playback of a rosbag or the operation of a real vehicle system, will not cause issues.
You need to apply the SCHED_DEADLINE
policy only after the system has fully started up and no further creation of new child threads is expected.
While the target ROS 2 application is running, the configurator node's window should not be closed and must remain open.
After the execution of the target ROS 2 application has ended, press the enter key in the window displaying Press enter to exit and remove cgroups...
.
This will terminate the execution of the configurator node and simultaneously delete the cgroup that was created for setting the affinity of tasks with the SCHED_DEADLINE
policy.