1295.95 Parallel과 Reactive 노드의 안티패턴
1. Parallel 노드의 안티패턴
1.1 안티패턴 1: 순서 의존적 자식 배치
Parallel 노드의 자식 간에 데이터 의존성이 존재하여, 자식의 실행 순서에 따라 결과가 달라지는 구성이다.
<!-- 안티패턴: 자식 간 순서 의존 -->
<ParallelAll max_failures="0">
<ComputeObstacleMap output="{obstacle_map}"/>
<PlanPath input="{obstacle_map}" output="{path}"/>
</ParallelAll>
PlanPath는 ComputeObstacleMap이 블랙보드에 기록한 obstacle_map에 의존한다. Parallel에서 두 자식은 동일 Tick에 순차적으로 Tick되므로, ComputeObstacleMap이 먼저 Tick되면 현재 Tick의 맵을 사용하지만, PlanPath가 먼저 Tick되면 이전 Tick의 맵을 사용하게 된다.
교정: 데이터 의존이 있는 노드는 Sequence로 구성한다.
<Sequence>
<ComputeObstacleMap output="{obstacle_map}"/>
<PlanPath input="{obstacle_map}" output="{path}"/>
</Sequence>
1.2 안티패턴 2: 블랙보드 쓰기 충돌
다수의 자식이 동일한 블랙보드 키에 쓰기를 수행하는 구성이다.
<!-- 안티패턴: 동일 키에 다중 쓰기 -->
<ParallelAll max_failures="1">
<LidarDetection output="{obstacle_distance}"/>
<CameraDetection output="{obstacle_distance}"/>
<UltrasonicDetection output="{obstacle_distance}"/>
</ParallelAll>
세 자식이 모두 obstacle_distance에 쓰기를 수행하므로, 최종 값은 마지막으로 Tick된 자식의 결과이다. 이는 Tick 순서에 의존하는 비결정론적 동작을 유발한다.
교정: 자식별로 고유한 출력 키를 사용하고, 별도의 융합 노드에서 결과를 통합한다.
<Sequence>
<ParallelAll max_failures="1">
<LidarDetection output="{lidar_distance}"/>
<CameraDetection output="{camera_distance}"/>
<UltrasonicDetection output="{ultrasonic_distance}"/>
</ParallelAll>
<FuseDistances lidar="{lidar_distance}"
camera="{camera_distance}"
ultrasonic="{ultrasonic_distance}"
output="{obstacle_distance}"/>
</Sequence>
1.3 안티패턴 3: 과도한 자식 수
하나의 Parallel 노드에 10개 이상의 자식을 배치하는 구성이다. 상태 조합이 3^{10} = 59049개에 달하여 테스트와 디버깅이 사실상 불가능해진다.
교정: 관련 자식을 서브트리로 그룹화하여 계층적 구조를 구성한다.
1.4 안티패턴 4: Halt 미구현
Parallel의 자식으로 사용되는 커스텀 행동 노드에서 onHalted() 메서드를 구현하지 않는 경우이다. Parallel이 정책을 충족하면 haltChildren()을 호출하는데, onHalted()가 미구현이면 자원 해제가 수행되지 않는다.
// 안티패턴: onHalted() 미구현
class MyAction : public BT::StatefulActionNode
{
BT::NodeStatus onStart() override
{
ros_action_client_->sendGoal(goal_);
return BT::NodeStatus::RUNNING;
}
BT::NodeStatus onRunning() override { /* ... */ }
// onHalted()가 없음 → ROS 액션이 취소되지 않음
};
교정: onHalted()에서 진행 중인 모든 외부 요청을 취소하고 자원을 해제한다.
1.5 안티패턴 5: 정책의 암묵적 사용
max_failures의 의미를 문서화하지 않고 사용하여, 코드 리뷰나 유지보수 시 정책의 의도를 파악하기 어렵게 만드는 경우이다.
<!-- 안티패턴: 의도 불명확 -->
<ParallelAll max_failures="2">
<A/> <B/> <C/> <D/>
</ParallelAll>
교정: XML 주석으로 정책의 의도를 명시한다.
<!-- 4개 센서 중 최소 2개 성공 필요 (2개까지 실패 허용) -->
<ParallelAll max_failures="2">
<SensorA/> <SensorB/> <SensorC/> <SensorD/>
</ParallelAll>
2. ReactiveSequence의 안티패턴
2.1 안티패턴 6: 중량 조건 노드
ReactiveSequence의 조건 노드에서 무거운 연산(경로 계획, 이미지 처리, 서비스 호출 등)을 직접 수행하는 경우이다. 조건은 매 Tick마다 재평가되므로, 중량 연산이 매 Tick에서 반복되어 심각한 성능 저하를 유발한다.
// 안티패턴: 조건 내 중량 연산
BT::NodeStatus IsPathClear::tick()
{
auto costmap = costmap_subscriber_->getData(); // 데이터 복사
auto path = getInput<Path>("path").value();
return checkCollisionFull(costmap, path) // 무거운 연산
? BT::NodeStatus::SUCCESS
: BT::NodeStatus::FAILURE;
}
교정: 중량 연산은 별도의 비동기 프로세스에서 수행하고, 조건 노드는 블랙보드에서 결과만 읽는다.
2.2 안티패턴 7: ReactiveSequence와 Sequence의 혼동
전제 조건의 지속적 검사가 불필요한 곳에 ReactiveSequence를 사용하는 경우이다. 일회성 초기화 작업에 ReactiveSequence를 사용하면, 이미 완료된 초기화를 매 Tick마다 재실행하게 된다.
<!-- 안티패턴: 일회성 작업에 ReactiveSequence 사용 -->
<ReactiveSequence>
<InitializeSensors/> <!-- 매 Tick마다 재초기화됨 -->
<CalibrateIMU/> <!-- 매 Tick마다 재보정됨 -->
<StartNavigation/>
</ReactiveSequence>
교정: 일회성 작업에는 일반 Sequence를, 지속적 전제 조건 검사에는 ReactiveSequence를 사용한다.
<Sequence>
<InitializeSensors/>
<CalibrateIMU/>
<ReactiveSequence>
<IsLocalized/>
<StartNavigation/>
</ReactiveSequence>
</Sequence>
2.3 안티패턴 8: 히스테리시스 없는 조건
센서 잡음에 의해 조건이 SUCCESS와 FAILURE 사이를 빠르게 진동하는 경우이다. 이로 인해 행동의 반복적 시작과 Halt가 발생하여 로봇의 동작이 불안정해진다.
교정: 조건 노드에 히스테리시스(진입 임계값과 복귀 임계값의 차이)를 적용한다.
3. ReactiveFallback의 안티패턴
3.1 안티패턴 9: 기본 행동 누락
ReactiveFallback의 마지막 자식이 조건부 분기로 구성되어, 모든 조건이 비활성일 때 ReactiveFallback이 FAILURE를 반환하는 경우이다.
<!-- 안티패턴: 기본 행동 없음 -->
<ReactiveFallback>
<Sequence>
<IsEmergency/> <EmergencyStop/>
</Sequence>
<Sequence>
<IsBatteryLow/> <ReturnToBase/>
</Sequence>
<!-- 모든 조건 FAILURE → ReactiveFallback FAILURE → 무동작 -->
</ReactiveFallback>
교정: 마지막 자식에 무조건 실행되는 기본 행동을 배치한다.
<ReactiveFallback>
<Sequence>
<IsEmergency/> <EmergencyStop/>
</Sequence>
<Sequence>
<IsBatteryLow/> <ReturnToBase/>
</Sequence>
<ExecuteMission/> <!-- 기본 행동 -->
</ReactiveFallback>
3.2 안티패턴 10: 우선순위 역전
낮은 우선순위의 조건이 높은 우선순위보다 앞에 배치되는 경우이다. ReactiveFallback은 자식의 나열 순서가 우선순위를 결정하므로, 배치 오류는 비상 대응 지연으로 직결된다.
<!-- 안티패턴: 우선순위 역전 -->
<ReactiveFallback>
<Sequence>
<IsBatteryLow/> <ReturnToBase/>
</Sequence>
<Sequence>
<IsEmergency/> <EmergencyStop/> <!-- 비상이 더 낮은 우선순위 -->
</Sequence>
<ExecuteMission/>
</ReactiveFallback>
교정: 비상 대응을 최상위에 배치한다.
4. 안티패턴 식별 점검표
| 점검 항목 | 안티패턴 | 위험도 |
|---|---|---|
| Parallel 자식 간 블랙보드 의존 | 순서 의존적 자식 | 높음 |
| 동일 블랙보드 키에 다중 쓰기 | 쓰기 충돌 | 높음 |
| onHalted() 미구현 | Halt 미처리 | 높음 |
| 조건 내 중량 연산 | 중량 조건 | 중간 |
| 일회성 작업에 ReactiveSequence | 노드 혼동 | 중간 |
| 기본 행동 누락 | 무동작 상태 | 높음 |
| 우선순위 역전 | 비상 지연 | 최고 |
| 히스테리시스 없는 조건 | 조건 진동 | 중간 |
| 과도한 자식 수 | 복잡도 폭발 | 중간 |
| 정책 의도 미문서화 | 가독성 저하 | 낮음 |
코드 리뷰 시 이 점검표를 활용하여 안티패턴을 체계적으로 식별하고 교정한다.