sm_multithread_test_1ο
- SMACC2 multi-threaded executor demonstration state machine.
 This state machine demonstrates the use of ExecutionModel::MULTI_THREAD_SPINNER for concurrent ROS2 callback processing. Addresses GitHub issue #571.
READMEο
sm_multithread_test_1 - SMACC2 Multi-threaded Executor Demonstrationο
A reference implementation demonstrating SMACC2βs multi-threaded executor capability.
π― Addresses GitHub Issue #571: βMultithread executor exampleβ
π Table of Contentsο
What is This?ο
This state machine demonstrates SMACC2βs multi-threaded executor feature by running four concurrent timers with simulated work. The logs clearly show the difference between single-threaded and multi-threaded execution through thread IDs and overlapping timestamps.
Key Features:
β Multi-threaded ROS2 callback processing
β Visual demonstration of concurrency via logs
β Side-by-side comparison with single-threaded mode
β Comprehensive documentation of usage and limitations
Quick Startο
Run Multi-threaded Version (Main Demo)ο
# Build the package
colcon build --packages-select sm_multithread_test_1
# Source the workspace
source install/setup.bash
# Launch multi-threaded version
ros2 launch sm_multithread_test_1 sm_multithread_test_1.launch.py
Run Single-threaded Version (For Comparison)ο
# Launch single-threaded version
ros2 launch sm_multithread_test_1 sm_multithread_test_1_single.launch.py
The state machine runs for 15 seconds then enters a terminal state. Press Ctrl+C to exit.
The Problem This Solvesο
Backgroundο
By default, SMACC2 uses a single-threaded executor where ROS2 callbacks (timers, subscribers, action clients) execute sequentially. This is simple and deterministic, but can be a bottleneck when:
Multiple callbacks have significant processing time
Callbacks involve I/O operations (network, disk, sensors)
You want maximum throughput for concurrent operations
Solutionο
SMACC2 supports ROS2βs Multi-threaded Executor which allows callbacks to execute concurrently on multiple threads, improving throughput for I/O-bound and concurrent operations.
Enabling it is trivial β just one parameter change:
// Single-threaded (default)
smacc2::run<MyStateMachine>();
// Multi-threaded
smacc2::run<MyStateMachine>(smacc2::ExecutionModel::MULTI_THREAD_SPINNER);
                            //  ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
                            //  THIS IS THE ONLY CHANGE NEEDED!
What Youβll Observeο
Multi-threaded Mode Outputο
[Timer-A] Tick   1 START (Thread: 12345678) - simulating  50ms work
[Timer-B] Tick   1 START (Thread: 87654321) - simulating 100ms work  β Different thread!
[Timer-A] Tick   1 END   (Thread: 12345678)
[Timer-C] Tick   1 START (Thread: 11223344) - simulating 150ms work  β Concurrent!
[Timer-A] Tick   2 START (Thread: 12345678) - simulating  50ms work
[Timer-B] Tick   1 END   (Thread: 87654321)
[Timer-A] Tick   2 END   (Thread: 12345678)
[Timer-D] Tick   1 START (Thread: 99887766) - simulating 200ms work
Observations:
β Different thread IDs (12345678, 87654321, 11223344, 99887766)
β Overlapping START/END timestamps
β True parallel execution
Single-threaded Mode Outputο
[Timer-A] Tick   1 START (Thread: 12345678) - simulating  50ms work
[Timer-A] Tick   1 END   (Thread: 12345678)
[Timer-A] Tick   2 START (Thread: 12345678) - simulating  50ms work
[Timer-A] Tick   2 END   (Thread: 12345678)
[Timer-B] Tick   1 START (Thread: 12345678) - simulating 100ms work  β Same thread
[Timer-B] Tick   1 END   (Thread: 12345678)
[Timer-C] Tick   1 START (Thread: 12345678) - simulating 150ms work  β Serial execution
Observations:
β Same thread ID for all (12345678)
β No overlapping timestamps
β Serial execution (one callback at a time)
How It Worksο
Architectureο
The state machine consists of:
4 Orthogonals β each with a timer at a different rate:
OrTimerA: 100ms periodOrTimerB: 250ms periodOrTimerC: 500ms periodOrTimerD: 1000ms period
Custom Client Behavior β
CbTimerWithWorkSimulation:Simulates work with
std::this_thread::sleep_for()Logs thread ID on each callback
Logs START/END timestamps
Makes concurrency visually obvious
Two States:
StConcurrentOperation: Runs timers for 15 secondsStComplete: Terminal state with summary
Timer Configurationο
Timer  | 
Period  | 
Work Duration  | 
Purpose  | 
|---|---|---|---|
A  | 
100ms  | 
50ms  | 
Fast, light work  | 
B  | 
250ms  | 
100ms  | 
Medium, medium work  | 
C  | 
500ms  | 
150ms  | 
Slow, heavy work  | 
D  | 
1000ms  | 
200ms  | 
Very slow, very heavy work  | 
The different rates and work durations create interesting interleaving patterns that clearly demonstrate concurrency.
When to Use Multi-threaded Modeο
β Use Multi-threaded When:ο
Multiple concurrent ROS2 callbacks
Multiple timer callbacks
Multiple subscriber callbacks
Parallel action client callbacks
Callbacks have blocking operations
Network I/O
Disk I/O
Sensor data acquisition
Long computations
Need maximum throughput
High-frequency data streams
Real-time sensor fusion
Parallel goal processing
Using callback-based patterns only
Timers β
Subscribers β
Action clients β
Service clients β
β Avoid Multi-threaded When:ο
Using
ISmaccUpdatablepatternComponents/behaviors with
update()methodPolling-based patterns
Custom periodic logic
Simple state machines
Minimal concurrent operations
No performance bottleneck
Debugging complex behavior
Single-threaded is easier to trace
More deterministic execution
Need strict determinism
Single-threaded provides guaranteed order
Multi-threaded has non-deterministic scheduling
Important Limitationsο
β οΈ ISmaccUpdatable Pattern Does NOT Workο
The update() method is never called in multi-threaded mode!
Why? The SignalDetectorβs pollOnce() function (which calls update() on all ISmaccUpdatable objects) is only invoked in single-threaded modeβs polling loop. Multi-threaded mode uses executor.spin() which never calls pollOnce().
Affected Patterns:
β Components inheriting from
ISmaccUpdatableβ Behaviors inheriting from
ISmaccUpdatableβ States inheriting from
ISmaccUpdatableβ Any custom
update()methods
Solution: Use ROS2 callback-based patterns instead:
β Timer callbacks via
ClRos2Timerβ Subscriber callbacks via
CpTopicSubscriberβ Action client callbacks
β Service client callbacks
Example Migration:
// β DON'T: This won't work in multi-threaded mode
class MyCb : public SmaccClientBehavior, public ISmaccUpdatable
{
  void update() override {
    // This is NEVER called in multi-threaded mode!
    checkCondition();
  }
};
// β
 DO: Use timer callbacks instead
class MyCb : public SmaccClientBehavior
{
  void onEntry() override {
    requiresClient(timerClient_);
    timerComponent->onTimerTick(&MyCb::onTimerCallback, this);
  }
  void onTimerCallback() {
    // This WILL be called in multi-threaded mode
    checkCondition();
  }
};
Code Deep Diveο
The One-Line Changeο
The only difference between single-threaded and multi-threaded SMACC2 is in the main node file:
Multi-threaded (sm_multithread_test_1_node.cpp):
smacc2::run<SmMultithreadTest1>(
  smacc2::ExecutionModel::MULTI_THREAD_SPINNER  // β ADD THIS
);
Single-threaded (sm_multithread_test_1_node_single.cpp):
smacc2::run<SmMultithreadTest1>(
  smacc2::ExecutionModel::SINGLE_THREAD_SPINNER  // β Or omit (default)
);
// Equivalent to:
smacc2::run<SmMultithreadTest1>();
Implementation Detailsο
Signal Detector Logicο
From smacc2/src/smacc2/signal_detector.cpp:365-386:
if (this->executionModel_ == ExecutionModel::SINGLE_THREAD_SPINNER)
{
  RCLCPP_INFO_STREAM(getLogger(), "[SignalDetector] Running in single-threaded mode.");
  rclcpp::Rate r(loop_rate_hz);  // Default 20Hz
  while (rclcpp::ok() && !end_)
  {
    pollOnce();              // β
 Calls update() on ISmaccUpdatable objects
    rclcpp::spin_some(nh);   // Process callbacks
    r.sleep();
  }
}
else
{
  RCLCPP_INFO_STREAM(getLogger(), "[SignalDetector] Running in multi-threaded mode.");
  rclcpp::executors::MultiThreadedExecutor executor;
  executor.add_node(nh);
  executor.spin();  // β pollOnce() NEVER CALLED
}
Key Insight: Multi-threaded mode skips pollOnce(), so ISmaccUpdatable::update() is never invoked.
Custom Behavior Implementationο
cb_timer_with_work_simulation.hpp demonstrates the pattern:
class CbTimerWithWorkSimulation : public smacc2::SmaccClientBehavior
{
  void onEntry() override {
    // Connect to timer callback
    timerComponent->onTimerTick(&CbTimerWithWorkSimulation::onTimerCallback, this);
  }
  void onTimerCallback() {
    auto thread_id = std::this_thread::get_id();  // Log thread ID
    std::size_t thread_hash = std::hash<std::thread::id>{}(thread_id);
    RCLCPP_INFO(getLogger(), "[Timer-%s] Tick %d START (Thread: %zu)",
                timerName_.c_str(), tickCount_, thread_hash);
    std::this_thread::sleep_for(workDuration_);  // Simulate work
    RCLCPP_INFO(getLogger(), "[Timer-%s] Tick %d END   (Thread: %zu)",
                timerName_.c_str(), tickCount_, thread_hash);
  }
};
Build Instructionsο
Prerequisitesο
ROS 2 (Humble or later)
SMACC2 framework installed
cl_ros2_timerclient library
Buildingο
# Navigate to your workspace
cd ~/your_workspace
# Build the package
colcon build --packages-select sm_multithread_test_1
# Source the workspace
source install/setup.bash
Runningο
# Multi-threaded version (main demonstration)
ros2 launch sm_multithread_test_1 sm_multithread_test_1.launch.py
# Single-threaded version (for comparison)
ros2 launch sm_multithread_test_1 sm_multithread_test_1_single.launch.py
Troubleshootingο
βNo matching function for call to βrunββο
Solution: Ensure youβre using a recent version of SMACC2 that supports the ExecutionModel parameter.
Logs show same thread ID in multi-threaded modeο
Possible causes:
Launched the wrong executable (single-threaded variant)
ROS 2 executor configuration issue
Check: Look for this log line at startup:
[SignalDetector] Running in multi-threaded mode.
If you see βsingle-threaded modeβ, you launched the wrong variant.
Behaviors not executingο
Check if they inherit from ISmaccUpdatable β this pattern doesnβt work in multi-threaded mode. Migrate to timer/subscriber callbacks instead.
Further Readingο
SMACC2 Documentationο
ROS 2 Documentationο
Code Filesο
sm_multithread_test_1_node.cpp- Multi-threaded entry pointsm_multithread_test_1_node_single.cpp- Single-threaded entry pointcb_timer_with_work_simulation.hpp- Custom behavior with thread loggingsignal_detector.cpp- SignalDetector implementation with execution model selection
Licenseο
Copyright 2025 RobosoftAI Inc.
Licensed under the Apache License, Version 2.0