배터리 잔량 확인 조건 노드 (Battery Level Check Condition Node)

배터리 잔량 확인 조건 노드 (Battery Level Check Condition Node)

1. 개요

배터리 잔량 확인 조건 노드는 로봇의 배터리 상태를 평가하여 임무 수행 가능 여부, 충전 필요성, 비상 귀환 판단 등의 의사 결정을 지원하는 조건 노드이다. 배터리 잔량은 로봇의 운용 지속 가능성을 결정하는 핵심 지표이며, 잔량이 부족한 상태에서의 임무 수행은 로봇의 안전한 귀환을 보장하지 못할 수 있으므로, 행동 트리에서 배터리 상태를 지속적으로 감시하는 것은 필수적이다.

2. ROS2 배터리 상태 메시지

2.1 sensor_msgs::msg::BatteryState

ROS2에서 배터리 상태 정보는 sensor_msgs::msg::BatteryState 메시지를 통해 발행된다. 주요 필드는 다음과 같다.

필드타입단위설명
voltagefloat32V현재 전압
currentfloat32A현재 전류 (방전 시 음수)
chargefloat32Ah현재 잔여 용량
capacityfloat32Ah최대 용량
design_capacityfloat32Ah설계 용량
percentagefloat32-잔량 비율 (0.0~1.0)
power_supply_statusuint8-전원 공급 상태
power_supply_healthuint8-배터리 건강 상태
presentbool-배터리 장착 여부

power_supply_status의 상수 값은 다음과 같다.

상수의미
POWER_SUPPLY_STATUS_UNKNOWN0상태 미상
POWER_SUPPLY_STATUS_CHARGING1충전 중
POWER_SUPPLY_STATUS_DISCHARGING2방전 중
POWER_SUPPLY_STATUS_NOT_CHARGING3비충전 상태
POWER_SUPPLY_STATUS_FULL4완충 상태

3. 잔량 비율 기반 조건 노드

3.1 기본 구현

class IsBatteryAbove
    : public BT::RosTopicSubNode<sensor_msgs::msg::BatteryState>
{
public:
    IsBatteryAbove(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>("min_percentage", 0.2,
                                  "최소 요구 잔량 비율 (0.0~1.0)")
        });
    }

    BT::NodeStatus onTick(
        const sensor_msgs::msg::BatteryState::SharedPtr& msg) override
    {
        if (!msg)
        {
            return BT::NodeStatus::FAILURE;
        }

        if (!msg->present)
        {
            return BT::NodeStatus::FAILURE;
        }

        double min_percentage;
        getInput("min_percentage", min_percentage);

        if (std::isfinite(msg->percentage) &&
            msg->percentage >= min_percentage)
        {
            return BT::NodeStatus::SUCCESS;
        }
        return BT::NodeStatus::FAILURE;
    }
};

msg->presentfalse인 경우 배터리가 물리적으로 장착되지 않은 것이므로 FAILURE를 반환한다.

3.2 히스테리시스 적용

배터리 잔량의 미세한 변동에 의한 조건 결과 진동을 방지하기 위해 히스테리시스를 적용한다.

class IsBatteryOkWithHysteresis
    : public BT::RosTopicSubNode<sensor_msgs::msg::BatteryState>
{
public:
    IsBatteryOkWithHysteresis(const std::string& name,
                              const BT::NodeConfiguration& config,
                              const BT::RosNodeParams& params)
        : RosTopicSubNode(name, config, params),
          was_ok_(true)
    {}

    static BT::PortsList providedPorts()
    {
        return providedBasicPorts({
            BT::InputPort<double>("low_threshold", 0.15,
                "저전력 임계값 - 이 이하면 FAILURE"),
            BT::InputPort<double>("recovery_threshold", 0.25,
                "복구 임계값 - 이 이상이면 SUCCESS 복귀")
        });
    }

    BT::NodeStatus onTick(
        const sensor_msgs::msg::BatteryState::SharedPtr& msg) override
    {
        if (!msg || !msg->present)
        {
            return BT::NodeStatus::FAILURE;
        }

        double low_thresh, recovery_thresh;
        getInput("low_threshold", low_thresh);
        getInput("recovery_threshold", recovery_thresh);

        if (msg->percentage < low_thresh)
        {
            was_ok_ = false;
        }
        else if (msg->percentage > recovery_thresh)
        {
            was_ok_ = true;
        }

        return was_ok_ ? BT::NodeStatus::SUCCESS
                       : BT::NodeStatus::FAILURE;
    }

private:
    bool was_ok_;
};

충전 후 잔량이 recovery_threshold(예: 25%)를 초과하여야만 정상 상태로 복귀하므로, 저전력 경고 해제와 충전 재개 사이의 불필요한 진동을 방지한다.

4. 전압 기반 조건 노드

일부 시스템에서는 잔량 비율(percentage)이 정확하지 않거나 제공되지 않을 수 있다. 이 경우 전압을 기준으로 배터리 상태를 판정한다.

class IsBatteryVoltageAbove
    : public BT::RosTopicSubNode<sensor_msgs::msg::BatteryState>
{
public:
    IsBatteryVoltageAbove(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>("min_voltage", 11.1,
                "최소 요구 전압 (V)")
        });
    }

    BT::NodeStatus onTick(
        const sensor_msgs::msg::BatteryState::SharedPtr& msg) override
    {
        if (!msg || !msg->present)
        {
            return BT::NodeStatus::FAILURE;
        }

        double min_voltage;
        getInput("min_voltage", min_voltage);

        if (std::isfinite(msg->voltage) &&
            msg->voltage >= min_voltage)
        {
            return BT::NodeStatus::SUCCESS;
        }
        return BT::NodeStatus::FAILURE;
    }
};

리튬 폴리머(LiPo) 배터리의 경우, 셀당 전압 범위는 일반적으로 3.0V(방전 한계)~4.2V(완충)이다. 3셀 배터리의 경우 최소 안전 전압은 약 3 \times 3.3 = 9.9\text{V}이며, 운용 최소 전압은 3 \times 3.7 = 11.1\text{V} 정도를 기준으로 설정한다.

5. 충전 상태 확인 조건 노드

배터리가 현재 충전 중인지를 확인하는 조건 노드이다.

class IsBatteryCharging
    : public BT::RosTopicSubNode<sensor_msgs::msg::BatteryState>
{
public:
    IsBatteryCharging(const std::string& name,
                      const BT::NodeConfiguration& config,
                      const BT::RosNodeParams& params)
        : RosTopicSubNode(name, config, params)
    {}

    static BT::PortsList providedPorts()
    {
        return providedBasicPorts({});
    }

    BT::NodeStatus onTick(
        const sensor_msgs::msg::BatteryState::SharedPtr& msg) override
    {
        if (!msg || !msg->present)
        {
            return BT::NodeStatus::FAILURE;
        }

        if (msg->power_supply_status ==
            sensor_msgs::msg::BatteryState::POWER_SUPPLY_STATUS_CHARGING)
        {
            return BT::NodeStatus::SUCCESS;
        }
        return BT::NodeStatus::FAILURE;
    }
};

6. XML 행동 트리에서의 활용

6.1 다단계 배터리 관리

<BehaviorTree ID="BatteryManagement">
    <ReactiveSequence>
        <Fallback>
            <!-- 배터리 충분: 정상 임무 수행 -->
            <Sequence>
                <Condition ID="IsBatteryAbove"
                           topic_name="/battery_state"
                           min_percentage="0.3"/>
                <Action ID="ExecuteMission"/>
            </Sequence>
            <!-- 배터리 경고: 귀환 -->
            <Sequence>
                <Condition ID="IsBatteryAbove"
                           topic_name="/battery_state"
                           min_percentage="0.1"/>
                <Action ID="ReturnToBase"/>
            </Sequence>
            <!-- 배터리 위험: 즉시 착륙/정지 -->
            <Action ID="EmergencyStop"/>
        </Fallback>
    </ReactiveSequence>
</BehaviorTree>

이 구조는 배터리 잔량에 따라 세 단계의 행동을 선택한다. 30% 이상이면 임무를 수행하고, 10%~30% 사이이면 기지로 귀환하며, 10% 미만이면 비상 정지를 실행한다.

7. 설계 시 고려 사항

7.1 배터리 센서의 정확도

배터리 잔량 추정은 일반적으로 전압 기반 추정, 전류 적분(coulomb counting), 칼만 필터 기반 추정 등의 방법을 사용한다. 각 방법의 정확도와 특성이 상이하므로, 센서의 추정 오차를 고려하여 임계값에 충분한 안전 여유를 설정하여야 한다.

7.2 부하에 따른 전압 강하

배터리 전압은 부하 전류에 따라 변동한다. 모터 구동 시 대전류가 흐르면 전압이 일시적으로 강하하며, 부하가 제거되면 전압이 회복된다. 전압 기반 조건 판정에서는 이러한 일시적 전압 강하에 의한 오판을 방지하기 위해, 이동 평균 필터나 히스테리시스를 적용하여야 한다.

7.3 귀환 소요 에너지 고려

배터리 잔량이 부족한 경우의 판정은 단순히 잔량 비율만이 아니라, 기지까지의 귀환 거리와 소요 에너지를 함께 고려하여야 한다. 잔량이 15%이더라도, 기지까지의 거리가 멀면 귀환이 불가능할 수 있다. 이러한 복합적 판단은 별도의 계획 모듈에서 수행하고, 그 결과를 블랙보드를 통해 조건 노드에 전달하는 것이 바람직하다.

8. 참고 문헌

  • Colledanchise, M., & Ogren, P. (2018). Behavior Trees in Robotics and AI: An Introduction. CRC Press.
  • ROS2 공식 문서. https://docs.ros.org/en/humble/
  • BehaviorTree.CPP 공식 문서. https://www.behaviortree.dev/

버전날짜변경 사항
v0.12026-04-04초안 작성