1293.77 Tick 단위 노드 반환 상태 로그
1. 반환 상태 로그의 정의
Tick 단위 노드 반환 상태 로그란, 단일 Tick 실행 중 각 노드가 반환한 상태(SUCCESS, FAILURE, RUNNING)를 기록한 것이다. 반환 상태 로그는 노드의 의사 결정 결과를 추적하여, 제어 흐름의 분기점과 트리의 최종 반환 상태가 어떻게 결정되었는지를 분석하는 데 활용된다(Colledanchise & Ogren, 2018).
2. 상태 전이와 반환 상태의 구분
반환 상태(returned status)는 노드의 tick() 메서드가 반환하는 값이며, 상태 전이(state transition)는 노드의 내부 상태가 변경되는 것이다. 동일한 반환 상태라도 상태 전이가 발생하는 경우와 그렇지 않은 경우가 있다.
| 이전 상태 | 반환 상태 | 상태 전이 | 의미 |
|---|---|---|---|
| IDLE | RUNNING | IDLE → RUNNING | 작업 개시 |
| RUNNING | RUNNING | 전이 없음 | 작업 계속 |
| RUNNING | SUCCESS | RUNNING → IDLE | 작업 완료 |
| RUNNING | FAILURE | RUNNING → IDLE | 작업 실패 |
| IDLE | SUCCESS | IDLE → IDLE | 동기 즉시 성공 |
| IDLE | FAILURE | IDLE → IDLE | 동기 즉시 실패 |
3. 반환 상태 로그의 형식
3.1 단순 텍스트 형식
Tick #142:
Sequence(MainSeq) → RUNNING
IsBatteryAbove → SUCCESS
IsLocalized → SUCCESS
NavigateToGoal → RUNNING ← Sequence를 RUNNING으로 만든 노드
3.2 구조화된 형식
struct StatusLogEntry {
int tick_id;
std::string node_name;
std::string node_type;
BT::NodeStatus returned_status;
BT::NodeStatus previous_status;
bool status_changed; // 상태 전이 여부
std::chrono::microseconds execution_time;
};
4. BehaviorTree.CPP에서의 구현
StatusChangeLogger를 활용하여 모든 상태 변화를 기록한다.
class StatusLogger : public BT::StatusChangeLogger {
public:
StatusLogger(const BT::Tree& tree)
: StatusChangeLogger(tree.rootNode()) {}
void callback(BT::Duration timestamp,
const BT::TreeNode& node,
BT::NodeStatus prev_status,
BT::NodeStatus status) override {
StatusLogEntry entry;
entry.timestamp = timestamp;
entry.node_name = node.name();
entry.prev_status = prev_status;
entry.new_status = status;
entry.is_transition = (prev_status != status);
entries_.push_back(entry);
// 실시간 출력 (선택적)
if (verbose_) {
printf("[%s] %s: %s → %s\n",
formatTime(timestamp).c_str(),
node.name().c_str(),
BT::toStr(prev_status).c_str(),
BT::toStr(status).c_str());
}
}
void flush() override {
// 파일 또는 버퍼 플러시
}
private:
std::vector<StatusLogEntry> entries_;
bool verbose_{true};
};
5. 반환 상태의 집계 분석
Tick 간에 반환 상태 로그를 집계하면 각 노드의 동작 특성을 파악할 수 있다.
P_{success}(n) = \frac{N_{SUCCESS}(n)}{N_{visited}(n)}
P_{failure}(n) = \frac{N_{FAILURE}(n)}{N_{visited}(n)}
P_{running}(n) = \frac{N_{RUNNING}(n)}{N_{visited}(n)}
이 비율은 노드의 성공/실패 빈도를 정량화하여, 조건 노드의 조기 종료 빈도, 액션 노드의 평균 실행 Tick 수 등을 분석하는 데 활용된다.
6. 상태 변화 패턴 분석
6.1 상태 전이 시퀀스
특정 노드의 상태 변화를 시간 순서로 나열하면 동작 패턴이 드러난다.
NavigateToGoal 상태 이력:
Tick 100: IDLE → RUNNING (작업 개시)
Tick 101: RUNNING (작업 계속)
Tick 102: RUNNING (작업 계속)
Tick 103: RUNNING → SUCCESS (작업 완료)
Tick 104: IDLE (미방문)
Tick 130: IDLE → RUNNING (새 작업 개시)
Tick 131: RUNNING → FAILURE (작업 실패)
6.2 비정상 패턴 검출
상태 전이 로그에서 비정상적 패턴을 검출할 수 있다.
| 비정상 패턴 | 증상 | 원인 |
|---|---|---|
| IDLE → FAILURE 반복 | 조건 항상 실패 | 센서 장애, 임계값 오류 |
| RUNNING 장기 유지 | 수십 초 이상 RUNNING | 작업 스턱, 타임아웃 미설정 |
| SUCCESS/FAILURE 진동 | 매 Tick 교대 반환 | 히스테리시스 미적용 |
| 모든 대안 FAILURE | Fallback의 모든 자식 실패 | 복구 전략 부재 |
7. 제어 노드의 반환 상태와 자식 상태의 관계
제어 노드의 반환 상태 로그를 자식 노드의 반환 상태와 함께 기록하면, 제어 흐름의 인과 관계를 추적할 수 있다.
Tick #142:
Fallback(RecoverStrategy) → SUCCESS
AutoRecover → FAILURE (자동 복구 실패)
RequestHelp → SUCCESS ← Fallback을 SUCCESS로 만든 대안
EnterSafeMode → (미방문) (조기 종료에 의해 건너뜀)
이 로그에서 자동 복구가 실패한 후 원격 지원 요청이 성공하여 Fallback이 SUCCESS를 반환했음을 알 수 있다.
8. 로그 기반 동작 검증
반환 상태 로그를 사전 정의된 기대 패턴과 비교하여 트리의 동작을 자동으로 검증할 수 있다.
void verifyBehavior(const std::vector<StatusLogEntry>& log) {
// 안전 조건이 FAILURE를 반환한 후
// 모든 액션이 중단되었는지 검증
for (size_t i = 0; i < log.size(); ++i) {
if (log[i].node_name == "SafetyCheck" &&
log[i].new_status == BT::NodeStatus::FAILURE) {
// 이후 어떤 액션 노드도 RUNNING이 아닌지 확인
verifyAllActionsStopped(log, i);
}
}
}
참고 문헌
- 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/