1293.12 Tick 주기의 설정 방법
1. 설정 방법의 분류
행동 트리(Behavior Tree)의 Tick 주기를 설정하는 방법은 크게 정적 설정(static configuration)과 동적 설정(dynamic configuration)으로 분류된다. 정적 설정은 시스템 초기화 시점에 Tick 주기를 고정하는 방식이며, 동적 설정은 실행 중에 Tick 주기를 변경할 수 있는 방식이다. 각 방법은 구현 복잡도, 유연성, 예측 가능성 측면에서 상이한 특성을 가지며, 응용 분야의 요구 사항에 따라 적절한 방법을 선택해야 한다.
2. 코드 내 직접 설정
가장 기본적인 Tick 주기 설정 방법은 행동 트리를 호출하는 메인 루프(main loop) 내에서 시간 간격을 직접 지정하는 것이다. BehaviorTree.CPP 프레임워크에서는 Tree::sleep() 메서드 또는 표준 라이브러리의 시간 지연 함수를 사용하여 Tick 간격을 제어한다(Faconti, 2022).
const auto tick_period = std::chrono::milliseconds(100);
while (status == BT::NodeStatus::RUNNING) {
status = tree.tickOnce();
tree.sleep(tick_period);
}
위 코드에서 tick_period를 100ms로 설정하면 10Hz의 Tick 주파수가 구현된다. tree.sleep() 메서드는 단순한 std::this_thread::sleep_for()와 달리, 트리 내부의 WakeUpSignal을 통해 비동기 노드가 조기 완료되었을 때 대기를 중단할 수 있는 기능을 제공한다.
이 방법은 구현이 단순하고 직관적이지만, Tick 주기를 변경하려면 소스 코드를 수정하고 재컴파일해야 하는 제약이 있다.
3. ROS2 파라미터를 통한 설정
ROS2 환경에서는 노드 파라미터(parameter)를 통해 Tick 주기를 설정하는 것이 권장된다. 파라미터 기반 설정은 실행 시점(runtime)에 외부에서 Tick 주기를 지정할 수 있으므로, 재컴파일 없이 다양한 환경에 대응할 수 있다.
class BehaviorTreeNode : public rclcpp::Node {
public:
BehaviorTreeNode() : Node("bt_node") {
this->declare_parameter("tick_rate_hz", 10.0);
double tick_rate = this->get_parameter("tick_rate_hz")
.as_double();
auto period = std::chrono::duration<double>(1.0 / tick_rate);
timer_ = this->create_wall_timer(
std::chrono::duration_cast<std::chrono::milliseconds>(period),
std::bind(&BehaviorTreeNode::tick_callback, this)
);
}
private:
void tick_callback() {
tree_.tickOnce();
}
rclcpp::TimerBase::SharedPtr timer_;
BT::Tree tree_;
};
이 구현에서 tick_rate_hz 파라미터는 launch 파일이나 명령줄을 통해 외부에서 설정할 수 있다.
# launch 파일 내 파라미터 설정 예시
bt_node:
ros__parameters:
tick_rate_hz: 20.0
4. YAML 설정 파일을 통한 설정
ROS2의 YAML 파라미터 파일을 활용하면, 복수의 행동 트리 노드에 대한 Tick 주기를 중앙 집중적으로 관리할 수 있다. 이는 대규모 로봇 시스템에서 다수의 행동 트리가 동시에 운용되는 경우에 유용하다.
behavior_tree_navigator:
ros__parameters:
tick_rate: 30 # Hz
behavior_tree_manipulator:
ros__parameters:
tick_rate: 50 # Hz
각 행동 트리는 자신에게 할당된 Tick 주기에 따라 독립적으로 동작하며, 네비게이션과 매니퓰레이션 등 서로 다른 시간 요구 사항을 가지는 서브시스템에 적절한 Tick 주기를 개별적으로 부여할 수 있다.
5. Launch 파일을 통한 설정
ROS2 launch 파일에서 Tick 주기를 파라미터로 전달하면, 동일한 실행 파일을 다양한 설정으로 기동할 수 있다. Python launch 파일에서의 설정 예시는 다음과 같다.
from launch import LaunchDescription
from launch_ros.actions import Node
from launch.substitutions import LaunchConfiguration
from launch.actions import DeclareLaunchArgument
def generate_launch_description():
return LaunchDescription([
DeclareLaunchArgument(
'tick_rate', default_value='10.0',
description='Behavior tree tick rate in Hz'
),
Node(
package='bt_executor',
executable='bt_node',
parameters=[{
'tick_rate_hz': LaunchConfiguration('tick_rate')
}]
)
])
이 방식은 launch 인자(argument)를 통해 Tick 주기를 동적으로 지정할 수 있으므로, 실험 환경과 배포 환경에서 서로 다른 Tick 주기를 손쉽게 적용할 수 있다.
6. 동적 재설정 (Dynamic Reconfiguration)
ROS2의 파라미터 콜백(parameter callback) 메커니즘을 활용하면, 시스템 실행 중에 Tick 주기를 동적으로 변경할 수 있다. 이는 시스템 부하 상황이나 임무 단계에 따라 Tick 주기를 조정해야 하는 경우에 유용하다.
rcl_interfaces::msg::SetParametersResult
on_parameter_change(
const std::vector<rclcpp::Parameter>& params)
{
for (const auto& param : params) {
if (param.get_name() == "tick_rate_hz") {
double new_rate = param.as_double();
auto new_period = std::chrono::duration<double>(
1.0 / new_rate);
timer_->cancel();
timer_ = this->create_wall_timer(
std::chrono::duration_cast<
std::chrono::milliseconds>(new_period),
std::bind(&BehaviorTreeNode::tick_callback, this)
);
}
}
rcl_interfaces::msg::SetParametersResult result;
result.successful = true;
return result;
}
동적 재설정 시에는 타이머 교체 과정에서의 경합 조건(race condition)을 방지하기 위한 동기화가 필요하며, 새로운 Tick 주기가 현재 진행 중인 Tick 실행에 영향을 미치지 않도록 해야 한다.
7. 실행 시간 기반 보상 설정
단순한 고정 주기 대기 방식은 Tick 실행 시간을 고려하지 않으므로, 실제 Tick 간격이 설정된 주기보다 길어질 수 있다. 이를 보상하기 위해 Tick 실행 시간을 측정하고, 대기 시간에서 차감하는 방식을 사용한다.
const auto desired_period = std::chrono::milliseconds(100);
while (running) {
auto tick_start = std::chrono::steady_clock::now();
tree.tickOnce();
auto tick_end = std::chrono::steady_clock::now();
auto execution_time = tick_end - tick_start;
auto sleep_time = desired_period - execution_time;
if (sleep_time > std::chrono::milliseconds(0)) {
std::this_thread::sleep_for(sleep_time);
} else {
// Tick 오버런 발생: 로깅 또는 경고 처리
RCLCPP_WARN(logger, "Tick overrun: execution took %ld ms",
std::chrono::duration_cast<
std::chrono::milliseconds>(execution_time).count());
}
}
이 방식에서 sleep_time이 음수가 되는 경우는 Tick 실행 시간이 설정된 주기를 초과한 것이므로, Tick 오버런(tick overrun) 경고를 발생시키고 즉시 다음 Tick을 실행한다.
8. Nav2에서의 Tick 주기 설정
ROS2 Navigation2(Nav2) 프레임워크는 행동 트리를 핵심 의사 결정 메커니즘으로 사용하며, bt_navigator 노드의 파라미터를 통해 Tick 주기를 설정한다(Macenski et al., 2020).
bt_navigator:
ros__parameters:
default_bt_xml_filename: "navigate_w_replanning.xml"
plugin_lib_names:
- nav2_compute_path_to_pose_action_bt_node
- nav2_follow_path_action_bt_node
# Tick 주기 관련 설정은 내부 루프에서 관리
Nav2의 BtNavigator 클래스는 내부적으로 tickOnce()와 sleep() 패턴을 사용하여 Tick 주기를 관리하며, 네비게이션 작업의 특성에 맞추어 기본 Tick 주기가 설정되어 있다.
9. Tick 주기 설정 시 고려 사항
Tick 주기를 설정할 때에는 다음 사항을 종합적으로 고려해야 한다.
| 고려 사항 | 설명 |
|---|---|
| 최악 Tick 실행 시간 | Tick 주기는 최악의 경우 실행 시간보다 커야 한다 |
| 환경 변화율 | 빠르게 변화하는 환경일수록 높은 Tick 주파수가 필요하다 |
| CPU 가용 자원 | 다른 프로세스와의 자원 경합을 고려하여 적절한 주파수를 선택한다 |
| 센서 갱신 주기 | 센서 데이터의 갱신 주기보다 높은 Tick 주파수는 불필요하다 |
| 액추에이터 응답 속도 | 액추에이터의 반응 속도를 초과하는 Tick 주파수는 실효성이 낮다 |
| 통신 지연 | 원격 시스템과의 통신 지연이 큰 경우 높은 Tick 주파수의 실익이 감소한다 |
최적의 Tick 주기는 이러한 제약 조건들의 교집합에서 결정되며, 실험적 검증을 통해 최종적으로 확정하는 것이 권장된다.
참고 문헌
- 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., Martin, F., White, R., & Clavero, J. G. (2020). The Marathon 2: A Navigation System. Proceedings of the IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS).