1295.79 커스텀 Parallel 변형 노드의 구현
1. 커스텀 Parallel의 필요성
BehaviorTree.CPP 4.x의 ParallelAll 노드는 SUCCESS_ALL 성공 정책과 max_failures 기반 실패 정책을 제공한다. 그러나 로봇공학의 실제 적용에서는 이 정책만으로 충분하지 않은 경우가 존재한다. SUCCESS_ONE(하나의 자식 성공 시 전체 성공), SUCCESS_COUNT(N개 이상 성공 시 전체 성공), 가중치 기반 정책 등의 변형이 필요할 수 있다. 이 경우 ControlNode를 상속하여 커스텀 Parallel 변형 노드를 구현한다.
2. ControlNode 상속 기반 구현
커스텀 Parallel 노드는 BT::ControlNode를 상속하고, tick()과 halt() 메서드를 구현한다.
2.1 SUCCESS_ONE 정책 Parallel
하나의 자식이 SUCCESS를 반환하면 즉시 전체가 SUCCESS를 반환하는 변형이다.
#include "behaviortree_cpp/control_node.h"
class ParallelOne : public BT::ControlNode
{
public:
ParallelOne(const std::string& name, const BT::NodeConfig& config)
: ControlNode(name, config) {}
static BT::PortsList providedPorts()
{
return {};
}
BT::NodeStatus tick() override
{
int failure_count = 0;
for (size_t i = 0; i < childrenCount(); i++)
{
auto* child = children_nodes_[i];
// 이미 완료된 자식은 재Tick하지 않음
if (child->status() == BT::NodeStatus::SUCCESS)
{
haltChildren();
return BT::NodeStatus::SUCCESS;
}
if (child->status() == BT::NodeStatus::FAILURE)
{
failure_count++;
continue;
}
auto status = child->executeTick();
if (status == BT::NodeStatus::SUCCESS)
{
haltChildren();
return BT::NodeStatus::SUCCESS;
}
if (status == BT::NodeStatus::FAILURE)
{
failure_count++;
}
}
// 모든 자식이 FAILURE이면 전체 FAILURE
if (failure_count == static_cast<int>(childrenCount()))
{
return BT::NodeStatus::FAILURE;
}
return BT::NodeStatus::RUNNING;
}
void halt() override
{
haltChildren();
ControlNode::halt();
}
};
2.2 SUCCESS_COUNT(N) 정책 Parallel
N개 이상의 자식이 SUCCESS를 반환하면 전체가 SUCCESS를 반환하는 변형이다.
class ParallelCount : public BT::ControlNode
{
public:
ParallelCount(const std::string& name, const BT::NodeConfig& config)
: ControlNode(name, config) {}
static BT::PortsList providedPorts()
{
return {
BT::InputPort<int>("success_threshold", 1,
"SUCCESS로 간주할 최소 성공 자식 수"),
BT::InputPort<int>("max_failures", 0,
"허용되는 최대 실패 자식 수")
};
}
BT::NodeStatus tick() override
{
int success_threshold, max_failures;
getInput("success_threshold", success_threshold);
getInput("max_failures", max_failures);
int success_count = 0;
int failure_count = 0;
for (size_t i = 0; i < childrenCount(); i++)
{
auto* child = children_nodes_[i];
if (child->status() == BT::NodeStatus::SUCCESS)
{
success_count++;
continue;
}
if (child->status() == BT::NodeStatus::FAILURE)
{
failure_count++;
continue;
}
auto status = child->executeTick();
if (status == BT::NodeStatus::SUCCESS)
success_count++;
else if (status == BT::NodeStatus::FAILURE)
failure_count++;
}
// 성공 임계값 도달
if (success_count >= success_threshold)
{
haltChildren();
return BT::NodeStatus::SUCCESS;
}
// 실패 한계 초과
if (failure_count > max_failures)
{
haltChildren();
return BT::NodeStatus::FAILURE;
}
// 성공 달성이 불가능한 경우 (남은 자식으로 임계값 도달 불가)
int remaining = static_cast<int>(childrenCount())
- success_count - failure_count;
if (success_count + remaining < success_threshold)
{
haltChildren();
return BT::NodeStatus::FAILURE;
}
return BT::NodeStatus::RUNNING;
}
void halt() override
{
haltChildren();
ControlNode::halt();
}
};
success_count + remaining < success_threshold 조건은 남은 RUNNING 자식이 모두 성공하더라도 임계값에 도달할 수 없는 경우를 조기에 감지하여, 불필요한 실행을 방지한다.
3. 노드 등록과 XML 사용
커스텀 노드를 팩토리에 등록하여 XML에서 사용한다.
BT::BehaviorTreeFactory factory;
// 커스텀 노드 등록
factory.registerNodeType<ParallelOne>("ParallelOne");
factory.registerNodeType<ParallelCount>("ParallelCount");
<!-- ParallelOne 사용 -->
<ParallelOne>
<AttemptPlanA />
<AttemptPlanB />
<AttemptPlanC />
</ParallelOne>
<!-- ParallelCount 사용 -->
<ParallelCount success_threshold="2" max_failures="1">
<SensorA />
<SensorB />
<SensorC />
</ParallelCount>
4. 완료된 자식의 재Tick 정책
커스텀 Parallel 구현에서 중요한 설계 결정은, 이미 SUCCESS 또는 FAILURE를 반환한 자식을 다음 Tick에서 재Tick할 것인지의 여부이다.
4.1 재Tick하지 않는 방식 (기본)
이미 완료된 자식의 상태를 유지하고, RUNNING 상태인 자식에게만 Tick을 전파한다. 위의 예시가 이 방식을 따른다.
장점: 완료된 행동을 불필요하게 재실행하지 않는다.
단점: 한 번 SUCCESS를 반환한 자식이 이후 상태가 변하여도 감지할 수 없다.
4.2 재Tick하는 방식
매 Tick에서 모든 자식에게 Tick을 전파한다.
// 재Tick 방식
for (size_t i = 0; i < childrenCount(); i++)
{
auto status = children_nodes_[i]->executeTick(); // 항상 Tick
// ...
}
장점: 조건 성격의 자식의 상태 변화를 즉시 감지할 수 있다.
단점: 이미 완료된 행동이 재시작될 수 있다.
적용 사례에 따라 적절한 방식을 선택하여야 한다.
5. 구현 시 유의 사항
-
haltChildren()의 올바른 호출:
SUCCESS나FAILURE를 반환하기 전에haltChildren()을 호출하여, 나머지RUNNING자식이 정리되도록 하라. -
halt() 메서드의 구현: 부모로부터의 Halt 시 모든 자식에 Halt를 전파하고, 자신의 상태를
IDLE로 설정하라. -
포트의 유효성 검증:
getInput()으로 읽은 포트 값의 유효성을 검증하라.success_threshold가 자식 수보다 큰 경우 등의 오류를 사전에 감지하라. -
스레드 안전성: BehaviorTree.CPP의 기본 실행 모델은 단일 스레드이므로 동기화가 필요하지 않다. 그러나 비동기 행동 노드(
StatefulActionNode)와 함께 사용하는 경우 스레드 안전성을 고려하라. -
테스트 코드 작성: 커스텀 노드에 대해 다양한 자식 상태 조합을 테스트하는 단위 테스트를 작성하라. BehaviorTree.CPP는 테스트용 모의(mock) 노드를 제공한다.