대상: ROS Melodic에서 C++ 노드를 작성하면서 Topic/Service/Action/Parameter 차이를 정리하고 싶은 개발자
환경: Ubuntu 18.04, ROS Melodic, C++ (catkin, roscpp)
1. 주제 요약
ROS Melodic를 쓰다 보면 이런 의문이 많이 생깁니다.
- “데이터를 보내야 하는데 Topic이 맞나? Service가 맞나?”
- “Action은 Service랑 뭐가 다르지?”
- “Parameter Server로 설정은 어떻게 주고 받지?”
이 글에서는 ROS에서 사용하는 주요 통신 방식인
- Topic (Publish/Subscribe)
- Service (Request/Response)
- Action (Goal/Feedback/Result)
- Parameter Server (설정값 공유)
를 각각 개념 + C++ 코드 예제로 정리합니다.
2. 배경/개념 정리
ROS(ROS1)에서는 노드끼리 데이터를 주고받기 위해 몇 가지 패턴을 제공합니다.
- Topic (비동기 스트리밍 데이터)
- 센서 데이터, 상태 스트림 등 계속 흘러가는 정보에 적합
- Publisher → (ROS Master가 중계) → Subscriber
- 1:N, N:1, N:N 모두 가능
- 예)
/scan,/cmd_vel,/camera/image_raw
- Service (동기 요청/응답)
- “지금 이 함수 한번만 호출” 같은 패턴
- Client → Server에게 요청, Server가 응답 (RPC 느낌)
- 요청-응답 후 통신 종료
- 예) 맵 저장 요청, 파라미터 한 번 읽어오기 등
- Action (긴 작업을 위한 비동기 요청)
- Service는 “응답이 바로 오는” 느낌인데,
- Action은 “조금 오래 걸리는 작업”에 사용
- Goal을 보내고, 중간중간 Feedback을 받고, 마지막에 Result를 받음
- 예) 로봇을 특정 위치까지 이동 (navigation), 팔을 특정 자세로 이동 (moveit)
- Parameter Server (설정값 저장소)
- 주로 설정/튜닝 값을 보관하는 서버
- 노드들이 값 읽기/쓰기 가능
- 예) PID 게인, 토픽 이름, 로봇의 물리 상수 등
이 네 가지를 적절히 섞어서 쓰는 것이 ROS 노드 설계의 핵심입니다.
3. 메시지 종류별 상세 설명 및 C++ 예제
예제용 패키지 이름은 my_ros_tutorials라고 가정하겠습니다.
cd ~/catkin_ws/src
catkin_create_pkg my_ros_tutorials roscpp std_msgs actionlib actionlib_msgs
CMakeLists.txt와 package.xml에 메시지 관련 설정은 공통 파트에서 같이 설명합니다.
3.1 Topic – Publish/Subscribe
3.1.1 메시지 타입 정의 (선택사항)
기본 메시지를 써도 되지만, 예제로 간단한 custom msg를 하나 만들어 봅니다.
my_ros_tutorials/msg/Num.msg
int32 value
string comment
CMakeLists.txt 일부 설정:
find_package(catkin REQUIRED COMPONENTS
roscpp
std_msgs
message_generation
)
add_message_files(
FILES
Num.msg
)
generate_messages(
DEPENDENCIES
std_msgs
)
catkin_package(
CATKIN_DEPENDS roscpp std_msgs message_runtime
)
3.1.2 Topic Publisher (C++)
src/topic_publisher.cpp
#include <ros/ros.h>
#include <my_ros_tutorials/Num.h> // 우리가 만든 메시지
int main(int argc, char** argv)
{
ros::init(argc, argv, "topic_publisher");
ros::NodeHandle nh;
// 토픽 이름: /my_number, 큐 사이즈: 10
ros::Publisher pub = nh.advertise<my_ros_tutorials::Num>("my_number", 10);
ros::Rate loop_rate(10); // 10 Hz
int count = 0;
while (ros::ok())
{
my_ros_tutorials::Num msg;
msg.value = count;
msg.comment = "Hello from publisher";
ROS_INFO("Publish: value=%d, comment=%s", msg.value, msg.comment.c_str());
pub.publish(msg);
ros::spinOnce();
loop_rate.sleep();
count++;
}
return 0;
}
3.1.3 Topic Subscriber (C++)
src/topic_subscriber.cpp
#include <ros/ros.h>
#include <my_ros_tutorials/Num.h>
void numberCallback(const my_ros_tutorials::Num::ConstPtr& msg)
{
ROS_INFO("Received: value=%d, comment=%s", msg->value, msg->comment.c_str());
}
int main(int argc, char** argv)
{
ros::init(argc, argv, "topic_subscriber");
ros::NodeHandle nh;
ros::Subscriber sub = nh.subscribe("my_number", 10, numberCallback);
ros::spin(); // 콜백을 계속 처리
return 0;
}
3.1.4 CMakeLists에 노드 추가
add_executable(topic_publisher src/topic_publisher.cpp)
add_dependencies(topic_publisher ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(topic_publisher ${catkin_LIBRARIES})
add_executable(topic_subscriber src/topic_subscriber.cpp)
add_dependencies(topic_subscriber ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(topic_subscriber ${catkin_LIBRARIES})
빌드 & 실행:
cd ~/catkin_ws
catkin_make
source devel/setup.bash
roscore
# 새 터미널
rosrun my_ros_tutorials topic_publisher
# 또 다른 터미널
rosrun my_ros_tutorials topic_subscriber
3.2 Service – Request/Response
Service는 .srv 파일로 요청(Request) / 응답(Response) 타입을 정의합니다.
3.2.1 srv 정의
my_ros_tutorials/srv/AddTwoInts.srv
int64 a
int64 b
---
int64 sum
CMakeLists.txt에 추가:
add_service_files(
FILES
AddTwoInts.srv
)
generate_messages(
DEPENDENCIES
std_msgs
)
(이미 generate_messages가 있다면 add_service_files만 추가)
3.2.2 Service Server (C++)
src/add_two_ints_server.cpp
#include <ros/ros.h>
#include <my_ros_tutorials/AddTwoInts.h>
bool add(my_ros_tutorials::AddTwoInts::Request &req,
my_ros_tutorials::AddTwoInts::Response &res)
{
res.sum = req.a + req.b;
ROS_INFO("request: a=%ld, b=%ld, sum=%ld",
(long int)req.a, (long int)req.b, (long int)res.sum);
return true; // 성공 여부
}
int main(int argc, char** argv)
{
ros::init(argc, argv, "add_two_ints_server");
ros::NodeHandle nh;
ros::ServiceServer service = nh.advertiseService("add_two_ints", add);
ROS_INFO("Ready to add two ints.");
ros::spin();
return 0;
}
3.2.3 Service Client (C++)
src/add_two_ints_client.cpp
#include <ros/ros.h>
#include <my_ros_tutorials/AddTwoInts.h>
int main(int argc, char** argv)
{
ros::init(argc, argv, "add_two_ints_client");
if (argc != 3)
{
ROS_INFO("usage: add_two_ints_client X Y");
return 1;
}
ros::NodeHandle nh;
ros::ServiceClient client = nh.serviceClient<my_ros_tutorials::AddTwoInts>("add_two_ints");
my_ros_tutorials::AddTwoInts srv;
srv.request.a = atoll(argv[1]);
srv.request.b = atoll(argv[2]);
if (client.call(srv))
{
ROS_INFO("Sum: %ld", (long int)srv.response.sum);
}
else
{
ROS_ERROR("Failed to call service add_two_ints");
return 1;
}
return 0;
}
CMakeLists.txt에 추가:
add_executable(add_two_ints_server src/add_two_ints_server.cpp)
add_dependencies(add_two_ints_server ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(add_two_ints_server ${catkin_LIBRARIES})
add_executable(add_two_ints_client src/add_two_ints_client.cpp)
add_dependencies(add_two_ints_client ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(add_two_ints_client ${catkin_LIBRARIES})
실행:
roscore
# 새 터미널
rosrun my_ros_tutorials add_two_ints_server
# 새 터미널
rosrun my_ros_tutorials add_two_ints_client 3 5
# -> Sum: 8
3.3 Action – 긴 작업 + Feedback
Action은 .action 파일로 Goal / Result / Feedback을 정의합니다.
예제로, 숫자를 1씩 세면서 중간값을 Feedback으로 보내고 마지막에 Result를 보내는 Action을 만듭니다.
3.3.1 action 정의
my_ros_tutorials/action/CountUntil.action
# goal
int32 target_number
float32 wait_duration # 초 단위 딜레이
---
# result
int32 final_number
---
# feedback
int32 current_number
CMakeLists.txt에 추가:
find_package(catkin REQUIRED COMPONENTS
roscpp
std_msgs
message_generation
actionlib
actionlib_msgs
)
add_action_files(
DIRECTORY action
FILES
CountUntil.action
)
generate_messages(
DEPENDENCIES
std_msgs
actionlib_msgs
)
catkin_package(
CATKIN_DEPENDS roscpp std_msgs actionlib actionlib_msgs message_runtime
)
3.3.2 Action Server (C++)
src/count_until_server.cpp
#include <ros/ros.h>
#include <actionlib/server/simple_action_server.h>
#include <my_ros_tutorials/CountUntilAction.h>
class CountUntilAction
{
protected:
ros::NodeHandle nh_;
actionlib::SimpleActionServer<my_ros_tutorials::CountUntilAction> as_;
std::string action_name_;
my_ros_tutorials::CountUntilFeedback feedback_;
my_ros_tutorials::CountUntilResult result_;
public:
CountUntilAction(std::string name) :
as_(nh_, name, boost::bind(&CountUntilAction::executeCB, this, _1), false),
action_name_(name)
{
as_.start();
}
~CountUntilAction(void) {}
void executeCB(const my_ros_tutorials::CountUntilGoalConstPtr &goal)
{
ros::Rate rate(1.0 / goal->wait_duration); // wait_duration 초마다 1 증가
int current = 0;
bool success = true;
ROS_INFO("%s: Starting to count until %d", action_name_.c_str(), goal->target_number);
while (ros::ok() && current < goal->target_number)
{
// preempt(취소) 요청 체크
if (as_.isPreemptRequested())
{
ROS_WARN("%s: Preempted", action_name_.c_str());
as_.setPreempted();
success = false;
break;
}
current++;
feedback_.current_number = current;
as_.publishFeedback(feedback_);
ROS_INFO("%s: Feedback: %d", action_name_.c_str(), current);
rate.sleep();
}
if (success)
{
result_.final_number = current;
ROS_INFO("%s: Succeeded, final_number=%d", action_name_.c_str(), current);
as_.setSucceeded(result_);
}
}
};
int main(int argc, char** argv)
{
ros::init(argc, argv, "count_until_server");
CountUntilAction count_until("count_until");
ros::spin();
return 0;
}
3.3.3 Action Client (C++)
src/count_until_client.cpp
#include <ros/ros.h>
#include <actionlib/client/simple_action_client.h>
#include <my_ros_tutorials/CountUntilAction.h>
void doneCb(const actionlib::SimpleClientGoalState& state,
const my_ros_tutorials::CountUntilResultConstPtr& result)
{
ROS_INFO("Finished in state: %s, final_number: %d",
state.toString().c_str(), result->final_number);
}
void activeCb()
{
ROS_INFO("Goal just went active");
}
void feedbackCb(const my_ros_tutorials::CountUntilFeedbackConstPtr& feedback)
{
ROS_INFO("Feedback: current_number = %d", feedback->current_number);
}
int main(int argc, char** argv)
{
ros::init(argc, argv, "count_until_client");
actionlib::SimpleActionClient<my_ros_tutorials::CountUntilAction> ac("count_until", true);
ROS_INFO("Waiting for action server to start...");
ac.waitForServer();
my_ros_tutorials::CountUntilGoal goal;
goal.target_number = 5;
goal.wait_duration = 1.0;
ROS_INFO("Sending goal: target_number=%d, wait_duration=%.2f",
goal.target_number, goal.wait_duration);
ac.sendGoal(goal, &doneCb, &activeCb, &feedbackCb);
bool finished_before_timeout = ac.waitForResult(ros::Duration(30.0));
if (!finished_before_timeout)
{
ROS_WARN("Action did not finish before timeout. Canceling goal.");
ac.cancelGoal();
}
return 0;
}
CMakeLists.txt에 추가:
add_executable(count_until_server src/count_until_server.cpp)
add_dependencies(count_until_server ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(count_until_server ${catkin_LIBRARIES})
add_executable(count_until_client src/count_until_client.cpp)
add_dependencies(count_until_client ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(count_until_client ${catkin_LIBRARIES})
3.4 Parameter Server – 설정값 공유
Parameter Server는 따로 .msg 같은 정의는 없고, 키-값 형태로 데이터를 보관합니다.
rosparam명령어 (YAML 기반)로 설정- C++에서는
ros::NodeHandle또는ros::param네임스페이스로 접근
3.4.1 rosparam으로 설정
rosparam set /my_robot/max_speed 1.5
rosparam get /my_robot/max_speed
yaml 파일을 로드할 수도 있습니다.
rosparam load config/my_params.yaml
3.4.2 C++에서 파라미터 읽기/쓰기
src/param_example.cpp
#include <ros/ros.h>
int main(int argc, char** argv)
{
ros::init(argc, argv, "param_example");
ros::NodeHandle nh;
// 1) setParam으로 쓰기
nh.setParam("max_speed", 1.5);
nh.setParam("/global_name", 10);
// 2) getParam으로 읽기
double max_speed;
if (nh.getParam("max_speed", max_speed))
{
ROS_INFO("max_speed = %f", max_speed);
}
else
{
ROS_WARN("Failed to get param 'max_speed'");
}
// 3) 기본값과 함께 읽기 (param 함수)
int some_value = nh.param<int>("some_value", 42); // 없으면 42
ROS_INFO("some_value = %d", some_value);
// ros::param 네임스페이스도 사용 가능
int global_name;
if (ros::param::get("/global_name", global_name))
{
ROS_INFO("/global_name = %d", global_name);
}
return 0;
}
4. 추가 팁 / 자주 하는 실수
- CMakeLists 메시지 설정 누락
add_message_files,add_service_files,add_action_files,generate_messages,catkin_package의message_runtime/actionlib_msgs누락하면 빌드 에러 잦음.- 새
.msg/.srv/.action추가 후catkin_make다시 해줘야 함.
- 헤더 include 경로
- custom msg:
#include <패키지이름/타입명.h> - Action:
#include <패키지이름/ActionNameAction.h>,ActionNameGoal.h,ActionNameResult.h,ActionNameFeedback.h등 존재 (보통Action만 쓰면 됨).
- custom msg:
- Topic queue_size
advertise/subscribe시 queue_size가 너무 작거나 0이면 메시지 누락/지연 이슈 발생 가능.- 일반적으로 10~100 정도에서 시작해서 필요시 조정.
- Service / Action 타임아웃 처리
client.call()이 오래 걸릴 수 있음 → 별도 스레드/타임아웃 설계 고려.- Action Client에서
waitForResult(ros::Duration(x))으로 제한 가능, 미완료 시cancelGoal().
- 네임스페이스 / 파라미터 이름
- NodeHandle의 네임스페이스에 따라 파라미터 키가 달라짐.
ros::NodeHandle nh("~");→ private namespace (~node_name/...)에 저장됨.
5. 정리
- Topic: 비동기 스트리밍 데이터 (Publisher/Subscriber). 센서/상태 전파용.
- Service: 동기 요청/응답 1회 호출 (RPC 느낌). 짧은 작업에 적합.
- Action: 오래 걸리는 작업용 비동기 요청 (Goal/Feedback/Result + cancel 가능).
- Parameter Server: 설정값/튜닝값을 키-값 형태로 저장/공유.
위의 예제 C++ 코드(talker/listener, service server/client, action server/client, param 사용)를 그대로 패키지에 넣고 빌드해 보면, ROS의 주요 통신 패턴이 어떻게 동작하는지 한 번에 감을 잡을 수 있습니다.