1295.84 Reactive 노드의 재평가 동작 테스트 케이스

1295.84 Reactive 노드의 재평가 동작 테스트 케이스

1. 재평가 동작 테스트의 핵심

ReactiveSequence와 ReactiveFallback의 본질적 특성은 매 Tick마다 이미 완료된 자식 노드를 포함하여 처음부터 재평가하는 것이다. 이 재평가 동작이 올바르게 구현되었는지를 검증하는 것이 Reactive 노드 테스트의 핵심이다. 일반 Sequence/Fallback과의 차이를 명확히 드러내는 테스트 케이스를 설계하여야 한다.

2. ReactiveSequence 재평가 테스트

2.1 조건 노드의 매 Tick 재평가 검증

ReactiveSequence에서 첫 번째 자식(조건 노드)이 매 Tick마다 재Tick되는지를 검증한다.

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

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

    condition->setExpectedResult(BT::NodeStatus::SUCCESS);

    // Tick 1: 조건 SUCCESS, 행동 RUNNING
    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::RUNNING);
    EXPECT_EQ(condition->tickCount(), 1);

    // Tick 2: 조건이 다시 평가됨
    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::RUNNING);
    EXPECT_EQ(condition->tickCount(), 2);

    // Tick 3: 조건이 또다시 평가됨
    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::RUNNING);
    EXPECT_EQ(condition->tickCount(), 3);
}

이 테스트는 조건 노드의 tickCount()가 매 Tick마다 증가하는지를 확인함으로써 재평가 동작을 검증한다. 일반 Sequence에서는 조건이 한 번 SUCCESS를 반환하면 이후 Tick에서 재평가되지 않으므로, tickCount()가 1에서 멈춘다.

2.2 조건 실패 시 행동 Halt 검증

조건이 SUCCESS에서 FAILURE로 전이할 때, 실행 중인 행동 노드에 Halt가 전파되는지를 검증한다.

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

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

    // 초기: 조건 SUCCESS
    condition->setExpectedResult(BT::NodeStatus::SUCCESS);

    // Tick 1: 조건 SUCCESS, 행동 RUNNING → 전체 RUNNING
    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::RUNNING);
    EXPECT_EQ(action->haltCount(), 0);

    // 조건을 FAILURE로 변경
    condition->setExpectedResult(BT::NodeStatus::FAILURE);

    // Tick 2: 조건 FAILURE → ReactiveSequence FAILURE
    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::FAILURE);

    // 행동 노드에 Halt가 전파되었는지 확인
    EXPECT_GE(action->haltCount(), 1);
}

2.3 조건 복원 시 행동 재시작 검증

조건이 FAILURE에서 다시 SUCCESS로 복원되었을 때, 행동 노드가 새롭게 시작되는지를 검증한다.

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

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

    // Tick 1: 조건 SUCCESS, 행동 RUNNING
    condition->setExpectedResult(BT::NodeStatus::SUCCESS);
    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::RUNNING);
    int initial_tick = action->tickCount();

    // Tick 2: 조건 FAILURE → 행동 Halt
    condition->setExpectedResult(BT::NodeStatus::FAILURE);
    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::FAILURE);

    // Tick 3: 조건 다시 SUCCESS → 행동이 onStart()부터 재시작
    condition->setExpectedResult(BT::NodeStatus::SUCCESS);
    action->reset();
    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::RUNNING);

    // 행동이 새로 시작되었으므로 tickCount가 1
    EXPECT_EQ(action->tickCount(), 1);
}

2.4 다중 조건의 순차 재평가 검증

ReactiveSequence에 다수의 조건 노드가 있는 경우, 앞선 조건이 FAILURE를 반환하면 후속 자식은 Tick되지 않아야 한다.

TEST_F(ReactiveNodeTest, ReactiveSequence_MultipleConditions)
{
    auto tree = factory_.createTreeFromText(R"(
        <root BTCPP_format="4">
            <BehaviorTree ID="main">
                <ReactiveSequence>
                    <MockCondition name="cond_1"/>
                    <MockCondition name="cond_2"/>
                    <MockAsync name="action"/>
                </ReactiveSequence>
            </BehaviorTree>
        </root>
    )");

    auto* cond1 = getNode<MockCondition>(tree, "cond_1");
    auto* cond2 = getNode<MockCondition>(tree, "cond_2");
    auto* action = getNode<MockAsyncAction>(tree, "action");

    cond1->setExpectedResult(BT::NodeStatus::SUCCESS);
    cond2->setExpectedResult(BT::NodeStatus::SUCCESS);

    // Tick 1: 모든 조건 SUCCESS, 행동 RUNNING
    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::RUNNING);

    // cond_1을 FAILURE로 변경
    cond1->setExpectedResult(BT::NodeStatus::FAILURE);
    int cond2_count_before = cond2->tickCount();

    // Tick 2: cond_1 FAILURE → cond_2는 평가되지 않아야 함
    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::FAILURE);
    EXPECT_EQ(cond2->tickCount(), cond2_count_before);
}

3. ReactiveFallback 재평가 테스트

3.1 상위 우선순위 조건의 재평가 검증

ReactiveFallback에서 하위 분기가 RUNNING 상태일 때, 매 Tick마다 상위 분기의 조건이 재평가되는지를 검증한다.

TEST_F(ReactiveNodeTest, ReactiveFallback_HighPriorityReevaluated)
{
    auto tree = factory_.createTreeFromText(R"(
        <root BTCPP_format="4">
            <BehaviorTree ID="main">
                <ReactiveFallback>
                    <MockCondition name="high_priority"/>
                    <MockAsync name="low_priority_action"/>
                </ReactiveFallback>
            </BehaviorTree>
        </root>
    )");

    auto* high = getNode<MockCondition>(tree, "high_priority");
    auto* low = getNode<MockAsyncAction>(tree, "low_priority_action");

    // 초기: 상위 조건 FAILURE → 하위 행동 실행
    high->setExpectedResult(BT::NodeStatus::FAILURE);

    // Tick 1: 상위 FAILURE, 하위 RUNNING
    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::RUNNING);
    EXPECT_EQ(high->tickCount(), 1);

    // Tick 2: 상위가 다시 평가됨
    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::RUNNING);
    EXPECT_EQ(high->tickCount(), 2);

    // Tick 3: 상위가 또다시 평가됨
    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::RUNNING);
    EXPECT_EQ(high->tickCount(), 3);
}

3.2 상위 분기 활성화 시 하위 분기 선점 검증

상위 분기의 조건이 SUCCESS로 전이하면, 실행 중이던 하위 분기가 Halt되고 상위 분기의 행동이 실행되는지를 검증한다.

TEST_F(ReactiveNodeTest, ReactiveFallback_Preemption)
{
    auto tree = factory_.createTreeFromText(R"(
        <root BTCPP_format="4">
            <BehaviorTree ID="main">
                <ReactiveFallback>
                    <Sequence name="emergency">
                        <MockCondition name="is_emergency"/>
                        <MockAsync name="emergency_action"/>
                    </Sequence>
                    <MockAsync name="normal_action"/>
                </ReactiveFallback>
            </BehaviorTree>
        </root>
    )");

    auto* is_emergency = getNode<MockCondition>(tree, "is_emergency");
    auto* emergency_action = getNode<MockAsyncAction>(tree, "emergency_action");
    auto* normal_action = getNode<MockAsyncAction>(tree, "normal_action");

    // 초기: 비상 아님 → 정상 행동 실행
    is_emergency->setExpectedResult(BT::NodeStatus::FAILURE);

    // Tick 1: 비상 조건 FAILURE → Sequence FAILURE → normal_action RUNNING
    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::RUNNING);
    EXPECT_EQ(normal_action->tickCount(), 1);

    // 비상 상황 발생
    is_emergency->setExpectedResult(BT::NodeStatus::SUCCESS);

    // Tick 2: 비상 조건 SUCCESS → emergency_action 시작, normal_action Halt
    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::RUNNING);
    EXPECT_GE(normal_action->haltCount(), 1);
    EXPECT_GE(emergency_action->tickCount(), 1);
}

3.3 상위 분기 비활성화 시 하위 분기 복원 검증

선점 후 상위 조건이 다시 FAILURE로 전이하면, 하위 분기의 행동이 새롭게 시작되는지를 검증한다.

TEST_F(ReactiveNodeTest, ReactiveFallback_ReturnToLowerPriority)
{
    auto tree = factory_.createTreeFromText(R"(
        <root BTCPP_format="4">
            <BehaviorTree ID="main">
                <ReactiveFallback>
                    <Sequence name="emergency">
                        <MockCondition name="is_emergency"/>
                        <MockAsync name="emergency_action"/>
                    </Sequence>
                    <MockAsync name="normal_action"/>
                </ReactiveFallback>
            </BehaviorTree>
        </root>
    )");

    auto* is_emergency = getNode<MockCondition>(tree, "is_emergency");
    auto* emergency_action = getNode<MockAsyncAction>(tree, "emergency_action");
    auto* normal_action = getNode<MockAsyncAction>(tree, "normal_action");

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

    // 비상 상황 해제
    is_emergency->setExpectedResult(BT::NodeStatus::FAILURE);

    // Tick: 비상 조건 FAILURE → emergency Sequence FAILURE
    //       → emergency_action Halt → normal_action 재시작
    normal_action->reset();
    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::RUNNING);
    EXPECT_GE(emergency_action->haltCount(), 1);
    EXPECT_GE(normal_action->tickCount(), 1);
}

3.4 다단계 우선순위 전환 검증

세 개 이상의 우선순위 분기 간 전환이 올바르게 동작하는지를 검증한다.

TEST_F(ReactiveNodeTest, ReactiveFallback_MultiLevelPriority)
{
    auto tree = factory_.createTreeFromText(R"(
        <root BTCPP_format="4">
            <BehaviorTree ID="main">
                <ReactiveFallback>
                    <Sequence name="P0">
                        <MockCondition name="cond_P0"/>
                        <MockAsync name="action_P0"/>
                    </Sequence>
                    <Sequence name="P1">
                        <MockCondition name="cond_P1"/>
                        <MockAsync name="action_P1"/>
                    </Sequence>
                    <MockAsync name="action_default"/>
                </ReactiveFallback>
            </BehaviorTree>
        </root>
    )");

    auto* cond_P0 = getNode<MockCondition>(tree, "cond_P0");
    auto* cond_P1 = getNode<MockCondition>(tree, "cond_P1");
    auto* action_P0 = getNode<MockAsyncAction>(tree, "action_P0");
    auto* action_P1 = getNode<MockAsyncAction>(tree, "action_P1");
    auto* action_default = getNode<MockAsyncAction>(tree, "action_default");

    // 상태 1: 모든 조건 FAILURE → 기본 행동 실행
    cond_P0->setExpectedResult(BT::NodeStatus::FAILURE);
    cond_P1->setExpectedResult(BT::NodeStatus::FAILURE);
    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::RUNNING);
    EXPECT_GE(action_default->tickCount(), 1);

    // 상태 2: P1 활성화 → 기본 행동 Halt, P1 행동 실행
    cond_P1->setExpectedResult(BT::NodeStatus::SUCCESS);
    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::RUNNING);
    EXPECT_GE(action_default->haltCount(), 1);
    EXPECT_GE(action_P1->tickCount(), 1);

    // 상태 3: P0 활성화 → P1 행동 Halt, P0 행동 실행
    cond_P0->setExpectedResult(BT::NodeStatus::SUCCESS);
    EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::RUNNING);
    EXPECT_GE(action_P1->haltCount(), 1);
    EXPECT_GE(action_P0->tickCount(), 1);
}

4. 일반 노드와의 비교 테스트

Reactive 노드의 재평가 동작이 일반 Sequence/Fallback과 다름을 대조적으로 검증하는 테스트이다.

4.1 ReactiveSequence vs Sequence 비교

TEST_F(ReactiveNodeTest, CompareReactiveSequenceWithSequence)
{
    // ReactiveSequence 트리
    auto reactive_tree = factory_.createTreeFromText(R"(
        <root BTCPP_format="4">
            <BehaviorTree ID="main">
                <ReactiveSequence>
                    <MockCondition name="condition"/>
                    <MockAsync name="action"/>
                </ReactiveSequence>
            </BehaviorTree>
        </root>
    )");

    // 일반 Sequence 트리
    auto standard_tree = factory_.createTreeFromText(R"(
        <root BTCPP_format="4">
            <BehaviorTree ID="main">
                <Sequence>
                    <MockCondition name="condition"/>
                    <MockAsync name="action"/>
                </Sequence>
            </BehaviorTree>
        </root>
    )");

    auto* reactive_cond = getNode<MockCondition>(reactive_tree, "condition");
    auto* standard_cond = getNode<MockCondition>(standard_tree, "condition");

    reactive_cond->setExpectedResult(BT::NodeStatus::SUCCESS);
    standard_cond->setExpectedResult(BT::NodeStatus::SUCCESS);

    // 3회 Tick
    for (int i = 0; i < 3; i++)
    {
        reactive_tree.tickOnce();
        standard_tree.tickOnce();
    }

    // ReactiveSequence: 조건이 매 Tick마다 재평가됨
    EXPECT_EQ(reactive_cond->tickCount(), 3);

    // 일반 Sequence: 조건이 한 번만 평가됨 (SUCCESS 후 건너뜀)
    EXPECT_EQ(standard_cond->tickCount(), 1);
}

이 비교 테스트는 Reactive 노드의 재평가 의미론을 가장 명확하게 드러낸다.

5. 테스트 케이스 요약

테스트 범주노드 유형검증 내용
매 Tick 재평가ReactiveSequence조건 노드의 tickCount 증가 확인
조건 실패 시 HaltReactiveSequence조건 FAILURE → 행동 Halt 전파
조건 복원 시 재시작ReactiveSequence조건 복원 → 행동 onStart()부터 재시작
다중 조건 순차 평가ReactiveSequence앞선 조건 FAILURE → 후속 자식 미평가
상위 조건 재평가ReactiveFallback하위 RUNNING 중 상위 조건 매 Tick 평가
우선순위 선점ReactiveFallback상위 조건 SUCCESS → 하위 행동 Halt
하위 복원ReactiveFallback상위 조건 해제 → 하위 행동 재시작
다단계 전환ReactiveFallback3단계 우선순위 간 전환 동작
비교 검증ReactiveSequence vs Sequence재평가 여부의 차이 대조

각 테스트 케이스는 Reactive 노드의 재평가 의미론의 구체적 측면을 격리하여 검증한다. 이들 테스트를 통과하면 Reactive 노드가 매 Tick 재평가, Halt 전파, 우선순위 선점의 세 가지 핵심 동작을 올바르게 구현하고 있음을 보장할 수 있다.