1293.61 단일 스레드 Tick 실행 모델
1. 단일 스레드 실행 모델의 정의
단일 스레드 Tick 실행 모델이란, 행동 트리의 전체 Tick 실행이 하나의 스레드에서 순차적으로 수행되는 실행 방식이다. 루트 노드의 tickOnce() 호출부터 모든 노드의 tick(), onStart(), onRunning(), onHalted() 호출, 블랙보드 접근, 상태 전이까지의 모든 연산이 단일 스레드의 호출 스택 내에서 완료된다. 이는 BehaviorTree.CPP의 기본 실행 모델이며, 행동 트리의 결정론적 실행을 보장하는 기반이다(Faconti, 2022).
2. 단일 스레드 모델의 실행 흐름
단일 스레드 모델에서의 Tick 실행은 다음과 같은 순차적 흐름으로 진행된다.
메인 루프 (단일 스레드):
┌─ spinSome() // ROS2 콜백 처리
├─ tree.tickOnce() // Tick 시작
│ ├─ Root.tick()
│ │ ├─ Sequence.tick()
│ │ │ ├─ Condition.tick() → SUCCESS
│ │ │ ├─ Action_1.onRunning() → RUNNING
│ │ │ └─ (Action_2 Tick 안 됨)
│ │ └─ Sequence 반환: RUNNING
│ └─ Root 반환: RUNNING
└─ rate.sleep() // 다음 Tick까지 대기
모든 노드의 실행이 동일한 호출 스택 내에서 완료되므로, 노드 간의 실행 순서가 완전히 결정론적이다.
3. 단일 스레드 모델의 구현
3.1 기본 구현 패턴
int main(int argc, char** argv) {
rclcpp::init(argc, argv);
auto node = rclcpp::Node::make_shared("bt_node");
BT::BehaviorTreeFactory factory;
// 노드 등록
registerNodes(factory);
auto tree = factory.createTreeFromFile("tree.xml");
rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(node);
rclcpp::Rate rate(10); // 10 Hz Tick
while (rclcpp::ok()) {
executor.spin_some(); // 콜백 처리
auto status = tree.tickOnce(); // Tick 실행
if (status == BT::NodeStatus::SUCCESS ||
status == BT::NodeStatus::FAILURE) {
break;
}
rate.sleep();
}
rclcpp::shutdown();
return 0;
}
3.2 tickWhileRunning 사용
BehaviorTree.CPP는 tickWhileRunning() 메서드를 제공하여 RUNNING 상태가 유지되는 동안 주기적으로 Tick을 실행한다.
// 내부적으로 단일 스레드에서 루프 실행
auto status = tree.tickWhileRunning(std::chrono::milliseconds(100));
이 메서드는 내부적으로 tickOnce()를 반복 호출하며, 각 호출 사이에 지정된 시간만큼 대기한다. 실행은 동일 스레드에서 수행된다.
4. 결정론적 실행의 보장
단일 스레드 모델에서 Tick의 실행 순서는 트리의 구조와 각 노드의 반환 상태에 의해 완전히 결정된다. 동일한 초기 상태와 입력이 주어지면, 동일한 실행 경로가 재현된다.
\text{ExecutionPath}(T, S_0, I) = \text{deterministic}
여기서 T는 트리 구조, S_0는 초기 상태, I는 입력이다. 이 결정론적 속성은 디버깅과 테스트를 용이하게 한다.
5. 단일 스레드 모델의 이점
5.1 스레드 안전성 보장
단일 스레드 내에서 모든 노드가 순차적으로 실행되므로, 노드 간의 데이터 공유에 대한 동기화가 불필요하다. 블랙보드 접근, 노드 상태 변경, 제어 노드의 인덱스 관리 등 모든 연산이 동일 스레드에서 수행되어 데이터 경쟁이 구조적으로 방지된다.
5.2 디버깅 용이성
단일 스레드 실행에서의 실행 흐름은 호출 스택을 통해 완전히 추적 가능하다. 브레이크포인트를 설정하면 Tick의 정확한 실행 지점에서 프로그램이 정지하며, 스택 프레임을 통해 호출 경로를 역추적할 수 있다.
5.3 예측 가능한 실행 시간
단일 스레드 모델에서 Tick 실행 시간은 실행되는 노드들의 연산 시간의 합으로 예측 가능하다.
T_{tick} = \sum_{i \in \text{visited}} T_{node_i}
스레드 스케줄링에 의한 비결정론적 지연이 없으므로, 실행 시간의 상한을 분석적으로 산출할 수 있다.
6. 단일 스레드 모델의 제약
6.1 Tick 차단 위험
동기 노드의 연산이 과중하거나 차단 호출(blocking call)이 포함된 경우, 전체 Tick이 차단된다. 차단 중에는 다른 노드의 Tick이 수행되지 않으며, ROS2 콜백도 처리되지 않는다.
위험한 패턴:
tick() 내에서 차단 호출:
auto response = service_client->call(request); // 응답 대기
// → 전체 Tick 차단
6.2 CPU 활용률 제한
단일 스레드 모델은 멀티코어 프로세서의 병렬 처리 능력을 활용하지 못한다. Parallel 노드에서 복수의 자식을 Tick하더라도, 실제 실행은 순차적으로 수행된다.
7. ROS2 SingleThreadedExecutor와의 통합
단일 스레드 Tick 모델과 ROS2의 SingleThreadedExecutor를 결합하면, ROS2 콜백과 Tick 실행이 동일 스레드에서 인터리빙 방식으로 수행된다. 이 조합에서 콜백과 Tick 간의 동기화가 불필요하다.
시간축:
├─ spinSome(): 토픽 콜백 A 실행
├─ spinSome(): 서비스 응답 콜백 B 실행
├─ tickOnce(): Tick 시작 → 노드 순차 실행 → Tick 종료
├─ sleep()
├─ spinSome(): 토픽 콜백 C 실행
├─ tickOnce(): Tick 시작 → 노드 순차 실행 → Tick 종료
└─ ...
콜백에 의한 데이터 갱신이 Tick 실행 전에 완료되므로, Tick 내에서 읽는 데이터는 일관성이 보장된다.
8. 단일 스레드 모델에서의 비동기 작업 처리
단일 스레드 모델에서 비동기 작업은 StatefulActionNode 패턴을 통해 처리한다. 작업의 개시와 결과 확인만 Tick 스레드에서 수행하고, 실제 작업은 외부 시스템(ROS2 액션 서버 등)에서 수행된다.
Tick 스레드 (단일):
onStart() → ROS2 액션 목표 전송 → RUNNING 반환 (비차단)
onRunning() → 결과 확인 → RUNNING/SUCCESS/FAILURE (비차단)
외부 시스템 (별도 프로세스):
액션 서버 → 실제 작업 수행 → 결과 발행
이 패턴에서 Tick 스레드는 차단되지 않으며, 단일 스레드 모델의 이점을 유지하면서 장시간 작업을 처리할 수 있다.
9. 단일 스레드 모델의 권장 사용 조건
단일 스레드 Tick 실행 모델은 다음 조건에서 권장된다.
- 행동 트리 내의 모든 액션 노드가
StatefulActionNode로 구현되어 비차단 실행을 보장하는 경우 - ROS2
SingleThreadedExecutor를 사용하여 콜백과 Tick의 스레드 안전성을 구조적으로 보장하는 경우 - Tick 실행 시간이 Tick 주기 이내로 유지되는 경우
- 결정론적 실행과 디버깅 용이성이 중요한 개발 및 테스트 단계
참고 문헌
- 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/