1. 실습 목표
이번 실습에서는 C++로 모바일 로봇의 긴급정지 서비스를 호출하는 구조를 작성합니다.
패키지는 이미 생성되어 있다고 가정합니다.
~/ros2_study/src/my_cpp_package
작성할 파일 구조는 다음과 같습니다.
my_cpp_package
├── src/
│ ├── emergency_stop_server.cpp
│ └── emergency_stop_client.cpp
├── CMakeLists.txt
└── package.xml
실습 동작은 단순합니다.
ros2 run my_cpp_package emergency_stop_client true
클라이언트가 /emergency_stop 서비스에 요청을 보냅니다.
data: true
서버는 다음과 같이 응답합니다.
success: true
message: Mobile robot emergency stop activated
이번 실습에서는 기본 std_srvs가 아니라, 이미 정의된 사용자 인터페이스 패키지인 my_first_package_msgs를 사용합니다.
2. 작업 공간 확인
작업 공간은 ros2_study를 사용합니다.
cd ~/ros2_study
source /opt/ros/humble/setup.bash
패키지 위치를 확인합니다.
cd ~/ros2_study/src/my_cpp_package
tree
예상 구조는 다음과 비슷합니다.
my_cpp_package
├── CMakeLists.txt
├── include
│ └── my_cpp_package
├── package.xml
└── src
3. 사용자 정의 서비스 인터페이스 생성
이번 예제에서는 std_srvs를 사용하지 않고, 이전에 만든 인터페이스 패키지인 my_first_package_msgs에 사용자 정의 서비스를 추가해서 사용합니다.
서비스 파일 이름은 다음과 같이 작성합니다.
RobotCommand.srv
작업 위치로 이동합니다.
cd ~/ros2_study/src/my_first_package_msgs
서비스 파일을 생성합니다.
touch srv/RobotCommand.srv

RobotCommand.srv 파일에 다음 내용을 작성합니다.
bool data
---
bool success
string message

이 인터페이스는 모바일 로봇에 명령을 보낼 때 사용할 수 있는 단순한 서비스 구조입니다.
요청부는 다음 한 줄입니다.
bool data
true를 보내면 긴급정지 활성화, false를 보내면 긴급정지 해제처럼 사용할 수 있습니다.
응답부는 다음 두 값으로 구성됩니다.
bool success
string message
success는 명령 처리 성공 여부를 나타내고, message는 처리 결과 메시지를 담습니다.
예를 들면 서버는 다음과 같이 응답할 수 있습니다.
success: true
message: Mobile robot emergency stop activated
4. my_first_package_msgs의 CMakeLists.txt 수정
사용자 정의 서비스 파일을 빌드하려면 my_first_package_msgs 패키지의 CMakeLists.txt에 인터페이스 생성 설정이 있어야 합니다.
cd ~/ros2_study/src/my_first_package_msgs
code CMakeLists.txt
또는
gedit CMakeLists.txt
아래 내용을 확인하거나 반영합니다.
cmake_minimum_required(VERSION 3.8)
project(my_first_package_msgs)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
find_package(ament_cmake REQUIRED)
find_package(rosidl_default_generators REQUIRED)
rosidl_generate_interfaces(${PROJECT_NAME}
"srv/RobotCommand.srv"
)
ament_export_dependencies(rosidl_default_runtime)
ament_package()

중요한 부분은 다음입니다.
find_package(rosidl_default_generators REQUIRED)
이 설정은 .srv, .msg, .action 파일을 C++, Python 등에서 사용할 수 있는 코드로 변환하기 위해 필요합니다.
서비스 파일 등록은 다음 부분에서 합니다.
rosidl_generate_interfaces(${PROJECT_NAME}
"srv/RobotCommand.srv"
)
서비스 파일이 여러 개라면 아래처럼 추가하면 됩니다.
rosidl_generate_interfaces(${PROJECT_NAME}
"srv/RobotCommand.srv"
"srv/AnotherService.srv"
)
5. my_first_package_msgs의 package.xml 수정
package.xml에도 인터페이스 생성에 필요한 의존성을 추가해야 합니다.
cd ~/ros2_study/src/my_first_package_msgs
code package.xml
아래 내용을 확인합니다.
<?xml version="1.0"?>
<package format="3">
<name>my_first_package_msgs</name>
<version>0.0.0</version>
<description>Custom interfaces for ROS 2 practice</description>
<maintainer email="user@example.com">user</maintainer>
<license>Apache-2.0</license>
<buildtool_depend>ament_cmake</buildtool_depend>
<build_depend>rosidl_default_generators</build_depend>
<exec_depend>rosidl_default_runtime</exec_depend>
<member_of_group>rosidl_interface_packages</member_of_group>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>

특히 아래 세 줄이 중요합니다.
<build_depend>rosidl_default_generators</build_depend>
<exec_depend>rosidl_default_runtime</exec_depend>
<member_of_group>rosidl_interface_packages</member_of_group>
rosidl_default_generators는 인터페이스 코드를 생성할 때 필요합니다.
rosidl_default_runtime은 생성된 인터페이스를 실행 시점에 사용할 때 필요합니다.
member_of_group은 이 패키지가 ROS 2 인터페이스 패키지임을 알려주는 설정입니다.
6. 인터페이스 패키지 빌드
이제 my_first_package_msgs를 먼저 빌드합니다.
cd ~/ros2_study
source /opt/ros/humble/setup.bash
colcon build --packages-select my_first_package_msgs
빌드 후 환경을 적용합니다.
source install/setup.bash

인터페이스가 정상적으로 생성되었는지 확인합니다.
ros2 interface show my_first_package_msgs/srv/RobotCommand
정상이라면 다음과 같이 출력됩니다.
bool data
---
bool success
string message

여기까지 완료되면 C++ 코드에서 다음 헤더를 사용할 수 있습니다.
#include "my_first_package_msgs/srv/robot_command.hpp"
그리고 타입은 다음처럼 사용합니다.
my_first_package_msgs::srv::RobotCommand
7. Service Server 작성
먼저 /emergency_stop 서비스를 제공하는 서버를 작성합니다.
클라이언트만 작성하면 테스트할 대상이 없기 때문에 서버도 함께 준비합니다.
파일을 생성합니다.
cd ~/ros2_study/src/my_cpp_package/src
touch emergency_stop_server.cpp

emergency_stop_server.cpp를 작성합니다.
#include "rclcpp/rclcpp.hpp"
#include "my_first_package_msgs/srv/robot_command.hpp"
#include <memory>
#include <string>
class EmergencyStopServer : public rclcpp::Node
{
public:
EmergencyStopServer()
: Node("emergency_stop_server")
{
service_ = this->create_service<my_first_package_msgs::srv::RobotCommand>(
"/emergency_stop",
std::bind(
&EmergencyStopServer::handle_emergency_stop,
this,
std::placeholders::_1,
std::placeholders::_2
)
);
RCLCPP_INFO(this->get_logger(), "Emergency stop server is ready.");
}
private:
void handle_emergency_stop(
const std::shared_ptr<my_first_package_msgs::srv::RobotCommand::Request> request,
std::shared_ptr<my_first_package_msgs::srv::RobotCommand::Response> response)
{
if (request->data) {
response->success = true;
response->message = "Mobile robot emergency stop activated";
RCLCPP_WARN(this->get_logger(), "Emergency stop ACTIVATED");
} else {
response->success = true;
response->message = "Mobile robot emergency stop released";
RCLCPP_INFO(this->get_logger(), "Emergency stop RELEASED");
}
}
rclcpp::Service<my_first_package_msgs::srv::RobotCommand>::SharedPtr service_;
};
int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
auto node = std::make_shared<EmergencyStopServer>();
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}

4. Server 소스 설명
1) 헤더 포함
#include "rclcpp/rclcpp.hpp"
#include "my_first_package_msgs/srv/robot_command.hpp"
rclcpp.hpp는 ROS 2 C++ 노드를 만들기 위한 기본 헤더입니다.
my_first_package_msgs/srv/robot_command.hpp는 사용자 정의 서비스 인터페이스를 사용하기 위한 헤더입니다.
서비스 파일 이름이 RobotCommand.srv라면 C++ include에서는 보통 다음처럼 소문자 스네이크 표기법으로 포함합니다.
#include "my_first_package_msgs/srv/robot_command.hpp"
만약 서비스 파일 이름이 EmergencyStop.srv라면 다음처럼 바꿔야 합니다.
#include "my_first_package_msgs/srv/emergency_stop.hpp"
2) 서버 노드 클래스
class EmergencyStopServer : public rclcpp::Node
EmergencyStopServer 클래스는 rclcpp::Node를 상속받습니다.
즉, 이 클래스 자체가 하나의 ROS 2 노드입니다.
생성자에서는 노드 이름을 지정합니다.
EmergencyStopServer()
: Node("emergency_stop_server")
실행하면 노드 이름은 다음과 같이 등록됩니다.
/emergency_stop_server
3) 서비스 생성
service_ = this->create_service<my_first_package_msgs::srv::RobotCommand>(
"/emergency_stop",
std::bind(
&EmergencyStopServer::handle_emergency_stop,
this,
std::placeholders::_1,
std::placeholders::_2
)
);
이 부분이 서버 코드의 핵심입니다.
create_service()는 특정 이름의 서비스를 엽니다.
여기서는 서비스 이름을 /emergency_stop으로 만들었습니다.
"/emergency_stop"
클라이언트는 이 이름으로 요청을 보내야 합니다.
서버와 클라이언트의 서비스 이름이 다르면 통신되지 않습니다.
두 번째 인자는 콜백 함수입니다.
&EmergencyStopServer::handle_emergency_stop
서비스 요청이 들어오면 handle_emergency_stop() 함수가 실행됩니다.
4) 요청 처리 함수
void handle_emergency_stop(
const std::shared_ptr<my_first_package_msgs::srv::RobotCommand::Request> request,
std::shared_ptr<my_first_package_msgs::srv::RobotCommand::Response> response)
이 함수는 요청과 응답을 처리합니다.
요청 데이터는 다음으로 접근합니다.
request->data
응답 데이터는 다음으로 설정합니다.
response->success
response->message
긴급정지 요청이 true이면 다음 코드가 실행됩니다.
if (request->data) {
response->success = true;
response->message = "Mobile robot emergency stop activated";
RCLCPP_WARN(this->get_logger(), "Emergency stop ACTIVATED");
}
모바일 로봇 기준으로는 이 위치에 실제 모터 정지 코드가 들어갈 수 있습니다.
예를 들면 다음과 같은 처리가 연결될 수 있습니다.
// motor_controller.stop();
// velocity_command = 0;
// brake.enable();
// robot_state = EMERGENCY_STOP;
하지만 이번 실습에서는 소스 흐름을 확인하는 것이 목적이므로 로그와 응답 메시지만 처리합니다.
긴급정지 해제 요청이 false이면 다음 코드가 실행됩니다.
else {
response->success = true;
response->message = "Mobile robot emergency stop released";
RCLCPP_INFO(this->get_logger(), "Emergency stop RELEASED");
}
실제 로봇에서는 이 부분이 바로 모터 재가동으로 연결되면 위험할 수 있습니다.
보통은 긴급정지 해제 후에도 별도의 상태 확인, 사용자 승인, 주행 가능 조건 확인을 거치는 구조가 더 안전합니다.
5) 서비스 객체 보관
rclcpp::Service<my_first_package_msgs::srv::RobotCommand>::SharedPtr service_;
서비스 객체를 멤버 변수로 보관합니다.
이 변수가 유지되어야 노드가 실행 중인 동안 서비스도 유지됩니다.
6) main 함수
int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
auto node = std::make_shared<EmergencyStopServer>();
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}
흐름은 간단합니다.
rclcpp::init(argc, argv);
ROS 2를 초기화합니다.
auto node = std::make_shared<EmergencyStopServer>();
서버 노드를 생성합니다.
rclcpp::spin(node);
노드를 계속 실행하면서 서비스 요청을 기다립니다.
rclcpp::shutdown();
노드 종료 시 ROS 2를 정리합니다.
5. Service Client 작성
이제 클라이언트 코드를 작성합니다.
파일을 생성합니다.
cd ~/ros2_study/src/my_cpp_package/src
touch emergency_stop_client.cpp

emergency_stop_client.cpp를 작성합니다.
#include "rclcpp/rclcpp.hpp"
#include "my_first_package_msgs/srv/robot_command.hpp"
#include <chrono>
#include <cstdlib>
#include <memory>
#include <string>
#include <stdexcept>
using namespace std::chrono_literals;
class EmergencyStopClient : public rclcpp::Node
{
public:
EmergencyStopClient()
: Node("emergency_stop_client")
{
client_ = this->create_client<my_first_package_msgs::srv::RobotCommand>(
"/emergency_stop"
);
}
bool send_request(bool emergency_stop)
{
auto request =
std::make_shared<my_first_package_msgs::srv::RobotCommand::Request>();
request->data = emergency_stop;
int retry_count = 0;
while (!client_->wait_for_service(1s)) {
if (!rclcpp::ok()) {
RCLCPP_ERROR(
this->get_logger(),
"ROS interrupted while waiting for service."
);
return false;
}
retry_count++;
if (retry_count >= 5) {
RCLCPP_ERROR(
this->get_logger(),
"/emergency_stop service is not available."
);
return false;
}
RCLCPP_INFO(
this->get_logger(),
"Waiting for /emergency_stop service..."
);
}
auto future = client_->async_send_request(request);
auto result = rclcpp::spin_until_future_complete(
this->get_node_base_interface(),
future
);
if (result == rclcpp::FutureReturnCode::SUCCESS) {
auto response = future.get();
RCLCPP_INFO(
this->get_logger(),
"Response success: %s",
response->success ? "true" : "false"
);
RCLCPP_INFO(
this->get_logger(),
"Response message: %s",
response->message.c_str()
);
return response->success;
}
RCLCPP_ERROR(
this->get_logger(),
"Failed to call /emergency_stop service."
);
return false;
}
private:
rclcpp::Client<my_first_package_msgs::srv::RobotCommand>::SharedPtr client_;
};
bool parse_bool_argument(const std::string & arg)
{
if (arg == "true" || arg == "1" || arg == "on" || arg == "stop") {
return true;
}
if (arg == "false" || arg == "0" || arg == "off" || arg == "release") {
return false;
}
throw std::invalid_argument(
"Invalid argument. Use true/false, 1/0, on/off, stop/release."
);
}
int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
if (argc != 2) {
RCLCPP_ERROR(
rclcpp::get_logger("emergency_stop_client"),
"Usage: ros2 run my_cpp_package emergency_stop_client true"
);
rclcpp::shutdown();
return 1;
}
bool emergency_stop = false;
try {
emergency_stop = parse_bool_argument(argv[1]);
} catch (const std::exception & e) {
RCLCPP_ERROR(
rclcpp::get_logger("emergency_stop_client"),
"%s",
e.what()
);
rclcpp::shutdown();
return 1;
}
auto node = std::make_shared<EmergencyStopClient>();
bool success = node->send_request(emergency_stop);
rclcpp::shutdown();
return success ? 0 : 1;
}

6. Client 소스 설명
1) 클라이언트 생성
client_ = this->create_client<my_first_package_msgs::srv::RobotCommand>(
"/emergency_stop"
);
이 코드는 /emergency_stop 서비스에 요청을 보낼 클라이언트를 생성합니다.
서버 코드의 서비스 이름도 /emergency_stop이므로 두 이름이 일치합니다.
서버:
this->create_service<my_first_package_msgs::srv::RobotCommand>(
"/emergency_stop",
...
);
클라이언트:
this->create_client<my_first_package_msgs::srv::RobotCommand>(
"/emergency_stop"
);
서비스 타입도 반드시 같아야 합니다.
my_first_package_msgs::srv::RobotCommand
서비스 이름이 같아도 타입이 다르면 정상 통신되지 않습니다.
2) 요청 생성
auto request =
std::make_shared<my_first_package_msgs::srv::RobotCommand::Request>();
서비스 요청 객체를 생성합니다.
이후 요청 값을 넣습니다.
request->data = emergency_stop;
emergency_stop 값은 터미널 인자에서 들어옵니다.
ros2 run my_cpp_package emergency_stop_client true
이면 request->data는 true가 됩니다.
ros2 run my_cpp_package emergency_stop_client false
이면 request->data는 false가 됩니다.
3) 서비스 대기
while (!client_->wait_for_service(1s)) {
서버가 아직 실행되지 않았을 수 있으므로 클라이언트는 서비스를 기다립니다.
기존 예제처럼 무한정 기다리게 만들 수도 있지만, 여기서는 5회 제한을 넣었습니다.
int retry_count = 0;
1초마다 한 번씩 확인합니다.
retry_count++;
if (retry_count >= 5) {
RCLCPP_ERROR(
this->get_logger(),
"/emergency_stop service is not available."
);
return false;
}
즉, 약 5초 동안 서비스를 찾지 못하면 실패 처리합니다.
이 방식이 실습에서는 더 좋습니다.
서버를 안 켠 상태에서 클라이언트가 계속 멈춘 것처럼 보이는 상황을 줄일 수 있습니다.
4) 비동기 요청 전송
auto future = client_->async_send_request(request);
서비스 요청을 보냅니다.
async_send_request()는 요청을 보낸 뒤 바로 응답을 반환하지 않습니다.
대신 나중에 응답을 받을 수 있는 future 객체를 반환합니다.
서비스 통신은 네트워크 또는 프로세스 간 통신이기 때문에 응답이 즉시 온다고 가정하면 안 됩니다.
그래서 C++에서는 이런 형태로 요청을 보내고, 결과가 올 때까지 기다리는 구조를 자주 사용합니다.
5) 응답 대기
auto result = rclcpp::spin_until_future_complete(
this->get_node_base_interface(),
future
);
이 코드는 서비스 응답이 올 때까지 현재 노드를 spin합니다.
응답을 정상적으로 받으면 결과는 다음 값이 됩니다.
rclcpp::FutureReturnCode::SUCCESS
그래서 아래 조건문으로 성공 여부를 확인합니다.
if (result == rclcpp::FutureReturnCode::SUCCESS) {
6) 응답 처리
auto response = future.get();
응답 객체를 가져옵니다.
응답에는 서버에서 설정한 값이 들어 있습니다.
response->success
response->message
성공 여부는 다음처럼 출력합니다.
RCLCPP_INFO(
this->get_logger(),
"Response success: %s",
response->success ? "true" : "false"
);
메시지는 다음처럼 출력합니다.
RCLCPP_INFO(
this->get_logger(),
"Response message: %s",
response->message.c_str()
);
C++의 std::string을 RCLCPP_INFO()에서 %s로 출력하려면 c_str()을 붙여야 합니다.
response->message.c_str()
7) 문자열 인자 처리
bool parse_bool_argument(const std::string & arg)
이 함수는 터미널에서 받은 문자열을 bool 값으로 변환합니다.
긴급정지 활성화는 다음 값을 허용합니다.
if (arg == "true" || arg == "1" || arg == "on" || arg == "stop") {
return true;
}
긴급정지 해제는 다음 값을 허용합니다.
if (arg == "false" || arg == "0" || arg == "off" || arg == "release") {
return false;
}
따라서 다음 명령은 모두 사용할 수 있습니다.
ros2 run my_cpp_package emergency_stop_client true
ros2 run my_cpp_package emergency_stop_client 1
ros2 run my_cpp_package emergency_stop_client on
ros2 run my_cpp_package emergency_stop_client stop
해제 명령은 다음과 같습니다.
ros2 run my_cpp_package emergency_stop_client false
ros2 run my_cpp_package emergency_stop_client 0
ros2 run my_cpp_package emergency_stop_client off
ros2 run my_cpp_package emergency_stop_client release
잘못된 값이 들어오면 예외를 발생시킵니다.
throw std::invalid_argument(
"Invalid argument. Use true/false, 1/0, on/off, stop/release."
);
8) main 함수 흐름
if (argc != 2) {
클라이언트는 인자 하나를 받아야 합니다.
예:
ros2 run my_cpp_package emergency_stop_client true
인자가 없거나 너무 많으면 사용법을 출력하고 종료합니다.
return 1;
return 1은 프로그램이 비정상 종료되었음을 의미합니다.
정상적으로 인자를 읽으면 클라이언트 노드를 생성합니다.
auto node = std::make_shared<EmergencyStopClient>();
그리고 요청을 보냅니다.
bool success = node->send_request(emergency_stop);
서비스 응답이 성공이면 0, 실패면 1을 반환합니다.
return success ? 0 : 1;
이런 식으로 작성하면 쉘 스크립트나 launch 파일에서 실행 결과를 판단하기 좋습니다.
7. CMakeLists.txt 수정
my_cpp_package의 CMakeLists.txt를 수정합니다.
cd ~/ros2_study/src/my_cpp_package
code CMakeLists.txt
또는
gedit CMakeLists.txt
아래 내용을 반영합니다.
cmake_minimum_required(VERSION 3.8)
project(my_cpp_package)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(my_first_package_msgs REQUIRED)
add_executable(emergency_stop_server src/emergency_stop_server.cpp)
ament_target_dependencies(emergency_stop_server rclcpp my_first_package_msgs)
add_executable(emergency_stop_client src/emergency_stop_client.cpp)
ament_target_dependencies(emergency_stop_client rclcpp my_first_package_msgs)
install(TARGETS
emergency_stop_server
emergency_stop_client
DESTINATION lib/${PROJECT_NAME}
)
ament_package()

여기서 중요한 부분은 세 군데입니다.
첫 번째는 사용자 정의 메시지 패키지를 찾는 부분입니다.
find_package(my_first_package_msgs REQUIRED)
두 번째는 실행 파일을 만드는 부분입니다.
add_executable(emergency_stop_server src/emergency_stop_server.cpp)
add_executable(emergency_stop_client src/emergency_stop_client.cpp)
세 번째는 의존성을 연결하는 부분입니다.
ament_target_dependencies(
emergency_stop_client
rclcpp
my_first_package_msgs
)
이 설정이 빠지면 my_first_package_msgs의 헤더를 찾지 못하거나 링크 과정에서 문제가 날 수 있습니다.
마지막으로 install(TARGETS ...)가 있어야 ros2 run으로 실행할 수 있습니다.
install(TARGETS
emergency_stop_server
emergency_stop_client
DESTINATION lib/${PROJECT_NAME}
)
8. package.xml 확인
package.xml에 다음 의존성이 있어야 합니다.
<depend>rclcpp</depend>
<depend>my_first_package_msgs</depend>
전체 예시는 다음과 비슷합니다.
<?xml version="1.0"?>
<package format="3">
<name>my_cpp_package</name>
<version>0.0.0</version>
<description>C++ service server and client practice package</description>
<maintainer email="user@example.com">user</maintainer>
<license>Apache-2.0</license>
<buildtool_depend>ament_cmake</buildtool_depend>
<depend>rclcpp</depend>
<depend>my_first_package_msgs</depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>
<build_type>ament_cmake</build_type>는 반드시 확인하는 것이 좋습니다.
이 부분이 빠지면 패키지 인식이나 빌드 과정에서 문제가 생길 수 있습니다.
9. 빌드
작업 공간 루트로 이동합니다.
cd ~/ros2_study
ROS 2 Humble 환경을 적용합니다.
source /opt/ros/humble/setup.bash
의존성을 확인합니다.
rosdep install -i --from-path src --rosdistro humble -y
만약 오류가 발생하면
sudo rosdep init
rosdep update
명령어를 실행한 후에 의존성을 다시 확인합니다.


빌드합니다.
colcon build --packages-select my_cpp_package
만약 my_first_package_msgs도 같은 워크스페이스에 있고 아직 빌드하지 않았다면 다음처럼 함께 빌드하는 것이 안전합니다.
colcon build --packages-select my_first_package_msgs my_cpp_package
빌드 후 환경을 적용합니다.
source install/setup.bash

10. 실행 실습
터미널 1번에서 서버를 실행합니다.
cd ~/ros2_study
source install/setup.bash
ros2 run my_cpp_package emergency_stop_server
예상 출력은 다음과 같습니다.
[INFO] [emergency_stop_server]: Emergency stop server is ready.

터미널 2번에서 클라이언트를 실행합니다.
cd ~/ros2_study
source install/setup.bash
ros2 run my_cpp_package emergency_stop_client true
예상 출력은 다음과 같습니다.
[INFO] [emergency_stop_client]: Response success: true
[INFO] [emergency_stop_client]: Response message: Mobile robot emergency stop activated

서버 터미널에는 다음 로그가 출력됩니다.
[WARN] [emergency_stop_server]: Emergency stop ACTIVATED

긴급정지를 해제하려면 다음처럼 실행합니다.
ros2 run my_cpp_package emergency_stop_client false
예상 출력은 다음과 같습니다.
[INFO] [emergency_stop_client]: Response success: true
[INFO] [emergency_stop_client]: Response message: Mobile robot emergency stop released


또는 다음 명령도 사용할 수 있습니다.
ros2 run my_cpp_package emergency_stop_client stop
ros2 run my_cpp_package emergency_stop_client release


11. ROS 2 CLI로 확인
서비스 목록을 확인합니다.
ros2 service list
다음 서비스가 보여야 합니다.
/emergency_stop

서비스 타입을 확인합니다.
ros2 service type /emergency_stop
예상 출력은 다음과 같습니다.
my_first_package_msgs/srv/RobotCommand

인터페이스 구조를 확인합니다.
ros2 interface show my_first_package_msgs/srv/RobotCommand
예상 출력은 다음과 같습니다.
bool data
---
bool success
string message

CLI로 직접 호출할 수도 있습니다.
ros2 service call /emergency_stop my_first_package_msgs/srv/RobotCommand "{data: true}"
예상 응답은 다음과 비슷합니다.
response:
my_first_package_msgs.srv.RobotCommand_Response(
success=True,
message='Mobile robot emergency stop activated'
)

12. 최종 정리
서비스 서버의 핵심은 다음입니다.
this->create_service<my_first_package_msgs::srv::RobotCommand>(
"/emergency_stop",
...
);
if (request->data) {
response->success = true;
response->message = "Mobile robot emergency stop activated";
}
서비스 클라이언트 핵심은 다음입니다.
client_ = this->create_client<my_first_package_msgs::srv::RobotCommand>(
"/emergency_stop"
);
auto request =
std::make_shared<my_first_package_msgs::srv::RobotCommand::Request>();
request->data = true;
client_->wait_for_service(1s);
auto future = client_->async_send_request(request);
rclcpp::spin_until_future_complete(
this->get_node_base_interface(),
future
);
auto response = future.get();
모바일 로봇 기준으로 이런 C++ 서비스 구조는 다음 작업에 사용할 수 있습니다.
긴급정지 요청
모터 전원 ON/OFF
주행 허용/차단
초기화 요청
센서 점검 요청
맵 저장 요청
도킹 시작 요청
작업 시작/정지 요청
이번 예제에서는 실제 모터 제어 대신 로그와 응답 메시지만 처리했습니다.
실제 모바일 로봇에 적용할 때는 handle_emergency_stop() 내부에 모터 정지, 속도 명령 0 설정, 브레이크 활성화, 상태 전환 코드를 연결하면 됩니다.
'강좌 > ROS2' 카테고리의 다른 글
| ROS 2 개발자를 위한 C/C++ 기초강의 #1 (0) | 2026.05.25 |
|---|---|
| 로봇 개발자를 위한 Python 기초 교육 #3 (0) | 2026.05.25 |
| ROS 2 C++ Action Server / Client 실습 #1 (0) | 2026.05.24 |
| ROS 2 에서 CMakeLists.txt 이해하기 (0) | 2026.05.24 |
| ROS 2 Python 패키지의 setup.py 이해하기 (0) | 2026.05.24 |