1295.75 BehaviorTree.CPP에서의 ReactiveSequence 구현
1. ReactiveSequence 클래스
BehaviorTree.CPP에서 ReactiveSequence는 ControlNode를 상속하는 내장 제어 노드로 제공된다. 이 노드는 메모리 없는 Sequence로, 매 Tick에서 항상 첫 번째 자식부터 순차적으로 평가한다.
class ReactiveSequence : public ControlNode
{
public:
ReactiveSequence(const std::string& name)
: ControlNode(name, {}) {}
ReactiveSequence(const std::string& name, const NodeConfig& config)
: ControlNode(name, config) {}
private:
NodeStatus tick() override;
void halt() override;
};
ReactiveSequence는 추가 포트를 정의하지 않는다. 성공/실패 정책이나 임계값 같은 설정 파라미터가 필요 없기 때문이다.
2. tick() 메서드의 구현
BehaviorTree.CPP에서 ReactiveSequence의 tick() 메서드는 다음과 같은 구조로 구현되어 있다.
NodeStatus ReactiveSequence::tick()
{
bool all_success = true;
for (size_t index = 0; index < childrenCount(); index++)
{
TreeNode* current_child = children_nodes_[index];
const NodeStatus child_status = current_child->executeTick();
switch (child_status)
{
case NodeStatus::RUNNING:
{
// 이후의 RUNNING 자식에 Halt 전파
for (size_t j = index + 1; j < childrenCount(); j++)
{
if (children_nodes_[j]->status() == NodeStatus::RUNNING)
{
haltChild(j);
}
}
return NodeStatus::RUNNING;
}
case NodeStatus::FAILURE:
{
// 이후의 RUNNING 자식에 Halt 전파
for (size_t j = index + 1; j < childrenCount(); j++)
{
if (children_nodes_[j]->status() == NodeStatus::RUNNING)
{
haltChild(j);
}
}
return NodeStatus::FAILURE;
}
case NodeStatus::SUCCESS:
{
// 다음 자식으로 계속
break;
}
default:
break;
}
}
// 모든 자식이 SUCCESS
return NodeStatus::SUCCESS;
}
핵심 특성을 정리한다.
- 항상 인덱스 0부터 시작:
for루프가index = 0에서 시작한다. 이전 Tick의 상태를 기억하지 않는다. - 단축 평가:
RUNNING또는FAILURE반환 시 루프가 즉시 종료된다. - Halt 전파: 현재 인덱스 이후의
RUNNING상태 자식에 Halt를 전파한다.
3. halt() 메서드의 구현
void ReactiveSequence::halt()
{
haltChildren();
ControlNode::halt();
}
haltChildren() 메서드가 모든 RUNNING 상태의 자식에 Halt를 전파하고, ControlNode::halt()가 노드의 상태를 IDLE로 설정한다.
4. haltChild() 메서드
BehaviorTree.CPP의 ControlNode는 개별 자식에 Halt를 전파하는 haltChild() 메서드를 제공한다.
void ControlNode::haltChild(size_t index)
{
auto child = children_nodes_[index];
if (child->status() == NodeStatus::RUNNING)
{
child->halt();
}
child->setStatus(NodeStatus::IDLE);
}
Halt 호출 후 자식의 상태를 IDLE로 설정하여, 다음 Tick에서 깨끗한 상태로 시작하도록 보장한다.
5. XML에서의 ReactiveSequence 정의
<BehaviorTree ID="ReactiveSequenceExample">
<ReactiveSequence>
<IsSafe />
<IsLocalized />
<NavigateToGoal goal="{target_position}" />
</ReactiveSequence>
</BehaviorTree>
<ReactiveSequence> 태그는 추가 속성 없이 자식 노드만을 포함한다.
6. 일반 Sequence와의 코드 차이
BehaviorTree.CPP에서 일반 SequenceNode는 running_child_ 멤버 변수를 통해 이전 RUNNING 자식의 인덱스를 기억한다.
// SequenceNode의 tick() (개념적)
NodeStatus SequenceNode::tick()
{
for (size_t index = running_child_; index < childrenCount(); index++)
{
// ...
if (child_status == NodeStatus::RUNNING)
{
running_child_ = index; // 인덱스 기억
return NodeStatus::RUNNING;
}
// ...
}
running_child_ = 0;
return NodeStatus::SUCCESS;
}
ReactiveSequence에는 running_child_ 변수가 없다. 이것이 코드 수준에서의 핵심 차이이다.
7. executeTick()과 tick()의 관계
BehaviorTree.CPP에서 외부 코드가 노드를 Tick할 때는 executeTick()을 호출한다. executeTick()은 tick()을 내부적으로 호출하며, 전후로 다음의 처리를 수행한다.
NodeStatus TreeNode::executeTick()
{
// 사전 조건(PreCondition) 확인 (4.x)
auto pre_status = checkPreConditions();
if (pre_status.has_value())
{
return pre_status.value();
}
// 실제 tick() 호출
NodeStatus status = tick();
// 사후 조건(PostCondition) 처리 (4.x)
auto post_status = checkPostConditions(status);
if (post_status.has_value())
{
status = post_status.value();
}
// 상태 변경 콜백 발생
setStatus(status);
return status;
}
BehaviorTree.CPP 4.x에서 도입된 사전 조건과 사후 조건 메커니즘에 의해, tick()이 호출되기 전에 노드의 실행이 건너뛰어질 수 있다.
8. ROS2 Nav2에서의 ReactiveSequence 사용
Nav2의 기본 행동 트리에서 ReactiveSequence는 이동 중 경로 유효성 감시에 사용된다.
<!-- Nav2 행동 트리에서의 ReactiveSequence 사용 -->
<ReactiveSequence>
<GoalUpdated />
<FollowPath path="{path}" controller_id="FollowPath" />
</ReactiveSequence>
GoalUpdated는 목표가 갱신되면 SUCCESS를, 그렇지 않으면 FAILURE를 반환하는 조건 노드이다. 목표가 갱신되면 FollowPath가 Halt되고 새 경로로 재시작된다.
9. 주의 사항
-
조건 노드의 RUNNING 반환 금지: ReactiveSequence의 선행 위치에 배치되는 조건 노드가
RUNNING을 반환하면, 후행 자식이 Tick을 수신하지 못한다. 조건 노드는 반드시SUCCESS또는FAILURE만을 반환하도록 구현하라. -
중간 위치의 상태 있는 행동 금지: ReactiveSequence의 중간 위치에
RUNNING을 반환하는 상태 있는 행동을 배치하면, 매 Tick에서 재평가되어 후행 자식이 반복적으로 Halt되는 문제가 발생한다. -
Halt의 안전한 구현: ReactiveSequence 하위의 행동 노드는 언제든 Halt를 수신할 수 있다. 물리적 동작의 안전한 정지와 자원 해제를 Halt 메서드에 구현하라.