1294.82 Sequence와 Fallback의 BehaviorTree.CPP 구현

1. BehaviorTree.CPP의 제어 노드 클래스 계층

BehaviorTree.CPP(v4) 라이브러리에서 Sequence와 Fallback은 ControlNode 기반 클래스를 상속하여 구현된다. 클래스 계층 구조는 다음과 같다(Faconti, 2022):

TreeNode
└── ControlNode
    ├── SequenceNode          (SequenceWithMemory)
    ├── ReactiveSequence
    ├── FallbackNode          (FallbackWithMemory)
    └── ReactiveFallback

2. ControlNode 기반 클래스

2.1 ControlNode의 핵심 인터페이스

class ControlNode : public TreeNode {
public:
    void addChild(TreeNode* child);
    size_t childrenCount() const;
    const std::vector<TreeNode*>& children() const;

    void halt() override;
    void haltChild(size_t index);
    void haltChildren();
    void haltChildren(size_t first);

protected:
    std::vector<TreeNode*> children_nodes_;
};

ControlNode는 자식 노드의 관리와 Halt 처리를 위한 공통 인터페이스를 제공한다. haltChildren(size_t first) 메서드는 지정된 인덱스부터 마지막 자식까지 Halt하는 기능으로, ReactiveSequence와 ReactiveFallback에서 활용된다.

2.2 halt() 메서드의 기본 구현

void ControlNode::halt() {
    haltChildren();
    setStatus(NodeStatus::IDLE);
}

void ControlNode::haltChildren() {
    for (size_t i = 0; i < children_nodes_.size(); i++) {
        haltChild(i);
    }
}

void ControlNode::haltChild(size_t index) {
    auto child = children_nodes_[index];
    if (child->status() == NodeStatus::RUNNING) {
        child->halt();
    }
    child->setStatus(NodeStatus::IDLE);
}

halt()가 호출되면 모든 자식을 순회하며, RUNNING 상태인 자식에 halt()를 재귀적으로 호출한 후 IDLE로 설정한다.

3. SequenceNode의 구현

3.1 SequenceNode의 클래스 정의

BehaviorTree.CPP v4에서 SequenceNode는 SequenceWithMemory 동작을 구현한다:

class SequenceNode : public ControlNode {
public:
    SequenceNode(const std::string& name, const NodeConfig& config);

    NodeStatus tick() override;
    void halt() override;

private:
    size_t current_child_idx_;
    bool all_skipped_ = true;
};

3.2 tick() 메서드의 핵심 로직

NodeStatus SequenceNode::tick() {
    const size_t children_count = children_nodes_.size();
    
    if (status() == NodeStatus::IDLE) {
        all_skipped_ = true;
    }
    
    setStatus(NodeStatus::RUNNING);
    
    while (current_child_idx_ < children_count) {
        TreeNode* current_child = children_nodes_[current_child_idx_];
        const NodeStatus child_status = current_child->executeTick();
        
        switch (child_status) {
            case NodeStatus::RUNNING:
                return NodeStatus::RUNNING;
                
            case NodeStatus::FAILURE:
                resetChildren();
                current_child_idx_ = 0;
                return NodeStatus::FAILURE;
                
            case NodeStatus::SUCCESS:
                all_skipped_ = false;
                current_child_idx_++;
                break;
                
            case NodeStatus::SKIPPED:
                current_child_idx_++;
                break;
        }
    }
    
    current_child_idx_ = 0;
    return all_skipped_ ? NodeStatus::SKIPPED : NodeStatus::SUCCESS;
}

current_child_idx_가 진행 상황을 기억하므로, RUNNING 반환 후 다음 Tick에서 해당 자식부터 재시작한다. FAILURE 시에는 current_child_idx_를 0으로 초기화한다.

4. ReactiveSequence의 구현

4.1 tick() 메서드의 핵심 로직

NodeStatus ReactiveSequence::tick() {
    bool all_skipped = true;
    setStatus(NodeStatus::RUNNING);
    
    for (size_t index = 0; index < childrenCount(); index++) {
        TreeNode* current_child = children_nodes_[index];
        const NodeStatus child_status = current_child->executeTick();
        
        switch (child_status) {
            case NodeStatus::RUNNING:
                for (size_t j = index + 1; j < childrenCount(); j++) {
                    haltChild(j);
                }
                return NodeStatus::RUNNING;
                
            case NodeStatus::FAILURE:
                resetChildren();
                return NodeStatus::FAILURE;
                
            case NodeStatus::SUCCESS:
                all_skipped = false;
                break;
                
            case NodeStatus::SKIPPED:
                break;
        }
    }
    
    resetChildren();
    return all_skipped ? NodeStatus::SKIPPED : NodeStatus::SUCCESS;
}

ReactiveSequence는 항상 인덱스 0부터 시작하며, RUNNING을 반환하는 자식 이후의 모든 자식을 Halt한다. 이 구현에서 current_child_idx_를 사용하지 않는다는 점이 SequenceNode와의 핵심적 차이이다.

5. FallbackNode의 구현

5.1 FallbackNode의 클래스 정의

class FallbackNode : public ControlNode {
public:
    FallbackNode(const std::string& name, const NodeConfig& config);

    NodeStatus tick() override;
    void halt() override;

private:
    size_t current_child_idx_;
    bool all_skipped_ = true;
};

5.2 tick() 메서드의 핵심 로직

NodeStatus FallbackNode::tick() {
    const size_t children_count = children_nodes_.size();
    
    if (status() == NodeStatus::IDLE) {
        all_skipped_ = true;
    }
    
    setStatus(NodeStatus::RUNNING);
    
    while (current_child_idx_ < children_count) {
        TreeNode* current_child = children_nodes_[current_child_idx_];
        const NodeStatus child_status = current_child->executeTick();
        
        switch (child_status) {
            case NodeStatus::RUNNING:
                return NodeStatus::RUNNING;
                
            case NodeStatus::SUCCESS:
                resetChildren();
                current_child_idx_ = 0;
                return NodeStatus::SUCCESS;
                
            case NodeStatus::FAILURE:
                all_skipped_ = false;
                current_child_idx_++;
                break;
                
            case NodeStatus::SKIPPED:
                current_child_idx_++;
                break;
        }
    }
    
    current_child_idx_ = 0;
    return all_skipped_ ? NodeStatus::SKIPPED : NodeStatus::FAILURE;
}

FallbackNode는 SequenceNode와 대칭적 구조를 가진다. SUCCESS와 FAILURE의 역할이 정확히 교환되어 있다: SUCCESS가 조기 종료를 유발하고, FAILURE가 다음 자식으로의 진행을 유발한다.

6. ReactiveFallback의 구현

6.1 tick() 메서드의 핵심 로직

NodeStatus ReactiveFallback::tick() {
    bool all_skipped = true;
    setStatus(NodeStatus::RUNNING);
    
    for (size_t index = 0; index < childrenCount(); index++) {
        TreeNode* current_child = children_nodes_[index];
        const NodeStatus child_status = current_child->executeTick();
        
        switch (child_status) {
            case NodeStatus::RUNNING:
                for (size_t j = index + 1; j < childrenCount(); j++) {
                    haltChild(j);
                }
                return NodeStatus::RUNNING;
                
            case NodeStatus::SUCCESS:
                resetChildren();
                return NodeStatus::SUCCESS;
                
            case NodeStatus::FAILURE:
                all_skipped = false;
                break;
                
            case NodeStatus::SKIPPED:
                break;
        }
    }
    
    resetChildren();
    return all_skipped ? NodeStatus::SKIPPED : NodeStatus::FAILURE;
}

ReactiveFallback은 ReactiveSequence와 대칭적이며, SUCCESS와 FAILURE의 역할만 교환되어 있다.

7. 네 가지 구현의 대칭적 관계

특성SequenceNodeFallbackNodeReactiveSequenceReactiveFallback
조기 종료 조건FAILURESUCCESSFAILURESUCCESS
진행 조건SUCCESSFAILURESUCCESSFAILURE
메모리 사용예 (idx 유지)예 (idx 유지)아니오아니오
재평가 시작점idx부터idx부터항상 0항상 0
후속 자식 Halt불필요불필요RUNNING 이후 HaltRUNNING 이후 Halt

8. SKIPPED 상태의 처리

BehaviorTree.CPP v4에서 추가된 NodeStatus::SKIPPED는 “이 노드는 실행할 필요가 없다“는 의미이다. SKIPPED는 SUCCESS/FAILURE와 달리 다음 자식으로의 진행을 유발하되, all_skipped_ 플래그에는 영향을 주지 않는다. 모든 자식이 SKIPPED를 반환하면 제어 노드 자체도 SKIPPED를 반환한다(Faconti, 2022).


참고 문헌

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