节点之间通过服务通信时,发送请求的一端称之为客户端(Client),应答的一端称之为服务器(Server),请求和应答的数据结构使用srv文件描述。 接下来我们就尝试实现一个简单的服务通信模型,客户端发送两个加数,服务器完成加数求和之后应答求和结果。
1.创建功能包
在dev_ws工作空间的src文件夹下,使用如下命令创建一个新的功能包。
ros2 pkg create --build-type ament_cmake cpp_srvcli --dependencies rclcpp example_interfaces
终端中会看到创建 cpp_srvcli 功能包的验证信息。 –dependencies 参数会将后边的依赖自动添加到package.xml和CMakeLists.txt中,example_interfaces 功能包中提供了接下来要使用的srv文件,其中有对服务请求和应答数据的描述:
int64 a
int64 b
---
int64 sum
在以上描述中,—上边是两个加数,下边的是求和结果。 记得要修改下功能包中的package.xml文件中的功能包信息:
<description>C++ client server tutorial</description>
<maintainer email="you@email.com">Your Name</maintainer>
<license>Apache License 2.0</license>
2.创建服务节点
在 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函数的传入参数是服务的请求和应答数据,在其中实现请求数据的求和,然后把求和结果放到应答数据中,同时在终端中打印信息。
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();
}
在main函数中主要实现以下配置:
- 初始化ROS2的C++库
- 创建一个叫做add_two_ints_server的节点
- 创建一个叫做add_two_ints的服务,绑定add回调函数
- 打印日志信息
- 进入自旋锁,等待客户端请求
代码编写完成后,需要在CmakeList.txt中设置编译规则:
add_executable(server src/add_two_ints_server.cpp)
ament_target_dependencies(server
rclcpp example_interfaces)
还需要添加一个install的规则:
install(TARGETS
server
DESTINATION lib/${PROJECT_NAME})
3.创建客户端节点
在 dev_ws/src/cpp_srvcli/src 路径下,创建名为 add_two_ints_client.cpp 的文件,拷贝如下代码:
#include "rclcpp/rclcpp.hpp"
#include "example_interfaces/srv/add_two_ints.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]);
接下来创建一个请求数据,包括两个加数的数值。
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...");
}
通过while循环等待1秒钟时间,查看服务器端是否已经启动。
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");
}
等待服务器端的反馈,如果用户按下Ctrl+C,也会退出,并且打印一个错误信息。 代码完成后同样需要配置CMakeLists.txt,完整的CMakeLists.txt内容如下:
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()
4.编译运行
接下来先确认下所有的依赖是否都安装了。
rosdep install -i --from-path src --rosdistro foxy -y
然后在工作空间的根目录下执行如下编译命令
colcon build --packages-select cpp_srvcli
编译成功后就可以运行啦,先来运行服务器端
. install/setup.bash
ros2 run cpp_srvcli server
终端中可以看到提示信息: 再打开一个新终端,cd到dev_ws下,使用类似的指令运行客户端:
. install/setup.bash
ros2 run cpp_srvcli client 2 3
终端中可以看到: 服务器端的终端也会有日志: 以上我们就创建了两个节点实现了服务通信的功能。