Skip to content

Tutorial#

This tutorial walks through the full workflow with the cie_sample_application package: launch a sample application under CallbackIsolatedExecutor, generate a thread configuration template, apply scheduling parameters, and verify the result.

It assumes you have already completed Build and Install and the thread configurator setup (granting capabilities and configuring library paths).

Sample Application#

SampleNode (node name sample_node, namespace /sample_space/sample_subspace) has three MutuallyExclusive CallbackGroups, each getting its own OS thread under CallbackIsolatedExecutor:

  • a 3000 ms timer (timer_callback, publishes on topic_out)
  • a 1333 ms timer (timer_callback2, publishes on topic_out2)
  • a subscription on topic_in

It also spawns a non-ROS worker thread named sample_non_ros_thread via spawn_non_ros2_thread (see Non-ROS Threads).

Step 1: Launch the Application#

ros2 launch cie_sample_application sample_node.launch.xml

This starts component_container_callback_isolated and loads SampleNode into it. You should see interleaved log messages from the two timer callbacks, each printing its own thread ID (tid), plus periodic messages from the non-ROS worker thread. Stop it with Ctrl+C for now.

Step 2: Generate a Template#

Start the prerun node before launching the application:

# Terminal 1: prerun node
ros2 launch cie_thread_configurator thread_configurator.launch.xml prerun:=true

# Terminal 2: the sample application
ros2 launch cie_sample_application sample_node.launch.xml

Wait until the prerun log output settles (all CallbackGroups discovered), then press Ctrl+C in Terminal 1. A template.yaml is created in the current directory. Its CallbackGroup IDs are generated automatically and look like this (the default group's id, listing every parameter service, is long and abbreviated here):

hardware_info:
  model_name: Intel(R) Xeon(R) Silver 4216 CPU @ 2.10GHz
  cpu_family: 6
  model: 85
  threads_per_core: 1
  frequency_boost: enabled
  cpu_max_mhz: 2101.0000
  cpu_min_mhz: 800.0000

callback_groups:
  # default group: /parameter_events + parameter services (full id generated by prerun)
  - id: /sample_space/sample_subspace/sample_node@Subscription(/parameter_events)@Service(...)
    affinity: ~
    policy: SCHED_OTHER
    priority: 0

  - id: /sample_space/sample_subspace/sample_node@Timer(3000000000)
    affinity: ~
    policy: SCHED_OTHER
    priority: 0

  - id: /sample_space/sample_subspace/sample_node@Timer(1333000000)
    affinity: ~
    policy: SCHED_OTHER
    priority: 0

  - id: /sample_space/sample_subspace/sample_node@Subscription(/sample_space/sample_subspace/topic_in)
    affinity: ~
    policy: SCHED_OTHER
    priority: 0

non_ros_threads:
  - id: sample_non_ros_thread
    affinity: ~
    policy: SCHED_OTHER
    priority: 0

Then stop the sample application (Ctrl+C).

Tip

Always use the IDs from your own generated template.yaml. The exact strings depend on the node's namespace, topic names, and parameter services, so do not hand-write them from this example.

Step 3: Edit the Configuration#

Copy and edit the template to assign real-time priorities. Here we give the faster (1333 ms) timer the higher priority, pin the two timers to separate cores, and leave everything else on the default scheduler:

cp template.yaml sample_config.yaml
callback_groups:
  - id: /sample_space/sample_subspace/sample_node@Timer(1333000000)
    policy: SCHED_FIFO
    priority: 90
    affinity:
      - 0

  - id: /sample_space/sample_subspace/sample_node@Timer(3000000000)
    policy: SCHED_FIFO
    priority: 80
    affinity:
      - 1

non_ros_threads:
  - id: sample_non_ros_thread
    policy: SCHED_OTHER
    priority: 0

CallbackGroups you do not list keep the default CFS scheduling.

Step 4: Launch with the Configuration#

Start the configurator before the application:

# Terminal 1: configurator
ros2 launch cie_thread_configurator thread_configurator.launch.xml config_file:=sample_config.yaml

# Terminal 2: the sample application
ros2 launch cie_sample_application sample_node.launch.xml

The configurator logs each CallbackGroup as it applies the configuration. It keeps running afterward and re-applies the configuration automatically if the application restarts.

Step 5: Verify#

While the application is running, inspect the thread scheduling with ps:

ps -eLo pid,tid,cls,rtprio,psr,comm | grep component_conta
   PID    TID CLS RTPRIO PSR COMMAND
429255 429255  TS      -   9 component_conta
429255 429257  TS      -   8 component_conta
429255 429268  FF     90   0 component_conta  <-- 1333 ms timer
429255 429269  FF     80   1 component_conta  <-- 3000 ms timer
429255 429270  TS      -  15 component_conta  <-- other groups (CFS)
  • CLS shows the scheduling class: FF = SCHED_FIFO, TS = SCHED_OTHER (CFS).
  • RTPRIO shows the real-time priority; PSR shows the CPU the thread last ran on.
  • Threads without RTPRIO are unconfigured groups and internal threads.

You can also inspect individual threads:

chrt -p <tid>      # show scheduling policy and priority
taskset -p <tid>   # show the CPU affinity mask

See the YAML Specification for all available configuration options.