1296.47 ROS2 서비스 요청 생성 액션 노드

1. 서비스 요청 생성의 개념

행동 트리에서 ROS2 서비스를 호출하는 액션 노드를 구현할 때, 서비스 요청(Request) 메시지의 생성은 핵심적인 단계이다. 서비스 요청 생성 액션 노드는 블랙보드로부터 입력 데이터를 수집하고, 이를 서비스 인터페이스가 정의한 요청 메시지 구조에 맞추어 조합하는 역할을 수행한다. 요청 메시지의 정확한 구성은 서비스 서버의 올바른 동작을 보장하는 전제 조건이다.

2. 서비스 요청 메시지의 구조

ROS2 서비스 인터페이스는 .srv 파일을 통하여 정의되며, 요청(Request)과 응답(Response) 두 부분으로 구성된다. 예를 들어, 경로 계산 서비스의 인터페이스는 다음과 같은 형태를 가진다.

# ComputePath.srv
geometry_msgs/PoseStamped start
geometry_msgs/PoseStamped goal
string planner_id
---
nav_msgs/Path path
uint16 error_code

서비스 요청 메시지는 --- 구분자 상위에 정의된 필드들로 구성되며, C++ 코드에서는 ServiceT::Request 타입으로 접근한다.

auto request = std::make_shared<nav2_msgs::srv::ComputePath::Request>();
request->start = start_pose;
request->goal = goal_pose;
request->planner_id = "GridBased";

3. 블랙보드로부터 요청 필드 구성

서비스 요청 생성 액션 노드에서 요청 메시지의 각 필드는 블랙보드의 입력 포트를 통하여 동적으로 설정된다. 이 설계를 통하여 동일한 액션 노드를 다양한 컨텍스트에서 재사용할 수 있다.

class ComputePathRequest : public BT::SyncActionNode
{
public:
    ComputePathRequest(const std::string& name,
                       const BT::NodeConfiguration& config)
        : BT::SyncActionNode(name, config)
    {}

    BT::NodeStatus tick() override
    {
        auto request =
            std::make_shared<nav2_msgs::srv::ComputePath::Request>();

        geometry_msgs::msg::PoseStamped start, goal;
        if (!getInput("start", start) || !getInput("goal", goal)) {
            return BT::NodeStatus::FAILURE;
        }

        request->start = start;
        request->goal = goal;

        std::string planner_id;
        if (getInput("planner_id", planner_id)) {
            request->planner_id = planner_id;
        }

        setOutput("request", *request);
        return BT::NodeStatus::SUCCESS;
    }

    static BT::PortsList providedPorts()
    {
        return {
            BT::InputPort<geometry_msgs::msg::PoseStamped>("start",
                "시작 자세"),
            BT::InputPort<geometry_msgs::msg::PoseStamped>("goal",
                "목표 자세"),
            BT::InputPort<std::string>("planner_id", "GridBased",
                "경로 계획기 식별자"),
            BT::OutputPort<nav2_msgs::srv::ComputePath::Request>(
                "request", "생성된 서비스 요청 메시지")
        };
    }
};

이 패턴에서 요청 메시지는 출력 포트를 통하여 블랙보드에 기록되며, 후속 서비스 호출 액션 노드가 이를 읽어 서비스 서버에 전송한다.

4. 필수 필드와 선택적 필드의 처리

서비스 요청 메시지의 필드는 도메인 요구 사항에 따라 필수 필드와 선택적 필드로 구분된다. 필수 필드가 블랙보드에 존재하지 않는 경우 액션 노드는 FAILURE를 반환하여야 하며, 선택적 필드는 기본값을 적용하여 처리한다.

BT::NodeStatus tick() override
{
    auto request = std::make_shared<ServiceT::Request>();

    // 필수 필드: 값이 없으면 실패
    if (!getInput("target_frame", request->target_frame)) {
        RCLCPP_ERROR(node_->get_logger(),
                     "필수 입력 포트 'target_frame'이 설정되지 않았다.");
        return BT::NodeStatus::FAILURE;
    }

    // 선택적 필드: 기본값 적용
    double timeout;
    if (getInput("timeout", timeout)) {
        request->timeout = rclcpp::Duration::from_seconds(timeout);
    } else {
        request->timeout = rclcpp::Duration::from_seconds(1.0);
    }

    setOutput("request", *request);
    return BT::NodeStatus::SUCCESS;
}

5. 복합 요청 메시지의 구성

서비스 요청 메시지에 중첩된 메시지 타입이 포함되는 경우, 각 하위 메시지를 개별적으로 구성한 후 조합하는 방식으로 처리한다.

BT::NodeStatus tick() override
{
    auto request = std::make_shared<ServiceT::Request>();

    // 헤더 구성
    request->header.stamp = node_->now();
    request->header.frame_id = "map";

    // 자세 구성
    geometry_msgs::msg::Pose pose;
    getInput("position_x", pose.position.x);
    getInput("position_y", pose.position.y);
    getInput("position_z", pose.position.z);

    double yaw;
    getInput("yaw", yaw);
    tf2::Quaternion q;
    q.setRPY(0.0, 0.0, yaw);
    pose.orientation = tf2::toMsg(q);

    request->pose = pose;

    setOutput("request", *request);
    return BT::NodeStatus::SUCCESS;
}

이 예시에서 자세(pose)의 방위(orientation)는 오일러 각(Euler angle) 형태의 yaw 값을 입력받아 쿼터니언(quaternion)으로 변환하여 할당한다. 이러한 변환 과정은 서비스 요청 생성 노드 내부에서 캡슐화되어, 행동 트리의 다른 노드들은 직관적인 yaw 값만을 다루면 된다.

6. 요청 메시지의 유효성 검증

서비스 서버에 잘못된 요청이 전달되는 것을 방지하기 위하여, 요청 메시지 생성 단계에서 기본적인 유효성 검증을 수행하는 것이 바람직하다.

BT::NodeStatus tick() override
{
    auto request = std::make_shared<ServiceT::Request>();

    double velocity;
    getInput("max_velocity", velocity);

    // 물리적 제약 조건 검증
    if (velocity <= 0.0 || velocity > MAX_ALLOWED_VELOCITY) {
        RCLCPP_ERROR(node_->get_logger(),
                     "허용 범위를 초과하는 최대 속도 값: %f", velocity);
        return BT::NodeStatus::FAILURE;
    }

    request->max_velocity = velocity;
    setOutput("request", *request);
    return BT::NodeStatus::SUCCESS;
}

유효성 검증 항목에는 수치 범위 확인, 좌표 프레임 유효성 확인, 문자열 필드의 비공백 확인 등이 포함된다. 이러한 검증을 통하여 서비스 서버 측의 불필요한 오류 처리 부담을 경감시킬 수 있다.

7. 템플릿 기반 범용 요청 생성 노드

서비스 타입에 독립적인 범용 요청 생성 패턴을 구현하기 위하여, 템플릿 기반의 기반 클래스를 설계할 수 있다.

template <class ServiceT>
class ServiceRequestNode : public BT::SyncActionNode
{
public:
    ServiceRequestNode(const std::string& name,
                       const BT::NodeConfiguration& config)
        : BT::SyncActionNode(name, config)
    {}

    BT::NodeStatus tick() override
    {
        auto request = std::make_shared<typename ServiceT::Request>();
        if (!populateRequest(request)) {
            return BT::NodeStatus::FAILURE;
        }
        setOutput("request", *request);
        return BT::NodeStatus::SUCCESS;
    }

protected:
    // 파생 클래스에서 요청 필드를 설정
    virtual bool populateRequest(
        std::shared_ptr<typename ServiceT::Request> request) = 0;
};

파생 클래스는 populateRequest() 메서드만을 재정의하여 서비스 타입별 요청 구성 로직을 구현한다. 이 패턴은 요청 생성의 공통 흐름(메모리 할당, 출력 포트 기록, 성공/실패 반환)을 기반 클래스에 위임하고, 도메인 고유의 필드 설정만을 파생 클래스의 책임으로 분리한다.

8. 요청 생성과 서비스 호출의 분리

요청 생성 액션 노드와 서비스 호출 액션 노드를 분리하는 설계는 단일 책임 원칙에 부합하며, 다음과 같은 이점을 제공한다.

첫째, 동일한 요청 생성 노드를 다양한 서비스 호출 전략(동기, 비동기, 재시도 포함 등)과 조합할 수 있다.

둘째, 요청 생성 로직만을 독립적으로 단위 테스트할 수 있다.

셋째, XML 행동 트리에서 요청 생성과 서비스 호출을 명시적으로 분리하여 트리의 가독성을 향상시킨다.

<Sequence>
    <ComputePathRequest start="{current_pose}"
                        goal="{target_pose}"
                        planner_id="GridBased"
                        request="{path_request}"/>
    <CallService service_name="compute_path"
                 request="{path_request}"
                 response="{path_response}"/>
</Sequence>

이 구조에서 ComputePathRequest 노드가 요청 메시지를 블랙보드의 {path_request} 키에 기록하면, 후속 CallService 노드가 이를 읽어 서비스 서버에 전송한다.

9. 참고 문헌

  • Macenski, S., Foote, T., Gerkey, B., Lalancette, C., & Woodall, W. (2022). “Robot Operating System 2: Design, Architecture, and Uses in the Wild.” Science Robotics, 7(66), eabm6074.
  • Colledanchise, M., & Ogren, P. (2018). Behavior Trees in Robotics and AI: An Introduction. CRC Press.
  • ROS 2 Documentation. Creating Custom ROS 2 Interfaces. Open Robotics. https://docs.ros.org/en/rolling/Tutorials/Beginner-Client-Libraries/Custom-ROS2-Interfaces.html
  • Faconti, D., & Colledanchise, M. (2022). BehaviorTree.CPP Documentation. https://www.behaviortree.dev/

본 문서는 ROS 2 Humble Hawksbill 및 BehaviorTree.CPP v4.x 기준으로 작성되었다.