1293.101 Tick 메커니즘의 모범 사례
1. Tick 주기 설정의 모범 사례
1.1 적절한 주기의 선택
Tick 주기는 로봇의 동작 환경과 응답 요구에 기반하여 설정해야 한다. 무조건 높은 빈도가 좋은 것이 아니며, 시스템의 실제 요구에 맞는 적절한 빈도를 선택해야 한다.
- 이동 로봇의 네비게이션: 10~30 Hz가 일반적이다. Nav2는 기본 10 Hz를 사용한다(Macenski et al., 2020).
- 산업용 매니퓰레이터: 50~100 Hz로, 빠른 반응이 필요한 작업에 적합하다.
- 감시/대기 로봇: 1~5 Hz로, 자원을 절약하면서 환경 변화를 감지한다.
1.2 Tick 주기와 실행 시간의 여유 확보
Tick 실행 시간은 Tick 주기의 50~70%를 넘지 않도록 설계한다. 나머지 시간은 시스템 스케줄링 지터, 캐시 미스, 예외적 처리 등의 변동을 흡수하기 위한 여유이다.
// 권장: 실행 시간 모니터링
auto start = std::chrono::steady_clock::now();
tree.tickOnce();
auto elapsed = std::chrono::steady_clock::now() - start;
auto utilization = elapsed.count() / period.count();
if (utilization > 0.7) {
RCLCPP_WARN(logger_, "Tick utilization %.0f%% — consider optimization",
utilization * 100);
}
2. 노드 구현의 모범 사례
2.1 tick() 함수의 비블로킹 원칙
노드의 tick() 함수는 블로킹 호출을 포함해서는 안 된다. 외부 서비스 호출, 파일 I/O, 네트워크 대기 등은 모두 비동기 패턴(StatefulActionNode)으로 처리한다.
// 잘못된 사례: 블로킹 서비스 호출
BT::NodeStatus tick() override {
auto response = client_->call(request_); // 블로킹
return processResponse(response);
}
// 모범 사례: 비동기 처리
BT::NodeStatus onStart() override {
future_ = client_->async_send_request(request_);
return BT::NodeStatus::RUNNING;
}
BT::NodeStatus onRunning() override {
if (future_.wait_for(std::chrono::milliseconds(0)) ==
std::future_status::ready) {
return processResponse(future_.get());
}
return BT::NodeStatus::RUNNING;
}
2.2 Halt 처리의 완전성
onHalted() 또는 halt() 함수에서 노드가 보유한 모든 자원을 확실히 정리해야 한다. 미완료된 ROS2 액션의 취소, 임시 파일의 삭제, 상태 변수의 초기화 등을 포함한다.
void onHalted() override {
// 진행 중인 액션 취소
if (goal_handle_) {
action_client_->async_cancel_goal(goal_handle_);
goal_handle_.reset();
}
// 상태 초기화
resetInternalState();
}
2.3 입출력 포트의 명시적 선언
모든 입출력 데이터를 포트를 통해 명시적으로 선언하여, 데이터 의존성을 투명하게 관리한다. 블랙보드에 직접 접근하여 암묵적으로 데이터를 읽고 쓰는 것은 피해야 한다.
static BT::PortsList providedPorts() {
return {
BT::InputPort<double>("battery_level", "Current battery level"),
BT::InputPort<double>("threshold", 0.2, "Minimum battery threshold"),
BT::OutputPort<bool>("is_low_battery", "True if battery is low")
};
}
3. ROS2 통합의 모범 사례
3.1 spin_some과 Tick의 분리
spin_some()의 호출 시점과 Tick 실행의 관계를 명확히 관리한다. Tick 직전에 spin_some()을 호출하여 최신 콜백을 처리한 후 Tick을 실행하는 것이 일반적 패턴이다.
while (rclcpp::ok()) {
// 1. 콜백 처리 (최신 데이터 수신)
executor.spin_some();
// 2. Tick 실행 (최신 데이터에 기반한 의사 결정)
tree.tickOnce();
// 3. 주기 대기
rate.sleep();
}
3.2 QoS 설정의 최적화
행동 트리 노드에서 사용하는 토픽 구독의 QoS를 데이터 특성에 맞게 설정한다.
| 데이터 유형 | 신뢰성 | 큐 크기 | 지속성 |
|---|---|---|---|
| 센서 데이터 | BEST_EFFORT | 1 | VOLATILE |
| 명령 출력 | RELIABLE | 1~5 | VOLATILE |
| 상태 정보 | RELIABLE | 10 | TRANSIENT_LOCAL |
4. 블랙보드 사용의 모범 사례
4.1 키 이름의 체계적 관리
블랙보드 키 이름은 체계적인 명명 규칙을 따라야 한다. 서브트리 간 이름 충돌을 방지하고, 데이터의 출처와 용도를 명확히 한다.
<!-- 권장: 체계적 이름 -->
<SetBlackboard output_key="nav/goal_pose" value="{goal}"/>
<SetBlackboard output_key="nav/current_speed" value="{speed}"/>
<SetBlackboard output_key="battery/level" value="{bat}"/>
<!-- 비권장: 모호한 이름 -->
<SetBlackboard output_key="data" value="{x}"/>
<SetBlackboard output_key="val" value="{y}"/>
4.2 블랙보드 데이터의 타입 일관성
동일한 키에 대해 항상 동일한 타입의 데이터를 저장해야 한다. 타입 불일치는 런타임 오류를 유발한다.
5. 로깅과 모니터링의 모범 사례
5.1 기본 로거의 활용
개발 단계에서는 StdCoutLogger를 사용하여 모든 상태 변화를 관찰하고, 배포 단계에서는 FileLogger2로 전환하여 사후 분석을 지원한다.
// 개발 시
BT::StdCoutLogger cout_logger(tree);
// 배포 시
BT::FileLogger2 file_logger(tree, "bt_session.btlog");
5.2 Groot2 연동
시각적 디버깅을 위해 Groot2Publisher를 항상 활성화하여, 필요 시 실시간 연결하여 트리 상태를 관찰할 수 있도록 한다.
BT::Groot2Publisher groot_pub(tree, 1667);
6. 트리 설계의 모범 사례
6.1 안전 조건의 최상위 배치
안전 관련 조건(비상 정지, 배터리 부족, 통신 두절 등)은 트리의 최상위에 배치하여, 모든 행동보다 먼저 평가되도록 한다.
<ReactiveSequence>
<Condition ID="IsNotEmergency"/>
<Condition ID="IsBatteryAbove" threshold="0.1"/>
<Condition ID="IsCommAlive"/>
<!-- 이하 임무 행동 -->
<SubTree ID="MissionBehavior"/>
</ReactiveSequence>
6.2 적절한 제어 노드 선택
- Sequence: 모든 자식이 성공해야 하는 순차 작업
- Fallback: 하나의 성공이면 충분한 대안 탐색
- ReactiveSequence: 조건을 매 Tick마다 재검사해야 하는 경우
- Sequence (WithMemory): 완료된 작업을 건너뛰어도 되는 경우
6.3 트리의 테스트 가능한 설계
각 서브트리가 독립적으로 테스트 가능하도록 모듈화한다. 블랙보드의 입출력이 명확히 정의되면, 모의(mock) 데이터를 주입하여 단위 테스트를 수행할 수 있다.
7. 종합 점검 목록
| 점검 항목 | 확인 내용 |
|---|---|
| 블로킹 호출 없음 | 모든 tick() 함수가 비블로킹 |
| Halt 처리 완전 | 모든 자원이 Halt에서 정리됨 |
| 포트 선언 완전 | 모든 입출력이 포트로 선언됨 |
| 안전 조건 최상위 | 안전 조건이 가장 먼저 평가됨 |
| Tick 시간 여유 | 실행 시간이 주기의 70% 이내 |
| 로깅 활성화 | FileLogger2 또는 Groot2Publisher 연결 |
| QoS 최적화 | 데이터 특성에 맞는 QoS 설정 |
참고 문헌
- Colledanchise, M., & Ogren, P. (2018). Behavior Trees in Robotics and AI: An Introduction. CRC Press.
- Faconti, D. (2022). BehaviorTree.CPP documentation and API reference. https://www.behaviortree.dev/
- Macenski, S., Martín, F., White, R., & Clavero, J. G. (2020). The Marathon 2: A Navigation System. arXiv preprint arXiv:2003.00368.