1293.48 비동기 액션 노드의 Halt 처리

1. 비동기 액션 노드와 Halt의 관계

비동기 액션 노드(StatefulActionNode)는 RUNNING 상태를 반환하여 장기 실행 작업의 진행 중임을 표시하는 노드이다. 이 노드는 onStart()에서 외부 시스템에 작업을 위임하고, onRunning()에서 완료 여부만 확인한다. Halt가 호출되면 위임된 외부 작업을 취소하고 내부 상태를 정리하는 onHalted() 메서드가 실행된다. 비동기 액션 노드의 Halt 처리는 행동 트리에서 가장 복잡하고 중요한 중단 처리이다(Colledanchise & Ogren, 2018).

2. StatefulActionNode의 Halt 생명 주기

StatefulActionNode의 생명 주기에서 Halt가 개입하는 지점은 다음과 같다.

[IDLE] → tick() → onStart() → RUNNING
         ↓
[RUNNING] → tick() → onRunning() → RUNNING (계속)
                                  → SUCCESS (완료)
                                  → FAILURE (실패)
         ↓
[RUNNING] → halt() → onHalted() → IDLE (중단)

onHalted()는 노드가 RUNNING 상태일 때 Halt가 호출되는 경우에만 실행된다. BehaviorTree.CPP v4에서 StatefulActionNodehalt() 메서드는 다음과 같이 구현된다(Faconti, 2022).

void StatefulActionNode::halt() {
    if (status() == NodeStatus::RUNNING) {
        onHalted();
    }
    resetStatus();  // IDLE로 리셋
}

3. ROS2 액션 클라이언트의 Halt 처리

로봇공학에서 비동기 액션 노드의 가장 일반적인 구현은 ROS2 액션 클라이언트를 래핑하는 것이다. 이 경우 Halt 처리는 액션 목표의 취소를 포함한다.

class NavigateToGoal : public BT::StatefulActionNode {
public:
    NavigateToGoal(const std::string& name, 
                   const BT::NodeConfig& config,
                   rclcpp::Node::SharedPtr node)
        : BT::StatefulActionNode(name, config), node_(node) {
        action_client_ = rclcpp_action::create_client<NavigateToPose>(
            node_, "navigate_to_pose");
    }

    BT::NodeStatus onStart() override {
        auto goal_msg = NavigateToPose::Goal();
        getInput("goal", goal_msg.pose);
        
        auto send_goal_options = 
            rclcpp_action::Client<NavigateToPose>::SendGoalOptions();
        goal_future_ = action_client_->async_send_goal(
            goal_msg, send_goal_options);
        
        return BT::NodeStatus::RUNNING;
    }

    BT::NodeStatus onRunning() override {
        if (!goal_handle_) {
            // 목표 응답 대기
            if (goal_future_.valid() && 
                goal_future_.wait_for(std::chrono::milliseconds(0)) 
                == std::future_status::ready) {
                goal_handle_ = goal_future_.get();
                if (!goal_handle_) {
                    return BT::NodeStatus::FAILURE;
                }
            }
            return BT::NodeStatus::RUNNING;
        }
        
        auto status = goal_handle_->get_status();
        if (status == action_msgs::msg::GoalStatus::STATUS_SUCCEEDED) {
            return BT::NodeStatus::SUCCESS;
        }
        if (status == action_msgs::msg::GoalStatus::STATUS_ABORTED ||
            status == action_msgs::msg::GoalStatus::STATUS_CANCELED) {
            return BT::NodeStatus::FAILURE;
        }
        return BT::NodeStatus::RUNNING;
    }

    void onHalted() override {
        if (goal_handle_) {
            action_client_->async_cancel_goal(goal_handle_);
        }
        goal_handle_.reset();
    }

private:
    rclcpp::Node::SharedPtr node_;
    rclcpp_action::Client<NavigateToPose>::SharedPtr action_client_;
    std::shared_future<rclcpp_action::ClientGoalHandle<NavigateToPose>::SharedPtr> 
        goal_future_;
    rclcpp_action::ClientGoalHandle<NavigateToPose>::SharedPtr goal_handle_;
};

4. Halt 처리의 비동기성

onHalted() 내에서 수행하는 외부 작업 취소는 비동기적이어야 한다. 취소 요청을 전송한 후 취소 완료를 동기적으로 대기하면, 액션 서버의 응답 시간만큼 Tick 실행이 차단된다.

// 부적절: 동기적 취소 대기
void onHalted() override {
    auto cancel_result = action_client_->cancel_goal(goal_handle_);
    // 액션 서버의 취소 응답을 대기 → Tick 차단
}

// 적절: 비동기 취소 요청
void onHalted() override {
    action_client_->async_cancel_goal(goal_handle_);
    // 취소 요청만 전송, 즉시 반환
    goal_handle_.reset();
}

비동기 취소 후 액션 서버가 실제로 작업을 중단하기까지 약간의 지연이 발생할 수 있다. 이 지연 동안 물리적 작업(이동, 회전 등)이 잠시 계속될 수 있으나, 이는 하위 제어 시스템의 응답 특성에 의한 것이며 행동 트리 수준에서는 취소 요청 전송으로 충분하다.

5. 스레드 기반 비동기 노드의 Halt 처리

BT::ThreadedAction을 사용하여 별도 스레드에서 동기적 작업을 실행하는 경우, Halt 처리 시 해당 스레드의 실행을 안전하게 중단해야 한다.

class HeavyComputation : public BT::ThreadedAction {
public:
    BT::NodeStatus tick() override {
        // 별도 스레드에서 실행됨
        for (int i = 0; i < 1000; i++) {
            if (isHaltRequested()) {
                return BT::NodeStatus::FAILURE;
            }
            performStep(i);
        }
        return BT::NodeStatus::SUCCESS;
    }

    void halt() override {
        // halt_requested_ 플래그 설정
        BT::ThreadedAction::halt();
        // 스레드 완료 대기
    }
};

isHaltRequested() 메서드는 Halt가 요청되었는지를 확인하는 원자적 플래그이다. 별도 스레드에서 실행 중인 작업은 주기적으로 이 플래그를 확인하여, Halt가 요청된 경우 루프를 탈출하고 반환한다.

6. 다양한 외부 작업의 Halt 처리 패턴

외부 작업Halt 처리 방법
ROS2 액션 목표async_cancel_goal() 호출
ROS2 서비스 호출결과 Future 포기 (취소 불가)
타이머 기반 대기타이머 취소
파일 I/O파일 핸들 닫기
네트워크 요청연결 취소 또는 포기
스레드 작업Halt 플래그 설정 + 스레드 조인
하드웨어 명령정지 명령 전송

7. Halt 처리 실패 시의 영향

onHalted()에서 외부 작업 취소가 실패하면, 해당 작업이 행동 트리의 제어 밖에서 계속 실행된다. 이는 다음과 같은 문제를 유발할 수 있다.

  1. 자원 누수: 취소되지 않은 작업이 시스템 자원을 계속 점유한다.
  2. 동작 충돌: 새로 시작된 작업과 취소되지 않은 이전 작업이 동시에 실행되어 물리적 충돌이 발생한다.
  3. 상태 불일치: 행동 트리는 작업이 중단된 것으로 판단하지만, 실제로는 계속 실행된다.

이러한 문제를 방지하기 위해, onHalted() 내의 취소 요청이 실패한 경우 이를 로그에 기록하고, 가능한 경우 대체 취소 방법(예: 직접 모터 정지 명령)을 시도해야 한다.

8. Halt 처리의 구현 체크리스트

비동기 액션 노드의 onHalted() 구현 시 다음 항목을 확인해야 한다.

  1. 외부 시스템에 위임된 모든 작업이 취소 요청을 수신하는가
  2. 내부 상태 변수(목표 핸들, 카운터, 플래그 등)가 초기값으로 리셋되는가
  3. 블로킹 연산 없이 즉시 반환하는가
  4. 예외가 발생하더라도 상위 노드의 Halt 처리를 방해하지 않는가
  5. 중복 호출에 대해 안전한가 (멱등성)
  6. 물리적 작업의 안전한 중단이 보장되는가

참고 문헌

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