1297.20 간단 조건 노드 (SimpleConditionNode)의 활용
1. SimpleConditionNode의 개념
BT::SimpleConditionNode는 BehaviorTree.CPP 라이브러리가 제공하는 경량 조건 노드 구현 방식이다. 별도의 클래스를 정의하지 않고, 함수 포인터나 람다 함수(lambda function)를 전달하여 조건 노드를 생성할 수 있다. 단순한 조건 평가 로직을 빠르게 구현할 때 유용하며, 프로토타이핑이나 간단한 조건에 적합하다(Faconti & Colledanchise, 2022).
2. SimpleConditionNode의 함수 시그니처
SimpleConditionNode에 전달되는 함수는 다음의 시그니처를 따라야 한다:
BT::NodeStatus functionName(BT::TreeNode& self);
매개변수 self는 현재 노드에 대한 참조로, 이를 통해 getInput() 등의 노드 메서드에 접근할 수 있다. 반환값은 BT::NodeStatus::SUCCESS 또는 BT::NodeStatus::FAILURE이어야 한다.
3. 팩토리에서의 등록
SimpleConditionNode는 BehaviorTreeFactory의 registerSimpleCondition() 메서드를 통해 등록한다.
BT::BehaviorTreeFactory factory;
factory.registerSimpleCondition(
"IsDoorOpen", // 노드 ID
[](BT::TreeNode&%20self) -> BT::NodeStatus { // 조건 평가 함수
bool door_open;
self.getInput("door_status", door_open);
return door_open ? BT::NodeStatus::SUCCESS : BT::NodeStatus::FAILURE;
},
{ BT::InputPort<bool>("door_status", "문 열림 상태") } // 포트 선언
);
registerSimpleCondition() 메서드의 매개변수는 다음과 같다:
| 매개변수 | 타입 | 설명 |
|---|---|---|
| 첫 번째 | std::string | XML에서 사용할 노드 ID |
| 두 번째 | SimpleConditionNode::TickFunctor | 조건 평가 함수 |
| 세 번째 (선택) | PortsList | 포트 선언 목록 |
4. 람다 함수를 이용한 등록
C++ 람다 함수를 사용하면 간결하게 조건 노드를 정의할 수 있다.
4.1 단순 비교 조건
factory.registerSimpleCondition(
"IsBatteryAbove",
[](BT::TreeNode&%20self) -> BT::NodeStatus {
double battery, threshold;
self.getInput("battery", battery);
self.getInput("threshold", threshold);
return (battery >= threshold) ? BT::NodeStatus::SUCCESS : BT::NodeStatus::FAILURE;
},
{
BT::InputPort<double>("battery", "배터리 잔량"),
BT::InputPort<double>("threshold", 20.0, "임계값")
}
);
4.2 외부 변수 캡처
람다의 캡처(capture) 기능을 사용하여 외부 변수를 참조할 수 있다. 이 패턴은 ROS2 노드의 공유 데이터나 원자적 변수(atomic variable)를 참조할 때 사용된다.
auto latest_scan = std::make_shared<std::atomic<double>>(
std::numeric_limits<double>::max());
// ROS2 구독자에서 비동기적으로 갱신
auto sub = ros_node->create_subscription<sensor_msgs::msg::LaserScan>(
"/scan", 10,
[latest_scan](const%20sensor_msgs::msg::LaserScan::SharedPtr%20msg) {
latest_scan->store(*std::min_element(msg->ranges.begin(), msg->ranges.end()));
});
// 조건 노드 등록: 캡처된 변수 참조
factory.registerSimpleCondition(
"IsObstacleNear",
[latest_scan](BT::TreeNode&%20self) -> BT::NodeStatus {
double threshold;
self.getInput("threshold", threshold);
double min_range = latest_scan->load();
return (min_range < threshold) ? BT::NodeStatus::SUCCESS : BT::NodeStatus::FAILURE;
},
{ BT::InputPort<double>("threshold", 0.5, "장애물 감지 거리") }
);
5. 함수 포인터를 이용한 등록
일반 함수를 사용할 수도 있다.
BT::NodeStatus checkBattery(BT::TreeNode& self)
{
double battery;
self.getInput("battery", battery);
return (battery > 20.0) ? BT::NodeStatus::SUCCESS : BT::NodeStatus::FAILURE;
}
factory.registerSimpleCondition(
"CheckBattery",
checkBattery,
{ BT::InputPort<double>("battery", "배터리 잔량") }
);
6. XML에서의 사용
SimpleConditionNode로 등록된 노드는 클래스 기반 조건 노드와 동일한 방식으로 XML에서 사용된다.
<BehaviorTree>
<Sequence>
<Condition ID="IsBatteryAbove" battery="{battery_level}" threshold="20.0"/>
<Condition ID="IsObstacleNear" threshold="0.5"/>
<Action ID="Navigate" goal="{target}"/>
</Sequence>
</BehaviorTree>
7. SimpleConditionNode와 클래스 기반 구현의 비교
| 특성 | SimpleConditionNode | 클래스 기반 ConditionNode |
|---|---|---|
| 구현 복잡도 | 낮음 (함수 하나) | 중간 (클래스 정의 필요) |
| 재사용성 | 제한적 | 높음 |
| 생성자 매개변수 | 불가 | 가능 (ROS2 노드 등) |
| 멤버 변수 | 불가 (캡처로 대체) | 가능 |
| 단위 테스트 | 함수 단위 테스트 | 클래스 단위 테스트 |
| 적용 범위 | 단순 조건 | 복잡한 조건 |
8. 적용 지침
SimpleConditionNode는 다음의 경우에 적합하다:
- 조건 평가 로직이 5줄 이내의 단순한 비교인 경우
- 프로토타이핑 단계에서 조건 노드를 빠르게 구현하고 테스트하는 경우
- 내부 상태 관리가 필요하지 않은 경우
다음의 경우에는 클래스 기반 구현이 적합하다:
- ROS2 노드, 구독자 등의 외부 자원에 대한 참조가 필요한 경우
- 생성자에서 초기화 로직이 필요한 경우
- 캐싱 등 내부 상태 관리가 필요한 경우
- 복수의 프로젝트에서 재사용되는 범용 조건 노드인 경우
9. 참고 문헌
- Colledanchise, M., & Ogren, P. (2018). Behavior Trees in Robotics and AI: An Introduction. CRC Press.
- Faconti, D., & Colledanchise, M. (2022). BehaviorTree.CPP Documentation. https://www.behaviortree.dev/
version: 0.1.0