1293.70 Tick 내 액션 클라이언트의 상태 확인
1. 액션 클라이언트와 Tick 메커니즘의 관계
ROS2 액션(action)은 장시간 실행되는 목표 지향적 작업을 위한 통신 패턴으로, 목표 전송, 피드백 수신, 결과 수신의 세 단계로 구성된다. 행동 트리에서 액션 클라이언트는 StatefulActionNode를 통해 구현되며, onStart()에서 목표를 전송하고 onRunning()에서 액션의 상태를 확인하여 Tick 메커니즘과 액션 프로토콜을 결합한다(Macenski et al., 2020).
2. 액션 상태 모델
ROS2 액션의 목표는 다음의 상태를 가진다.
UNKNOWN → ACCEPTED → EXECUTING → SUCCEEDED
→ ABORTED
→ CANCELED
→ REJECTED
Tick 내에서 onRunning()은 이 상태를 확인하여 행동 트리의 반환 상태로 변환한다.
| 액션 목표 상태 | 행동 트리 반환 상태 | 의미 |
|---|---|---|
| ACCEPTED | RUNNING | 목표 수락, 실행 대기 |
| EXECUTING | RUNNING | 작업 진행 중 |
| SUCCEEDED | SUCCESS | 작업 성공 완료 |
| ABORTED | FAILURE | 작업 중단 (서버 오류) |
| CANCELED | FAILURE | 작업 취소 완료 |
| REJECTED | FAILURE | 목표 거부 |
| UNKNOWN | FAILURE | 상태 불명 |
3. 상태 확인의 구현 패턴
3.1 결과 콜백 기반 확인
액션 클라이언트의 결과 콜백(result callback)을 통해 최종 상태를 수신하고, onRunning()에서 이를 확인하는 패턴이다.
class NavigateAction : public BT::StatefulActionNode {
public:
BT::NodeStatus onStart() override {
auto goal = NavigateToPose::Goal();
getInput("goal_pose", goal.pose);
auto options = rclcpp_action::Client<NavigateToPose>::SendGoalOptions();
options.result_callback =
[this](const%20auto&%20wrapped_result) {
result_code_ = wrapped_result.code;
result_received_.store(true, std::memory_order_release);
};
options.feedback_callback =
[this](auto,%20const%20auto&%20feedback) {
distance_remaining_.store(
feedback->distance_remaining,
std::memory_order_release);
};
auto future = action_client_->async_send_goal(goal, options);
result_received_.store(false, std::memory_order_release);
return BT::NodeStatus::RUNNING;
}
BT::NodeStatus onRunning() override {
if (result_received_.load(std::memory_order_acquire)) {
switch (result_code_) {
case rclcpp_action::ResultCode::SUCCEEDED:
return BT::NodeStatus::SUCCESS;
case rclcpp_action::ResultCode::ABORTED:
case rclcpp_action::ResultCode::CANCELED:
default:
return BT::NodeStatus::FAILURE;
}
}
// 피드백 정보를 블랙보드에 기록
setOutput("distance_remaining",
distance_remaining_.load(std::memory_order_acquire));
return BT::NodeStatus::RUNNING;
}
void onHalted() override {
if (goal_handle_) {
action_client_->async_cancel_goal(goal_handle_);
}
}
private:
std::atomic<bool> result_received_{false};
rclcpp_action::ResultCode result_code_;
std::atomic<double> distance_remaining_{0.0};
rclcpp_action::ClientGoalHandle<NavigateToPose>::SharedPtr goal_handle_;
};
3.2 목표 핸들 상태 직접 확인
목표 핸들(goal handle)의 상태를 직접 조회하여 진행 상황을 확인하는 패턴이다.
BT::NodeStatus onRunning() override {
if (!goal_handle_) {
return BT::NodeStatus::FAILURE;
}
auto status = goal_handle_->get_status();
switch (status) {
case action_msgs::msg::GoalStatus::STATUS_SUCCEEDED:
return BT::NodeStatus::SUCCESS;
case action_msgs::msg::GoalStatus::STATUS_ABORTED:
case action_msgs::msg::GoalStatus::STATUS_CANCELED:
return BT::NodeStatus::FAILURE;
case action_msgs::msg::GoalStatus::STATUS_ACCEPTED:
case action_msgs::msg::GoalStatus::STATUS_EXECUTING:
return BT::NodeStatus::RUNNING;
default:
return BT::NodeStatus::FAILURE;
}
}
4. 목표 전송과 수락 확인
onStart()에서 목표를 전송한 후, 서버의 수락 여부를 확인해야 한다. 비동기 목표 전송은 SharedFuture를 반환하며, 이 future의 완료 시 목표 핸들을 획득한다.
BT::NodeStatus onStart() override {
auto goal = NavigateToPose::Goal();
getInput("goal_pose", goal.pose);
goal_handle_future_ = action_client_->async_send_goal(goal, options);
goal_handle_ = nullptr;
return BT::NodeStatus::RUNNING;
}
BT::NodeStatus onRunning() override {
// 목표 핸들 미획득 시: 수락 대기
if (!goal_handle_) {
if (goal_handle_future_.wait_for(std::chrono::milliseconds(0))
== std::future_status::ready) {
goal_handle_ = goal_handle_future_.get();
if (!goal_handle_) {
return BT::NodeStatus::FAILURE; // 목표 거부
}
} else {
return BT::NodeStatus::RUNNING; // 수락 대기 중
}
}
// 목표 핸들 획득 후: 결과 대기
if (result_received_.load(std::memory_order_acquire)) {
return mapResultCode(result_code_);
}
return BT::NodeStatus::RUNNING;
}
5. 피드백 처리와 블랙보드 연동
액션 피드백은 작업 진행 상황을 나타내며, 콜백을 통해 수신된다. 수신된 피드백 정보를 블랙보드에 기록하면 트리 내의 다른 노드에서 활용할 수 있다.
Tick N:
onRunning() → result 미수신 → 피드백: distance=5.2m → 블랙보드 기록 → RUNNING
Tick N+1:
조건 노드: getInput("distance_remaining") → 5.2m → 조건 평가
onRunning() → result 미수신 → 피드백: distance=3.8m → 블랙보드 기록 → RUNNING
6. 상태 확인의 Tick 실행 시간 영향
onRunning()에서의 상태 확인은 원자적 변수 읽기 또는 목표 핸들 상태 조회로 구현되며, 이는 나노초에서 마이크로초 수준의 비용을 가진다.
T_{onRunning} = T_{status\_check} + T_{feedback\_write} \approx \text{μs}
이 비용은 Tick 예산의 극히 일부이므로, 복수의 액션 노드가 동시에 RUNNING 상태를 유지하더라도 Tick 실행 시간에 유의미한 영향을 미치지 않는다.
7. Halt 시 액션 취소
onHalted()에서는 진행 중인 액션의 목표를 취소해야 한다. 취소 요청은 비동기로 전송되며, 서버의 취소 확인을 대기하지 않는다.
void onHalted() override {
if (goal_handle_) {
auto cancel_future = action_client_->async_cancel_goal(goal_handle_);
// 취소 확인을 대기하지 않음: Halt의 즉시 반환 보장
}
goal_handle_ = nullptr;
}
참고 문헌
- 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/
- Macenski, S., et al. (2020). The Marathon 2: A Navigation System. arXiv preprint arXiv:2003.00368.