Curieux.JY
  • JungYeon Lee
  • Post
  • Projects
  • Note

On this page

  • Callback이란?
    • ROS2에서 콜백이 사용되는 곳
    • 콜백의 동작 방식
  • Executor란?
    • Executor 종류
  • 여러 노드를 하나의 Executor로 관리하기
    • Pattern A: main()에서 직접 등록
    • Pattern B: 클래스 내부에서 등록
    • 권장 패턴: 노드 소유권 분리
  • 복잡한 시스템에서의 Executor 사용
  • SingleThreadedExecutor vs MultiThreadedExecutor 실험
    • 실험 설정
    • 실험 결과
  • Callback Group 이해하기
    • 종류
    • Callback Group 적용 예시
  • Deadlock 주의사항
    • Deadlock 발생 원인
    • 해결 방법
  • 정리
  • 참고 자료

📝ROS2 Executor 이해하기

ros2
callback
executor
python
2025
ROS2 Executor와 Callback Group의 동작 원리
Published

December 26, 2025

flowchart TB
    subgraph 기초개념["1. 기초 개념"]
        CB[Callback<br/>이벤트 발생 시 호출되는 함수]
        EX[Executor<br/>콜백 실행을 관리]
    end

    subgraph Executor종류["2. Executor 종류"]
        STE[SingleThreadedExecutor<br/>순차 실행]
        MTE[MultiThreadedExecutor<br/>병렬 실행 가능]
    end

    subgraph 콜백그룹["3. Callback Group"]
        MEG[MutuallyExclusive<br/>동시 실행 불가]
        REG[Reentrant<br/>동시 실행 허용]
    end

    subgraph 실전패턴["4. 실전 패턴"]
        MULTI[여러 노드 관리]
        GUI[GUI/스레드 분리]
        DL[Deadlock 방지]
    end

    CB -->|실행 담당| EX
    EX --> STE
    EX --> MTE
    MTE -->|병렬 실행 조건| MEG
    MTE -->|병렬 실행 조건| REG
    MEG --> MULTI
    REG --> MULTI
    MULTI --> GUI
    MEG -->|주의| DL

    style CB fill:#e1f5fe
    style EX fill:#e1f5fe
    style STE fill:#fff3e0
    style MTE fill:#fff3e0
    style MEG fill:#f3e5f5
    style REG fill:#f3e5f5
    style MULTI fill:#e8f5e9
    style GUI fill:#e8f5e9
    style DL fill:#ffebee

Tip핵심 학습 포인트
  1. Callback → Executor가 실행
  2. MultiThreadedExecutor 사용해도 Callback Group 없이는 병렬 실행 안됨
  3. MutuallyExclusiveCallbackGroup이 기본값 → 명시적 설정 필요

Callback이란?

ROS2에서 Callback(콜백)은 특정 이벤트가 발생했을 때 자동으로 호출되는 함수입니다. 직접 함수를 호출하는 것이 아니라, “이 이벤트가 발생하면 이 함수를 실행해줘”라고 미리 등록해두는 방식입니다.

ROS2에서 콜백이 사용되는 곳

종류 설명 예시
Subscription Callback 토픽에서 메시지를 수신했을 때 create_subscription(Topic, callback)
Timer Callback 일정 시간 간격마다 create_timer(1.0, callback) → 1초마다 실행
Service Callback 서비스 요청을 받았을 때 create_service(SrvType, callback)
Action Callback 액션 goal/feedback/result 처리 Action Server/Client의 각종 콜백

콜백의 동작 방식

class MyNode(Node):
    def __init__(self):
        super().__init__('my_node')
        # 콜백 등록: /topic에서 메시지가 오면 listener_callback 실행
        self.subscription = self.create_subscription(
            String, '/topic', self.listener_callback, 10)

    def listener_callback(self, msg):  # ← 이 함수가 콜백
        self.get_logger().info(f'받은 메시지: {msg.data}')

콜백은 등록만 해두고, 실제 실행은 Executor가 담당합니다. 메시지가 도착하거나 타이머가 만료되면, Executor가 해당 콜백을 적절한 시점에 호출합니다.

Note

콜백 함수는 직접 호출하지 않습니다. spin()을 통해 Executor가 이벤트를 감지하고 콜백을 실행합니다.


Executor란?

ROS2에서 Executor는 콜백(callback) 함수들의 실행을 관리하는 핵심 컴포넌트입니다. Subscription, Timer, Service Server, Action Server 등에서 발생하는 콜백들을 언제, 어떻게 실행할지 결정합니다.

executor.spin()을 호출하면, 해당 스레드가 rcl 및 미들웨어 계층에 들어오는 메시지와 이벤트를 지속적으로 확인하고, 대응하는 콜백 함수들을 호출합니다. 이 과정은 노드가 종료될 때까지 계속됩니다.

Executor 종류

Executor 설명
SingleThreadedExecutor 단일 스레드에서 콜백을 순차적으로 실행. 이전 콜백이 완료되어야 다음 콜백 실행 가능
MultiThreadedExecutor 여러 스레드를 사용해 콜백을 병렬로 실행 가능. 스레드 수 지정 가능 (기본값: CPU 코어 수)
Note

rclpy.spin(node)은 내부적으로 SingleThreadedExecutor를 생성하여 사용합니다.


여러 노드를 하나의 Executor로 관리하기

하나의 Executor에 여러 노드를 등록하여 함께 실행할 수 있습니다. 아래 두 패턴은 런타임에서 동일하게 동작합니다.

Pattern A: main()에서 직접 등록

def main():
    executor = MultiThreadedExecutor()
    executor.add_node(node_a)
    executor.add_node(node_b)
    executor.spin()

Pattern B: 클래스 내부에서 등록

class MyNode(Node):
    def __init__(self, executor):
        self.executor = executor
        self.executor.add_node(node_a)
        self.executor.add_node(node_b)

def main():
    executor = MultiThreadedExecutor()
    node = MyNode(executor)
    executor.spin()

두 패턴 모두 정상 동작하지만, 코드의 재사용성, 생명주기 명확성, 소유권 관계 측면에서 차이가 있습니다.

권장 패턴: 노드 소유권 분리

Executor 의존성을 클래스 외부로 분리하면 테스트와 재사용이 용이해집니다.

class MyApp:
    def __init__(self):
        self.node_a = NodeA()
        self.node_b = NodeB()

def main():
    app = MyApp()
    executor = MultiThreadedExecutor()
    executor.add_node(app.node_a)
    executor.add_node(app.node_b)
    executor.spin()

복잡한 시스템에서의 Executor 사용

GUI(예: tkinter)나 별도 루프가 필요한 경우, Executor를 별도 스레드에서 실행해야 합니다.

def main():
    rclpy.init()

    marker_publisher = MarkerPublisher()
    vision_node = VisionNode(marker_publisher)
    bt_controller = BTController(vision_node, marker_publisher)

    executor = MultiThreadedExecutor()
    executor.add_node(marker_publisher)
    executor.add_node(bt_controller)

    # Executor를 별도 스레드에서 실행
    executor_thread = threading.Thread(target=executor.spin, daemon=True)
    executor_thread.start()

    # Behavior Tree 로직을 별도 스레드에서 실행
    bt_thread = threading.Thread(target=bt_controller.bt_loop, daemon=True)
    bt_thread.start()

    try:
        rclpy.spin(vision_node)  # 메인 스레드에서 vision_node 처리
WarningGUI와 함께 사용 시 주의

tkinter 같은 GUI 프레임워크는 메인 스레드에서만 동작합니다. 위 패턴에서 GUI를 추가하려면 rclpy.spin(vision_node) 대신 GUI 메인 루프를 실행하고, 모든 ROS 노드를 별도 스레드의 Executor에서 처리해야 합니다. 또는 별도 프로세스로 분리하는 방법도 고려할 수 있습니다.


SingleThreadedExecutor vs MultiThreadedExecutor 실험

아래 코드로 두 Executor의 동작 차이를 직접 확인할 수 있습니다.

실험 설정

  • NodeB: 두 개의 토픽에 메시지를 발행
    • /testLong: 0.5초 간격
    • /testShort: 0.01초 간격 (빠름)
  • NodeA: 두 개의 subscription
    • long_sleep_callback: 메시지 수신 후 1초 sleep (느린 처리)
    • no_sleep_callback: 메시지 수신 후 즉시 완료 (빠른 처리)
import rclpy
from rclpy.node import Node
from rclpy.executors import MultiThreadedExecutor, SingleThreadedExecutor
from rclpy.callback_groups import ReentrantCallbackGroup, MutuallyExclusiveCallbackGroup
import time
from std_msgs.msg import String

class NodeA(Node):
    def __init__(self):
        super().__init__('node_a')
        self.sub_short = self.create_subscription(
            String, '/testShort', self.no_sleep_callback, 100)
        self.sub_long = self.create_subscription(
            String, '/testLong', self.long_sleep_callback, 10)

    def long_sleep_callback(self, msg):
        self.get_logger().info(f'LONG SLEEP {msg.data}')
        time.sleep(1.0)  # 1초 동안 블로킹

    def no_sleep_callback(self, msg):
        self.get_logger().info(f'NO SLEEP {msg.data}')

class NodeB(Node):
    def __init__(self):
        super().__init__('node_b')
        self.pub_long = self.create_publisher(String, '/testLong', 10)
        self.pub_short = self.create_publisher(String, '/testShort', 10)

        self.timer_long = self.create_timer(0.5, self.publish_long)
        self.timer_short = self.create_timer(0.01, self.publish_short)

    def publish_long(self):
        msg = String()
        msg.data = f'Time: {self.get_clock().now().to_msg().sec}'
        self.pub_long.publish(msg)

    def publish_short(self):
        msg = String()
        msg.data = f'Time: {self.get_clock().now().to_msg().sec}'
        self.pub_short.publish(msg)

def main():
    rclpy.init()

    node_a = NodeA()
    node_b = NodeB()

    # 테스트할 Executor 선택
    executor = SingleThreadedExecutor()
    # executor = MultiThreadedExecutor()

    executor.add_node(node_a)
    executor.add_node(node_b)

    try:
        executor.spin()
    except KeyboardInterrupt:
        pass
    finally:
        node_a.destroy_node()
        node_b.destroy_node()
        rclpy.shutdown()

if __name__ == '__main__':
    main()

실험 결과

Executor Callback Group 설정 결과
SingleThreadedExecutor 기본값 LONG SLEEP만 출력되거나, 둘 다 출력되지만 순차적
MultiThreadedExecutor 기본값 (MutuallyExclusive) SingleThreadedExecutor와 동일 - 병렬 실행 안됨!
MultiThreadedExecutor ReentrantCallbackGroup 둘 다 병렬로 출력
Important핵심 포인트

노드의 기본 Callback Group은 MutuallyExclusiveCallbackGroup입니다.

따라서 MultiThreadedExecutor를 사용하더라도, Callback Group을 명시적으로 설정하지 않으면 모든 콜백이 순차적으로 실행됩니다. 병렬 실행을 원한다면 반드시 Callback Group을 설정해야 합니다.


Callback Group 이해하기

Callback Group은 MultiThreadedExecutor에서 콜백들의 동시 실행 규칙을 정의합니다.

종류

Callback Group 동작
MutuallyExclusiveCallbackGroup 그룹 내 콜백들이 동시에 실행되지 않음. 한 번에 하나의 콜백만 실행
ReentrantCallbackGroup 그룹 내 콜백들이 동시에 실행 가능. 같은 콜백의 여러 인스턴스도 병렬 실행 가능
Tip언제 어떤 것을 사용할까?
  • MutuallyExclusiveCallbackGroup: 스레드 안전하지 않은 리소스에 접근하는 콜백들
  • ReentrantCallbackGroup: 여러 요청을 동시에 처리해야 하는 서비스/액션 서버

Callback Group 적용 예시

class NodeA(Node):
    def __init__(self):
        super().__init__('node_a')

        # 방법 1: 하나의 ReentrantCallbackGroup으로 모든 콜백 병렬 실행
        self.group = ReentrantCallbackGroup()
        self.sub_short = self.create_subscription(
            String, '/testShort', self.no_sleep_callback, 10,
            callback_group=self.group)
        self.sub_long = self.create_subscription(
            String, '/testLong', self.long_sleep_callback, 10,
            callback_group=self.group)

        # 방법 2: 각각 다른 MutuallyExclusiveCallbackGroup 사용
        # -> 서로 다른 그룹의 콜백은 병렬 실행 가능
        # self.group_long = MutuallyExclusiveCallbackGroup()
        # self.group_short = MutuallyExclusiveCallbackGroup()
        # self.sub_long = self.create_subscription(..., callback_group=self.group_long)
        # self.sub_short = self.create_subscription(..., callback_group=self.group_short)
Note

서로 다른 Callback Group에 속한 콜백들은 그룹 종류와 관계없이 항상 병렬 실행이 가능합니다.


Deadlock 주의사항

동기식 서비스 호출(client.call())을 사용할 때 Deadlock이 발생할 수 있습니다.

Deadlock 발생 원인

# Timer 콜백 내에서 동기식 서비스 호출
def timer_callback(self):
    response = self.client.call(request)  # 여기서 블로킹
    # call() 내부의 done-callback이 실행되어야 응답을 받을 수 있지만,
    # 같은 MutuallyExclusiveCallbackGroup에 있으면 실행 불가 -> Deadlock!

해결 방법

  1. 비동기 호출 사용 (권장): client.call_async()
  2. Callback Group 분리: Timer와 Service Client를 다른 그룹에 배치
  3. ReentrantCallbackGroup 사용: 같은 그룹 내 콜백 병렬 실행 허용

정리

상황 권장 설정
단순한 단일 노드 rclpy.spin(node) (SingleThreadedExecutor)
여러 노드, 순차 처리 OK SingleThreadedExecutor + 여러 노드
병렬 처리 필요 MultiThreadedExecutor + ReentrantCallbackGroup 또는 다른 MutuallyExclusiveCallbackGroup들
GUI와 함께 사용 별도 스레드/프로세스로 분리
동기 서비스 호출 비동기 호출로 변경 또는 Callback Group 분리

참고 자료

  • ROS 2 Executors 공식 문서 (Rolling)
  • Using Callback Groups 가이드
  • rclpy Execution and Callbacks API
  • ROS2 Concurrency, Executors and Callback Groups (Medium)
  • Deadlocks in rclpy and how to prevent them (Karelics)
  • Executor and Spin Explained (LearnROS2)

Copyright 2026, JungYeon Lee