1296.99 액션 노드 설계의 안티패턴
1. 개요
안티패턴(anti-pattern)은 겉보기에는 합리적이지만 실제로는 유지보수성, 재사용성, 안전성, 성능 등에 부정적인 영향을 미치는 반복적인 설계 실수이다. 행동 트리의 액션 노드 설계에서 발생하는 안티패턴을 식별하고 이해하면, 동일한 실수를 방지하고 더 나은 설계를 달성할 수 있다.
본 절에서는 BehaviorTree.CPP 기반 액션 노드 설계에서 빈번히 관찰되는 안티패턴과 그 개선 방안을 기술한다.
2. 안티패턴 1: 거대 노드 (God Node)
2.1 문제
하나의 액션 노드에 과도하게 많은 기능을 구현하여, 이미지 촬영, 물체 탐지, 경로 계획, 이동 명령을 모두 하나의 노드에서 수행하는 설계이다.
// 안티패턴
class DoEverythingAction : public BT::StatefulActionNode
{
BT::NodeStatus onStart() override
{
captureImage();
detectObjects();
planPath();
sendNavigationGoal();
return BT::NodeStatus::RUNNING;
}
};
2.2 해악
- 노드의 재사용이 불가능하다.
- 부분적 실패의 원인을 특정할 수 없다.
- 단위 테스트가 극히 어렵다.
- 코드의 복잡도가 비선형적으로 증가한다.
2.3 개선
각 기능을 독립적인 노드로 분리하고 행동 트리에서 조합한다.
<Sequence>
<CaptureImage image="{img}" />
<DetectObject image="{img}" detections="{det}" />
<ComputePath detections="{det}" path="{path}" />
<FollowPath path="{path}" />
</Sequence>
3. 안티패턴 2: SyncActionNode에서의 블로킹
3.1 문제
동기 액션 노드의 tick() 메서드에서 장시간 블로킹되는 연산을 수행한다.
// 안티패턴
class BlockingSyncAction : public BT::SyncActionNode
{
BT::NodeStatus tick() override
{
// 서비스 응답을 동기적으로 대기 (수 초 소요)
auto future = client_->async_send_request(req);
rclcpp::spin_until_future_complete(node_, future);
return BT::NodeStatus::SUCCESS;
}
};
3.2 해악
- 행동 트리의 tick 루프 전체가 블로킹되어, 다른 노드의 반응성이 저하된다.
ReactiveFallback등 반응형 제어 노드의 조건 재평가가 지연된다.- halt 요청에 즉시 응답할 수 없다.
3.3 개선
StatefulActionNode로 전환하여 비동기 처리한다.
class AsyncServiceAction : public BT::StatefulActionNode
{
BT::NodeStatus onStart() override
{
future_ = client_->async_send_request(req);
return BT::NodeStatus::RUNNING;
}
BT::NodeStatus onRunning() override
{
if (future_.wait_for(std::chrono::milliseconds(0))
== std::future_status::ready)
{
auto result = future_.get();
return result->success
? BT::NodeStatus::SUCCESS
: BT::NodeStatus::FAILURE;
}
return BT::NodeStatus::RUNNING;
}
};
4. 안티패턴 3: onHalted() 미구현
4.1 문제
비동기 액션 노드에서 onHalted() 콜백을 구현하지 않거나, 빈 구현으로 방치한다.
// 안티패턴
void onHalted() override
{
// 아무것도 하지 않음
}
4.2 해악
- 진행 중인 ROS2 액션이 취소되지 않아 로봇이 의도하지 않은 동작을 계속 수행한다.
- 구독, 타이머 등의 자원이 해제되지 않아 자원 누수가 발생한다.
- 이전 실행의 상태가 다음 실행에 영향을 미쳐 예측 불가능한 동작이 발생한다.
4.3 개선
모든 외부 작업 취소, 자원 해제, 상태 초기화를 완전히 수행한다.
5. 안티패턴 4: 직접 블랙보드 접근
5.1 문제
providedPorts()에 포트를 선언하지 않고 블랙보드에 직접 접근하여 데이터를 읽고 쓴다.
// 안티패턴
BT::NodeStatus tick() override
{
auto bb = config().blackboard;
double value;
bb->get("hidden_key", value); // 포트 미선언
bb->set("secret_output", result); // 포트 미선언
}
5.2 해악
- 노드의 인터페이스가 불투명하여, XML 행동 트리 정의에서 데이터 의존성을 파악할 수 없다.
- Groot2 등의 시각화 도구에서 포트 연결이 표시되지 않는다.
- 리매핑(remapping)이 불가능하여 서브트리에서의 재사용이 제한된다.
5.3 개선
모든 데이터를 providedPorts()에 선언하고, getInput()과 setOutput()을 통해 접근한다.
6. 안티패턴 5: 하드코딩된 토픽 이름
6.1 문제
ROS2 토픽, 서비스, 액션 서버 이름을 코드에 하드코딩한다.
// 안티패턴
MyAction(...)
{
client_ = rclcpp_action::create_client<Nav>(
node_, "/navigate_to_pose"); // 하드코딩
}
6.2 해악
- 동일 유형의 복수 서버(예: 다중 로봇)에 대응할 수 없다.
- 네임스페이스 변경 시 코드를 수정해야 한다.
- 테스트 시 모의 서버로의 전환이 어렵다.
6.3 개선
토픽 이름을 입력 포트 또는 생성자 파라미터로 외부화한다.
static BT::PortsList providedPorts()
{
return {
BT::InputPort<std::string>("server_name",
"navigate_to_pose",
"액션 서버 이름")
};
}
7. 안티패턴 6: 타임아웃 미구현
7.1 문제
비동기 액션 노드에 타임아웃을 구현하지 않아, 외부 서비스 장애 시 RUNNING 상태가 무한히 지속된다.
7.2 해악
- 행동 트리가 교착 상태에 빠져 다른 경로를 탐색하지 못한다.
- 로봇이 응답하지 않는 것처럼 보인다.
- 배터리 등 제한된 자원이 소진된다.
7.3 개선
모든 비동기 노드에 타임아웃을 구현하고, 타임아웃 값을 입력 포트로 파라미터화한다.
8. 안티패턴 7: 상태 은닉
8.1 문제
액션 노드가 멤버 변수에 상태를 축적하여, tick 간에 암묵적으로 전달한다.
// 안티패턴
class StatefulCounter : public BT::SyncActionNode
{
int count_ = 0; // 호출 간에 상태 유지
BT::NodeStatus tick() override
{
count_++;
if (count_ > 5) return BT::NodeStatus::SUCCESS;
return BT::NodeStatus::FAILURE;
}
};
8.2 해악
- 행동 트리의 반복 실행에서 예측 불가능한 동작이 발생한다.
- halt 후 상태가 초기화되지 않을 수 있다.
- 테스트의 결정론성이 보장되지 않는다.
8.3 개선
상태를 블랙보드에 명시적으로 저장하고, 포트를 통해 접근한다.
9. 안티패턴 8: SyncActionNode에서 RUNNING 반환
9.1 문제
동기 액션 노드에서 RUNNING을 반환한다.
// 안티패턴
class BadSyncAction : public BT::SyncActionNode
{
BT::NodeStatus tick() override
{
if (!ready_)
return BT::NodeStatus::RUNNING; // 위반
return BT::NodeStatus::SUCCESS;
}
};
9.2 해악
- BehaviorTree.CPP의 설계 규약을 위반한다.
- 프레임워크가
RUNNING반환을FAILURE로 강제 변환할 수 있다. - 예기치 않은 행동 트리 실행 흐름이 발생한다.
9.3 개선
StatefulActionNode로 전환하여 RUNNING을 올바르게 반환한다.
10. 안티패턴 9: 예외 미처리
10.1 문제
콜백 메서드 내에서 예외를 처리하지 않아, 행동 트리 전체가 비정상 종료될 수 있다.
10.2 해악
- ROS2 실행기(executor)가 중단된다.
- 자원 해제가 보장되지 않는다.
- 로봇이 안전하지 않은 상태에 놓일 수 있다.
10.3 개선
모든 외부 호출과 자원 접근을 try-catch로 감싸고, 예외 발생 시 적절한 상태를 반환한다.
11. 안티패턴 10: 과도한 내부 재시도
11.1 문제
액션 노드 내부에서 과도한 재시도 루프를 구현하여, 행동 트리의 제어 흐름을 우회한다.
// 안티패턴
BT::NodeStatus onStart() override
{
for (int i = 0; i < 10; ++i)
{
if (tryConnect())
return BT::NodeStatus::RUNNING;
std::this_thread::sleep_for(
std::chrono::seconds(1));
}
return BT::NodeStatus::FAILURE;
}
11.2 해악
onStart()가 10초 이상 블로킹된다.- 행동 트리의
RetryNode데코레이터와 역할이 중복된다. - halt 요청에 응답할 수 없다.
11.3 개선
재시도 로직을 행동 트리 구조(RetryNode)로 외부화한다.
<RetryNode num_attempts="10">
<ConnectToServer server="{addr}" />
</RetryNode>
12. 안티패턴 요약
| 안티패턴 | 핵심 문제 | 대표적 증상 |
|---|---|---|
| 거대 노드 | 단일 책임 위반 | 재사용 불가, 테스트 불가 |
| 동기 블로킹 | tick 루프 차단 | 반응성 저하 |
| Halt 미구현 | 자원 누수 | 비정상 동작 지속 |
| 직접 BB 접근 | 인터페이스 불투명 | 시각화 불가 |
| 하드코딩 이름 | 유연성 부재 | 다중 인스턴스 불가 |
| 타임아웃 없음 | 무한 RUNNING | 교착 상태 |
| 상태 은닉 | 비결정론적 동작 | 재현 불가 버그 |
| RUNNING 위반 | 규약 위반 | 예기치 않은 전이 |
| 예외 미처리 | 비정상 종료 | 시스템 중단 |
| 과도한 재시도 | 트리 제어 우회 | 블로킹, 중복 로직 |
13. 참고 문헌
- Colledanchise, M. and Ögren, P., “Behavior Trees in Robotics and AI: An Introduction,” CRC Press, 2018.
- Faconti, D. and Contributors, “BehaviorTree.CPP: A C++ library to build Behavior Trees,” GitHub Repository, https://github.com/BehaviorTree/BehaviorTree.CPP.
- Brown, W. J. et al., “AntiPatterns: Refactoring Software, Architectures, and Projects in Crisis,” Wiley, 1998.
- Macenski, S. et al., “The Marathon 2: A Navigation System,” arXiv preprint arXiv:2003.00368, 2020.
버전: 2026-04-04