1297.24 등호 비교 조건 노드의 구현
1. 등호 비교의 정의
등호 비교 조건 노드(equality comparison condition node)는 블랙보드에서 읽은 값이 기대값과 동일한지를 판정하는 조건 노드이다. 두 값 a와 b에 대하여 a = b이면 SUCCESS를, a \neq b이면 FAILURE를 반환한다. 등호 비교는 모드 일치 확인, 상태 코드 검증, 열거형 값 판별 등에 사용된다.
2. 정수형 등호 비교
정수(int) 타입의 등호 비교는 정확한 일치를 판정하므로 수치적 오차 문제가 발생하지 않는다.
class IsIntEqual : public BT::ConditionNode
{
public:
IsIntEqual(const std::string& name, const BT::NodeConfig& config)
: BT::ConditionNode(name, config) {}
BT::NodeStatus tick() override
{
int value, expected;
auto result = getInput("value", value);
if (!result)
{
return BT::NodeStatus::FAILURE;
}
getInput("expected", expected);
return (value == expected) ? BT::NodeStatus::SUCCESS : BT::NodeStatus::FAILURE;
}
static BT::PortsList providedPorts()
{
return {
BT::InputPort<int>("value", "비교 대상 값"),
BT::InputPort<int>("expected", "기대 값")
};
}
};
<!-- 오류 코드가 0인지 확인 -->
<Condition ID="IsIntEqual" value="{error_code}" expected="0"/>
<!-- 현재 상태가 특정 값인지 확인 -->
<Condition ID="IsIntEqual" value="{system_state}" expected="3"/>
3. 부동소수점 등호 비교
부동소수점(double, float) 값의 등호 비교는 IEEE 754 부동소수점 표현의 유한 정밀도로 인해 정확한 일치를 기대할 수 없다. 수학적으로 동일한 결과가 서로 다른 계산 경로를 통해 미세하게 다른 값을 산출할 수 있기 때문이다. 따라서 부동소수점 등호 비교에는 허용 오차(epsilon)를 적용한 근사 비교(approximate comparison)를 사용해야 한다.
class IsDoubleEqual : public BT::ConditionNode
{
public:
IsDoubleEqual(const std::string& name, const BT::NodeConfig& config)
: BT::ConditionNode(name, config) {}
BT::NodeStatus tick() override
{
double value, expected, epsilon;
auto result = getInput("value", value);
if (!result)
{
return BT::NodeStatus::FAILURE;
}
getInput("expected", expected);
getInput("epsilon", epsilon);
return (std::abs(value - expected) <= epsilon)
? BT::NodeStatus::SUCCESS
: BT::NodeStatus::FAILURE;
}
static BT::PortsList providedPorts()
{
return {
BT::InputPort<double>("value", "비교 대상 값"),
BT::InputPort<double>("expected", "기대 값"),
BT::InputPort<double>("epsilon", 1e-6, "허용 오차 (기본값: 1e-6)")
};
}
};
3.1 허용 오차의 선택
허용 오차의 크기는 비교 대상 데이터의 특성에 따라 결정한다:
| 데이터 유형 | 권장 허용 오차 | 근거 |
|---|---|---|
| 각도 (라디안) | 10^{-4} | 센서 정밀도 수준 |
| 위치 (미터) | 10^{-3} ~ 10^{-2} | 위치 추정 오차 |
| 전압, 전류 | 10^{-2} | 아날로그 센서 잡음 |
| 정규화된 값 (0~1) | 10^{-6} | 수치 연산 오차 |
4. 문자열 등호 비교
문자열(string) 타입의 등호 비교는 문자열 일치를 판정한다. 비행 모드, 로봇 상태, 임무 이름 등 열거형 대신 문자열로 표현된 값의 비교에 사용된다.
class IsStringEqual : public BT::ConditionNode
{
public:
IsStringEqual(const std::string& name, const BT::NodeConfig& config)
: BT::ConditionNode(name, config) {}
BT::NodeStatus tick() override
{
std::string value, expected;
auto result = getInput("value", value);
if (!result)
{
return BT::NodeStatus::FAILURE;
}
getInput("expected", expected);
return (value == expected) ? BT::NodeStatus::SUCCESS : BT::NodeStatus::FAILURE;
}
static BT::PortsList providedPorts()
{
return {
BT::InputPort<std::string>("value", "비교 대상 문자열"),
BT::InputPort<std::string>("expected", "기대 문자열")
};
}
};
<!-- 비행 모드 확인 -->
<Condition ID="IsStringEqual" value="{flight_mode}" expected="OFFBOARD"/>
<!-- 임무 상태 확인 -->
<Condition ID="IsStringEqual" value="{mission_status}" expected="READY"/>
4.1 대소문자 무시 비교
대소문자를 구분하지 않는 비교가 필요한 경우, 비교 전에 양쪽 문자열을 동일한 대소문자로 변환한다.
BT::NodeStatus tick() override
{
std::string value, expected;
getInput("value", value);
getInput("expected", expected);
// 대소문자 무시 비교
std::transform(value.begin(), value.end(), value.begin(), ::tolower);
std::transform(expected.begin(), expected.end(), expected.begin(), ::tolower);
return (value == expected) ? BT::NodeStatus::SUCCESS : BT::NodeStatus::FAILURE;
}
5. 불리언 등호 비교
불리언(bool) 타입의 등호 비교는 플래그 값의 확인에 사용된다.
class IsBoolEqual : public BT::ConditionNode
{
public:
IsBoolEqual(const std::string& name, const BT::NodeConfig& config)
: BT::ConditionNode(name, config) {}
BT::NodeStatus tick() override
{
bool value, expected;
auto result = getInput("value", value);
if (!result)
{
return BT::NodeStatus::FAILURE;
}
getInput("expected", expected);
return (value == expected) ? BT::NodeStatus::SUCCESS : BT::NodeStatus::FAILURE;
}
static BT::PortsList providedPorts()
{
return {
BT::InputPort<bool>("value", "비교 대상 불리언 값"),
BT::InputPort<bool>("expected", true, "기대 값 (기본값: true)")
};
}
};
불리언 등호 비교는 대부분의 경우 expected가 true이므로, 기본값을 true로 설정하여 XML에서 생략할 수 있도록 한다.
<!-- is_armed가 true인지 확인 (expected 생략 → true) -->
<Condition ID="IsBoolEqual" value="{is_armed}"/>
6. NaN 처리
부동소수점 비교에서 입력값이 NaN인 경우, IEEE 754 표준에 따라 NaN과의 모든 비교는 거짓을 반환한다. 따라서 NaN == NaN은 거짓이다. 이 동작을 명시적으로 처리하여 예측 가능한 결과를 보장한다.
if (std::isnan(value) || std::isnan(expected))
{
return BT::NodeStatus::FAILURE;
}
7. 참고 문헌
- 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