ROS2 통신 인터페이스 정리: Topic / Service / Action 장단점, C++ 예제 코드

대상: ROS2(Humble 기준)에서 “언제 Topic을 쓰고, 언제 Service/Action을 써야 하는지”가 헷갈리는 C++ 개발자
환경: Ubuntu 22.04, ROS2 Humble, C++17, rclcpp, rclcpp_action, ament_cmake, colcon


1. 문제/주제 요약

ROS2에는 여러 가지 통신 방법이 있습니다.

  • Topic (Publisher / Subscriber)
  • Service (Client / Server)
  • Action (Action Client / Server)

처음에는 “메시지 = topic만 있나?” 정도로 생각하다가,

  • “이건 요청/응답인데 topic이 맞나?”
  • “로봇 목표 위치를 보낼 때 service? topic? action?”

처럼 헷갈리기 쉽습니다.

이 글에서는:

  1. Topic / Service / Action의 역할, 장단점, 사용 시나리오를 정리하고
  2. 각각의 C++ 예제 코드 패턴을 보여줍니다.

2. 원인/배경 설명

ROS2에서 “메시지 종류”라고 부르는 건 사실 통신 패턴입니다.

  • Topic: 스트리밍 / 이벤트 방송
  • Service: 요청(Request) → 응답(Response), 짧게 끝나는 RPC
  • Action: 긴 시간이 걸리는 작업에 대한 Goal/Feedback/Result 패턴

각각 장단점이 뚜렷해서, 상황에 따라 잘 골라 써야 합니다.

2-1. Topic (토픽)

  • 특징
    • 단방향 스트리밍: Publisher → Subscriber
    • 실시간 센서, 상태 브로드캐스트, 제어 명령 등
    • “누가 듣든 말든” 계속 쏘는 느낌 (broadcast)
  • 장점
    • 설계가 단순, 확장에 강함 (N:1, 1:N, N:N 구조)
    • 주기적인 데이터(센서, 상태)를 표현하기 좋음
  • 단점
    • “요청 → 결과” 구조 표현이 힘듦
    • 메시지 한 개만으로는 “작업이 성공했는지/끝났는지” 표현하기 어려움
    • 보통 “현재 상태”를 표현할 뿐, 과거/완료 여부는 별도로 관리해야 함

2-2. Service (서비스)

  • 특징
    • Request/Response RPC 패턴
    • 클라이언트가 요청하면 서버가 처리 후 한 번만 응답
  • 장점
    • “설정값 변경”, “한 번 짜리 동기 작업”에 적합
      • 예: 파라미터 설정, 캘리브레이션 시작/정지, 한 번 데이터 요청 등
    • 호출 측에서 결과를 바로 받을 수 있음
  • 단점
    • 긴 시간이 걸리는 작업에는 부적합
      • 요청-응답 사이에 시간 초과, 커넥션 끊김 등 이슈
    • 중간 진행 상황(Progress)을 표현하기 어려움

2-3. Action (액션)

  • 특징
    • “Goal → 진행중 Feedback → Result/Cancel” 구조
    • 내부적으로는 여러 토픽 + 서비스 조합처럼 동작하지만,
      개발자는 Action 인터페이스만 알면 됨.
  • 장점
    • “시간이 오래 걸리는 작업 + 중간 진행 상황/취소 필요”에 딱 맞음
      • 예: 내비게이션(goal pose), 긴 모션 시퀀스, 장시간 계산 작업
    • Goal 취소, 결과 기다리기, 실시간 feedback 등 고수준 API 제공
  • 단점
    • Topic/Service보다 설정/코드 구조가 조금 더 복잡
    • .action 정의, rclcpp_action 의존성, 서버/클라이언트 로직 필요

요약하면:

  • 센서 스트림 → Topic
  • 짧은 요청/응답 → Service
  • 오래 걸리는 목표 지향 작업(취소/피드백 필요) → Action

3. C++ 예제 코드 (topic / service / action)

예제 패키지: ros2_comm_examples (Humble 기준)

cd ~/ros2_ws/src
ros2 pkg create \
  --build-type ament_cmake \
  ros2_comm_examples \
  --dependencies rclcpp std_msgs example_interfaces rclcpp_action
  • std_msgs : topic String 예제
  • example_interfaces : 기본 service/action 메시지 사용 (AddTwoInts, Fibonacci 등)
  • rclcpp_action : Action 예제용

아래 예제 코드에서는 핵심 구조 위주로 보여줍니다.
실제 프로젝트에서는 namespace, 에러 처리, 헤더 분리 등을 더 정리해서 쓰면 좋습니다.


3-1. Topic 예제 (Publisher / Subscriber)

3-1-1. Publisher: src/topic_publisher.cpp

#include <chrono>
#include <memory>
#include <string>

#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"

using namespace std::chrono_literals;

class TopicPublisher : public rclcpp::Node
{
public:
  TopicPublisher()
  : Node("topic_publisher"), count_(0)
  {
    // QoS depth 10
    publisher_ = this->create_publisher<std_msgs::msg::String>("chatter", 10);

    timer_ = this->create_wall_timer(
      500ms, std::bind(&TopicPublisher::timer_callback, this));
  }

private:
  void timer_callback()
  {
    auto msg = std_msgs::msg::String();
    msg.data = "Hello from publisher: " + std::to_string(count_++);

    RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", msg.data.c_str());
    publisher_->publish(msg);
  }

  rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher_;
  rclcpp::TimerBase::SharedPtr timer_;
  size_t count_;
};

int main(int argc, char * argv[])
{
  rclcpp::init(argc, argv);
  auto node = std::make_shared<TopicPublisher>();
  rclcpp::spin(node);
  rclcpp::shutdown();
  return 0;
}

3-1-2. Subscriber: src/topic_subscriber.cpp

#include <memory>

#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"

class TopicSubscriber : public rclcpp::Node
{
public:
  TopicSubscriber()
  : Node("topic_subscriber")
  {
    subscription_ = this->create_subscription<std_msgs::msg::String>(
      "chatter",
      10,
      std::bind(&TopicSubscriber::topic_callback, this, std::placeholders::_1));
  }

private:
  void topic_callback(const std_msgs::msg::String::SharedPtr msg) const
  {
    RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg->data.c_str());
  }

  rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscription_;
};

int main(int argc, char * argv[])
{
  rclcpp::init(argc, argv);
  auto node = std::make_shared<TopicSubscriber>();
  rclcpp::spin(node);
  rclcpp::shutdown();
  return 0;
}

3-2. Service 예제 (Server / Client)

여기서는 ROS2 기본 패키지인 example_interfaces/srv/AddTwoInts를 사용합니다.

3-2-1. Service Server: src/add_two_ints_server.cpp

#include <memory>

#include "rclcpp/rclcpp.hpp"
#include "example_interfaces/srv/add_two_ints.hpp"

using AddTwoInts = example_interfaces::srv::AddTwoInts;

class AddTwoIntsServer : public rclcpp::Node
{
public:
  AddTwoIntsServer()
  : Node("add_two_ints_server")
  {
    service_ = this->create_service<AddTwoInts>(
      "add_two_ints",
      std::bind(&AddTwoIntsServer::handle_service, this,
                std::placeholders::_1, std::placeholders::_2));
  }

private:
  void handle_service(
    const std::shared_ptr<AddTwoInts::Request> request,
    std::shared_ptr<AddTwoInts::Response> response)
  {
    response->sum = request->a + request->b;
    RCLCPP_INFO(this->get_logger(), "Incoming request: a=%ld, b=%ld, sum=%ld",
                request->a, request->b, response->sum);
  }

  rclcpp::Service<AddTwoInts>::SharedPtr service_;
};

int main(int argc, char * argv[])
{
  rclcpp::init(argc, argv);
  auto node = std::make_shared<AddTwoIntsServer>();
  rclcpp::spin(node);
  rclcpp::shutdown();
  return 0;
}

3-2-2. Service Client: src/add_two_ints_client.cpp

#include <chrono>
#include <memory>

#include "rclcpp/rclcpp.hpp"
#include "example_interfaces/srv/add_two_ints.hpp"

using namespace std::chrono_literals;
using AddTwoInts = example_interfaces::srv::AddTwoInts;

class AddTwoIntsClient : public rclcpp::Node
{
public:
  AddTwoIntsClient()
  : Node("add_two_ints_client")
  {
    client_ = this->create_client<AddTwoInts>("add_two_ints");

    // 서비스 서버 뜰 때까지 대기
    while (!client_->wait_for_service(1s)) {
      if (!rclcpp::ok()) {
        RCLCPP_ERROR(this->get_logger(), "Interrupted while waiting for service.");
        return;
      }
      RCLCPP_INFO(this->get_logger(), "Service not available, waiting again...");
    }

    auto request = std::make_shared<AddTwoInts::Request>();
    request->a = 40;
    request->b = 2;

    auto future = client_->async_send_request(request);

    // 결과 대기 (간단 예제에서는 spin_until_future_complete 사용)
    if (rclcpp::spin_until_future_complete(
          this->get_node_base_interface(), future) ==
        rclcpp::FutureReturnCode::SUCCESS)
    {
      auto response = future.get();
      RCLCPP_INFO(this->get_logger(), "Result: %ld", response->sum);
    } else {
      RCLCPP_ERROR(this->get_logger(), "Failed to call service add_two_ints");
    }
  }

private:
  rclcpp::Client<AddTwoInts>::SharedPtr client_;
};

int main(int argc, char * argv[])
{
  rclcpp::init(argc, argv);
  auto node = std::make_shared<AddTwoIntsClient>();
  rclcpp::shutdown();
  return 0;
}

포인트

  • Service는 “요청 → 응답 한 번”으로 끝나기 때문에, Client 쪽에서 async_send_request 후 결과를 기다리는 패턴.
  • 이 예제처럼 spin_until_future_complete를 쓰거나, 노드를 계속 스핀하면서 적절한 시점에 future를 폴링하는 방식도 가능.

3-3. Action 예제 (Fibonacci: Action Server / Client)

ROS2 튜토리얼에 자주 나오는 action/Fibonacci 예제를 살짝 단순화해서 보여드립니다.
메시지 타입: example_interfaces/action/Fibonacci 사용.

3-3-1. Action Server: src/fibonacci_action_server.cpp

#include <memory>
#include <thread>

#include "rclcpp/rclcpp.hpp"
#include "rclcpp_action/rclcpp_action.hpp"
#include "example_interfaces/action/fibonacci.hpp"

using Fibonacci = example_interfaces::action::Fibonacci;
using GoalHandleFibonacci = rclcpp_action::ServerGoalHandle<Fibonacci>;

class FibonacciActionServer : public rclcpp::Node
{
public:
  FibonacciActionServer()
  : Node("fibonacci_action_server")
  {
    using namespace std::placeholders;

    action_server_ = rclcpp_action::create_server<Fibonacci>(
      this,
      "fibonacci",
      std::bind(&FibonacciActionServer::handle_goal, this, _1, _2),
      std::bind(&FibonacciActionServer::handle_cancel, this, _1),
      std::bind(&FibonacciActionServer::handle_accepted, this, _1));
  }

private:
  rclcpp_action::Server<Fibonacci>::SharedPtr action_server_;

  rclcpp_action::GoalResponse handle_goal(
    const rclcpp_action::GoalUUID &,
    std::shared_ptr<const Fibonacci::Goal> goal)
  {
    RCLCPP_INFO(this->get_logger(), "Received goal request, order = %d", goal->order);
    // 목표 허용
    return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
  }

  rclcpp_action::CancelResponse handle_cancel(
    const std::shared_ptr<GoalHandleFibonacci> goal_handle)
  {
    RCLCPP_INFO(this->get_logger(), "Received request to cancel goal");
    (void)goal_handle;
    return rclcpp_action::CancelResponse::ACCEPT;
  }

  void handle_accepted(const std::shared_ptr<GoalHandleFibonacci> goal_handle)
  {
    // 별도 스레드에서 실행
    std::thread{std::bind(&FibonacciActionServer::execute, this, std::placeholders::_1),
                goal_handle}.detach();
  }

  void execute(const std::shared_ptr<GoalHandleFibonacci> goal_handle)
  {
    RCLCPP_INFO(this->get_logger(), "Executing goal");

    const auto goal = goal_handle->get_goal();
    auto feedback = std::make_shared<Fibonacci::Feedback>();
    auto & sequence = feedback->partial_sequence;
    sequence.clear();
    sequence.push_back(0);
    sequence.push_back(1);

    auto result = std::make_shared<Fibonacci::Result>();

    rclcpp::Rate loop_rate(1);
    for (int i = 2; i < goal->order; ++i) {
      if (goal_handle->is_canceling()) {
        result->sequence = sequence;
        goal_handle->canceled(result);
        RCLCPP_INFO(this->get_logger(), "Goal canceled");
        return;
      }

      sequence.push_back(sequence[i - 1] + sequence[i - 2]);
      goal_handle->publish_feedback(feedback);
      RCLCPP_INFO(this->get_logger(), "Publish feedback, sequence size: %zu", sequence.size());
      loop_rate.sleep();
    }

    if (rclcpp::ok()) {
      result->sequence = sequence;
      goal_handle->succeed(result);
      RCLCPP_INFO(this->get_logger(), "Goal succeeded");
    }
  }
};

int main(int argc, char * argv[])
{
  rclcpp::init(argc, argv);
  auto node = std::make_shared<FibonacciActionServer>();
  rclcpp::spin(node);
  rclcpp::shutdown();
  return 0;
}

3-3-2. Action Client: src/fibonacci_action_client.cpp

#include <chrono>
#include <functional>
#include <memory>

#include "rclcpp/rclcpp.hpp"
#include "rclcpp_action/rclcpp_action.hpp"
#include "example_interfaces/action/fibonacci.hpp"

using namespace std::chrono_literals;
using Fibonacci = example_interfaces::action::Fibonacci;

class FibonacciActionClient : public rclcpp::Node
{
public:
  FibonacciActionClient()
  : Node("fibonacci_action_client")
  {
    client_ptr_ = rclcpp_action::create_client<Fibonacci>(this, "fibonacci");

    // 서버가 준비될 때까지 대기
    while (!client_ptr_->wait_for_action_server(1s)) {
      if (!rclcpp::ok()) {
        RCLCPP_ERROR(this->get_logger(), "Interrupted while waiting for the action server.");
        return;
      }
      RCLCPP_INFO(this->get_logger(), "Action server not available, waiting...");
    }

    send_goal();
  }

private:
  rclcpp_action::Client<Fibonacci>::SharedPtr client_ptr_;

  void send_goal()
  {
    auto goal_msg = Fibonacci::Goal();
    goal_msg.order = 10;

    RCLCPP_INFO(this->get_logger(), "Sending goal");

    auto send_goal_options = rclcpp_action::Client<Fibonacci>::SendGoalOptions();
    send_goal_options.goal_response_callback =
      std::bind(&FibonacciActionClient::goal_response_callback, this, std::placeholders::_1);
    send_goal_options.feedback_callback =
      std::bind(&FibonacciActionClient::feedback_callback, this, std::placeholders::_1, std::placeholders::_2);
    send_goal_options.result_callback =
      std::bind(&FibonacciActionClient::result_callback, this, std::placeholders::_1);

    client_ptr_->async_send_goal(goal_msg, send_goal_options);
  }

  void goal_response_callback(
    std::shared_ptr<rclcpp_action::ClientGoalHandle<Fibonacci>> goal_handle)
  {
    if (!goal_handle) {
      RCLCPP_ERROR(this->get_logger(), "Goal was rejected by server");
    } else {
      RCLCPP_INFO(this->get_logger(), "Goal accepted by server, waiting for result");
    }
  }

  void feedback_callback(
    rclcpp_action::ClientGoalHandle<Fibonacci>::SharedPtr,
    const std::shared_ptr<const Fibonacci::Feedback> feedback)
  {
    RCLCPP_INFO(this->get_logger(), "Feedback: sequence length = %zu",
                feedback->partial_sequence.size());
  }

  void result_callback(
    const rclcpp_action::ClientGoalHandle<Fibonacci>::WrappedResult & result)
  {
    switch (result.code) {
      case rclcpp_action::ResultCode::SUCCEEDED:
        RCLCPP_INFO(this->get_logger(), "Result received, final sequence size = %zu",
                    result.result->sequence.size());
        break;
      case rclcpp_action::ResultCode::ABORTED:
        RCLCPP_ERROR(this->get_logger(), "Goal was aborted");
        break;
      case rclcpp_action::ResultCode::CANCELED:
        RCLCPP_ERROR(this->get_logger(), "Goal was canceled");
        break;
      default:
        RCLCPP_ERROR(this->get_logger(), "Unknown result code");
        break;
    }
  }
};

int main(int argc, char * argv[])
{
  rclcpp::init(argc, argv);
  auto node = std::make_shared<FibonacciActionClient>();
  rclcpp::spin(node);
  rclcpp::shutdown();
  return 0;
}

3-4. CMakeLists.txt에 타겟 등록 예시

ros2_comm_examples/CMakeLists.txt 하단에 예제 타겟들을 등록:

find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
find_package(example_interfaces REQUIRED)
find_package(rclcpp_action REQUIRED)

# Topic
add_executable(topic_publisher src/topic_publisher.cpp)
ament_target_dependencies(topic_publisher rclcpp std_msgs)

add_executable(topic_subscriber src/topic_subscriber.cpp)
ament_target_dependencies(topic_subscriber rclcpp std_msgs)

# Service
add_executable(add_two_ints_server src/add_two_ints_server.cpp)
ament_target_dependencies(add_two_ints_server rclcpp example_interfaces)

add_executable(add_two_ints_client src/add_two_ints_client.cpp)
ament_target_dependencies(add_two_ints_client rclcpp example_interfaces)

# Action
add_executable(fibonacci_action_server src/fibonacci_action_server.cpp)
ament_target_dependencies(fibonacci_action_server rclcpp rclcpp_action example_interfaces)

add_executable(fibonacci_action_client src/fibonacci_action_client.cpp)
ament_target_dependencies(fibonacci_action_client rclcpp rclcpp_action example_interfaces)

install(TARGETS
  topic_publisher
  topic_subscriber
  add_two_ints_server
  add_two_ints_client
  fibonacci_action_server
  fibonacci_action_client
  DESTINATION lib/${PROJECT_NAME})

빌드 & 실행:

cd ~/ros2_ws
colcon build --packages-select ros2_comm_examples
source install/setup.bash

실행 예:

# Topic
ros2 run ros2_comm_examples topic_publisher
ros2 run ros2_comm_examples topic_subscriber

# Service
ros2 run ros2_comm_examples add_two_ints_server
ros2 run ros2_comm_examples add_two_ints_client

# Action
ros2 run ros2_comm_examples fibonacci_action_server
ros2 run ros2_comm_examples fibonacci_action_client

4. 추가 팁 / 자주 하는 실수

  1. Topic으로 Action 흉내 내기
    • “목표 토픽 하나, 결과 토픽 하나, 상태 토픽 하나…”
    • 이렇게 직접 짜기 시작하면 Action이 이미 그걸 다 해주는 패턴이라,
      나중에 유지보수/타 팀 협업 시 더 힘들어집니다.
    • “길게 걸리는 목표 + 피드백 + 취소/완료” → 고민 없이 Action 선택이 보통 정답.
  2. Service로 긴 작업 처리
    • Service 안에서 수십 초 걸리는 일을 처리하면,
    • 클라이언트가 기다리다 timeout, 중간 취소도 어려움.
    • 이럴 땐 Service 대신 Action + 별도 상태 관리가 안정적입니다.
  3. QoS 생각 안 하고 Topic만 쓰기
    • 센서 토픽, TF, 제어 명령 등은 QoS에 따라 동작이 달라질 수 있습니다.
    • 기본 예제에서는 QoS(10)만 쓰더라도, 실제 프로젝트 들어가면
      • best_effort vs reliable
      • transient_local
        을 고민해야 합니다.
  4. CMake / package.xml 의존성 누락
    • Action 쓸 때 rclcpp_action, example_interfaces 의존성 추가를 빼먹으면
      • 빌드 에러 (target not found, unknown type 등)
    • 새 통신 패턴 추가하면 항상 CMakeLists + package.xml 둘 다 점검.
  5. 빌드 후 source 안 함
    • ROS2 클리셰지만 제일 많이 하는 실수
    • colcon build source install/setup.bash
    • 새 터미널 열 때마다 잊지 말기.

5. 정리

  • ROS2에서 “메시지 종류”는 Topic / Service / Action 세 가지 고수준 통신 패턴으로 나뉩니다.
    • Topic: 스트리밍, 상태/센서/이벤트 브로드캐스트
    • Service: 짧은 요청/응답, 설정 변경, 한 번 계산
    • Action: 오래 걸리는 목표 작업, 피드백/취소/결과 관리
  • C++ 코드에서는 rclcpp::Node를 기반으로
    • create_publisher / create_subscription
    • create_service / create_client
    • rclcpp_action::create_server / create_client
      패턴에 익숙해지면, 나머지는 메시지 타입만 바뀌는 수준입니다.
  • 프로젝트 설계할 때 “이 기능은 Topic/Service/Action 중 무엇이 맞나?”를 먼저 한 번 정리하고 들어가면, 나중에 리팩토링 부담을 크게 줄일 수 있습니다.

댓글 남기기