1293.69 Tick 내 서비스 호출과 응답 대기

1. 서비스 호출의 특성

ROS2 서비스는 요청-응답(request-response) 패턴의 동기적 통신 메커니즘이다. 클라이언트가 요청을 전송하면 서버가 처리하고 응답을 반환한다. 서비스 호출은 본질적으로 양방향 통신이며, 응답이 반환될 때까지 호출자가 대기해야 한다. 행동 트리의 Tick 내에서 서비스 호출을 수행하는 경우, 이 대기 시간이 Tick 실행 시간에 직접적 영향을 미친다(Faconti, 2022).

2. 동기 서비스 호출의 위험

Tick 내에서 동기 서비스 호출(call())을 수행하면, 서버의 응답이 반환될 때까지 Tick 스레드가 차단된다.

// 위험: Tick 스레드 차단
BT::NodeStatus tick() override {
    auto request = std::make_shared<std_srvs::srv::SetBool::Request>();
    request->data = true;
    
    auto result = service_client_->call(request);  // 차단 대기
    // ← 서버 응답까지 Tick 전체가 멈춤
    
    return result->success 
        ? BT::NodeStatus::SUCCESS 
        : BT::NodeStatus::FAILURE;
}

동기 호출에 의한 Tick 차단의 영향:

  • Tick 실행 시간이 서비스 응답 시간만큼 증가한다.
  • 다른 노드의 Tick이 지연되어 조건 재평가가 늦어진다.
  • 서버가 응답하지 않으면 Tick이 무한 대기 상태에 진입할 수 있다.

T_{tick} = T_{normal} + T_{service\_response} \quad \text{(동기 호출 시)}

3. 비동기 서비스 호출 패턴

Tick 차단을 방지하기 위해 비동기 서비스 호출(async_send_request())을 사용하고, 후속 Tick에서 응답 수신 여부를 확인하는 패턴이 권장된다.

class ServiceCallNode : public BT::StatefulActionNode {
public:
    BT::NodeStatus onStart() override {
        auto request = std::make_shared<GetMapStatus::Request>();
        
        future_result_ = service_client_->async_send_request(request);
        return BT::NodeStatus::RUNNING;
    }

    BT::NodeStatus onRunning() override {
        if (future_result_.wait_for(std::chrono::milliseconds(0)) 
            == std::future_status::ready) {
            auto response = future_result_.get();
            setOutput("map_status", response->status);
            return response->success
                ? BT::NodeStatus::SUCCESS
                : BT::NodeStatus::FAILURE;
        }
        return BT::NodeStatus::RUNNING;
    }

    void onHalted() override {
        // 비동기 요청 취소 (가능한 경우)
    }

private:
    rclcpp::Client<GetMapStatus>::SharedFuture future_result_;
};

이 패턴에서 onStart()는 요청을 전송하고 즉시 RUNNING을 반환하며, onRunning()은 비차단 방식으로 응답 수신 여부를 확인한다.

4. 경량 서비스의 동기 호출 허용 조건

서비스 응답 시간이 극히 짧은(마이크로초 단위) 경량 서비스의 경우, 동기 호출이 허용될 수 있다. 이 경우에도 타임아웃을 설정하여 무한 대기를 방지해야 한다.

BT::NodeStatus tick() override {
    auto request = std::make_shared<std_srvs::srv::Trigger::Request>();
    
    // 서비스 서버 대기 (짧은 타임아웃)
    if (!service_client_->wait_for_service(std::chrono::milliseconds(10))) {
        return BT::NodeStatus::FAILURE;  // 서버 미가용
    }
    
    auto future = service_client_->async_send_request(request);
    
    // 짧은 타임아웃으로 동기적 대기
    if (future.wait_for(std::chrono::milliseconds(5)) 
        == std::future_status::ready) {
        auto response = future.get();
        return response->success 
            ? BT::NodeStatus::SUCCESS 
            : BT::NodeStatus::FAILURE;
    }
    
    return BT::NodeStatus::FAILURE;  // 타임아웃
}

5. SingleThreadedExecutor에서의 서비스 호출 주의사항

SingleThreadedExecutor에서 서비스 클라이언트와 서비스 서버가 동일한 노드에 등록된 경우, 동기 서비스 호출은 교착 상태를 유발한다. 서비스 요청의 콜백 처리가 동일 스레드에서 수행되어야 하지만, 해당 스레드가 응답을 대기하며 차단되어 있기 때문이다.

교착 상태:
  Tick 스레드: service_client->call() → 응답 대기 (차단)
  서비스 서버: 콜백 대기 (동일 스레드에서 실행되어야 하나, 차단됨)
  → 영구 대기

이 문제를 방지하기 위해 비동기 서비스 호출을 사용하거나, 서비스 서버를 별도의 노드(별도 프로세스)에 배치해야 한다.

6. 서비스 호출 시 오류 처리

서비스 호출에서 발생할 수 있는 오류 상황과 Tick 내 처리 방법을 정리한다.

오류 상황원인Tick 내 처리
서버 미가용서버 노드 미시작 또는 종료FAILURE 반환
응답 타임아웃서버 처리 지연 또는 장애FAILURE 반환 (StatefulAction에서는 RUNNING 유지 후 타임아웃 시 FAILURE)
응답 오류서버가 오류 응답 반환FAILURE 반환
네트워크 장애DDS 통신 단절FAILURE 반환
BT::NodeStatus onStart() override {
    if (!service_client_->service_is_ready()) {
        RCLCPP_WARN(node_->get_logger(), "Service not available");
        return BT::NodeStatus::FAILURE;
    }
    
    auto request = std::make_shared<ServiceType::Request>();
    future_ = service_client_->async_send_request(request);
    start_time_ = std::chrono::steady_clock::now();
    return BT::NodeStatus::RUNNING;
}

BT::NodeStatus onRunning() override {
    auto elapsed = std::chrono::steady_clock::now() - start_time_;
    if (elapsed > std::chrono::seconds(5)) {
        RCLCPP_ERROR(node_->get_logger(), "Service call timeout");
        return BT::NodeStatus::FAILURE;
    }
    
    if (future_.wait_for(std::chrono::milliseconds(0)) 
        == std::future_status::ready) {
        return processResponse(future_.get());
    }
    return BT::NodeStatus::RUNNING;
}

7. 서비스 호출과 Tick 실행 시간의 관계

비동기 서비스 호출 패턴에서 Tick 실행 시간에 대한 영향은 onRunning()의 상태 확인 비용에만 비례한다.

T_{tick\_async} = T_{future\_check} \approx \text{μs} \quad \text{(비동기 패턴)}

T_{tick\_sync} = T_{service\_response} \approx \text{ms} \sim \text{s} \quad \text{(동기 패턴)}

비동기 패턴은 서비스 응답 시간과 무관하게 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/