과전류 감지 조건 노드 (Overcurrent Detection Condition Node)
1. 개요
과전류 감지 조건 노드는 로봇 시스템의 모터, 제어기, 전원 공급 장치 등에 흐르는 전류가 허용 한계를 초과하는지를 판정하는 조건 노드이다. 과전류는 모터 과부하, 기계적 간섭, 단락(short circuit), 제어 오류 등 다양한 원인에 의해 발생하며, 지속되면 구성 요소의 열적 손상이나 화재로 이어질 수 있다. 본 조건 노드는 과전류를 조기에 감지하여 보호 행동을 유발한다.
2. 전류 측정 메시지
2.1 sensor_msgs::msg::BatteryState 기반
배터리 메시지의 current 필드를 통해 시스템 전체 전류를 모니터링한다.
2.2 사용자 정의 메시지 기반
개별 모터의 전류는 모터 드라이버에서 사용자 정의 메시지로 발행되거나, sensor_msgs::msg::JointState의 effort 필드에 토크(전류에 비례)로 반영될 수 있다.
3. 구현
3.1 시스템 전류 기반 과전류 감지
class IsCurrentNormal
: public BT::RosTopicSubNode<sensor_msgs::msg::BatteryState>
{
public:
IsCurrentNormal(const std::string& name,
const BT::NodeConfiguration& config,
const BT::RosNodeParams& params)
: RosTopicSubNode(name, config, params)
{}
static BT::PortsList providedPorts()
{
return providedBasicPorts({
BT::InputPort<double>("max_current", 30.0,
"최대 허용 전류 (A)")
});
}
BT::NodeStatus onTick(
const sensor_msgs::msg::BatteryState::SharedPtr& msg) override
{
if (!msg || !msg->present)
{
return BT::NodeStatus::FAILURE;
}
double max_current;
getInput("max_current", max_current);
// current 필드: 방전 시 음수, 충전 시 양수
double abs_current = std::abs(msg->current);
if (!std::isfinite(abs_current))
{
return BT::NodeStatus::FAILURE;
}
if (abs_current <= max_current)
{
return BT::NodeStatus::SUCCESS;
}
return BT::NodeStatus::FAILURE;
}
};
3.2 관절 토크 기반 과부하 감지
모터 드라이버��� 전류 값을 직접 제공하지 않는 경우, JointState의 effort 필드(토크)를 통해 간접적으로 과부하를 감지한다.
class IsJointEffortNormal
: public BT::RosTopicSubNode<sensor_msgs::msg::JointState>
{
public:
IsJointEffortNormal(const std::string& name,
const BT::NodeConfiguration& config,
const BT::RosNodeParams& params)
: RosTopicSubNode(name, config, params)
{}
static BT::PortsList providedPorts()
{
return providedBasicPorts({
BT::InputPort<double>("max_effort", 100.0,
"최대 허용 토크/힘 (N·m 또는 N)")
});
}
BT::NodeStatus onTick(
const sensor_msgs::msg::JointState::SharedPtr& msg) override
{
if (!msg || msg->effort.empty())
{
return BT::NodeStatus::FAILURE;
}
double max_effort;
getInput("max_effort", max_effort);
for (const auto& effort : msg->effort)
{
if (std::abs(effort) > max_effort)
{
return BT::NodeStatus::FAILURE;
}
}
return BT::NodeStatus::SUCCESS;
}
};
3.3 히스테리시스를 적용한 과전류 감지
순간적 전류 스파이크(모터 기동 시)에 의한 오탐을 방지한다.
class IsCurrentSafe
: public BT::RosTopicSubNode<sensor_msgs::msg::BatteryState>
{
public:
IsCurrentSafe(const std::string& name,
const BT::NodeConfiguration& config,
const BT::RosNodeParams& params)
: RosTopicSubNode(name, config, params),
is_normal_(true)
{}
static BT::PortsList providedPorts()
{
return providedBasicPorts({
BT::InputPort<double>("overcurrent_threshold", 35.0,
"과전류 판정 임계값 (A)"),
BT::InputPort<double>("recovery_threshold", 25.0,
"복구 판정 임계값 (A)")
});
}
BT::NodeStatus onTick(
const sensor_msgs::msg::BatteryState::SharedPtr& msg) override
{
if (!msg || !msg->present)
{
return BT::NodeStatus::FAILURE;
}
double over_thresh, recovery_thresh;
getInput("overcurrent_threshold", over_thresh);
getInput("recovery_threshold", recovery_thresh);
double abs_current = std::abs(msg->current);
if (abs_current >= over_thresh)
{
is_normal_ = false;
}
else if (abs_current <= recovery_thresh)
{
is_normal_ = true;
}
return is_normal_ ? BT::NodeStatus::SUCCESS
: BT::NodeStatus::FAILURE;
}
private:
bool is_normal_;
};
4. XML 행동 트리에서의 활용
4.1 과전류 감시 하 운용
<BehaviorTree ID="CurrentProtectedOperation">
<ReactiveSequence>
<Condition ID="IsCurrentSafe"
topic_name="/battery_state"
overcurrent_threshold="35.0"
recovery_threshold="25.0"/>
<Action ID="ExecuteTask"/>
</ReactiveSequence>
</BehaviorTree>
4.2 다중 전류 소스 감시
<BehaviorTree ID="MultiCurrentMonitoring">
<ReactiveSequence>
<Condition ID="IsCurrentNormal"
topic_name="/battery_state"
max_current="40.0"/>
<Condition ID="IsJointEffortNormal"
topic_name="/joint_states"
max_effort="150.0"/>
<Action ID="ContinueOperation"/>
</ReactiveSequence>
</BehaviorTree>
5. 설계 시 고려 사항
5.1 전류 측정의 주기
전류 센서의 측정 주기가 조건 노드의 tick 주기보다 낮으면, 짧은 시간 동안의 과전류를 감지하지 못할 수 있다. 과전류의 지속 시간과 심각도에 따른 보호 전략을 구성하여야 한다.
5.2 돌입 전류(Inrush current)
모터 기동 시 정격 전류의 수 배에 달하는 돌입 전류가 발생한다. 이를 과전류로 오판하지 않기 위해, 기동 후 일정 시간(수백 밀리초) 동안은 과전류 감지를 비활성화하거나, 높은 임계값을 일시적으로 적용하는 전략이 필요하다.
5.3 I²t 보호
모터 보호에서는 순간 전류뿐만 아니라 전류의 시간 적분(I^2 t)을 기준으로 열적 한계를 평가한다. 이 방식은 짧은 시간의 큰 전류와 긴 시간의 작은 과전류를 모두 감지할 수 있으나, 조건 노드에서 이를 구현하려면 내부 상태로 적분값을 유지하여야 한다.
6. 참고 문헌
- Colledanchise, M., & Ogren, P. (2018). Behavior Trees in Robotics and AI: An Introduction. CRC Press.
- IEC 60034-1: Rotating electrical machines — Rating and performance.
- BehaviorTree.CPP 공식 문서. https://www.behaviortree.dev/
| 버전 | 날짜 | 변경 사항 |
|---|---|---|
| v0.1 | 2026-04-04 | 초안 작성 |