1293.83 단일 Tick 단계 실행 (Single Step)
1. 단일 Tick 단계 실행의 정의
단일 Tick 단계 실행(single step execution)이란, 행동 트리의 Tick을 한 번에 하나씩 수동으로 실행하고, 각 Tick의 결과를 확인한 후 다음 Tick의 실행 여부를 결정하는 디버깅 기법이다. 이는 전통적 디버거의 단계 실행(step-over, step-into)과 유사한 개념으로, Tick 단위에서의 트리 동작을 정밀하게 분석할 수 있다(Faconti, 2022).
2. 단계 실행의 구현
2.1 기본 단계 실행
class SingleStepExecutor {
public:
SingleStepExecutor(BT::Tree& tree,
rclcpp::executors::SingleThreadedExecutor& executor)
: tree_(tree), executor_(executor) {}
BT::NodeStatus step() {
// ROS2 콜백 처리
executor_.spin_some();
// 단일 Tick 실행
auto status = tree_.tickOnce();
tick_count_++;
return status;
}
void printState() const {
printf("\n=== Tick #%d ===\n", tick_count_);
printTreeStatus(tree_);
printf("\nTree status: %s\n",
BT::toStr(tree_.rootNode()->status()).c_str());
}
int getTickCount() const { return tick_count_; }
private:
BT::Tree& tree_;
rclcpp::executors::SingleThreadedExecutor& executor_;
int tick_count_{0};
};
2.2 대화형 단계 실행
사용자 입력에 따라 다양한 디버깅 명령을 수행하는 대화형 인터페이스를 제공한다.
void interactiveDebug(SingleStepExecutor& executor) {
bool running = true;
while (running) {
printf("\n[Commands] s:step r:run b:blackboard q:quit\n> ");
std::string cmd;
std::getline(std::cin, cmd);
if (cmd == "s" || cmd.empty()) {
auto status = executor.step();
executor.printState();
if (status == BT::NodeStatus::SUCCESS ||
status == BT::NodeStatus::FAILURE) {
printf("Tree completed with %s\n",
BT::toStr(status).c_str());
}
} else if (cmd == "r") {
// 연속 실행 (특정 조건까지)
runUntilChange(executor);
} else if (cmd == "b") {
printBlackboard(executor.getTree().rootBlackboard());
} else if (cmd == "q") {
running = false;
}
}
}
3. 단계 실행의 분석 활용
3.1 상태 전이 추적
각 Tick에서 어떤 노드의 상태가 변경되었는지를 순차적으로 추적한다.
[Step 1] Tick #0:
Sequence (IDLE → RUNNING)
IsBatteryAbove (IDLE → SUCCESS)
NavigateToGoal (IDLE → RUNNING)
Tree: RUNNING
[Step 2] Tick #1:
IsBatteryAbove (SUCCESS) ← 변화 없음
NavigateToGoal (RUNNING) ← 변화 없음
Tree: RUNNING
[Step 3] Tick #2:
IsBatteryAbove (SUCCESS → FAILURE) ← 조건 변화!
NavigateToGoal (RUNNING → IDLE) ← Halt 발생
Sequence (RUNNING → FAILURE)
Tree: FAILURE
3.2 블랙보드 변화 추적
각 Tick 전후의 블랙보드 상태를 비교하여 데이터 흐름을 분석한다.
[Before Tick #5]
battery_level: 0.25
robot_pose: (1.2, 3.4, 0.5)
[After Tick #5]
battery_level: 0.23 ← 변경됨
robot_pose: (1.3, 3.5, 0.5) ← 변경됨
distance_to_goal: 2.1 ← 새로 추가됨
4. 조건부 자동 실행
단계 실행에서 특정 조건이 충족될 때까지 자동으로 Tick을 실행하는 기능이다. 이는 장기간 RUNNING 상태가 유지되는 동안 수동으로 반복 실행하는 번거로움을 줄인다.
void runUntilChange(SingleStepExecutor& executor) {
auto initial_snapshot = captureSnapshot(executor.getTree());
while (rclcpp::ok()) {
auto status = executor.step();
auto current_snapshot = captureSnapshot(executor.getTree());
if (hasStateChange(initial_snapshot, current_snapshot)) {
printf("State change detected at Tick #%d\n",
executor.getTickCount());
executor.printState();
break;
}
if (status != BT::NodeStatus::RUNNING) {
printf("Tree completed at Tick #%d\n",
executor.getTickCount());
break;
}
}
}
5. N-Tick 일괄 실행
지정된 횟수의 Tick을 일괄 실행한 후 결과를 확인하는 방식이다.
void stepN(SingleStepExecutor& executor, int n) {
for (int i = 0; i < n; ++i) {
auto status = executor.step();
if (status != BT::NodeStatus::RUNNING) {
printf("Tree completed at Tick #%d (after %d steps)\n",
executor.getTickCount(), i + 1);
break;
}
}
executor.printState();
}
6. 단계 실행의 제약
6.1 실시간 의존성
실시간 센서 데이터나 외부 시스템에 의존하는 노드는 단계 실행에서 정상적으로 동작하지 않을 수 있다. 수동 Tick 간의 간격이 불규칙하므로, 시간 의존적 로직이 비정상적으로 동작할 수 있다.
6.2 비동기 작업의 시간 왜곡
비동기 액션 노드가 외부 시스템에서 수행하는 작업은 실제 시간에 따라 진행된다. 단계 실행에서 Tick 간격이 길어지면, 비동기 작업이 첫 재진입에서 이미 완료되어 있을 수 있어 정상 실행과 다른 동작을 보일 수 있다.
6.3 시뮬레이션 환경의 활용
이러한 제약을 극복하기 위해, 시뮬레이션 환경에서 시간을 멈추고(pause) 단계 실행을 수행하면 시간 의존적 동작을 정확하게 분석할 수 있다. Gazebo 등의 시뮬레이터는 시뮬레이션 시간의 정지와 재개를 지원한다.
참고 문헌
- 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/