1293.19 ROS2 SpinSome과 Tick의 관계

1. spin_some의 동작 원리

rclcpp::spin_some()은 ROS2 노드에 대기 중인(ready) 콜백들을 즉시 실행하고 반환하는 비차단(non-blocking) 실행 함수이다. rclcpp::spin()이 프로그램의 제어권을 실행기에 넘겨 무한 루프에서 콜백을 처리하는 것과 달리, spin_some()은 호출 시점에 준비된 콜백만 처리한 후 즉시 호출자에게 제어권을 반환한다(Macenski et al., 2022).

이 비차단 특성은 행동 트리(Behavior Tree)의 Tick 루프와 ROS2 콜백 처리를 단일 스레드에서 교대로 실행하는 패턴을 가능하게 한다. 개발자가 spin_some()의 호출 시점을 직접 제어함으로써, Tick 실행과 ROS2 콜백 처리의 순서를 명시적으로 결정할 수 있다.

2. spin_some과 spin_some_for의 차이

ROS2는 spin_some()의 변형으로 spin_some(max_duration) 형태를 제공한다. 기본 spin_some()은 호출 시점에 이미 준비된 콜백만 처리하는 반면, 최대 지속 시간을 지정하면 해당 시간 동안 새로 준비되는 콜백도 추가로 처리한다.

// 현재 준비된 콜백만 처리
rclcpp::spin_some(node);

// 최대 10ms 동안 준비되는 콜백 처리
executor.spin_some(std::chrono::milliseconds(10));

행동 트리 Tick과의 통합에서는 일반적으로 기본 spin_some()을 사용하여 처리 시간을 최소화하는 것이 권장된다. 지속 시간을 지정하면 해당 시간 동안 Tick 실행이 지연되므로, Tick 주기에 대한 영향을 고려해야 한다.

3. Tick 루프에서의 spin_some 배치

spin_some()을 Tick 루프 내에서 배치하는 위치는 행동 트리의 동작 특성에 직접적인 영향을 미친다.

3.1 Tick 전 호출 패턴

while (rclcpp::ok() && status == BT::NodeStatus::RUNNING) {
    rclcpp::spin_some(node);  // 먼저 콜백 처리
    status = tree.tickOnce();  // 최신 데이터로 Tick
    tree.sleep(period);
}

이 패턴에서는 Tick 실행 직전에 spin_some()이 호출되어 대기 중인 모든 구독 콜백이 처리된다. 따라서 행동 트리의 조건 노드가 평가하는 센서 데이터와 상태 정보가 가능한 한 최신 값으로 갱신된 상태에서 Tick이 실행된다. 이는 행동 트리의 의사 결정이 최신 환경 정보에 기반하도록 보장한다는 점에서 가장 일반적으로 권장되는 패턴이다.

3.2 Tick 후 호출 패턴

while (rclcpp::ok() && status == BT::NodeStatus::RUNNING) {
    status = tree.tickOnce();  // 먼저 Tick
    rclcpp::spin_some(node);  // 이후 콜백 처리
    tree.sleep(period);
}

이 패턴에서는 Tick 실행 후에 콜백이 처리된다. Tick 중에 발송된 ROS2 메시지(예: 액션 목표 전송)에 대한 응답이 spin_some() 호출 시 처리되므로, 다음 Tick에서 해당 응답을 사용할 수 있다. 그러나 첫 번째 Tick에서는 이전 주기의 데이터를 사용하게 되는 한 Tick 지연이 존재한다.

3.3 Tick 전후 호출 패턴

while (rclcpp::ok() && status == BT::NodeStatus::RUNNING) {
    rclcpp::spin_some(node);  // 최신 데이터 수신
    status = tree.tickOnce();  // Tick 실행
    rclcpp::spin_some(node);  // 응답 처리
    tree.sleep(period);
}

이 패턴은 Tick 전에 최신 센서 데이터를 수신하고, Tick 후에 Tick 중 발생한 요청에 대한 응답을 처리한다. 가장 완전한 콜백 처리를 제공하지만, 두 번의 spin_some() 호출로 인한 오버헤드가 추가된다.

4. spin_some과 데이터 일관성

spin_some() 호출 시 복수의 구독 콜백이 순차적으로 실행되므로, 서로 다른 토픽에서 수신된 데이터 간의 시간적 일관성(temporal consistency)이 보장되지 않을 수 있다. 예를 들어, LiDAR 데이터와 카메라 데이터가 서로 다른 시점에 발행된 메시지일 수 있다.

이 문제는 행동 트리의 조건 노드가 복수의 센서 데이터를 결합하여 판단하는 경우에 잠재적 오류를 유발할 수 있다. 이를 완화하기 위해 ROS2의 메시지 필터(message filter)나 message_filters::TimeSynchronizer를 사용하여 시간적으로 동기화된 데이터만을 행동 트리에 전달하는 방법을 고려할 수 있다.

5. spin_some의 실행 시간 특성

spin_some()의 실행 시간은 호출 시점에 준비된 콜백의 수와 각 콜백의 실행 시간에 의해 결정된다. 대기 중인 콜백이 없으면 거의 즉시 반환되지만, 다수의 콜백이 누적된 경우 상당한 시간이 소요될 수 있다.

T_{spin\_some} = \sum_{i=1}^{n} T_{callback_i}

여기서 n은 준비된 콜백의 수, T_{callback_i}는 각 콜백의 실행 시간이다. 이 시간은 Tick 주기의 시간 예산에서 차감되어야 하므로, 총 소요 시간이 다음 조건을 만족해야 한다.

T_{spin\_some} + T_{exec} \leq T_{tick}

높은 주파수의 토픽 구독이 다수 존재하는 경우, spin_some() 호출 시 처리해야 할 콜백이 누적되어 예상보다 긴 실행 시간이 소요될 수 있다. 이를 관리하기 위해 구독 큐 크기(queue size)를 적절히 제한하거나, 최신 메시지만 유지하는 QoS 설정을 적용하는 것이 권장된다.

6. spin_some과 BehaviorTree.CPP의 sleep 메서드

BehaviorTree.CPP의 Tree::sleep() 메서드는 지정된 시간 동안 대기하되, 비동기 노드의 WakeUpSignal에 의해 조기에 깨어날 수 있는 기능을 제공한다. spin_some()Tree::sleep()을 함께 사용하는 경우, 대기 시간 동안에도 ROS2 콜백이 처리될 수 있도록 설계해야 한다.

while (rclcpp::ok() && status == BT::NodeStatus::RUNNING) {
    rclcpp::spin_some(node);
    status = tree.tickOnce();
    
    // sleep 대신 spin_some을 반복하여 대기
    auto deadline = std::chrono::steady_clock::now() + period;
    while (std::chrono::steady_clock::now() < deadline 
           && rclcpp::ok()) {
        rclcpp::spin_some(node);
        std::this_thread::sleep_for(std::chrono::milliseconds(1));
    }
}

이 구현은 Tick 간 대기 시간 동안에도 ROS2 콜백을 지속적으로 처리하여, 메시지 수신 지연을 최소화한다. 다만 Tree::sleep()WakeUpSignal 기능은 활용하지 못하므로, 비동기 노드의 조기 완료에 대한 대응이 다소 지연될 수 있다.

7. spin_some 기반 패턴의 적합 조건

spin_some() 기반 Tick 통합 패턴은 다음 조건에서 특히 적합하다.

조건근거
Tick과 콜백의 실행 순서 제어가 필요spin_some()의 호출 위치로 순서를 명시적으로 제어
단일 스레드 실행 환경동기화 문제 없이 안전한 데이터 접근
센서 데이터의 최신성이 중요Tick 직전 spin_some() 호출로 최신 데이터 보장
행동 트리가 ROS2 통신을 직접 수행노드 내에서 발행/구독이 이루어지는 구조

반면, spin() 기반 타이머 콜백 패턴이 더 적합한 경우도 있다. 특히 복수의 ROS2 노드가 동일한 실행기에서 운용되거나, ROS2의 표준 수명 주기 관리(lifecycle management)를 활용하는 경우에는 타이머 콜백 패턴이 ROS2 생태계와의 호환성이 높다.


참고 문헌

  • Colledanchise, M., & Ogren, P. (2018). Behavior Trees in Robotics and AI: An Introduction. CRC Press.
  • Faconti, D. (2022). BehaviorTree.CPP documentation and API reference. https://www.behaviortree.dev/
  • Macenski, S., Foote, T., Gerkey, B., Lalancette, C., & Woodall, W. (2022). Robot Operating System 2: Design, architecture, and uses in the wild. Science Robotics, 7(66), eabm6074.