1293.65 Tick 내 블랙보드 읽기/쓰기 순서
1. 읽기/쓰기 순서의 결정 요인
단일 Tick 내에서 블랙보드의 읽기/쓰기 순서는 Tick 전파 순서에 의해 결정론적으로 결정된다. 행동 트리의 Tick은 깊이 우선, 왼쪽에서 오른쪽 순서로 전파되므로, 트리 구조에서 왼쪽에 위치한 노드가 오른쪽 노드보다 먼저 블랙보드에 접근한다. 이 순서는 노드 간 데이터 의존성을 충족시키기 위한 기본적 메커니즘이다(Colledanchise & Ogren, 2018).
2. 순서 보장의 원리
단일 스레드 Tick 실행 모델에서 노드의 tick() 메서드는 순차적으로 호출된다. 노드 A의 tick()이 완료된 후에 노드 B의 tick()이 호출되므로, 노드 A의 setOutput() 결과는 노드 B의 getInput()에서 반드시 가시적이다.
\text{Node}_A.\text{setOutput}(k, v) \prec \text{Node}_B.\text{getInput}(k) \quad \Rightarrow \quad \text{Node}_B \text{는 } v \text{를 읽음}
여기서 \prec는 실행 순서에서의 선행 관계를 나타낸다.
3. Sequence에서의 읽기/쓰기 순서
Sequence의 자식 노드들은 왼쪽에서 오른쪽으로 순차적으로 Tick된다. 이 순서에 의해 파이프라인 형태의 데이터 흐름이 자연스럽게 형성된다.
<Sequence>
<GetRobotPose output="{pose}"/> <!-- 1. 쓰기: pose -->
<ComputeDistance input="{pose}"
output="{distance}"/> <!-- 2. 읽기: pose, 쓰기: distance -->
<IsCloseEnough input="{distance}"/> <!-- 3. 읽기: distance -->
</Sequence>
Tick 실행 순서:
1. GetRobotPose.tick()
└─ setOutput("pose", current_pose) 블랙보드["pose"] = P1
2. ComputeDistance.tick()
├─ getInput("pose") → P1 블랙보드["pose"] 읽기
└─ setOutput("distance", 3.5) 블랙보드["distance"] = 3.5
3. IsCloseEnough.tick()
└─ getInput("distance") → 3.5 블랙보드["distance"] 읽기
4. 동일 키에 대한 복수 쓰기
단일 Tick 내에서 복수의 노드가 동일한 블랙보드 키에 쓰기를 수행하면, 최후에 실행된 노드의 값이 최종 값이 된다.
<Sequence>
<SetValue key="{target}" value="A"/> <!-- 쓰기: target = "A" -->
<SetValue key="{target}" value="B"/> <!-- 쓰기: target = "B" (덮어쓰기) -->
<UseTarget input="{target}"/> <!-- 읽기: target → "B" -->
</Sequence>
이 경우 UseTarget은 “B“를 읽는다. 의도하지 않은 덮어쓰기를 방지하기 위해 동일 키에 대한 복수 쓰기는 설계 시 주의가 필요하다.
5. Fallback에서의 조건부 쓰기
Fallback에서는 조기 종료에 의해 일부 자식만 Tick되므로, 블랙보드 쓰기가 조건부로 발생한다.
<Fallback>
<Sequence>
<UseGPS output="{position}"/> <!-- GPS 성공 시 position 기록 -->
<ForceSuccess/>
</Sequence>
<Sequence>
<UseVisualOdom output="{position}"/> <!-- GPS 실패 시 position 기록 -->
<ForceSuccess/>
</Sequence>
</Fallback>
GPS가 성공하면 첫 번째 자식이 SUCCESS를 반환하여 Fallback이 조기 종료되고, position에는 GPS 값이 기록된다. GPS가 실패하면 두 번째 자식이 실행되어 시각 주행 거리 측정 값이 기록된다. 어느 경로를 통과하든 position 키에는 유효한 값이 기록된다.
6. ReactiveSequence에서의 재평가와 읽기 순서
ReactiveSequence에서 조건 노드가 매 Tick마다 재평가될 때, 조건 노드와 액션 노드의 블랙보드 접근 순서가 중요하다.
<ReactiveSequence>
<IsBatteryAbove threshold="20"
battery="{battery_level}"/> <!-- 1. 읽기 -->
<NavigateAction target="{goal}"
result="{nav_status}"/> <!-- 2. 읽기/쓰기 -->
</ReactiveSequence>
매 Tick에서 IsBatteryAbove가 먼저 battery_level을 읽고, 이후 NavigateAction의 onRunning()이 실행된다. 조건 노드가 항상 액션 노드보다 먼저 실행되므로, 조건 판정이 액션의 부수 효과에 의해 영향받지 않는다.
7. 읽기 전 쓰기 보장 (Write-Before-Read)
데이터 의존성이 있는 노드 쌍에서, 데이터를 생산하는 노드가 소비하는 노드보다 먼저 Tick되도록 트리를 구성해야 한다. 이를 읽기 전 쓰기 보장(write-before-read guarantee)이라 한다.
7.1 보장되는 경우
Sequence [A, B]: A가 쓰고 B가 읽음 → 보장됨
SubTree 내부 Sequence: 내부 순서 보장됨
7.2 보장되지 않는 경우
Parallel [A, B]: A와 B의 실행 순서가 논리적으로 독립
(구현상 순차적이나 의미적으로 동시)
서로 다른 Fallback 분기의 노드: 동일 Tick에서 실행 안 됨
8. 읽기/쓰기 순서 위반의 증상
읽기/쓰기 순서가 위반되면 다음과 같은 증상이 발생한다.
| 증상 | 원인 | 해결 방법 |
|---|---|---|
| 노드가 이전 Tick의 값을 읽음 | 쓰기 노드가 읽기 노드 뒤에 위치 | 노드 순서 재배치 |
| 초기 Tick에서 빈 값 읽기 | 최초 쓰기 전에 읽기 발생 | 기본값 설정 또는 조건 검사 |
| 간헐적 잘못된 값 | 조건 분기에 의한 비결정적 쓰기 경로 | 데이터 흐름 분석 |
9. 데이터 흐름 분석을 통한 순서 검증
트리 설계 시 블랙보드 키별로 쓰기 노드와 읽기 노드를 추출하고, Tick 전파 순서에서 쓰기가 읽기보다 선행하는지 검증해야 한다.
\forall k \in \text{keys}: \quad \text{Writer}(k) \prec \text{Reader}(k) \quad \text{(Tick 전파 순서 기준)}
BehaviorTree.CPP v4의 포트 시스템은 정적 분석을 통해 미연결 포트나 타입 불일치를 검출할 수 있지만, 읽기/쓰기 순서의 검증은 개발자의 설계 책임에 속한다.
10. 설계 원칙
- 생산자를 소비자 왼쪽에 배치: Sequence 내에서 데이터를 생산하는 노드를 왼쪽에, 소비하는 노드를 오른쪽에 배치한다.
- 순환 의존성 회피: 노드 A가 노드 B의 출력을 읽고, 노드 B가 노드 A의 출력을 읽는 순환 의존성은 단일 Tick 내에서 해결할 수 없으므로 설계에서 배제한다.
- 기본값 설정: 블랙보드 키에 초기 기본값을 설정하여, 최초 Tick에서 읽기 노드가 유효한 값을 얻을 수 있도록 한다.
참고 문헌
- 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/