1296.29 최소 부작용 원칙의 적용
1. 최소 부작용 원칙의 정의
최소 부작용 원칙(Minimal Side Effect Principle)은 액션 노드가 자신의 명시된 역할 이외의 시스템 상태 변경을 최소화하여야 한다는 설계 원칙이다. 여기서 부작용(side effect)이란 노드의 주된 행동과 명시적 출력 포트 이외에 발생하는 모든 상태 변경을 의미한다. 이 원칙은 함수형 프로그래밍의 순수 함수(pure function) 개념에서 유래하며, 행동 트리의 예측 가능성과 디버깅 용이성을 보장하기 위해 적용된다.
행동 트리에서 각 노드의 행동은 노드의 명칭, 입력 포트, 출력 포트만으로 예측 가능하여야 한다. 부작용이 과도한 노드는 이 예측 가능성을 파괴하여, 트리의 동작을 이해하고 디버깅하는 것을 곤란하게 한다(Colledanchise & Ögren, 2018).
2. 부작용의 분류
행동 트리의 액션 노드에서 발생하는 부작용을 성격에 따라 분류한다.
2.1 의도적 부작용
의도적 부작용(intended side effect)은 노드의 주된 목적에 해당하는 외부 상태 변경이다. 로봇 시스템의 액션 노드는 물리적 세계에 작용하는 것이 본질적 목적이므로, 이러한 부작용은 불가피하며 허용된다.
// NavigateToPose: 로봇의 물리적 위치를 변경
// → 의도적 부작용 (노드의 주된 목적)
BT::NodeStatus onStart() override
{
Pose target;
getInput("target_pose", target);
sendNavigationGoal(target); // 로봇 이동 명령
return BT::NodeStatus::RUNNING;
}
2.2 명시적 부작용
명시적 부작용(explicit side effect)은 출력 포트를 통해 선언된 블랙보드 상태 변경이다. providedPorts()에서 OutputPort로 선언되고, setOutput()을 통해 기록되는 데이터이다.
static BT::PortsList providedPorts()
{
return {
BT::InputPort<Pose>("target_pose"),
BT::OutputPort<double>("distance_traveled",
"이동한 거리 (미터)") // 명시적 출력
};
}
BT::NodeStatus onRunning() override
{
if (isNavigationComplete())
{
setOutput("distance_traveled", getDistanceTraveled());
return BT::NodeStatus::SUCCESS;
}
return BT::NodeStatus::RUNNING;
}
명시적 부작용은 포트 선언에 의해 가시화되므로, 트리의 데이터 흐름을 추적하는 것이 가능하다.
2.3 암묵적 부작용
암묵적 부작용(implicit side effect)은 포트에 선언되지 않은 블랙보드 키의 수정, 전역 상태의 변경, 예기치 않은 외부 시스템 호출 등 노드의 인터페이스에 드러나지 않는 상태 변경이다. 이 유형의 부작용이 최소 부작용 원칙의 주된 규제 대상이다.
// 암묵적 부작용의 예
BT::NodeStatus tick() override
{
Pose target;
getInput("target_pose", target);
// 암묵적 부작용 1: 포트에 선언되지 않은 블랙보드 키 수정
config().blackboard->set("last_navigation_target", target);
// 암묵적 부작용 2: 전역 로그 카운터 증가
GlobalLogger::incrementNavigationCount();
// 암묵적 부작용 3: 예기치 않은 토픽 발행
debug_publisher_->publish(createDebugMsg(target));
return BT::NodeStatus::SUCCESS;
}
3. 암묵적 부작용의 문제점
3.1 예측 불가능성
암묵적 부작용이 존재하면, 노드의 명칭과 포트 선언만으로는 노드의 전체 효과를 파악할 수 없다. 트리의 XML 정의를 검토하는 것만으로는 시스템의 상태 변경을 완전히 이해할 수 없게 된다.
<!-- XML만으로는 last_navigation_target이 설정되는 것을 알 수 없음 -->
<NavigateToPose target_pose="{goal}" />
3.2 순서 의존성
암묵적 부작용에 의해 노드 간에 포트로 선언되지 않은 의존성이 형성된다. 이 의존성은 XML에서 가시화되지 않으므로, 트리 구조를 변경할 때 예기치 않은 오동작이 발생할 수 있다.
<!-- NodeA가 암묵적으로 블랙보드 키 X를 설정 -->
<!-- NodeB가 암묵적으로 블랙보드 키 X를 읽음 -->
<!-- 순서를 변경하면 NodeB가 올바른 값을 읽지 못함 -->
<Sequence>
<NodeA />
<NodeB /> <!-- X에 대한 암묵적 의존 -->
</Sequence>
이러한 암묵적 의존성은 “보이지 않는 와이어(invisible wire)“로서, 트리의 구조적 변경을 위험하게 만든다.
3.3 디버깅 곤란
블랙보드의 특정 키가 예기치 않은 값을 가지는 경우, 그 값을 설정한 노드를 추적하기 위해 모든 노드의 소스 코드를 검사하여야 한다. 포트를 통한 명시적 데이터 흐름에서는 XML의 포트 연결만으로 데이터의 출처를 추적할 수 있으나, 암묵적 부작용에서는 이것이 불가능하다.
3.4 테스트 복잡도 증가
암묵적 부작용이 존재하면, 노드의 단위 테스트에서 명시된 입출력뿐 아니라 암묵적으로 변경되는 모든 상태를 검증하여야 한다. 이는 테스트의 범위와 복잡도를 증가시킨다.
4. 최소 부작용 원칙의 적용 방법
4.1 블랙보드 접근의 포트 한정
블랙보드에 대한 모든 읽기와 쓰기는 providedPorts()에서 선언된 포트를 통해서만 수행한다. config().blackboard에 직접 접근하여 포트에 선언되지 않은 키를 읽거나 쓰는 것을 금지한다.
// 위반: 블랙보드 직접 접근
config().blackboard->set("undeclared_key", value);
// 준수: 포트를 통한 접근
setOutput("declared_output", value);
4.2 전역 상태 변경의 금지
싱글턴 객체, 정적 변수, 전역 변수의 수정은 노드의 인터페이스에 드러나지 않는 부작용이다. 전역 상태에 의존하는 노드는 테스트와 재사용이 곤란하며, 실행 순서에 대한 암묵적 의존성을 형성한다.
// 위반: 전역 상태 변경
class IncrementCounter : public BT::SyncActionNode
{
BT::NodeStatus tick() override
{
GlobalState::counter++; // 전역 상태 변경
return BT::NodeStatus::SUCCESS;
}
};
// 준수: 포트를 통한 상태 전달
class IncrementCounter : public BT::SyncActionNode
{
public:
static BT::PortsList providedPorts()
{
return {
BT::InputPort<int>("current_count"),
BT::OutputPort<int>("updated_count")
};
}
BT::NodeStatus tick() override
{
int count;
if (!getInput("current_count", count))
return BT::NodeStatus::FAILURE;
setOutput("updated_count", count + 1);
return BT::NodeStatus::SUCCESS;
}
};
4.3 예상 외 외부 통신의 제한
노드의 주된 역할이 아닌 추가적인 ROS2 통신(토픽 발행, 서비스 호출 등)은 암묵적 부작용에 해당한다. 디버그 정보의 발행, 상태 보고, 로깅 등이 이에 해당하며, 이러한 기능은 별도의 전용 노드로 분리하는 것이 원칙이다.
// 위반: 내비게이션 노드에서 상태 토픽 발행
class NavigateToPose : public BT::StatefulActionNode
{
BT::NodeStatus onRunning() override
{
// 주된 역할: 내비게이션 완료 확인
if (isNavigationComplete())
return BT::NodeStatus::SUCCESS;
// 부작용: 상태 토픽 발행 (주된 역할이 아님)
status_publisher_->publish(createStatusMsg());
return BT::NodeStatus::RUNNING;
}
};
// 준수: 상태 발행을 별도 노드로 분리
// NavigateToPose는 내비게이션만 수행
// PublishNavigationStatus는 상태 발행만 수행
5. 허용되는 부작용의 범위
최소 부작용 원칙은 모든 부작용을 금지하는 것이 아니라, 불필요한 부작용을 최소화하는 것이다. 다음의 부작용은 노드의 역할에 필수적이므로 허용된다.
| 부작용 유형 | 허용 여부 | 이유 |
|---|---|---|
| ROS2 액션 목표 전송 | 허용 | 노드의 주된 역할 |
| 선언된 출력 포트 기록 | 허용 | 명시적 인터페이스 |
ROS2 로깅 (RCLCPP_INFO 등) | 허용 | 관측 전용, 상태 변경 없음 |
| 노드 내부 멤버 변수 수정 | 허용 | 노드 내부 상태 |
| 미선언 블랙보드 키 수정 | 금지 | 암묵적 데이터 흐름 |
| 전역 변수 수정 | 금지 | 가시성 부재 |
| 의도하지 않은 토픽 발행 | 금지 | 암묵적 외부 통신 |
| 다른 노드의 상태 직접 변경 | 금지 | 캡슐화 위반 |
ROS2의 로깅 호출(RCLCPP_INFO, RCLCPP_WARN 등)은 시스템 상태를 변경하지 않는 관측 전용(observation-only) 행위이므로 부작용에 해당하지 않는다.
6. 부작용 분석 기법
노드의 부작용을 체계적으로 분석하기 위한 기법을 제시한다.
6.1 입출력 대조 분석
노드의 providedPorts() 선언과 실제 코드에서의 블랙보드 접근을 대조하여, 포트에 선언되지 않은 접근을 식별한다.
[분석 대상 노드: NavigateToPose]
선언된 포트:
입력: target_pose (Pose)
출력: distance_traveled (double)
실제 블랙보드 접근:
getInput("target_pose") → 선언됨 ✓
setOutput("distance_traveled") → 선언됨 ✓
blackboard->set("last_target") → 미선언 ✗ ← 암묵적 부작용
6.2 외부 호출 목록화
노드 내부에서 수행되는 모든 외부 시스템 호출(ROS2 통신, 파일 I/O, 네트워크 등)을 목록화하고, 노드의 주된 역할에 해당하지 않는 호출을 식별한다.
7. 최소 부작용과 트리의 투명성
최소 부작용 원칙의 준수는 행동 트리의 “투명성(transparency)“을 보장한다. 투명한 행동 트리에서는 트리의 XML 정의와 각 노드의 포트 선언만으로 전체 시스템의 데이터 흐름과 행동 순서를 파악할 수 있다.
<!-- 투명한 트리: 모든 데이터 흐름이 포트로 가시화 -->
<Sequence>
<DetectObject object_id="{id}" object_pose="{pose}" />
<NavigateToPose target_pose="{pose}"
distance_traveled="{dist}" />
<PickupObject object_id="{id}" success="{picked}" />
</Sequence>
이 트리에서 데이터 흐름은 {id}, {pose}, {dist}, {picked}의 블랙보드 키를 통해 완전히 가시화된다. 암묵적 부작용이 없으므로, 노드의 순서를 변경하거나 새로운 노드를 삽입할 때 예기치 않은 부작용이 발생하지 않는다.
8. 설계 지침
-
포트 선언의 완전성: 노드가 블랙보드에 기록하는 모든 데이터를 출력 포트로 선언한다.
-
블랙보드 직접 접근 금지:
config().blackboard->set()또는config().blackboard->get()에 의한 포트 우회 접근을 금지한다. -
전역 상태 비의존: 싱글턴, 정적 변수, 전역 변수에 대한 읽기와 쓰기를 피하고, 필요한 데이터는 포트를 통해 전달한다.
-
부수적 통신의 분리: 노드의 주된 역할이 아닌 ROS2 통신(상태 발행, 로깅 등)은 별도 노드로 분리한다.
-
코드 리뷰 시 부작용 검증: 액션 노드의 코드 리뷰에서 입출력 대조 분석을 수행하여 암묵적 부작용을 검출한다(Faconti, 2022).