ROS2 서비스 기반 조건 노드 (ROS2 Service-Based Condition Nodes)

ROS2 서비스 기반 조건 노드 (ROS2 Service-Based Condition Nodes)

1. 개요

ROS2 서비스 기반 조건 노드는 ROS2 서비스(Service)를 호출하여 그 응답 결과를 기반으로 조건을 평가하는 조건 노드이다. 토픽 기반 조건 노드가 지속적으로 발행되는 데이터 스트림을 구독하여 조건을 판정하는 반면, 서비스 기반 조건 노드는 요청-응답(request-response) 패턴을 통해 특정 시점의 상태를 질의한다. 이 방식은 주기적으로 발행되지 않는 정보, 계산이 필요한 질의, 외부 시스템과의 동기적 상호작용이 요구되는 상황에서 활용된다.

2. 서비스와 토픽의 통신 패턴 차이

2.1 통신 모델 비교

특성토픽 (Topic)서비스 (Service)
통신 패턴발행-구독 (Publish-Subscribe)요청-응답 (Request-Response)
시간 특성비동기, 연속적동기적, 일회성
결합도느슨한 결합 (loose coupling)밀접한 결합 (tight coupling)
데이터 흐름단방향 (Publisher → Subscriber)양방향 (Client ↔ Server)
적합한 용도센서 데이터 스트림, 상태 정보상태 질의, 설정 변경, 계산 요청

서비스 기반 조건 노드를 사용하는 주요 동기는, 해당 정보가 토픽으로 발행되지 않거나 요청 시점에 동적으로 계산되어야 하는 경우에 있다.

3. 서비스 기반 조건 노드의 설계 과제

3.1 동기 호출과 빠른 평가 원칙의 충돌

조건 노드의 핵심 원칙 중 하나는 빠른 평가(fast evaluation)이다. tick() 메서드는 가능한 한 짧은 시간 내에 반환되어야 하며, 행동 트리의 전체 tick 주기를 지연시켜서는 안 된다. 그러나 ROS2 서비스의 동기 호출은 서버의 응답을 대기하는 시간이 포함되므로, 이 원칙과 상충할 수 있다.

이 문제를 해결하기 위한 접근 방식은 다음과 같다.

  1. 비동기 서비스 호출과 결과 캐싱: 서비스를 비동기적으로 호출하고, 응답이 도착하면 결과를 캐싱한다. tick() 메서드는 캐싱된 결과를 기반으로 즉시 평가한다.
  2. 타임아웃 설정: 서비스 호출에 타임아웃을 설정하여, 서버가 응답하지 않는 경우 FAILURE를 반환한다.
  3. 주기적 사전 호출: 별도의 타이머로 서비스를 주기적으로 호출하여 결과를 갱신하고, tick() 메서드는 최신 결과만 참조한다.

3.2 Running 미반환 원칙과의 조화

조건 노드는 RUNNING 상태를 반환하지 않는다. 서비스 응답을 기다리는 동안 RUNNING을 반환할 수 없으므로, 응답이 아직 도착하지 않은 경우에는 FAILURE를 반환하거나, 이전에 캐싱된 결과를 사용하여 판정하여야 한다.

4. 비동기 서비스 호출 기반 구현

4.1 기본 구조

다음은 비동기 서비스 호출과 결과 캐싱을 결합한 서비스 기반 조건 노드의 일반적 구현이다.

template <typename ServiceT>
class ServiceConditionNode : public BT::ConditionNode
{
public:
    ServiceConditionNode(const std::string& name,
                         const BT::NodeConfiguration& config,
                         rclcpp::Node::SharedPtr node)
        : BT::ConditionNode(name, config),
          node_(node),
          request_pending_(false),
          response_received_(false)
    {
        std::string service_name;
        getInput("service_name", service_name);

        client_ = node_->create_client<ServiceT>(service_name);
    }

    static BT::PortsList providedPorts()
    {
        return {
            BT::InputPort<std::string>("service_name",
                                       "서비스 이름"),
            BT::InputPort<double>("timeout_sec", 1.0,
                                  "서비스 응답 대기 시간 (초)")
        };
    }

    BT::NodeStatus tick() override
    {
        std::lock_guard<std::mutex> lock(mutex_);

        if (!client_->service_is_ready())
        {
            return BT::NodeStatus::FAILURE;
        }

        if (!request_pending_ && !response_received_)
        {
            sendRequest();
        }

        if (response_received_)
        {
            response_received_ = false;
            request_pending_ = false;
            return evaluateResponse(last_response_);
        }

        // 응답 대기 중: 이전 결과가 있으면 사용, 없으면 FAILURE
        if (has_previous_result_)
        {
            return previous_result_;
        }
        return BT::NodeStatus::FAILURE;
    }

protected:
    virtual typename ServiceT::Request::SharedPtr
    createRequest() = 0;

    virtual BT::NodeStatus evaluateResponse(
        const typename ServiceT::Response::SharedPtr& response) = 0;

private:
    void sendRequest()
    {
        auto request = createRequest();
        request_pending_ = true;

        client_->async_send_request(
            request,
            [this](typename%20rclcpp::Client<ServiceT>::SharedFuture%20future) {
                std::lock_guard<std::mutex> lock(mutex_);
                last_response_ = future.get();
                response_received_ = true;
                request_pending_ = false;
            });
    }

    rclcpp::Node::SharedPtr node_;
    typename rclcpp::Client<ServiceT>::SharedPtr client_;
    typename ServiceT::Response::SharedPtr last_response_;
    std::mutex mutex_;
    bool request_pending_;
    bool response_received_;
    bool has_previous_result_{false};
    BT::NodeStatus previous_result_;
};

이 구현에서 tick() 메서드의 실행 흐름은 다음과 같다.

  1. 서비스 서버가 준비되지 않은 경우 즉시 FAILURE를 반환한다.
  2. 요청이 진행 중이 아니고 응답도 수신되지 않은 경우 비동기 요청을 전송한다.
  3. 응답이 수신된 경우 evaluateResponse() 메서드를 호출하여 결과를 평가한다.
  4. 응답 대기 중인 경우, 이전에 캐싱된 결과가 있으면 이를 반환하고, 없으면 FAILURE를 반환한다.

4.2 구체적 구현 예시: 경로 유효성 확인

nav2_msgs::srv::IsPathValid 서비스를 호출하여 현재 경로의 유효성을 확인하는 조건 노드이다.

class IsPathValid
    : public ServiceConditionNode<nav2_msgs::srv::IsPathValid>
{
public:
    IsPathValid(const std::string& name,
                const BT::NodeConfiguration& config,
                rclcpp::Node::SharedPtr node)
        : ServiceConditionNode(name, config, node)
    {}

    static BT::PortsList providedPorts()
    {
        auto ports = ServiceConditionNode::providedPorts();
        ports.emplace(BT::InputPort<nav_msgs::msg::Path>("path",
                      "검증할 경로"));
        return ports;
    }

protected:
    nav2_msgs::srv::IsPathValid::Request::SharedPtr
    createRequest() override
    {
        auto request =
            std::make_shared<nav2_msgs::srv::IsPathValid::Request>();
        getInput("path", request->path);
        return request;
    }

    BT::NodeStatus evaluateResponse(
        const nav2_msgs::srv::IsPathValid::Response::SharedPtr&
            response) override
    {
        if (response && response->is_valid)
        {
            return BT::NodeStatus::SUCCESS;
        }
        return BT::NodeStatus::FAILURE;
    }
};

5. BehaviorTree.ROS2의 RosServiceNode 활용

BehaviorTree.ROS2 패키지는 RosServiceNode<ServiceT> 기반 클래스를 제공한다. 이 클래스는 서비스 클라이언트 관리, 비동기 호출, 타임아웃 처리 등을 내장하고 있어 개발자가 서비스 기반 노드를 간결하게 구현할 수 있다. 다만, RosServiceNode는 기본적으로 액션 노드의 의미론(RUNNING 반환 가능)을 따르므로, 조건 노드로 활용하려면 추가적인 설계 고려가 필요하다.

조건 노드에서 서비스를 사용하는 대안적 접근으로, 서비스 호출 결과를 블랙보드에 기록하는 별도의 액션 노드를 구현하고, 조건 노드는 블랙보드의 값만을 참조하여 판정하는 패턴이 있다.

<BehaviorTree ID="PathValidation">
    <Sequence>
        <Action ID="CheckPathValidity"
                service_name="/is_path_valid"
                path="{current_path}"
                result="{path_valid}"/>
        <Condition ID="IsBoolTrue"
                   value="{path_valid}"/>
        <Action ID="FollowPath"/>
    </Sequence>
</BehaviorTree>

이 패턴은 서비스 호출의 비동기 특성을 액션 노드가 처리하고, 조건 노드는 순수한 값 비교만 수행하므로 각 노드의 역할이 명확히 분리된다.

6. 동기 서비스 호출 기반 조건 노드

서비스 서버의 응답 시간이 매우 짧아(수 밀리초 이내) tick 주기에 영향을 미치지 않는 경우, 동기적 서비스 호출을 사용하는 것도 허용될 수 있다.

class IsNodeActive : public BT::ConditionNode
{
public:
    IsNodeActive(const std::string& name,
                 const BT::NodeConfiguration& config,
                 rclcpp::Node::SharedPtr node)
        : BT::ConditionNode(name, config), node_(node)
    {
        std::string service_name;
        getInput("service_name", service_name);
        client_ = node_->create_client<lifecycle_msgs::srv::GetState>(
            service_name);
    }

    static BT::PortsList providedPorts()
    {
        return {
            BT::InputPort<std::string>("service_name",
                "생명주기 상태 질의 서비스 이름"),
            BT::InputPort<int>("expected_state", 3,
                "기대 상태 ID (3=active)")
        };
    }

    BT::NodeStatus tick() override
    {
        if (!client_->service_is_ready())
        {
            return BT::NodeStatus::FAILURE;
        }

        auto request =
            std::make_shared<lifecycle_msgs::srv::GetState::Request>();
        auto future = client_->async_send_request(request);

        auto timeout = std::chrono::milliseconds(50);
        if (future.wait_for(timeout) != std::future_status::ready)
        {
            return BT::NodeStatus::FAILURE;
        }

        auto response = future.get();
        int expected_state;
        getInput("expected_state", expected_state);

        if (response->current_state.id ==
            static_cast<uint8_t>(expected_state))
        {
            return BT::NodeStatus::SUCCESS;
        }
        return BT::NodeStatus::FAILURE;
    }

private:
    rclcpp::Node::SharedPtr node_;
    rclcpp::Client<lifecycle_msgs::srv::GetState>::SharedPtr client_;
};

위 구현에서 future.wait_for() 호출에 50밀리초의 타임아웃을 설정하여, 서버 응답 지연으로 인한 tick 차단(blocking)을 방지한다. 타임아웃이 경과하면 FAILURE를 반환하며, 이는 “상태를 확인할 수 없다“는 보수적 판단에 해당한다.

7. XML 행동 트리에서의 활용

<BehaviorTree ID="LifecycleCheck">
    <ReactiveSequence>
        <Condition ID="IsNodeActive"
                   service_name="/map_server/get_state"
                   expected_state="3"/>
        <Action ID="NavigateToGoal"/>
    </ReactiveSequence>
</BehaviorTree>

8. 설계 시 고려 사항

8.1 서비스 호출의 부작용 문제

조건 노드는 부작용 금지 원칙을 준수하여야 한다. 서비스 호출 자체가 서버 측에서 상태를 변경하는 부작용을 초래하는 경우(예: 카운터 증가, 로그 기록), 해당 서비스를 조건 노드에서 호출하는 것은 부적절하다. 조건 노드에서 호출하는 서비스는 읽기 전용(read-only) 질의에 한정하여야 한다.

8.2 서비스 서버 장애 대응

서비스 서버가 비정상 종료하거나 응답하지 않는 경우, 조건 노드는 FAILURE를 반환하여야 한다. client_->service_is_ready() 검사를 통해 서버의 가용성을 사전에 확인하고, 타임아웃 메커니즘을 통해 응답 지연에 대응한다.

8.3 호출 빈도 제어

ReactiveSequence 내부에 서비스 기반 조건 노드를 배치하면 매 tick마다 서비스가 호출될 수 있다. 서비스 호출은 토픽 구독보다 높은 오버헤드를 수반하므로, 캐싱 전략을 적용하여 호출 빈도를 제한하는 것이 바람직하다. 일정 시간 이내에 수신된 응답은 재사용하고, 캐시가 만료된 경우에만 새로운 요청을 전송하는 시간 기반 캐싱이 효과적이다.

8.4 서비스와 토픽의 선택 기준

동일한 정보를 서비스와 토픽 중 어느 것을 통해 얻을지 판단하는 기준은 다음과 같다.

기준토픽 선호서비스 선호
데이터 갱신 빈도높음 (주기적)낮음 (비주기적)
조건 평가 빈도높음 (매 tick)낮음 (간헐적)
응답 시간 요구엄격유연
계산 비용낮음높음 (요청 시 계산)
발행자 존재 여부이미 발행 중발행되지 않음

가능한 한 토픽 기반 조건 노드를 우선적으로 사용하고, 토픽으로 제공되지 않는 정보에 한하여 서비스 기반 조건 노드를 적용하는 것이 행동 트리의 반응성을 유지하는 데 유리하다.

9. 참고 문헌

  • Colledanchise, M., & Ogren, P. (2018). Behavior Trees in Robotics and AI: An Introduction. CRC Press.
  • Macenski, S., et al. (2020). “The Marathon 2: A Navigation System.” arXiv preprint arXiv:2003.00368.
  • BehaviorTree.CPP 공식 문서. https://www.behaviortree.dev/
  • ROS2 공식 문서. https://docs.ros.org/en/humble/

버전날짜변경 사항
v0.12026-04-04초안 작성