1297.9 단일 조건 평가 원칙
1. 원칙의 정의
단일 조건 평가 원칙(Single Condition Evaluation Principle)은 하나의 조건 노드가 정확히 하나의 논리적 명제만을 평가해야 한다는 설계 원칙이다. 이 원칙은 소프트웨어 공학의 단일 책임 원칙(Single Responsibility Principle, SRP)을 행동 트리(Behavior Tree)의 조건 노드에 적용한 것이다(Martin, 2003).
하나의 조건 노드는 “배터리가 충분한가?”, “장애물이 감지되었는가?”, “목표에 도달하였는가?“와 같이 하나의 명확한 질문에 대한 답을 제공해야 한다. 복수의 질문을 하나의 노드에서 동시에 답하는 것은 이 원칙에 위배된다.
2. 원칙의 근거
2.1 실패 원인의 식별
복수의 조건을 하나의 노드에서 평가하면, FAILURE 반환 시 어떤 조건이 미충족되었는지를 외부에서 판별할 수 없다. 이는 디버깅을 어렵게 하고, 행동 트리 로그의 진단적 가치를 저하시킨다.
// 단일 조건 평가 원칙 위반
BT::NodeStatus IsReadyToNavigate::tick()
{
double battery;
getInput("battery", battery);
double localization_quality;
getInput("localization_quality", localization_quality);
bool has_path;
getInput("has_path", has_path);
// 세 가지 조건을 동시 평가 → FAILURE 시 원인 불명
if (battery > 20.0 && localization_quality > 0.7 && has_path)
{
return BT::NodeStatus::SUCCESS;
}
return BT::NodeStatus::FAILURE;
}
위 구현에서 FAILURE가 반환되면, 배터리 부족인지, 위치 추정 품질 저하인지, 경로 부재인지를 노드 외부에서 구분할 수 없다.
2.2 재사용성
단일 조건을 평가하는 노드는 다양한 트리 구조에서 재사용할 수 있다. IsBatteryOk 노드는 내비게이션 트리, 충전 트리, 비상 정지 트리 등 배터리 상태를 확인해야 하는 모든 곳에서 동일하게 사용된다. 그러나 IsReadyToNavigate처럼 복합 조건을 포함하는 노드는 내비게이션 맥락에서만 의미를 가지며, 다른 맥락에서 재사용하기 어렵다.
2.3 조합의 유연성
행동 트리의 제어 노드는 자체적으로 논리 연산을 구현한다. Sequence는 AND 연산을, Fallback은 OR 연산을, Inverter 데코레이터는 NOT 연산을 수행한다. 단일 조건 노드를 이러한 제어 노드와 조합하면, 임의의 복합 조건을 트리 구조로 표현할 수 있다.
// AND 조합: 세 조건 모두 충족 시 내비게이션 실행
Sequence
├── IsBatteryOk
├── IsLocalized
├── HasValidPath
└── Navigate
// OR 조합: 하나라도 충족되면 대기
Fallback
├── IsCharging
├── IsWaitingForCommand
└── Idle
이 방식은 복합 조건 노드를 작성하는 것보다 유연하다. 조건의 추가, 제거, 순서 변경이 XML 트리 정의의 수정만으로 가능하며, C++ 코드의 변경이 필요하지 않다.
3. 단일 조건의 정의 기준
어떤 평가가 “단일 조건“에 해당하는지를 판단하기 위한 기준은 다음과 같다.
3.1 하나의 명제
조건 노드가 평가하는 내용을 하나의 자연어 문장으로 표현할 수 있어야 한다. “배터리가 20% 이상인가?“는 단일 조건이다. “배터리가 20% 이상이고 온도가 정상 범위인가?“는 두 개의 조건이 결합된 복합 조건이다.
3.2 하나의 데이터 소스
이상적으로 하나의 조건 노드는 하나의 데이터 소스로부터 정보를 읽어 판정을 내린다. 배터리 잔량, 장애물 거리, 위치 추정 품질 등 각각 독립적인 데이터 소스에 기반한 판정은 별도의 조건 노드로 분리한다.
3.3 하나의 변경 이유
단일 책임 원칙에 따라, 조건 노드의 구현이 변경되어야 하는 이유가 하나여야 한다. 배터리 임계값의 변경과 온도 범위의 변경은 서로 독립적인 변경 이유이므로, 이를 하나의 노드에서 처리하면 안 된다.
4. 올바른 분리 사례
4.1 분리 전: 복합 조건 노드
BT::NodeStatus IsSafeToFly::tick()
{
double altitude, wind_speed, battery;
getInput("altitude", altitude);
getInput("wind_speed", wind_speed);
getInput("battery", battery);
bool altitude_ok = (altitude >= min_altitude_ && altitude <= max_altitude_);
bool wind_ok = (wind_speed < max_wind_speed_);
bool battery_ok = (battery > min_battery_);
return (altitude_ok && wind_ok && battery_ok)
? BT::NodeStatus::SUCCESS
: BT::NodeStatus::FAILURE;
}
4.2 분리 후: 단일 조건 노드의 조합
// 고도 범위 확인
BT::NodeStatus IsAltitudeInRange::tick()
{
double altitude;
getInput("altitude", altitude);
double min_alt, max_alt;
getInput("min_altitude", min_alt);
getInput("max_altitude", max_alt);
return (altitude >= min_alt && altitude <= max_alt)
? BT::NodeStatus::SUCCESS : BT::NodeStatus::FAILURE;
}
// 풍속 한계 확인
BT::NodeStatus IsWindSpeedSafe::tick()
{
double wind_speed, max_wind;
getInput("wind_speed", wind_speed);
getInput("max_wind_speed", max_wind);
return (wind_speed < max_wind)
? BT::NodeStatus::SUCCESS : BT::NodeStatus::FAILURE;
}
// 배터리 잔량 확인
BT::NodeStatus IsBatteryOk::tick()
{
double battery, threshold;
getInput("battery", battery);
getInput("threshold", threshold);
return (battery > threshold)
? BT::NodeStatus::SUCCESS : BT::NodeStatus::FAILURE;
}
<Sequence name="SafeToFly">
<Condition ID="IsAltitudeInRange"
altitude="{altitude}" min_altitude="10.0" max_altitude="120.0"/>
<Condition ID="IsWindSpeedSafe"
wind_speed="{wind_speed}" max_wind_speed="15.0"/>
<Condition ID="IsBatteryOk"
battery="{battery}" threshold="30.0"/>
</Sequence>
분리 후의 구조에서는 각 조건의 성공/실패가 개별적으로 추적되며, 임계값의 독립적 조정이 가능하고, 각 노드를 다른 트리에서 재사용할 수 있다.
5. 단일 조건의 범위 판단
단일 조건의 범위가 지나치게 좁아져 사소한 연산까지 별도의 노드로 분리하는 것은 비효율적이다. 다음의 경우는 하나의 조건 노드 내에서 처리하는 것이 적절하다.
- 범위 검사: 하한과 상한을 동시에 비교하는 것은 “값이 범위 내에 있는가?“라는 단일 명제이다.
- 거리 계산과 비교: 유클리드 거리를 계산하고 임계값과 비교하는 것은 “목표까지의 거리가 임계값 이내인가?“라는 단일 명제이다.
- 널(null) 검사와 값 비교: 값의 존재 여부를 확인한 후 비교하는 것은 하나의 평가 절차의 일부이다.
// 적절한 단일 조건: 거리 계산 + 비교
BT::NodeStatus IsGoalReached::tick()
{
double robot_x, robot_y, goal_x, goal_y, tolerance;
getInput("robot_x", robot_x);
getInput("robot_y", robot_y);
getInput("goal_x", goal_x);
getInput("goal_y", goal_y);
getInput("tolerance", tolerance);
double distance = std::sqrt(
std::pow(robot_x - goal_x, 2) + std::pow(robot_y - goal_y, 2));
return (distance <= tolerance)
? BT::NodeStatus::SUCCESS
: BT::NodeStatus::FAILURE;
}
이 구현에서 거리 계산과 임계값 비교는 하나의 논리적 명제(“목표에 도달하였는가?”)를 평가하기 위한 연산이므로, 분리할 필요가 없다.
6. 참고 문헌
- Colledanchise, M., & Ogren, P. (2018). Behavior Trees in Robotics and AI: An Introduction. CRC Press.
- Martin, R. C. (2003). Agile Software Development: Principles, Patterns, and Practices. Prentice Hall.
- Faconti, D., & Colledanchise, M. (2022). BehaviorTree.CPP Documentation. https://www.behaviortree.dev/
version: 0.1.0