1297.14 ConditionNode의 인터페이스

1. 인터페이스 개요

BT::ConditionNode의 인터페이스는 사용자가 구현해야 하는 메서드와 프레임워크가 제공하는 메서드로 구분된다. 조건 노드의 인터페이스는 의도적으로 단순하게 설계되어 있으며, 사용자가 반드시 구현해야 하는 메서드는 tick()providedPorts() 두 가지이다(Faconti & Colledanchise, 2022).

2. 사용자 필수 구현 인터페이스

2.1 tick() 메서드

tick() 메서드는 조건 노드의 핵심 인터페이스로, 조건 평가 로직을 구현하는 곳이다. 이 메서드는 부모 제어 노드로부터 tick 신호가 전달될 때 호출된다.

virtual BT::NodeStatus tick() override;

반환값: BT::NodeStatus::SUCCESS 또는 BT::NodeStatus::FAILURE만 허용된다. BT::NodeStatus::RUNNING을 반환하면 런타임 오류가 발생한다.

호출 주기: 부모 제어 노드에 의해 결정된다. ReactiveSequence 하위에서는 매 tick마다 호출되며, 일반 Sequence 하위에서는 해당 노드의 차례에만 호출된다.

구현 예시:

BT::NodeStatus tick() override
{
    double value;
    auto result = getInput("sensor_value", value);

    if (!result)
    {
        return BT::NodeStatus::FAILURE;
    }

    double threshold;
    getInput("threshold", threshold);

    return (value >= threshold)
        ? BT::NodeStatus::SUCCESS
        : BT::NodeStatus::FAILURE;
}

2.2 providedPorts() 정적 메서드

providedPorts() 메서드는 조건 노드가 사용하는 블랙보드 포트를 선언하는 정적 메서드이다. 이 메서드는 노드 등록(registration) 시 호출되어 포트 정보를 트리 빌더에 제공한다.

static BT::PortsList providedPorts();

반환값: BT::PortsList 타입으로, 노드가 사용하는 입력 포트(InputPort)와 출력 포트(OutputPort)의 목록을 반환한다. 조건 노드는 원칙적으로 입력 포트만을 사용한다.

구현 예시:

static BT::PortsList providedPorts()
{
    return {
        BT::InputPort<double>("sensor_value", "센서에서 측정된 값"),
        BT::InputPort<double>("threshold", 0.5, "비교 임계값 (기본값: 0.5)")
    };
}

포트 선언 시 기본값(default value)을 지정할 수 있다. 기본값이 지정된 포트는 XML 트리 정의에서 해당 속성을 생략할 수 있다.

3. 프레임워크 제공 인터페이스

3.1 블랙보드 접근 메서드

3.1.1 getInput()

블랙보드에서 입력 포트의 값을 읽는다. 템플릿 매개변수로 기대하는 타입을 지정한다.

template <typename T>
Result getInput(const std::string& key, T& destination) const;

매개변수:

  • key: providedPorts()에서 선언한 포트 이름
  • destination: 읽어온 값을 저장할 변수의 참조

반환값: BT::Result 타입으로, 성공 시 유효한 값을 포함하며, 실패 시(키 부재, 타입 불일치 등) 오류 정보를 포함한다.

double value;
auto result = getInput("sensor_value", value);
if (!result)
{
    // 포트 값을 읽을 수 없음
    return BT::NodeStatus::FAILURE;
}

또는 Expected<T> 반환 형식을 사용할 수 있다:

auto expected_value = getInput<double>("sensor_value");
if (!expected_value)
{
    return BT::NodeStatus::FAILURE;
}
double value = expected_value.value();

3.1.2 setOutput()

블랙보드에 출력 포트의 값을 쓴다. 조건 노드에서는 부작용 금지 원칙에 따라 사용을 자제해야 한다.

template <typename T>
Result setOutput(const std::string& key, const T& value);

3.2 노드 정보 메서드

3.2.1 name()

노드의 인스턴스 이름을 반환한다. XML에서 name 속성으로 지정된 값이다.

const std::string& name() const;

3.2.2 registrationName()

노드의 등록 ID를 반환한다. BehaviorTreeFactory에 등록할 때 사용된 문자열이다.

const std::string& registrationName() const;

3.2.3 status()

노드의 현재 상태를 반환한다. IDLE, RUNNING, SUCCESS, FAILURE 중 하나이다.

NodeStatus status() const;

3.2.4 config()

노드의 설정 정보(NodeConfig)를 반환한다. 블랙보드 포트 매핑 등의 정보가 포함된다.

const NodeConfig& config() const;

3.3 로깅 관련 메서드

3.3.1 emitWakeUpSignal()

트리 실행 엔진에 웨이크업 신호를 전달한다. 조건 노드에서는 일반적으로 사용하지 않는다.

4. 인터페이스의 제약 사항

4.1 halt() 재정의 불가

halt() 메서드는 ConditionNode에서 final로 선언되어 있으므로, 사용자 정의 조건 노드에서 재정의할 수 없다.

// 컴파일 오류 발생
void halt() override  // error: cannot override final function
{
    // ...
}

4.2 출력 포트의 제한적 사용

providedPorts()에서 OutputPort를 선언하고 setOutput()을 호출하는 것은 기술적으로 가능하나, 부작용 금지 원칙에 위배된다. 조건 노드가 블랙보드 값을 변경하면, 해당 값에 의존하는 다른 노드의 동작이 예기치 않게 변경될 수 있다.

5. 전체 인터페이스 요약

메서드구분반환 타입설명
tick()사용자 필수 구현NodeStatus조건 평가 로직
providedPorts()사용자 필수 구현PortsList포트 선언
halt()재정의 불가 (final)void상태 초기화만 수행
getInput<T>()프레임워크 제공Result블랙보드 읽기
setOutput<T>()프레임워크 제공Result블랙보드 쓰기 (비권장)
name()프레임워크 제공const string&노드 이름 조회
registrationName()프레임워크 제공const string&등록 ID 조회
status()프레임워크 제공NodeStatus현재 상태 조회
config()프레임워크 제공const NodeConfig&설정 정보 조회

6. 완전한 조건 노드 구현 예시

다음은 모든 필수 인터페이스를 구현한 완전한 조건 노드의 예시이다:

#include <behaviortree_cpp/condition_node.h>

class IsSpeedInRange : public BT::ConditionNode
{
public:
    IsSpeedInRange(const std::string& name, const BT::NodeConfig& config)
        : BT::ConditionNode(name, config)
    {}

    BT::NodeStatus tick() override
    {
        double speed;
        auto result = getInput("current_speed", speed);
        if (!result)
        {
            return BT::NodeStatus::FAILURE;
        }

        double min_speed, max_speed;
        getInput("min_speed", min_speed);
        getInput("max_speed", max_speed);

        return (speed >= min_speed && speed <= max_speed)
            ? BT::NodeStatus::SUCCESS
            : BT::NodeStatus::FAILURE;
    }

    static BT::PortsList providedPorts()
    {
        return {
            BT::InputPort<double>("current_speed", "현재 속도 (m/s)"),
            BT::InputPort<double>("min_speed", 0.0, "최소 허용 속도"),
            BT::InputPort<double>("max_speed", 2.0, "최대 허용 속도")
        };
    }
};

7. 참고 문헌

  • Colledanchise, M., & Ogren, P. (2018). Behavior Trees in Robotics and AI: An Introduction. CRC Press.
  • Faconti, D., & Colledanchise, M. (2022). BehaviorTree.CPP Documentation. https://www.behaviortree.dev/

version: 0.1.0