1293.64 Tick과 블랙보드의 상호작용

1. 블랙보드의 역할

블랙보드(Blackboard)는 행동 트리에서 노드 간 데이터를 공유하는 중앙 저장소이다. 각 노드는 Tick 실행 중에 블랙보드에서 데이터를 읽고(입력 포트) 데이터를 기록하여(출력 포트) 다른 노드에 정보를 전달한다. 블랙보드는 키-값(key-value) 구조로 데이터를 관리하며, BehaviorTree.CPP에서는 타입 안전한 포트 시스템을 통해 접근이 제어된다(Faconti, 2022).

2. Tick 실행 중 블랙보드 접근 시점

노드가 블랙보드에 접근하는 시점은 해당 노드의 tick(), onStart(), 또는 onRunning() 메서드가 호출될 때이다. Tick 전파에 의해 노드가 방문되면, 해당 노드는 입력 포트를 통해 블랙보드에서 데이터를 읽고, 연산 후 출력 포트를 통해 결과를 블랙보드에 기록한다.

Tick 전파 중 블랙보드 접근:
  Sequence.tick()
    ├─ Node_A.tick()
    │   ├─ getInput("sensor_data", data)    ← 블랙보드 읽기
    │   ├─ 연산 수행
    │   └─ setOutput("result", value)       ← 블랙보드 쓰기
    └─ Node_B.tick()
        └─ getInput("result", value)        ← Node_A의 출력 읽기

3. 포트 시스템을 통한 접근

BehaviorTree.CPP v4에서 블랙보드 접근은 포트(port) 선언을 통해 구조화된다. 각 노드는 사용할 입력 포트와 출력 포트를 정적으로 선언하며, XML에서 포트와 블랙보드 키를 매핑한다.

class ComputeDistance : public BT::SyncActionNode {
public:
    static BT::PortsList providedPorts() {
        return {
            BT::InputPort<geometry_msgs::msg::Pose>("current_pose"),
            BT::InputPort<geometry_msgs::msg::Pose>("target_pose"),
            BT::OutputPort<double>("distance")
        };
    }

    BT::NodeStatus tick() override {
        geometry_msgs::msg::Pose current, target;
        getInput("current_pose", current);   // 블랙보드 읽기
        getInput("target_pose", target);     // 블랙보드 읽기
        
        double dist = computeEuclidean(current, target);
        setOutput("distance", dist);         // 블랙보드 쓰기
        
        return BT::NodeStatus::SUCCESS;
    }
};

XML에서의 포트 매핑:

<ComputeDistance current_pose="{robot_pose}" 
                 target_pose="{goal_pose}" 
                 distance="{goal_distance}"/>

{robot_pose}, {goal_pose}, {goal_distance}는 블랙보드 키이며, 중괄호 표기는 해당 포트가 블랙보드 키에 바인딩됨을 의미한다.

4. Tick 전파 순서와 블랙보드 데이터 흐름

Tick의 깊이 우선, 왼쪽에서 오른쪽 전파 순서는 블랙보드를 통한 데이터 흐름의 순서를 결정한다. 앞선 노드가 기록한 데이터를 후속 노드가 읽을 수 있으려면, 기록 노드가 읽기 노드보다 먼저 Tick되어야 한다.

<Sequence>
    <!-- 1. 센서 데이터를 블랙보드에 기록 -->
    <UpdateSensorData output="{scan_data}"/>
    
    <!-- 2. 기록된 센서 데이터로 장애물 검출 -->
    <DetectObstacles input="{scan_data}" output="{obstacles}"/>
    
    <!-- 3. 장애물 정보에 기반한 경로 계획 -->
    <PlanPath obstacles="{obstacles}" output="{path}"/>
</Sequence>

이 Sequence에서 세 노드는 왼쪽에서 오른쪽 순서로 Tick되므로, 데이터 흐름이 scan_data → obstacles → path 순서로 자연스럽게 형성된다.

5. 블랙보드 접근의 비용

getInput()setOutput() 호출은 블랙보드 내부의 키 검색과 값 복사를 수반한다. BehaviorTree.CPP v4에서 블랙보드는 std::unordered_map 기반으로 구현되어 있으므로, 평균적으로 O(1) 시간 복잡도로 접근이 가능하다.

T_{getInput} = T_{lookup} + T_{typecheck} + T_{copy}

단순 타입(정수, 실수, 문자열)의 경우 이 비용은 무시할 수 있을 정도로 작다. 그러나 대용량 데이터(점군, 이미지 등)를 블랙보드에 저장하면 복사 비용이 증가하여 Tick 실행 시간에 영향을 미칠 수 있다.

6. 블랙보드와 조건 재평가

ReactiveSequence에서 조건 노드가 매 Tick마다 재평가될 때, 조건 노드는 블랙보드에서 최신 데이터를 읽어 조건을 판정한다. 블랙보드 값이 Tick 간에 변경되면, 조건 재평가의 결과도 변경될 수 있다.

Tick N:
  ReactiveSequence
    ├─ IsBatteryAbove: getInput("battery") → 0.5 → SUCCESS
    └─ NavigateAction: onRunning() → RUNNING

Tick N+1:  (콜백에 의해 battery 값이 0.15로 갱신됨)
  ReactiveSequence
    ├─ IsBatteryAbove: getInput("battery") → 0.15 → FAILURE
    └─ NavigateAction에 Halt

이 패턴에서 블랙보드는 외부 상태 변화를 행동 트리의 의사 결정에 반영하는 매개체로 기능한다.

7. 블랙보드 값 갱신과 콜백의 관계

블랙보드의 값은 두 가지 경로로 갱신된다.

  1. 노드 내부 갱신: Tick 실행 중 노드가 setOutput()을 통해 갱신한다.
  2. 외부 콜백 갱신: ROS2 토픽 콜백 등 외부 이벤트에 의해 갱신된다.
// 콜백에서 블랙보드 갱신 (Tick 외부)
void odomCallback(const nav_msgs::msg::Odometry::SharedPtr msg) {
    blackboard_->set("robot_pose", msg->pose.pose);
}

단일 스레드 실행기 환경에서 콜백은 spinSome() 호출 시 실행되므로, Tick 실행 전에 블랙보드가 갱신되고 Tick 내에서는 갱신된 값이 읽힌다.

8. 블랙보드 미존재 키 처리

노드가 getInput()으로 읽으려는 블랙보드 키가 아직 설정되지 않은 경우, getInput()은 실패를 반환한다. 노드는 이 상황을 적절히 처리해야 한다.

BT::NodeStatus tick() override {
    geometry_msgs::msg::Pose target;
    auto result = getInput("target_pose", target);
    
    if (!result) {
        // 블랙보드에 키가 없거나 타입 불일치
        return BT::NodeStatus::FAILURE;
    }
    
    // 정상 처리
    return navigateTo(target);
}

이는 트리 설계 시 데이터 흐름의 선후 관계를 명확히 하여, 데이터를 기록하는 노드가 읽는 노드보다 반드시 먼저 실행되도록 구성해야 함을 의미한다.

9. 서브트리 간 블랙보드 격리

BehaviorTree.CPP v4에서 서브트리는 독립된 블랙보드를 가지며, 부모 트리의 블랙보드와는 포트 리매핑을 통해 명시적으로 데이터를 교환한다. 이 격리에 의해 서브트리 내의 블랙보드 접근이 부모 트리의 블랙보드에 의도하지 않은 영향을 미치지 않는다(Faconti, 2022).

<SubTree ID="NavigateSubtree" 
         target="{goal_pose}" 
         result="{nav_result}"/>

서브트리의 target 포트가 부모의 goal_pose 키에, result 포트가 부모의 nav_result 키에 매핑된다. 서브트리 내부의 다른 블랙보드 키는 부모에서 접근할 수 없다.


참고 문헌

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