파라미터 변경 감지 조건 노드 (Parameter Change Detection Condition Node)
1. 개요
파라미터 변경 감지 조건 노드는 ROS2 파라미터의 값이 변경되었는지를 판정하는 조건 노드이다. 파라미터의 현재 값 자체를 평가하는 것이 아니라, 이전 평가 시점 대비 값이 변화하였는지를 감지한다. 이 조건 노드는 설정 변경에 대한 반응적 행동을 구현하는 데 활용되며, 파라미터 변경 시 경로 재계획, 행동 트리 재구성, 시스템 재초기화 등의 작업을 유발하는 트리거(trigger) 역할을 수행한다.
2. 변경 감���의 의미론
2.1 변경의 정의
파라미터 변경은 다음과 같이 정의된다.
\text{changed}(t) = \begin{cases} \text{true} & \text{if } p(t) \neq p(t_{\text{prev}}) \\ \text{false} & \text{if } p(t) = p(t_{\text{prev}}) \end{cases}
여기서 p(t)는 현재 시점 t에서의 파라미터 값이고, p(t_{\text{prev}})는 이전 평가 시점의 파라미터 값이다. 변경이 감지되면 SUCCESS를 반환하고, 변경이 없으면 FAILURE를 반환한다.
일회성 감지와 지속성 감지
변경 감지에는 두 가지 의미론이 ���다.
| 유형 | 설명 | 동작 |
|---|---|---|
| 일회성 감지 (One-shot) | 변경이 발생한 첫 번째 tick에서만 SUCCESS를 반환하고, 이후에는 다시 FAILURE를 반환 | 변경 플래그가 확인 후 즉시 리셋됨 |
| 지속성 감지 (Latched) | 변경이 발생한 이후 외부에서 리셋할 때까지 계속 SUCCESS를 반환 | 변경 플래그가 명시적 리셋 전까지 유지됨 |
일회성 감지는 변경 이벤트에 대한 단일 반응을 유발하는 데 적합하며, 지속성 감지는 변경된 상태가 처리 완료될 때까지 후속 행동을 지속시키는 데 적합하다.
폴링 기반 변경 감지 구현
일회성 변경 감지
가장 단순한 구현은 매 tick마다 파라미터 값을 읽어 이전 값과 비교하는 방식이다.
class HasParameterChanged : public BT::ConditionNode
{
public:
HasParameterChanged(const std::string& name,
const BT::NodeConfiguration& config,
rclcpp::Node::SharedPtr node)
: BT::ConditionNode(name, config),
node_(node),
initialized_(false)
{}
static BT::PortsList providedPorts()
{
return {
BT::InputPort<std::string>("param_name",
"감시할 파라미터 이름")
};
}
BT::NodeStatus tick() override
{
std::string param_name;
getInput("param_name", param_name);
if (!node_->has_parameter(param_name))
{
return BT::NodeStatus::FAILURE;
}
rclcpp::Parameter current = node_->get_parameter(param_name);
std::string current_str = current.value_to_string();
if (!initialized_)
{
previous_value_str_ = current_str;
initialized_ = true;
return BT::NodeStatus::FAILURE;
}
if (current_str != previous_value_str_)
{
previous_value_str_ = current_str;
return BT::NodeStatus::SUCCESS;
}
return BT::NodeStatus::FAILURE;
}
private:
rclcpp::Node::SharedPtr node_;
std::string previous_value_str_;
bool initialized_;
};
이 구현에서 value_to_string() 메서드를 사용하여 모든 파라미터 타입을 문자열로 변환한 후 비교한다. 이를 통해 단일 구현으로 모든 파라미터 타입의 변경을 감지할 수 있다. 초기화 시점(initialized_가 false인 경우)에는 현재 값을 기준값으로 저장하고 FAILURE를 반환한다.
부동소수점 파라미터의 변경 감지
부동소수점 파라미터의 경우, 미세한 수치 변동을 변경으로 감지하지 않기 위해 허용 오차(tolerance)를 적용할 수 있다.
class HasDoubleParameterChanged : public BT::ConditionNode
{
public:
HasDoubleParameterChanged(const std::string& name,
const BT::NodeConfiguration& config,
rclcpp::Node::SharedPtr node)
: BT::ConditionNode(name, config),
node_(node),
initialized_(false)
{}
static BT::PortsList providedPorts()
{
return {
BT::InputPort<std::string>("param_name",
"감시할 파라미터 이름"),
BT::InputPort<double>("tolerance", 1e-6,
"변경 감지 허용 오차")
};
}
BT::NodeStatus tick() override
{
std::string param_name;
double tolerance;
getInput("param_name", param_name);
getInput("tolerance", tolerance);
if (!node_->has_parameter(param_name))
{
return BT::NodeStatus::FAILURE;
}
auto param = node_->get_parameter(param_name);
if (param.get_type() !=
rclcpp::ParameterType::PARAMETER_DOUBLE)
{
return BT::NodeStatus::FAILURE;
}
double current = param.as_double();
if (!initialized_)
{
previous_value_ = current;
initialized_ = true;
return BT::NodeStatus::FAILURE;
}
if (std::abs(current - previous_value_) > tolerance)
{
previous_value_ = current;
return BT::NodeStatus::SUCCESS;
}
return BT::NodeStatus::FAILURE;
}
private:
rclcpp::Node::SharedPtr node_;
double previous_value_;
bool initialized_;
};
허용 오차 \delta를 적용하여 \lvert p(t) - p(t_{\text{prev}}) \rvert > \delta인 경우에만 변경으로 판정한다.
이벤트 기반 변경 감지 구현
ParameterEventHandler를 활용한 변경 감지
ROS2의 ParameterEventHandler를 활용하면, 파라미터가 변경될 때에만 콜백이 호출되므로 폴링 방식보다 효율적이다.
class HasParameterChangedEvent : public BT::ConditionNode
{
public:
HasParameterChangedEvent(const std::string& name,
const BT::NodeConfiguration& config,
rclcpp::Node::SharedPtr node)
: BT::ConditionNode(name, config),
node_(node),
changed_(false)
{
std::string param_name;
getInput("param_name", param_name);
param_handler_ =
std::make_shared<rclcpp::ParameterEventHandler>(node_);
cb_handle_ = param_handler_->add_parameter_callback(
param_name,
[this](const%20rclcpp::Parameter&%20/*param*/) {
std::lock_guard<std::mutex> lock(mutex_);
changed_ = true;
});
}
static BT::PortsList providedPorts()
{
return {
BT::InputPort<std::string>("param_name",
"감시할 파라미터 이름"),
BT::InputPort<bool>("one_shot", true,
"일회성 감지 모드 (true: 감지 후 리셋)")
};
}
BT::NodeStatus tick() override
{
std::lock_guard<std::mutex> lock(mutex_);
if (changed_)
{
bool one_shot;
getInput("one_shot", one_shot);
if (one_shot)
{
changed_ = false;
}
return BT::NodeStatus::SUCCESS;
}
return BT::NodeStatus::FAILURE;
}
private:
rclcpp::Node::SharedPtr node_;
std::shared_ptr<rclcpp::ParameterEventHandler> param_handler_;
std::shared_ptr<rclcpp::ParameterCallbackHandle> cb_handle_;
std::mutex mutex_;
bool changed_;
};
이 구현의 핵심 특징은 다음과 같다.
- 파라미터 변경 시 콜백이
changed_플래그를true로 설정한다. tick()메서드에서 플래그를 확인하여 ��경 여부를 판정한다.one_shot모드에서는 플래그 확인 후 즉시 리셋한다.one_shot이false인 경우, 외부에서 명시적으로 리셋하기 전까지SUCCESS를 반환한다.
원격 노드의 파라미터 변경 감지
다른 ROS2 노드의 파라미터 변경을 감지하기 위해, 원격 노드를 지정한 ParameterEventHandler를 사용한다.
class HasRemoteParameterChanged : public BT::ConditionNode
{
public:
HasRemoteParameterChanged(const std::string& name,
const BT::NodeConfiguration& config,
rclcpp::Node::SharedPtr node)
: BT::ConditionNode(name, config),
node_(node),
changed_(false)
{
std::string param_name, remote_node;
getInput("param_name", param_name);
getInput("remote_node", remote_node);
param_handler_ =
std::make_shared<rclcpp::ParameterEventHandler>(node_);
cb_handle_ =
param_handler_->add_parameter_callback(
param_name,
[this](const%20rclcpp::Parameter&%20/*param*/) {
std::lock_guard<std::mutex> lock(mutex_);
changed_ = true;
},
remote_node);
}
static BT::PortsList providedPorts()
{
return {
BT::InputPort<std::string>("param_name",
"감시할 파라미터 이름"),
BT::InputPort<std::string>("remote_node",
"원격 노드 이름")
};
}
BT::NodeStatus tick() override
{
std::lock_guard<std::mutex> lock(mutex_);
if (changed_)
{
changed_ = false;
return BT::NodeStatus::SUCCESS;
}
return BT::NodeStatus::FAILURE;
}
private:
rclcpp::Node::SharedPtr node_;
std::shared_ptr<rclcpp::ParameterEventHandler> param_handler_;
std::shared_ptr<rclcpp::ParameterCallbackHandle> cb_handle_;
std::mutex mutex_;
bool changed_;
};
add_parameter_callback()의 세 번째 인자로 원격 노드의 이름을 지정하면, 해당 노드의 파라미터 변경 이벤트만을 수신한다. 내부적으로 /parameter_events 토픽을 ���독하여 모든 노드의 파라미터 이벤트를 수신한 후, 지정된 노드와 파라미터 이름에 해당하는 이벤트만을 필터링한다.
XML 행동 트리에서의 활용
파라미터 변경 시 경로 재계획
<BehaviorTree ID="DynamicNavigation">
<ReactiveSequence>
<Fallback>
<Condition ID="HasParameterChanged"
param_name="goal_tolerance"/>
<Condition ID="HasParameterChanged"
param_name="planner_plugin"/>
<Condition ID="IsPathInvalid"/>
</Fallback>
<Action ID="ComputeNewPath"/>
</ReactiveSequence>
</BehaviorTree>
goal_tolerance 또는 planner_plugin 파라미터가 변경되거나 현재 경로가 유효하지 않은 경우, 새로운 경로를 계산한다. Fallback 노드에 의해 세 조건 중 하나라도 SUCCESS를 반환하면 경로 재계획이 실행된다.
설정 변경 시 시스템 재초기화
<BehaviorTree ID="ConfigChangeHandler">
<Sequence>
<Condition ID="HasParameterChangedEvent"
param_name="sensor_config"
one_shot="true"/>
<Action ID="ReinitializeSensors"/>
<Action ID="RecalibrateSystem"/>
</Sequence>
</BehaviorTree>
one_shot 모드에서는 변경이 감지된 첫 번째 tick에서만 SUCCESS를 반환하므로, 재초기화 작업이 한 번만 실행된다.
다중 파라미터 변경 감시
<BehaviorTree ID="MultiParamWatch">
<ReactiveSequence>
<Sequence>
<Condition ID="HasParameterChanged"
param_name="max_velocity"/>
<Action ID="UpdateVelocityLimits"/>
</Sequence>
</ReactiveSequence>
</BehaviorTree>
변경 감지와 순수 함수 원칙의 관계
파라미터 변경 감지 조건 노드는 내부 상태(previous_value_ 또는 changed_ 플래그)를 유지하므로, 엄밀한 의미에서 순수 함수 원칙과 완전히 부합하지 않는다. 동일한 외부 조건(파라미터 값)에서도 이전 상태에 따라 다른 결과를 반환할 수 있기 때문이다.
그러나 이러한 상태 유지는 변경 감지라는 본질적 요구에 의한 것이며, 조건 노드의 핵심 원칙인 부작용 금지(외부 상태 변경 없음), 빠른 평가, RUNNING 미반환 원칙은 준수한다. 내부 상태는 조건 노드 자체의 ��정 이력에 한정되므로, 행�� 트리의 다른 노드나 ��부 시스템에 영향을 미치지 않는다.
설계 시 고려 사항
초기 상태 처리
노드가 처음 tick될 때, 비교 기준이 되는 이전 값이 존재하지 않는다. 이 경우의 처리 방법은 다음과 같다.
- 첫 tick에서 FAILURE 반환: 현재 값을 기준값으로 저장하고, 변경이 없는 것으로 간주한다. 이 방식이 가장 일반적이다.
- 첫 tick에서 SUCCESS 반환: 초기 상태를 변경으로 간주하여, 시스템 시작 시 초기화 작업을 유발한다.
경쟁 조건 방지
이벤트 기반 구현에�� 콜백 스레드와 tick 스레드 간의 경쟁 조건(race condition)을 방지하기 위해 뮤텍스를 사용하여야 한다. 특히 일회성 감지 모드에서 changed_ 플래그의 읽기와 리셋이 원자적으로 수행되어야 한다.
파라미터 이벤트 토픽의 부하
/parameter_events 토픽은 시스템 내 모든 노드의 파라미터 변경 이벤트를 발행한다. 노드 수��� 많고 파라미터 변경이 빈번한 시스템에서는 이 토픽의 메시지 볼륨이 증가하여 콜백 처리 부하가 발생할 수 있다. ParameterEventHandler는 내부적으로 노드 이름과 파라미터 이름을 필터링하므로, 콜백 함수 자체의 호출 빈도는 제한되지만, 토픽 구독에 따른 기본적인 오버헤드는 존재한다.
변경 이력 관리
단순 변경 감지를 넘어, 이전 값과 현재 값의 차이를 정량적으로 평가하여야 하는 경우가 있다. 예를 들어, 속도 제한 파라미터가 10% 이상 변경된 경우에만 경로를 재계획하도록 하려면, 변경 비율을 계산하여 임계값과 비교하는 추가 로직이 필요하다. 이 경우에는 변경 감지 조건 노드보다는 파���미터 값 확인 조건 노드를 블랙보드와 결합하여 사용하는 것이 더 적절할 수 있다.
참고 문헌
- Colledanchise, M., & Ogren, P. (2018). Behavior Trees in Robotics and AI: An Introduction. CRC Press.
- ROS2 파라미터 공식 문서. https://docs.ros.org/en/humble/Concepts/Basic/About-Parameters.html
- BehaviorTree.CPP 공식 문서. https://www.behaviortree.dev/
| 버전 | 날짜 | 변경 사항 |
|---|---|---|
| v0.1 | 2026-04-04 | 초안 작성 |