1297.25 부등호 비교 조건 노드의 구현
1. 부등호 비교의 정의
부등호 비교 조건 노드(inequality comparison condition node)는 블랙보드에서 읽은 값이 기준값보다 크거나, 작거나, 크거나 같거나, 작거나 같은지를 판정하는 조건 노드이다. 행동 트리(Behavior Tree)에서 가장 빈번하게 사용되는 조건 평가 유형으로, 센서 값의 임계값 검사, 상한/하한 확인, 허용 범위 판정 등에 적용된다(Colledanchise & Ogren, 2018).
2. 부등호 비교의 네 가지 유형
| 비교 유형 | 수학 표현 | SUCCESS 조건 | 로봇공학 적용 예시 |
|---|---|---|---|
| 초과 (greater than) | a > b | 값이 기준보다 큼 | 배터리 잔량이 임계값 초과 |
| 이상 (greater than or equal) | a \geq b | 값이 기준 이상 | 신호 품질이 최소 기준 이상 |
| 미만 (less than) | a < b | 값이 기준보다 작음 | 장애물 거리가 안전 거리 미만 |
| 이하 (less than or equal) | a \leq b | 값이 기준 이하 | 속도가 최대 허용 속도 이하 |
3. 개별 부등호 비교 조건 노드의 구현
3.1 IsValueGreater (초과 비교)
class IsValueGreater : public BT::ConditionNode
{
public:
IsValueGreater(const std::string& name, const BT::NodeConfig& config)
: BT::ConditionNode(name, config) {}
BT::NodeStatus tick() override
{
double value, threshold;
auto result = getInput("value", value);
if (!result)
{
return BT::NodeStatus::FAILURE;
}
getInput("threshold", threshold);
return (value > threshold) ? BT::NodeStatus::SUCCESS : BT::NodeStatus::FAILURE;
}
static BT::PortsList providedPorts()
{
return {
BT::InputPort<double>("value", "비교 대상 값"),
BT::InputPort<double>("threshold", "비교 기준 값")
};
}
};
3.2 IsValueGreaterOrEqual (이상 비교)
class IsValueGreaterOrEqual : public BT::ConditionNode
{
public:
IsValueGreaterOrEqual(const std::string& name, const BT::NodeConfig& config)
: BT::ConditionNode(name, config) {}
BT::NodeStatus tick() override
{
double value, threshold;
auto result = getInput("value", value);
if (!result)
{
return BT::NodeStatus::FAILURE;
}
getInput("threshold", threshold);
return (value >= threshold) ? BT::NodeStatus::SUCCESS : BT::NodeStatus::FAILURE;
}
static BT::PortsList providedPorts()
{
return {
BT::InputPort<double>("value", "비교 대상 값"),
BT::InputPort<double>("threshold", "비교 기준 값")
};
}
};
3.3 IsValueLess (미만 비교)
class IsValueLess : public BT::ConditionNode
{
public:
IsValueLess(const std::string& name, const BT::NodeConfig& config)
: BT::ConditionNode(name, config) {}
BT::NodeStatus tick() override
{
double value, threshold;
auto result = getInput("value", value);
if (!result)
{
return BT::NodeStatus::FAILURE;
}
getInput("threshold", threshold);
return (value < threshold) ? BT::NodeStatus::SUCCESS : BT::NodeStatus::FAILURE;
}
static BT::PortsList providedPorts()
{
return {
BT::InputPort<double>("value", "비교 대상 값"),
BT::InputPort<double>("threshold", "비교 기준 값")
};
}
};
3.4 IsValueLessOrEqual (이하 비교)
class IsValueLessOrEqual : public BT::ConditionNode
{
public:
IsValueLessOrEqual(const std::string& name, const BT::NodeConfig& config)
: BT::ConditionNode(name, config) {}
BT::NodeStatus tick() override
{
double value, threshold;
auto result = getInput("value", value);
if (!result)
{
return BT::NodeStatus::FAILURE;
}
getInput("threshold", threshold);
return (value <= threshold) ? BT::NodeStatus::SUCCESS : BT::NodeStatus::FAILURE;
}
static BT::PortsList providedPorts()
{
return {
BT::InputPort<double>("value", "비교 대상 값"),
BT::InputPort<double>("threshold", "비교 기준 값")
};
}
};
4. XML에서의 활용
<Sequence>
<!-- 배터리가 20% 이상인지 확인 -->
<Condition ID="IsValueGreaterOrEqual"
value="{battery_level}" threshold="20.0"/>
<!-- 장애물 거리가 1.0m 초과인지 확인 -->
<Condition ID="IsValueGreater"
value="{obstacle_distance}" threshold="1.0"/>
<!-- 속도가 최대 허용 속도 이하인지 확인 -->
<Condition ID="IsValueLessOrEqual"
value="{current_speed}" threshold="{max_speed}"/>
<Action ID="Navigate"/>
</Sequence>
5. 매개변수화된 범용 부등호 비교 노드
네 가지 부등호 비교를 하나의 클래스로 통합하여, 비교 연산자를 매개변수로 받는 범용 노드를 구현할 수도 있다.
class CompareValue : public BT::ConditionNode
{
public:
CompareValue(const std::string& name, const BT::NodeConfig& config)
: BT::ConditionNode(name, config) {}
BT::NodeStatus tick() override
{
double value, threshold;
auto result = getInput("value", value);
if (!result)
{
return BT::NodeStatus::FAILURE;
}
getInput("threshold", threshold);
std::string op;
getInput("op", op);
bool met = false;
if (op == ">" || op == "gt") met = (value > threshold);
else if (op == ">=" || op == "ge") met = (value >= threshold);
else if (op == "<" || op == "lt") met = (value < threshold);
else if (op == "<=" || op == "le") met = (value <= threshold);
else if (op == "==" || op == "eq") met = (value == threshold);
else if (op == "!=" || op == "ne") met = (value != threshold);
return met ? BT::NodeStatus::SUCCESS : BT::NodeStatus::FAILURE;
}
static BT::PortsList providedPorts()
{
return {
BT::InputPort<double>("value", "비교 대상 값"),
BT::InputPort<double>("threshold", "비교 기준 값"),
BT::InputPort<std::string>("op", ">=", "비교 연산자 (>, >=, <, <=, ==, !=)")
};
}
};
<Condition ID="CompareValue"
value="{battery}" threshold="20.0" op="ge"/>
범용 노드는 코드 중복을 줄이지만, XML에서의 의미 전달이 전용 노드에 비해 약하다. 프로젝트의 규모와 요구사항에 따라 적절한 방식을 선택한다.
6. 비교 연산자 선택 기준
“초과“와 “이상”, “미만“과 “이하“의 선택은 도메인의 의미에 따라 결정한다.
| 상황 | 권장 연산자 | 근거 |
|---|---|---|
| 배터리 잔량 확인 | \geq (이상) | 정확히 임계값일 때도 허용 |
| 장애물 안전 거리 | > (초과) | 정확히 임계값에서는 위험 |
| 속도 상한 | \leq (이하) | 정확히 상한값은 허용 |
| 온도 한계 | < (미만) | 정확히 한계값에서는 과열 판정 |
경계값에서의 판정이 시스템의 안전성에 영향을 미치는 경우, 보수적인 방향(안전한 방향)으로 연산자를 선택해야 한다.
7. NaN 및 Inf 처리
부등호 비교에서 NaN과 Inf에 대한 처리는 다음과 같다:
- NaN: IEEE 754 표준에 따라 NaN과의 모든 비교 연산은 거짓을 반환한다. 따라서 입력값이 NaN이면 모든 부등호 비교가
FAILURE를 반환한다. - 양의 무한대 (+Inf): 모든 유한 값보다 크다.
+Inf > threshold는 참이다. - 음의 무한대 (-Inf): 모든 유한 값보다 작다.
-Inf < threshold는 참이다.
비정상적인 값에 의한 예기치 않은 판정을 방지하려면, 비교 전에 입력값의 유효성을 검사한다.
BT::NodeStatus tick() override
{
double value, threshold;
getInput("value", value);
getInput("threshold", threshold);
if (std::isnan(value) || std::isinf(value))
{
return BT::NodeStatus::FAILURE;
}
return (value >= threshold) ? BT::NodeStatus::SUCCESS : BT::NodeStatus::FAILURE;
}
8. 참고 문헌
- 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/
- IEEE Computer Society. (2019). IEEE Standard for Floating-Point Arithmetic. IEEE Std 754-2019.
version: 0.1.0