1293.84 조건부 Tick 브레이크포인트
1. 조건부 브레이크포인트의 개념
조건부 Tick 브레이크포인트란, 사전에 정의된 조건이 충족될 때 Tick 실행을 자동으로 중단하고 개발자에게 제어를 반환하는 디버깅 메커니즘이다. 전통적 디버거의 조건부 브레이크포인트와 유사하지만, 소스 코드의 특정 행이 아닌 트리의 상태, 노드의 반환 값, 블랙보드의 값 등 행동 트리 고유의 조건을 기준으로 한다(Faconti, 2022).
2. 브레이크포인트 조건의 유형
2.1 노드 상태 기반 조건
특정 노드가 특정 상태를 반환할 때 중단한다.
struct NodeStatusBreakpoint {
std::string node_name;
BT::NodeStatus trigger_status;
};
// 예: NavigateToGoal이 FAILURE를 반환하면 중단
NodeStatusBreakpoint bp{"NavigateToGoal", BT::NodeStatus::FAILURE};
2.2 상태 전이 기반 조건
특정 노드의 상태가 특정 방향으로 전이할 때 중단한다.
struct TransitionBreakpoint {
std::string node_name;
BT::NodeStatus from_status;
BT::NodeStatus to_status;
};
// 예: NavigateToGoal이 RUNNING에서 FAILURE로 전이하면 중단
TransitionBreakpoint bp{"NavigateToGoal",
BT::NodeStatus::RUNNING, BT::NodeStatus::FAILURE};
2.3 블랙보드 값 기반 조건
블랙보드의 특정 키 값이 조건을 충족할 때 중단한다.
struct BlackboardBreakpoint {
std::string key;
std::function<bool(const BT::Any&)> condition;
};
// 예: battery_level이 0.15 이하로 떨어지면 중단
BlackboardBreakpoint bp{"battery_level",
[](const%20BT::Any&%20val) {
return val.cast<double>() <= 0.15;
}
};
2.4 Halt 이벤트 기반 조건
특정 노드에 Halt가 호출될 때 중단한다.
2.5 Tick 횟수 기반 조건
지정된 Tick 번호에 도달하면 중단한다.
// 예: Tick #500에서 중단
int breakpoint_tick = 500;
3. 브레이크포인트 엔진의 구현
class BreakpointEngine {
public:
void addNodeBreakpoint(const std::string& node_name,
BT::NodeStatus status) {
node_breakpoints_.push_back({node_name, status});
}
void addBlackboardBreakpoint(const std::string& key,
std::function<bool(double)> cond) {
bb_breakpoints_.push_back({key, cond});
}
void addTickBreakpoint(int tick_number) {
tick_breakpoints_.insert(tick_number);
}
bool shouldBreak(int tick_id, const BT::Tree& tree) {
// Tick 번호 확인
if (tick_breakpoints_.count(tick_id)) return true;
// 블랙보드 값 확인
auto bb = tree.rootBlackboard();
for (const auto& bp : bb_breakpoints_) {
auto entry = bb->getEntry(bp.key);
if (entry) {
double val = entry->value.cast<double>();
if (bp.condition(val)) return true;
}
}
return false;
}
bool checkNodeStatus(const std::string& name,
BT::NodeStatus status) {
for (const auto& bp : node_breakpoints_) {
if (bp.node_name == name && bp.status == status) {
return true;
}
}
return false;
}
private:
std::vector<NodeStatusBreakpoint> node_breakpoints_;
std::vector<BlackboardBreakpoint> bb_breakpoints_;
std::set<int> tick_breakpoints_;
};
4. 브레이크포인트 통합 실행 루프
void debugWithBreakpoints(BT::Tree& tree,
BreakpointEngine& engine) {
int tick_id = 0;
bool paused = false;
// 상태 변화 모니터
auto observer = std::make_shared<BreakpointObserver>(engine);
while (rclcpp::ok()) {
if (!paused) {
executor_.spin_some();
tree.tickOnce();
tick_id++;
// 브레이크포인트 확인
if (engine.shouldBreak(tick_id, tree) ||
observer->wasTriggered()) {
paused = true;
printf("\n*** Breakpoint hit at Tick #%d ***\n", tick_id);
printTreeStatus(tree);
printBlackboard(tree.rootBlackboard());
}
}
if (paused) {
printf("[c]ontinue [s]tep [q]uit: ");
char cmd;
std::cin >> cmd;
if (cmd == 'c') paused = false;
else if (cmd == 's') {
executor_.spin_some();
tree.tickOnce();
tick_id++;
printTreeStatus(tree);
}
else if (cmd == 'q') break;
} else {
rate_.sleep();
}
}
}
5. StatusChangeLogger를 활용한 노드 브레이크포인트
class BreakpointObserver : public BT::StatusChangeLogger {
public:
BreakpointObserver(BreakpointEngine& engine)
: engine_(engine) {}
void callback(BT::Duration timestamp,
const BT::TreeNode& node,
BT::NodeStatus prev_status,
BT::NodeStatus status) override {
if (engine_.checkNodeStatus(node.name(), status)) {
triggered_ = true;
triggered_node_ = node.name();
triggered_status_ = status;
}
}
bool wasTriggered() {
bool result = triggered_;
triggered_ = false;
return result;
}
void flush() override {}
private:
BreakpointEngine& engine_;
bool triggered_{false};
std::string triggered_node_;
BT::NodeStatus triggered_status_;
};
6. 브레이크포인트의 실무 활용 시나리오
| 시나리오 | 브레이크포인트 조건 | 분석 목적 |
|---|---|---|
| 네비게이션 실패 진단 | NavigateToGoal → FAILURE | 실패 시점의 블랙보드 값 확인 |
| 배터리 저하 동작 검증 | battery_level ≤ 0.15 | 저배터리 시 안전 동작 확인 |
| Halt 연쇄 분석 | 특정 노드 Halt 발생 | Halt 원인과 전파 범위 확인 |
| 조건 진동 검출 | 조건 노드 FAILURE → SUCCESS | 진동 발생 시점과 블랙보드 확인 |
| 장시간 RUNNING 검출 | RUNNING 100 Tick 이상 | 스턱된 작업 식별 |
7. 브레이크포인트와 운영 환경
운영 환경에서 브레이크포인트에 의한 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/