서비스에서 데이터를 요청하는 노드를 클라이언트 노드라 부르고, 그 요청에 응답하는 노드는 서비스 노드라 부른다.
요청과 응답 메시지의 구조는 .srv
파일에 의해 결정된다.
두 정수를 더한 값을 전해주는 간단한 서비스를 만들어 보자.
기존의 dev_ws
를 계속해서 사용한다.
dev_ws/src
로 이동한 후 패키지를 생성하자.
ros2 pkg create --build-type ament_cmake cpp_srvcli --dependencies rclcpp example_interfaces
인자 dependencies
는 필요한 의존성을 package.xml
과 CMakeLists.txt
에 자동으로 추가해 준다.
example_interfaces
는 요청과 응답 메시지의 구조에 필요한 .srv
파일을 포함하고 있는 패키지다.
int64 a
int64 b
---
int64 sum
구분 선 ---
위쪽은 요청 메시지의 구조, 아래는 응답 메시지의 구조이다.
package.xml
업데이트--dependencies
를 통해 의존성을 추가했기 때문에 수동으로 package.xml
을 건들 필요는 없다.
<description>
과 <maintainer>
, <license>
부분만 수정하자.
<description>C++ client server tutorial</description>
<maintainer email="you@email.com">Your Name</maintainer>
<license>Apache License 2.0</license>
dev_ws/src/cpp_srvcli/src
디렉터리에 add_two_ints_server.cpp
파일을 생성하고 다음을 붙여 넣자.
#include "example_interfaces/srv/add_two_ints.hpp"
#include "rclcpp/rclcpp.hpp"
#include <memory>
void add(
const std::shared_ptr<example_interfaces::srv::AddTwoInts::Request> request,
std::shared_ptr<example_interfaces::srv::AddTwoInts::Response> response) {
response->sum = request->a + request->b;
RCLCPP_INFO(rclcpp::get_logger("rclcpp"),
"Incoming request\na: %ld"
" b: %ld",
request->a, request->b);
RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "sending back response: [%ld]",
(long int)response->sum);
}
int main(int argc, char** argv) {
rclcpp::init(argc, argv);
std::shared_ptr<rclcpp::Node> node =
rclcpp::Node::make_shared("add_two_ints_server");
rclcpp::Service<example_interfaces::srv::AddTwoInts>::SharedPtr service =
node->create_service<example_interfaces::srv::AddTwoInts>(
"add_two_ints", &add);
RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Ready to add two ints.");
rclcpp::spin(node);
rclcpp::shutdown();
}
void add(
const std::shared_ptr<example_interfaces::srv::AddTwoInts::Request> request,
std::shared_ptr<example_interfaces::srv::AddTwoInts::Response> response) {
response->sum = request->a + request->b;
RCLCPP_INFO(rclcpp::get_logger("rclcpp"),
"Incoming request\na: %ld"
" b: %ld",
request->a, request->b);
RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "sending back response: [%ld]",
(long int)response->sum);
}
add
함수는 request
로부터 2개의 정수를 받아 reponse
의 sum
에 전달하고, 매크로 함수 RCLCPP_INFO
를 통해 콘솔에 출력해 준다.
int main(int argc, char** argv) {
rclcpp::init(argc, argv);
std::shared_ptr<rclcpp::Node> node =
rclcpp::Node::make_shared("add_two_ints_server");
rclcpp::Service<example_interfaces::srv::AddTwoInts>::SharedPtr service =
node->create_service<example_interfaces::srv::AddTwoInts>(
"add_two_ints", &add);
RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Ready to add two ints.");
rclcpp::spin(node);
rclcpp::shutdown();
}
rclcpp::init(argc, argv);
ROS 2 클라이언트 라이브러리를 초기화 한다.
std::shared_ptr<rclcpp::Node> node = rclcpp::Node::make_shared("add_two_ints_server");
add_two_ints_server
이름을 갖는 노드를 생성한다.
rclcpp::Service<example_interfaces::srv::AddTwoInts>::SharedPtr service =
node->create_service<example_interfaces::srv::AddTwoInts>("add_two_ints", &add);
add_two_ints
이름을 갖는 서비스를 생성하고 &add
를 통해 add
함수와 연결한다.
RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Ready to add two ints.");
준비가 끝나면 로그 메시지를 출력한다.
rclcpp::spin(node);
노드를 실행하고 서비스를 활성화한다.
add_executable
매크로는 ros2 run
명령을 실행하기 위한 실행 파일을 생성해 준다.
CMakeLists.txt
에 다음 코드를 추가하자.
add_executable(server src/add_two_ints_server.cpp)
ament_target_dependencies(server
rclcpp example_interfaces)
파일의 끝에 있는 ament_package()
직전에 다음을 추가하자.
install(TARGETS
server
DESTINATION lib/${PROJECT_NAME})
이제 빌드 할 수 있지만, 클라이언트 코드를 마저 작성하고 빌드 하자.
서비스 노드처럼 해당 디렉터리에 add_two_ints_client.cpp
를 생성하고 다음을 붙여 넣자.
#include "example_interfaces/srv/add_two_ints.hpp"
#include "rclcpp/rclcpp.hpp"
#include <chrono>
#include <cstdlib>
#include <memory>
using namespace std::chrono_literals;
int main(int argc, char** argv) {
rclcpp::init(argc, argv);
if (argc != 3) {
RCLCPP_INFO(rclcpp::get_logger("rclcpp"),
"usage: add_two_ints_client X Y");
return 1;
}
std::shared_ptr<rclcpp::Node> node =
rclcpp::Node::make_shared("add_two_ints_client");
rclcpp::Client<example_interfaces::srv::AddTwoInts>::SharedPtr client =
node->create_client<example_interfaces::srv::AddTwoInts>(
"add_two_ints");
auto request =
std::make_shared<example_interfaces::srv::AddTwoInts::Request>();
request->a = atoll(argv[1]);
request->b = atoll(argv[2]);
while (!client->wait_for_service(1s)) {
if (!rclcpp::ok()) {
RCLCPP_ERROR(rclcpp::get_logger("rclcpp"),
"Interrupted while waiting for the service. Exiting.");
return 0;
}
RCLCPP_INFO(rclcpp::get_logger("rclcpp"),
"service not available, waiting again...");
}
auto result = client->async_send_request(request);
// Wait for the result.
if (rclcpp::spin_until_future_complete(node, result) ==
rclcpp::FutureReturnCode::SUCCESS) {
RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Sum: %ld",
result.get()->sum);
} else {
RCLCPP_ERROR(rclcpp::get_logger("rclcpp"),
"Failed to call service add_two_ints");
}
rclcpp::shutdown();
return 0;
}
std::shared_ptr<rclcpp::Node> node =
rclcpp::Node::make_shared("add_two_ints_client");
rclcpp::Client<example_interfaces::srv::AddTwoInts>::SharedPtr client =
node->create_client<example_interfaces::srv::AddTwoInts>(
"add_two_ints");
서비스 노드와 비슷하게, 클라이언트 노드를 생성한다.
auto request = std::make_shared<example_interfaces::srv::AddTwoInts::Request>();
request->a = atoll(argv[1]);
request->b = atoll(argv[2]);
그다음 .srv
파일에 정의된 구조에 맞추어 요청 메시지의 구조를 만든다.
RCLCPP_INFO(rclcpp::get_logger("rclcpp"),
"service not available, waiting again...");
while
문은 1 초마다 서비스 노드를 찾을 때까지 서비스 노드를 기다린다.
if (!rclcpp::ok()) {
RCLCPP_ERROR(rclcpp::get_logger("rclcpp"),
"Interrupted while waiting for the service. Exiting.");
return 0;
}
클라이언트가 취소하면(eg. Ctrl + C
인터럽트) 인터럽트가 발생했다는 오류 메시지가 출력된다.
CMakeLists.txt
을 열어 클라이언트 노드를 추가하자. 최종적인 CMakeLists.txt
파일은 다음과 같을 것이다.
cmake_minimum_required(VERSION 3.5)
project(cpp_srvcli)
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(example_interfaces REQUIRED)
add_executable(server src/add_two_ints_server.cpp)
ament_target_dependencies(server
rclcpp example_interfaces)
add_executable(client src/add_two_ints_client.cpp)
ament_target_dependencies(client
rclcpp example_interfaces)
install(TARGETS
server
client
DESTINATION lib/${PROJECT_NAME})
ament_package()
rosdep
으로 의존성을 확인하자.
rosdep install -i --from-path src --rosdistro foxy -y
워크스페이스의 루트 디렉터리로 이동 후 빌드를 시작하자.
colcon build --packages-select cpp_srvcli
새 터미널을 열고 설정 파일을 소싱하자.
. install/setup.bash
서버 노드를 실행하자.
ros2 run cpp_srvcli server
새 터미널을 열고 같은 작업을 클라이언트 노드에 대해 실행하자.
. install/setup.bash
ros2 run cpp_srvcli client 11 22