커스텀 데코레이터 구현 사례 (Custom Decorator Implementation Examples)

커스텀 데코레이터 구현 사례 (Custom Decorator Implementation Examples)

1. 개요

본 절에서는 BehaviorTree.CPP의 내장 데코레이터로는 충족되지 않는 특수한 요구를 위한 커스텀 데코레이터의 구체적 구현 사례를 다룬다. 횟수 제한, 조건부 halt, 로깅, 프로파일링 등의 실용적 데코레이터를 구현하며, 각 사례는 DecoratorNode 상속, tick() ���현, halt() 구현, 포트 정의, 등록의 전체 과정을 포함한다.

2. 사례 1: 쿨다운 데코레이터

자식이 성공한 후 지정된 시간 동안 재실행을 방지한다.

class CooldownDecorator : public BT::DecoratorNode
{
public:
    CooldownDecorator(const std::string& name,
                      const BT::NodeConfiguration& config)
        : DecoratorNode(name, config),
          last_success_(std::chrono::steady_clock::time_point::min())
    {}

    static BT::PortsList providedPorts()
    {
        return {BT::InputPort<double>("sec", 5.0, "쿨다운 (초)")};
    }

private:
    BT::NodeStatus tick() override
    {
        setStatus(BT::NodeStatus::RUNNING);
        double sec;
        getInput("sec", sec);

        auto elapsed = std::chrono::duration<double>(
            std::chrono::steady_clock::now() - last_success_).count();

        if (elapsed < sec)
            return BT::NodeStatus::FAILURE;

        auto status = child_node_->executeTick();
        if (status == BT::NodeStatus::SUCCESS)
            last_success_ = std::chrono::steady_clock::now();

        return status;
    }

    void halt() override { DecoratorNode::halt(); }

    std::chrono::steady_clock::time_point last_success_;
};

3. 사례 2: 실행 횟수 제한 데코레이터

자식의 총 실행 횟수를 제한한다.

class ExecutionLimiter : public BT::DecoratorNode
{
public:
    ExecutionLimiter(const std::string& name,
                     const BT::NodeConfiguration& config)
        : DecoratorNode(name, config), count_(0) {}

    static BT::PortsList providedPorts()
    {
        return {BT::InputPort<int>("max", 10, "최대 실행 횟수")};
    }

private:
    BT::NodeStatus tick() override
    {
        int max;
        getInput("max", max);
        if (count_ >= max)
            return BT::NodeStatus::FAILURE;
        ++count_;
        return child_node_->executeTick();
    }

    void halt() override
    {
        count_ = 0;
        DecoratorNode::halt();
    }

    int count_;
};

4. 사례 3: 로깅 데코레이터

자식의 상태 전환을 로깅한다.

class LoggingDecorator : public BT::DecoratorNode
{
public:
    LoggingDecorator(const std::string& name,
                     const BT::NodeConfiguration& config)
        : DecoratorNode(name, config),
          prev_(BT::NodeStatus::IDLE) {}

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

private:
    BT::NodeStatus tick() override
    {
        setStatus(BT::NodeStatus::RUNNING);
        auto status = child_node_->executeTick();
        if (status != prev_)
        {
            std::cout << "[" << name() << "] "
                      << child()->name() << ": "
                      << BT::toStr(prev_) << " -> "
                      << BT::toStr(status) << std::endl;
            prev_ = status;
        }
        return status;
    }

    void halt() override
    {
        prev_ = BT::NodeStatus::IDLE;
        DecoratorNode::halt();
    }

    BT::NodeStatus prev_;
};

5. 사례 4: 프로파일링 데코레이터

자식의 tick 실행 시간을 측정한다.

class ProfilingDecorator : public BT::DecoratorNode
{
public:
    ProfilingDecorator(const std::string& name,
                       const BT::NodeConfiguration& config)
        : DecoratorNode(name, config) {}

    static BT::PortsList providedPorts()
    {
        return {BT::OutputPort<double>("elapsed_ms", "실행 시간 (ms)")};
    }

private:
    BT::NodeStatus tick() override
    {
        setStatus(BT::NodeStatus::RUNNING);
        auto start = std::chrono::steady_clock::now();
        auto status = child_node_->executeTick();
        auto end = std::chrono::steady_clock::now();

        double ms = std::chrono::duration<double, std::milli>(
            end - start).count();
        setOutput("elapsed_ms", ms);

        return status;
    }
};

6. 등록 및 XML 사용

factory.registerNodeType<CooldownDecorator>("Cooldown");
factory.registerNodeType<ExecutionLimiter>("ExecutionLimit");
factory.registerNodeType<LoggingDecorator>("Log");
factory.registerNodeType<ProfilingDecorator>("Profile");
<Cooldown sec="10.0">
    <Action ID="RecoveryAction"/>
</Cooldown>

<Log>
    <Action ID="NavigateToPose"/>
</Log>

<Profile elapsed_ms="{tick_time}">
    <Action ID="ComputePath"/>
</Profile>

7. 참고 문헌

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

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