ROS 2 Executor & Callback Groups Guide 2026
Master ROS 2 concurrency: SingleThreadedExecutor vs MultiThreadedExecutor, ReentrantCallbackGroup vs MutuallyExclusiveCallbackGroup, deadlock fixes, and spin_once for custom event loops.
The Executor Mental Model
Think of the executor as a callback scheduler. Nodes publish callbacks (timers, subscribers, service handlers) into a queue. The executor dequeues and calls them. A SingleThreadedExecutor processes them one by one. A MultiThreadedExecutor processes them with N threads — but which callbacks can run simultaneously is controlled by callback groups, not by the executor alone.
What Is a ROS 2 Executor?
An executor manages a thread pool and decides which callbacks (timers, subscribers, service handlers) to call and when. rclpy.spin() creates a SingleThreadedExecutor internally.
ROS 2 Executors
═══════════════════════════════════════════════════════
SingleThreadedExecutor (default)
• One thread — callbacks execute one at a time, never concurrently
• rclpy.spin(node) uses this under the hood
• Safe: no race conditions between callbacks in the same node
• Problem: a slow callback blocks ALL other callbacks in that node
MultiThreadedExecutor
• N threads — can run multiple callbacks simultaneously
• Requires explicit callback group assignments to control concurrency
• Enables concurrent subscriber callbacks, timers, and service handlers
• Needs thread-safety in shared data (use locks or atomic types)
StaticSingleThreadedExecutor (C++ only)
• Preallocates callback structures at startup — lower latency
• Available in rclcpp, not rclpy
Callback groups control WHICH callbacks can run concurrently:
MutuallyExclusiveCallbackGroup → at most 1 callback at a time
ReentrantCallbackGroup → any number concurrently⚡ By default, every callback (timer, subscriber, service) is in the node's default MutuallyExclusive group. Adding a MultiThreadedExecutor alone does NOT enable concurrency unless you also use ReentrantCallbackGroup.
SingleThreadedExecutor (Default)
The default executor. All callbacks in all added nodes run sequentially. rclpy.spin(node) is a convenience wrapper around this executor with one node.
import rclpy
from rclpy.node import Node
from rclpy.executors import SingleThreadedExecutor
class MyNode(Node):
def __init__(self):
super().__init__("my_node")
# Timer fires at 10 Hz
self.timer = self.create_timer(0.1, self._timer_cb)
# Subscriber
self.sub = self.create_subscription(
String, "/data", self._sub_cb, 10
)
def _timer_cb(self):
self.get_logger().info("Timer tick")
def _sub_cb(self, msg):
# ⚠️ If this takes 0.5s, the timer misses 5 ticks
time.sleep(0.5)
self.get_logger().info(f"Got: {msg.data}")
def main():
rclpy.init()
node = MyNode()
# Explicit — same as rclpy.spin(node)
executor = SingleThreadedExecutor()
executor.add_node(node)
try:
executor.spin()
finally:
executor.shutdown()
node.destroy_node()
rclpy.shutdown()⚡ rclpy.spin(node) is equivalent to SingleThreadedExecutor().add_node(node); executor.spin(). Use explicit executor when you need to add multiple nodes or call spin_once.
MultiThreadedExecutor — Enabling Concurrency
Pass num_threads to control the thread pool size. Without ReentrantCallbackGroup, callbacks in the same MutuallyExclusive group still serialize — the threads only help across different groups.
import rclpy
from rclpy.node import Node
from rclpy.executors import MultiThreadedExecutor
from rclpy.callback_groups import ReentrantCallbackGroup, MutuallyExclusiveCallbackGroup
from std_msgs.msg import String
import time
class ConcurrentNode(Node):
def __init__(self):
super().__init__("concurrent_node")
# ReentrantCallbackGroup: callbacks CAN run concurrently
self.reentrant_group = ReentrantCallbackGroup()
# MutuallyExclusiveCallbackGroup: callbacks serialize within this group
self.exclusive_group = MutuallyExclusiveCallbackGroup()
# Timer A — fast (10 Hz) in reentrant group
self.timer_a = self.create_timer(
0.1, self._fast_timer, callback_group=self.reentrant_group
)
# Timer B — slow processing in its own exclusive group
# Won't block timer_a because it's in a different group
self.timer_b = self.create_timer(
1.0, self._slow_timer, callback_group=self.exclusive_group
)
# Subscriber — can run concurrently with timers
self.sub = self.create_subscription(
String, "/data", self._sub_cb, 10,
callback_group=self.reentrant_group
)
def _fast_timer(self):
self.get_logger().info("Fast tick — never blocked by slow timer")
def _slow_timer(self):
self.get_logger().info("Slow processing start")
time.sleep(2.0) # simulate heavy work
self.get_logger().info("Slow processing done")
def _sub_cb(self, msg):
self.get_logger().info(f"Sub: {msg.data}")
def main():
rclpy.init()
node = ConcurrentNode()
# num_threads=4 → up to 4 callbacks run at the same time
executor = MultiThreadedExecutor(num_threads=4)
executor.add_node(node)
try:
executor.spin()
finally:
executor.shutdown()
node.destroy_node()
rclpy.shutdown()MutuallyExclusiveCallbackGroup vs ReentrantCallbackGroup
The callback group determines the concurrency contract for callbacks assigned to it. Choose based on whether your callback shares mutable state.
MutuallyExclusiveCallbackGroup
────────────────────────────────────────────────────────
• At most ONE callback in this group runs at any moment
• Other callbacks in the group queue and wait
• Default group for all subscribers/timers/services
• Safe for callbacks that share mutable node state
• Use case: callbacks that update the same variable, list, or dict
Node default group = MutuallyExclusive
→ Even with MultiThreadedExecutor, node callbacks are safe by default
ReentrantCallbackGroup
────────────────────────────────────────────────────────
• Any number of callbacks can run concurrently
• YOU are responsible for thread safety (use threading.Lock)
• Use case: independent callbacks (e.g. multiple subscribers reading
different sensors, timers that don't share state)
• High throughput: 10 sensor callbacks process in parallel
Example: Two callbacks sharing a buffer
WRONG — race condition with ReentrantCallbackGroup:
self.buffer.append(msg.data) # not thread-safe
RIGHT:
with self._lock: # use threading.Lock
self.buffer.append(msg.data)
Multiple exclusive groups:
group_a = MutuallyExclusiveCallbackGroup()
group_b = MutuallyExclusiveCallbackGroup()
# → callbacks in group_a serialize among themselves
# → callbacks in group_b serialize among themselves
# → group_a and group_b CAN run concurrently (different groups)Calling a Service Inside a Callback (Deadlock Fix)
Calling a service synchronously inside a callback blocks the executor thread — the response can never arrive if only one thread exists. Use a separate callback group.
import rclpy
from rclpy.node import Node
from rclpy.callback_groups import ReentrantCallbackGroup
from rclpy.executors import MultiThreadedExecutor
from std_srvs.srv import SetBool
class ServiceCallerNode(Node):
def __init__(self):
super().__init__("service_caller")
# CRITICAL: the client must be in a DIFFERENT callback group
# than the callback that calls it — or use ReentrantCallbackGroup
self.cb_group = ReentrantCallbackGroup()
self.client = self.create_client(
SetBool, "/enable_motor",
callback_group=self.cb_group # <-- key
)
# Timer that calls the service
self.timer = self.create_timer(
1.0, self._on_timer,
callback_group=self.cb_group
)
def _on_timer(self):
if not self.client.wait_for_service(timeout_sec=0.5):
self.get_logger().warn("Service not available")
return
req = SetBool.Request()
req.data = True
future = self.client.call_async(req)
# ⚠️ Do NOT call future.result() here — it would block
future.add_done_callback(self._on_response)
def _on_response(self, future):
result = future.result()
self.get_logger().info(f"Motor {'enabled' if result.success else 'failed'}")
def main():
rclpy.init()
node = ServiceCallerNode()
executor = MultiThreadedExecutor(num_threads=2)
executor.add_node(node)
executor.spin()⚡ DEADLOCK pattern: single-threaded executor + call_async inside a callback + no spin_until_future_complete = the response never arrives because the executor thread is blocked waiting. Fix: MultiThreadedExecutor + ReentrantCallbackGroup, or move the service call outside the callback.
Multiple Nodes in One Executor
One executor can manage many nodes. This is more efficient than spinning each node in a separate thread, and enables callback scheduling across node boundaries.
import rclpy
from rclpy.executors import MultiThreadedExecutor
from my_pkg.lidar_node import LidarNode
from my_pkg.camera_node import CameraNode
from my_pkg.fusion_node import FusionNode
def main():
rclpy.init()
lidar = LidarNode()
camera = CameraNode()
fusion = FusionNode()
executor = MultiThreadedExecutor(num_threads=6)
executor.add_node(lidar)
executor.add_node(camera)
executor.add_node(fusion)
try:
# Spins ALL three nodes in the same thread pool
executor.spin()
except KeyboardInterrupt:
pass
finally:
executor.shutdown()
lidar.destroy_node()
camera.destroy_node()
fusion.destroy_node()
rclpy.shutdown()⚡ spin_once(timeout_sec=0) processes one pending callback and returns — useful in custom event loops. spin_until_future_complete(future) blocks until the future resolves.
spin_once and Custom Event Loops
For integration with external event loops (asyncio, Qt, ROS bag playback), use spin_once() instead of spin() to process one callback at a time.
import rclpy
from rclpy.executors import SingleThreadedExecutor
import time
def main():
rclpy.init()
node = rclpy.create_node("manual_spin")
executor = SingleThreadedExecutor()
executor.add_node(node)
# Custom event loop — process ROS 2 and other work interleaved
rate = node.create_rate(100) # 100 Hz target
try:
while rclpy.ok():
# Process one pending ROS 2 callback (non-blocking)
executor.spin_once(timeout_sec=0.0)
# Your non-ROS work here
do_custom_work()
rate.sleep()
finally:
executor.shutdown()
node.destroy_node()
rclpy.shutdown()
# ── asyncio integration ────────────────────────────────────────
import asyncio
async def ros_spin_async(executor):
"""Yield control to asyncio event loop between each ROS callback."""
while rclpy.ok():
executor.spin_once(timeout_sec=0.0)
await asyncio.sleep(0.01) # yield to asyncioQuick Reference
| Concept | Details |
|---|---|
| Default executor | SingleThreadedExecutor — one callback at a time, all nodes |
| rclpy.spin(node) | SingleThreadedExecutor().add_node(node); executor.spin() |
| Concurrent callbacks | MultiThreadedExecutor(num_threads=N) + ReentrantCallbackGroup |
| MutuallyExclusive | Default group — callbacks in this group never run concurrently |
| Reentrant | Callbacks CAN run concurrently — you need locks for shared state |
| Multiple groups | Two MutuallyExclusive groups CAN run concurrently with each other |
| Service in callback | Use ReentrantCallbackGroup + call_async + add_done_callback |
| spin_once(0.0) | Non-blocking — process one callback if available, return immediately |
| Multiple nodes | executor.add_node(a); executor.add_node(b); executor.spin() |
| Thread count | MultiThreadedExecutor(num_threads=os.cpu_count()) for max throughput |