1295.85 Halt 전파 테스트 케이스

1. Halt 전파 테스트의 중요성

Halt 전파는 행동 트리의 안전성과 자원 정리를 보장하는 핵심 메커니즘이다. Parallel 노드가 성공/실패 정책을 충족하여 결과를 반환할 때, 아직 RUNNING 상태인 나머지 자식 노드는 반드시 Halt되어야 한다. Reactive 노드에서 우선순위 전환이 발생할 때에도, 이전에 실행 중이던 분기의 노드가 Halt되어야 한다. Halt가 누락되면 로봇이 이전 행동을 지속하거나 자원이 해제되지 않는 결함이 발생한다. 따라서 Halt 전파의 정확성을 검증하는 테스트 케이스는 안전 관련(safety-critical) 로봇 시스템에서 필수적이다.

2. 모의 노드의 Halt 추적 인프라

Halt 전파를 검증하기 위해, 모의 노드에 Halt 호출을 추적하는 기능을 구현한다.

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

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

    BT::NodeStatus onStart() override
    {
        halted_ = false;
        return BT::NodeStatus::RUNNING;
    }

    BT::NodeStatus onRunning() override
    {
        return current_status_;
    }

    void onHalted() override
    {
        halt_count_++;
        halted_ = true;
        halt_timestamp_ = std::chrono::steady_clock::now();
    }

    void setStatus(BT::NodeStatus s) { current_status_ = s; }
    bool wasHalted() const { return halted_; }
    int haltCount() const { return halt_count_; }
    auto haltTimestamp() const { return halt_timestamp_; }
    void resetTracking()
    {
        halt_count_ = 0;
        halted_ = false;
    }

private:
    BT::NodeStatus current_status_ = BT::NodeStatus::RUNNING;
    bool halted_ = false;
    int halt_count_ = 0;
    std::chrono::steady_clock::time_point halt_timestamp_;
};

wasHalted()는 Halt 호출 여부를, haltCount()는 Halt 호출 횟수를, haltTimestamp()는 Halt 호출 시점을 각각 추적한다.

3. Parallel 노드의 Halt 전파 테스트

3.1 성공 정책 충족 시 RUNNING 자식 Halt

Parallel이 성공 정책을 충족하여 SUCCESS를 반환할 때, 아직 RUNNING인 자식에 Halt가 전파되는지를 검증한다.

TEST_F(HaltPropagationTest, Parallel_SuccessPolicy_HaltsRunning)
{
    auto tree = factory_.createTreeFromText(R"(
        <root BTCPP_format="4">
            <BehaviorTree ID="main">
                <ParallelAll max_failures="2">
                    <HaltTracking name="child_0"/>
                    <HaltTracking name="child_1"/>
                    <HaltTracking name="child_2"/>
                </ParallelAll>
            </BehaviorTree>
        </root>
    )");

    auto* c0 = getNode<HaltTrackingAction>(tree, "child_0");
    auto* c1 = getNode<HaltTrackingAction>(tree, "child_1");
    auto* c2 = getNode<HaltTrackingAction>(tree, "child_2");

    // Tick 1: 모든 자식 RUNNING
    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::RUNNING);

    // child_0만 SUCCESS, 나머지 RUNNING
    c0->setStatus(BT::NodeStatus::SUCCESS);
    // child_1, child_2 FAILURE → 실패 2개 ≤ max_failures(2) → SUCCESS
    c1->setStatus(BT::NodeStatus::FAILURE);
    c2->setStatus(BT::NodeStatus::FAILURE);

    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::SUCCESS);

    // 이미 완료된 노드의 Halt도 호출됨 (haltChildren은 모든 자식에 전파)
    // 중요한 것은 노드가 정리되었는지의 여부
    EXPECT_TRUE(c0->wasHalted() || 
                c0->status() == BT::NodeStatus::IDLE);
}

3.2 실패 정책 충족 시 RUNNING 자식 Halt

TEST_F(HaltPropagationTest, Parallel_FailurePolicy_HaltsRunning)
{
    auto tree = factory_.createTreeFromText(R"(
        <root BTCPP_format="4">
            <BehaviorTree ID="main">
                <ParallelAll max_failures="0">
                    <HaltTracking name="child_0"/>
                    <HaltTracking name="child_1"/>
                    <HaltTracking name="child_2"/>
                </ParallelAll>
            </BehaviorTree>
        </root>
    )");

    auto* c0 = getNode<HaltTrackingAction>(tree, "child_0");
    auto* c1 = getNode<HaltTrackingAction>(tree, "child_1");
    auto* c2 = getNode<HaltTrackingAction>(tree, "child_2");

    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::RUNNING);

    // child_0 FAILURE → max_failures(0) 초과 → FAILURE
    c0->setStatus(BT::NodeStatus::FAILURE);

    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::FAILURE);

    // RUNNING이었던 child_1, child_2에 Halt 전파 확인
    EXPECT_TRUE(c1->wasHalted());
    EXPECT_TRUE(c2->wasHalted());
}

3.3 부분 완료 상태에서의 Halt 전파

일부 자식이 이미 SUCCESS를 반환하고, 다른 자식이 FAILURE를 반환하여 정책이 충족되는 경우이다.

TEST_F(HaltPropagationTest, Parallel_PartialComplete_HaltRemaining)
{
    auto tree = factory_.createTreeFromText(R"(
        <root BTCPP_format="4">
            <BehaviorTree ID="main">
                <ParallelAll max_failures="0">
                    <HaltTracking name="child_0"/>
                    <HaltTracking name="child_1"/>
                    <HaltTracking name="child_2"/>
                    <HaltTracking name="child_3"/>
                </ParallelAll>
            </BehaviorTree>
        </root>
    )");

    auto* c0 = getNode<HaltTrackingAction>(tree, "child_0");
    auto* c1 = getNode<HaltTrackingAction>(tree, "child_1");
    auto* c2 = getNode<HaltTrackingAction>(tree, "child_2");
    auto* c3 = getNode<HaltTrackingAction>(tree, "child_3");

    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::RUNNING);

    // child_0, child_1 SUCCESS 완료
    c0->setStatus(BT::NodeStatus::SUCCESS);
    c1->setStatus(BT::NodeStatus::SUCCESS);
    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::RUNNING);

    // child_2 FAILURE → 정책 위반 → Parallel FAILURE
    c2->setStatus(BT::NodeStatus::FAILURE);
    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::FAILURE);

    // 아직 RUNNING이었던 child_3에 Halt 전파
    EXPECT_TRUE(c3->wasHalted());
}

4. ReactiveSequence의 Halt 전파 테스트

4.1 조건 위반 시 행동 Halt

TEST_F(HaltPropagationTest, ReactiveSequence_ConditionFail_HaltsAction)
{
    auto tree = factory_.createTreeFromText(R"(
        <root BTCPP_format="4">
            <BehaviorTree ID="main">
                <ReactiveSequence>
                    <MockCondition name="condition"/>
                    <HaltTracking name="action"/>
                </ReactiveSequence>
            </BehaviorTree>
        </root>
    )");

    auto* condition = getNode<MockCondition>(tree, "condition");
    auto* action = getNode<HaltTrackingAction>(tree, "action");

    condition->setExpectedResult(BT::NodeStatus::SUCCESS);
    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::RUNNING);
    EXPECT_FALSE(action->wasHalted());

    // 조건 위반
    condition->setExpectedResult(BT::NodeStatus::FAILURE);
    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::FAILURE);

    // 행동에 Halt 전파 확인
    EXPECT_TRUE(action->wasHalted());
    EXPECT_EQ(action->haltCount(), 1);
}

4.2 다중 행동 자식의 Halt 전파

ReactiveSequence에 다수의 행동 자식이 있는 경우, 조건 위반 시 모든 RUNNING 자식에 Halt가 전파되는지를 검증한다.

TEST_F(HaltPropagationTest, ReactiveSequence_MultipleActions_AllHalted)
{
    auto tree = factory_.createTreeFromText(R"(
        <root BTCPP_format="4">
            <BehaviorTree ID="main">
                <ReactiveSequence>
                    <MockCondition name="condition"/>
                    <HaltTracking name="action_1"/>
                    <HaltTracking name="action_2"/>
                </ReactiveSequence>
            </BehaviorTree>
        </root>
    )");

    auto* condition = getNode<MockCondition>(tree, "condition");
    auto* action1 = getNode<HaltTrackingAction>(tree, "action_1");
    auto* action2 = getNode<HaltTrackingAction>(tree, "action_2");

    condition->setExpectedResult(BT::NodeStatus::SUCCESS);
    // action_1이 SUCCESS를 반환하면 action_2로 진행
    action1->setStatus(BT::NodeStatus::SUCCESS);

    // Tick 1: condition SUCCESS, action_1 SUCCESS, action_2 RUNNING
    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::RUNNING);

    // 조건 위반
    condition->setExpectedResult(BT::NodeStatus::FAILURE);
    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::FAILURE);

    // action_2에 Halt가 전파되었는지 확인
    EXPECT_TRUE(action2->wasHalted());
}

5. ReactiveFallback의 Halt 전파 테스트

5.1 상위 분기 선점 시 하위 분기 Halt

TEST_F(HaltPropagationTest, ReactiveFallback_Preemption_HaltsLower)
{
    auto tree = factory_.createTreeFromText(R"(
        <root BTCPP_format="4">
            <BehaviorTree ID="main">
                <ReactiveFallback>
                    <MockCondition name="high_cond"/>
                    <HaltTracking name="low_action"/>
                </ReactiveFallback>
            </BehaviorTree>
        </root>
    )");

    auto* high_cond = getNode<MockCondition>(tree, "high_cond");
    auto* low_action = getNode<HaltTrackingAction>(tree, "low_action");

    // 초기: 상위 FAILURE → 하위 행동 실행
    high_cond->setExpectedResult(BT::NodeStatus::FAILURE);
    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::RUNNING);
    EXPECT_FALSE(low_action->wasHalted());

    // 상위 조건 SUCCESS → 하위 행동 Halt
    high_cond->setExpectedResult(BT::NodeStatus::SUCCESS);
    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::SUCCESS);

    EXPECT_TRUE(low_action->wasHalted());
    EXPECT_EQ(low_action->haltCount(), 1);
}

5.2 중첩 구조에서의 Halt 전파

ReactiveFallback 내부에 Sequence가 중첩된 경우, 상위 분기 활성화 시 하위 Sequence의 모든 자식에 Halt가 전파되는지를 검증한다.

TEST_F(HaltPropagationTest, ReactiveFallback_NestedSequence_DeepHalt)
{
    auto tree = factory_.createTreeFromText(R"(
        <root BTCPP_format="4">
            <BehaviorTree ID="main">
                <ReactiveFallback>
                    <Sequence name="emergency">
                        <MockCondition name="is_emergency"/>
                        <HaltTracking name="emergency_action"/>
                    </Sequence>
                    <Sequence name="normal">
                        <MockCondition name="is_ready"/>
                        <HaltTracking name="move_action"/>
                        <HaltTracking name="report_action"/>
                    </Sequence>
                </ReactiveFallback>
            </BehaviorTree>
        </root>
    )");

    auto* is_emergency = getNode<MockCondition>(tree, "is_emergency");
    auto* is_ready = getNode<MockCondition>(tree, "is_ready");
    auto* move_action = getNode<HaltTrackingAction>(tree, "move_action");

    // 초기: 비상 아님, 정상 분기 실행
    is_emergency->setExpectedResult(BT::NodeStatus::FAILURE);
    is_ready->setExpectedResult(BT::NodeStatus::SUCCESS);

    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::RUNNING);

    // 비상 발생
    is_emergency->setExpectedResult(BT::NodeStatus::SUCCESS);
    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::RUNNING);

    // 정상 분기의 move_action에 Halt 전파 확인
    EXPECT_TRUE(move_action->wasHalted());
}

6. 외부 Halt 전파 테스트

부모 노드로부터 전파되는 외부 Halt가 Parallel 및 Reactive 노드를 통해 모든 자식에 전파되는지를 검증한다.

6.1 Parallel 노드에 대한 외부 Halt

TEST_F(HaltPropagationTest, ExternalHalt_Parallel_AllChildrenHalted)
{
    auto tree = factory_.createTreeFromText(R"(
        <root BTCPP_format="4">
            <BehaviorTree ID="main">
                <Sequence>
                    <ParallelAll max_failures="0" name="parallel">
                        <HaltTracking name="child_0"/>
                        <HaltTracking name="child_1"/>
                        <HaltTracking name="child_2"/>
                    </ParallelAll>
                    <MockAction name="next_action"/>
                </Sequence>
            </BehaviorTree>
        </root>
    )");

    auto* c0 = getNode<HaltTrackingAction>(tree, "child_0");
    auto* c1 = getNode<HaltTrackingAction>(tree, "child_1");
    auto* c2 = getNode<HaltTrackingAction>(tree, "child_2");

    // Tick: Parallel RUNNING (모든 자식 RUNNING)
    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::RUNNING);

    // 트리 전체 Halt (외부 Halt)
    tree.haltTree();

    // 모든 자식에 Halt 전파 확인
    EXPECT_TRUE(c0->wasHalted());
    EXPECT_TRUE(c1->wasHalted());
    EXPECT_TRUE(c2->wasHalted());
}

6.2 ReactiveSequence에 대한 외부 Halt

TEST_F(HaltPropagationTest, ExternalHalt_ReactiveSequence_AllHalted)
{
    auto tree = factory_.createTreeFromText(R"(
        <root BTCPP_format="4">
            <BehaviorTree ID="main">
                <ReactiveSequence>
                    <MockCondition name="condition"/>
                    <HaltTracking name="action"/>
                </ReactiveSequence>
            </BehaviorTree>
        </root>
    )");

    auto* condition = getNode<MockCondition>(tree, "condition");
    auto* action = getNode<HaltTrackingAction>(tree, "action");

    condition->setExpectedResult(BT::NodeStatus::SUCCESS);
    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::RUNNING);

    tree.haltTree();

    EXPECT_TRUE(action->wasHalted());
}

7. Halt 중복 호출 방지 테스트

이미 IDLE 상태인 노드에 Halt가 중복 호출되지 않는지, 또는 중복 호출 시 부작용이 없는지를 검증한다.

TEST_F(HaltPropagationTest, Halt_Idempotency)
{
    auto tree = factory_.createTreeFromText(R"(
        <root BTCPP_format="4">
            <BehaviorTree ID="main">
                <ParallelAll max_failures="0">
                    <HaltTracking name="child_0"/>
                    <HaltTracking name="child_1"/>
                </ParallelAll>
            </BehaviorTree>
        </root>
    )");

    auto* c0 = getNode<HaltTrackingAction>(tree, "child_0");
    auto* c1 = getNode<HaltTrackingAction>(tree, "child_1");

    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::RUNNING);

    // child_0 FAILURE → Parallel FAILURE → haltChildren 호출
    c0->setStatus(BT::NodeStatus::FAILURE);
    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::FAILURE);

    int halt_count_after_failure = c1->haltCount();

    // 트리 전체 Halt 추가 호출
    tree.haltTree();

    // Halt가 과도하게 중복 호출되지 않는지 확인
    // (이미 IDLE인 노드에 대한 Halt는 onHalted를 호출하지 않음)
    EXPECT_LE(c1->haltCount(), halt_count_after_failure + 1);
}

8. Halt 전파 순서 검증

Parallel 노드에서 자식에 대한 Halt 전파가 인덱스 순서대로 수행되는지를 검증한다.

TEST_F(HaltPropagationTest, Parallel_HaltOrder)
{
    auto tree = factory_.createTreeFromText(R"(
        <root BTCPP_format="4">
            <BehaviorTree ID="main">
                <ParallelAll max_failures="0">
                    <HaltTracking name="child_0"/>
                    <HaltTracking name="child_1"/>
                    <HaltTracking name="child_2"/>
                </ParallelAll>
            </BehaviorTree>
        </root>
    )");

    auto* c0 = getNode<HaltTrackingAction>(tree, "child_0");
    auto* c1 = getNode<HaltTrackingAction>(tree, "child_1");
    auto* c2 = getNode<HaltTrackingAction>(tree, "child_2");

    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::RUNNING);

    c0->setStatus(BT::NodeStatus::FAILURE);
    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::FAILURE);

    // Halt 시점의 순서 확인
    // BehaviorTree.CPP는 haltChildren()에서 인덱스 역순으로 Halt를 전파
    if (c1->wasHalted() && c2->wasHalted())
    {
        // child_2가 child_1보다 먼저 Halt되었는지 확인 (역순)
        EXPECT_LE(c2->haltTimestamp(), c1->haltTimestamp());
    }
}

BehaviorTree.CPP의 haltChildren() 구현은 자식을 역순으로 순회하면서 Halt를 호출한다. 이 순서를 검증함으로써, 자원 해제가 생성의 역순으로 수행됨을 보장할 수 있다.

9. 테스트 케이스 요약

테스트 범주노드 유형검증 내용
성공 정책 HaltParallelSUCCESS 반환 시 RUNNING 자식 Halt
실패 정책 HaltParallelFAILURE 반환 시 RUNNING 자식 Halt
부분 완료 HaltParallel일부 완료 후 정책 위반 시 나머지 Halt
조건 위반 HaltReactiveSequence조건 FAILURE → 행동 Halt
다중 행동 HaltReactiveSequence조건 위반 시 모든 RUNNING 행동 Halt
선점 HaltReactiveFallback상위 분기 활성화 → 하위 분기 Halt
중첩 구조 HaltReactiveFallback중첩 Sequence 내부까지 Halt 전파
외부 HaltParallel / Reactive트리 Halt 시 모든 자식에 전파
멱등성공통Halt 중복 호출 시 부작용 없음
전파 순서Parallel자식 Halt의 역순 전파 확인

Halt 전파 테스트는 로봇의 안전 동작을 보장하는 최후의 방어선이다. 모든 Halt 경로를 100% 커버하는 것을 목표로 하여야 하며, 특히 중첩 구조와 외부 Halt 시나리오에서의 전파를 철저히 검증하여야 한다.