1294.91 자식 노드 반환 조합에 따른 테스트 케이스

1294.91 자식 노드 반환 조합에 따른 테스트 케이스

1. 자식 반환 상태 조합의 체계적 열거

Sequence와 Fallback 제어 노드의 동작을 완전히 검증하기 위해서는 자식 노드가 반환할 수 있는 모든 상태 조합을 체계적으로 열거해야 한다. BehaviorTree.CPP v4에서 노드가 반환할 수 있는 상태는 SUCCESS(S), FAILURE(F), RUNNING(R), SKIPPED(K)의 네 가지이다. 자식이 N개인 제어 노드의 경우, 이론적으로 4^N개의 조합이 존재하지만, 제어 노드의 조기 종료(short-circuit) 특성에 의해 실제로 도달 가능한 조합은 이보다 적다(Colledanchise & Ogren, 2018).

2. 자식 Sequence의 완전한 테스트 케이스

2.1 도달 가능한 상태 조합

자식 2개인 SequenceNode에서 도달 가능한 반환 조합은 다음과 같다:

케이스Child1Child2Sequence 결과근거
S-1SSSUCCESS모든 자식 성공
S-2SFFAILURE두 번째 자식 실패
S-3SRRUNNING두 번째 자식 진행 중
S-4SKSUCCESS*두 번째 자식 건너뜀
S-5F-FAILURE첫 번째 자식 실패, 조기 종료
S-6R-RUNNING첫 번째 자식 진행 중, 조기 종료
S-7KSSUCCESS*첫 번째 건너뜀, 두 번째 성공
S-8KFFAILURE첫 번째 건너뜀, 두 번째 실패
S-9KRRUNNING첫 번째 건너뜀, 두 번째 진행 중
S-10KKSKIPPED모든 자식 건너뜀

*SKIPPED 자식이 포함된 경우의 최종 반환 상태는 all_skipped_ 플래그에 의해 결정된다.

Child1이 F 또는 R을 반환하면 Sequence가 즉시 종료하므로 Child2는 실행되지 않는다. 따라서 (F, S), (F, F), (R, S) 등의 조합은 도달 불가능하다.

2.2 테스트 구현

// S-1: 모든 자식 SUCCESS
TEST(Sequence2Children, AllSuccess) {
    child1->setReturn(S);
    child2->setReturn(S);
    EXPECT_EQ(seq.executeTick(), S);
    EXPECT_EQ(child1->tickCount(), 1);
    EXPECT_EQ(child2->tickCount(), 1);
}

// S-5: 첫 번째 자식 FAILURE (조기 종료)
TEST(Sequence2Children, FirstFailure) {
    child1->setReturn(F);
    EXPECT_EQ(seq.executeTick(), F);
    EXPECT_EQ(child1->tickCount(), 1);
    EXPECT_EQ(child2->tickCount(), 0);  // 실행되지 않음
}

// S-6: 첫 번째 자식 RUNNING (조기 종료)
TEST(Sequence2Children, FirstRunning) {
    child1->setReturn(R);
    EXPECT_EQ(seq.executeTick(), R);
    EXPECT_EQ(child2->tickCount(), 0);  // 실행되지 않음
}

3. 자식 Fallback의 완전한 테스트 케이스

3.1 도달 가능한 상태 조합

케이스Child1Child2Fallback 결과근거
F-1S-SUCCESS첫 번째 자식 성공, 조기 종료
F-2FSSUCCESS첫 번째 실패, 두 번째 성공
F-3FFFAILURE모든 자식 실패
F-4FRRUNNING두 번째 자식 진행 중
F-5FKFAILURE*첫 번째 실패, 두 번째 건너뜀
F-6R-RUNNING첫 번째 자식 진행 중, 조기 종료
F-7KSSUCCESS첫 번째 건너뜀, 두 번째 성공
F-8KFFAILURE첫 번째 건너뜀, 두 번째 실패
F-9KRRUNNING첫 번째 건너뜀, 두 번째 진행 중
F-10KKSKIPPED모든 자식 건너뜀

Sequence와의 대칭성이 명확하다. Child1이 S 또는 R을 반환하면 Fallback이 즉시 종료하므로 Child2는 실행되지 않는다.

4. 자식 제어 노드의 테스트 케이스 도출

4.1 자식 Sequence의 핵심 케이스

자식 3개인 Sequence에서는 조기 종료의 위치에 따라 테스트 케이스를 분류한다:

[모든 자식 실행]
S,S,S → SUCCESS    (정상 완료)
S,S,F → FAILURE    (마지막에서 실패)
S,S,R → RUNNING    (마지막에서 진행 중)

[두 번째에서 조기 종료]
S,F,- → FAILURE    (중간에서 실패)
S,R,- → RUNNING    (중간에서 진행 중)

[첫 번째에서 조기 종료]
F,-,- → FAILURE    (시작에서 실패)
R,-,- → RUNNING    (시작에서 진행 중)

4.2 위치별 FAILURE 테스트

// 첫 번째 위치 FAILURE
TEST(Sequence3Children, FailAtPosition0) {
    child1->setReturn(F);
    EXPECT_EQ(seq.executeTick(), F);
    EXPECT_EQ(child1->tickCount(), 1);
    EXPECT_EQ(child2->tickCount(), 0);
    EXPECT_EQ(child3->tickCount(), 0);
}

// 두 번째 위치 FAILURE
TEST(Sequence3Children, FailAtPosition1) {
    child1->setReturn(S);
    child2->setReturn(F);
    EXPECT_EQ(seq.executeTick(), F);
    EXPECT_EQ(child1->tickCount(), 1);
    EXPECT_EQ(child2->tickCount(), 1);
    EXPECT_EQ(child3->tickCount(), 0);
}

// 세 번째 위치 FAILURE
TEST(Sequence3Children, FailAtPosition2) {
    child1->setReturn(S);
    child2->setReturn(S);
    child3->setReturn(F);
    EXPECT_EQ(seq.executeTick(), F);
    EXPECT_EQ(child1->tickCount(), 1);
    EXPECT_EQ(child2->tickCount(), 1);
    EXPECT_EQ(child3->tickCount(), 1);
}

각 위치에서의 FAILURE가 후속 자식의 실행을 정확히 차단하는지 검증한다.

5. 다중 Tick 조합 테스트

5.1 RUNNING 상태 전이 시나리오

RUNNING을 반환하는 자식이 후속 Tick에서 다른 상태로 전이하는 경우를 검증한다.

// RUNNING → SUCCESS 전이
TEST(Sequence3Children, RunningThenSuccess) {
    // Tick 1: child1 S, child2 R
    child1->setReturn(S);
    child2->setReturn(R);
    EXPECT_EQ(seq.executeTick(), R);
    
    // Tick 2: child2 S, child3 S
    child2->setReturn(S);
    child3->setReturn(S);
    EXPECT_EQ(seq.executeTick(), S);
}

// RUNNING → FAILURE 전이
TEST(Sequence3Children, RunningThenFailure) {
    // Tick 1: child1 S, child2 R
    child1->setReturn(S);
    child2->setReturn(R);
    EXPECT_EQ(seq.executeTick(), R);
    
    // Tick 2: child2 F
    child2->setReturn(F);
    EXPECT_EQ(seq.executeTick(), F);
}

5.2 다중 RUNNING 단계 시나리오

// 순차적 RUNNING 진행
TEST(Sequence3Children, SequentialRunning) {
    // Tick 1: child1 R
    child1->setReturn(R);
    EXPECT_EQ(seq.executeTick(), R);
    
    // Tick 2: child1 S, child2 R
    child1->setReturn(S);
    child2->setReturn(R);
    EXPECT_EQ(seq.executeTick(), R);
    
    // Tick 3: child2 S, child3 R
    child2->setReturn(S);
    child3->setReturn(R);
    EXPECT_EQ(seq.executeTick(), R);
    
    // Tick 4: child3 S
    child3->setReturn(S);
    EXPECT_EQ(seq.executeTick(), S);
}

6. Reactive 변형의 조합 테스트

6.1 ReactiveSequence의 상태 변경 감지

ReactiveSequence에서는 이전에 SUCCESS를 반환한 자식이 후속 Tick에서 다른 상태로 변경되는 경우를 검증해야 한다.

// 조건 변경에 의한 FAILURE 전파
TEST(ReactiveSequence, ConditionChangesToFailure) {
    // Tick 1: child1 S, child2 R
    child1->setReturn(S);
    child2->setReturn(R);
    EXPECT_EQ(rseq.executeTick(), R);
    
    // Tick 2: child1이 F로 변경
    child1->setReturn(F);
    EXPECT_EQ(rseq.executeTick(), F);
    
    // child2가 Halt되었는지 검증
    EXPECT_EQ(asyncChild2->haltCount(), 1);
}

6.2 ReactiveFallback의 우선순위 전환

// 하위 대안에서 상위 대안으로 전환
TEST(ReactiveFallback, HigherPriorityPreemption) {
    // Tick 1: child1 F, child2 R
    child1->setReturn(F);
    child2->setReturn(R);
    EXPECT_EQ(rfb.executeTick(), R);
    
    // Tick 2: child1이 S로 변경 → 즉시 SUCCESS
    child1->setReturn(S);
    EXPECT_EQ(rfb.executeTick(), S);
    
    // child2가 Halt되었는지 검증
    EXPECT_EQ(asyncChild2->haltCount(), 1);
}

7. SKIPPED 상태의 조합 테스트

7.1 SKIPPED와 다른 상태의 혼합

// Sequence: SKIPPED 후 SUCCESS
TEST(SequenceSkipped, SkippedThenSuccess) {
    child1->setReturn(K);
    child2->setReturn(S);
    auto result = seq.executeTick();
    EXPECT_EQ(result, S);  // all_skipped_가 false이므로 SUCCESS
}

// Sequence: 모든 자식 SKIPPED
TEST(SequenceSkipped, AllSkipped) {
    child1->setReturn(K);
    child2->setReturn(K);
    child3->setReturn(K);
    auto result = seq.executeTick();
    EXPECT_EQ(result, K);  // all_skipped_가 true이므로 SKIPPED
}

// Fallback: FAILURE와 SKIPPED 혼합
TEST(FallbackSkipped, FailureThenSkipped) {
    child1->setReturn(F);
    child2->setReturn(K);
    child3->setReturn(F);
    auto result = fb.executeTick();
    EXPECT_EQ(result, F);  // all_skipped_가 false이므로 FAILURE
}

SKIPPED 상태의 처리는 all_skipped_ 플래그의 정확한 갱신에 의존하므로, SKIPPED와 다른 상태가 혼합된 모든 패턴을 검증해야 한다.

8. 테스트 케이스 축소 기법

8.1 등가 분할(Equivalence Partitioning)

자식 수가 증가하면 조합 수가 지수적으로 증가하므로, 등가 분할 기법을 적용하여 테스트 케이스를 축소한다:

  1. 조기 종료 위치 분할: FAILURE 또는 SUCCESS가 발생하는 위치(첫 번째, 중간, 마지막)별로 대표 케이스를 선정한다.

  2. RUNNING 위치 분할: RUNNING이 발생하는 위치별로 대표 케이스를 선정한다.

  3. 상태 전이 분할: RUNNING→SUCCESS, RUNNING→FAILURE 전이의 대표 케이스를 선정한다.

8.2 경계 값 분석(Boundary Value Analysis)

인덱스 경계:
  - 첫 번째 자식(index=0)에서의 각 상태
  - 마지막 자식(index=N-1)에서의 각 상태
  - 마지막 직전 자식(index=N-2)에서의 RUNNING→다음 Tick 전이

자식 수 경계:
  - 자식 0개 (오류 상황)
  - 자식 1개 (최소 동작)
  - 자식 2개 (최소 분기)

9. 테스트 결과의 검증 항목

각 테스트 케이스에서 검증해야 하는 항목은 다음과 같다:

  1. 제어 노드의 반환 상태: 예상된 SUCCESS, FAILURE, RUNNING, SKIPPED 중 하나와 일치하는가.
  2. 자식 실행 횟수: 각 자식의 tick() 호출 횟수가 예상과 일치하는가. 특히 조기 종료 이후의 자식이 실행되지 않았는가.
  3. 자식 실행 순서: 자식이 XML 정의 순서대로 실행되었는가(Reactive 변형에서 매 Tick 재평가 포함).
  4. Halt 호출 여부: RUNNING 자식이 적절한 시점에 Halt되었는가.
  5. 내부 상태 일관성: 제어 노드의 내부 인덱스와 플래그가 예상된 값을 유지하는가.

참고 문헌

  • 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/