?
当节点使用服务进行通信时,发送数据请求的节点称为客户端节点,响应请求的节点称为服务节点。请求和响应的结构由.srv
文件确定。
这里使用的例子是一个简单的整数加法系统;一个节点请求两个整数之和,另一个节点响应结果。
导航到上一教程ros2_ws
中创建的目录。
回想一下,包应该在src
目录中创建,而不是在工作区的根目录中。导航到ros2_ws/src
并创建一个新包:
ros2 pkg create --build-type ament_cmake cpp_srvcli --dependencies rclcpp example_interfaces
cpp_srvcli
您的终端将返回一条消息,验证您的包及其所有必需文件和文件夹的创建。
该--dependencies
参数将自动将必要的依赖行添加到package.xml
和CMakeLists.txt
。?是包含.srv 文件的example_interfaces
包,您需要构建请求和响应:
int64 a
int64 b
---
int64 sum
前两行是请求的参数,破折号下面是响应。
package.xml
?由于您--dependencies
在包创建期间使用了该选项,因此无需手动将依赖项添加到package.xml
或CMakeLists.txt
。
不过,与往常一样,请确保将描述、维护者电子邮件和姓名以及许可证信息添加到package.xml
.
<description>C++ client server tutorial</description>
<maintainer email="you@email.com">Your Name</maintainer>
<license>Apache License 2.0</license>
在ros2_ws/src/cpp_srvcli/src
目录中,创建一个名为的新文件add_two_ints_server.cpp
,并将以下代码粘贴到其中:
#include "rclcpp/rclcpp.hpp"
#include "example_interfaces/srv/add_two_ints.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();
}
前两条#include
语句是您的包依赖项。
该add
函数将请求中的两个整数相加,并将总和提供给响应,同时使用日志通知控制台其状态。
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);
}
该main
函数逐行完成以下任务:
初始化 ROS 2 C++ 客户端库:
rclcpp::init(argc, argv);
创建一个名为 的节点add_two_ints_server
:
std::shared_ptr<rclcpp::Node> node = rclcpp::Node::make_shared("add_two_ints_server");
创建一个以add_two_ints
该节点命名的服务,并使用以下方法自动在网络上通告它&add
:
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);
该add_executable
宏生成一个可执行文件,您可以使用 运行。添加以下代码块以创建名为 的可执行文件:ros2?run
CMakeLists.txt
server
add_executable(server src/add_two_ints_server.cpp)
ament_target_dependencies(server
rclcpp example_interfaces)
因此可以找到可执行文件,将以下行添加到文件末尾之前:ros2?run
ament_package()
install(TARGETS
server
DESTINATION lib/${PROJECT_NAME})
您现在可以构建包,获取本地安装文件并运行它,但我们首先创建客户端节点,以便您可以看到完整的系统在工作。
在ros2_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");
接下来,创建请求。它的结构是由.srv
前面提到的文件定义的。
auto request = std::make_shared<example_interfaces::srv::AddTwoInts::Request>();
request->a = atoll(argv[1]);
request->b = atoll(argv[2]);
该while
循环给客户端 1 秒的时间来搜索网络中的服务节点。如果找不到,它将继续等待。
RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "service not available, waiting again...");
如果客户端被取消(例如,通过您进入Ctrl+C
终端),它将返回一条错误日志消息,表明它被中断。
RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "Interrupted while waiting for the service. Exiting.");
return 0;
然后客户端发送请求,节点旋转直到收到响应或失败。
返回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
在工作区的根目录 (?ros2_ws
) 中运行以检查是否缺少依赖项:
rosdep install -i --from-path src --rosdistro galactic -y
导航回工作区的根目录,ros2_ws
并构建新包:
colcon build --packages-select cpp_srvcli
打开一个新终端,导航到ros2_ws
并获取安装文件:
. install/setup.bash
现在运行服务节点:
ros2 run cpp_srvcli server
终端应返回以下消息,然后等待:
[INFO] [rclcpp]: Ready to add two ints.
打开另一个终端,再次从内部获取安装文件ros2_ws
。启动客户端节点,后跟任意两个以空格分隔的整数:
ros2 run cpp_srvcli client 2 3
例如,如果您选择2
和3
,客户端将收到如下响应:
[INFO] [rclcpp]: Sum: 5
返回到运行服务节点的终端。您将看到它在收到请求和收到的数据以及发回的响应时发布了日志消息:
[INFO] [rclcpp]: Incoming request
a: 2 b: 3
[INFO] [rclcpp]: sending back response: [5]
在服务器终端中输入Ctrl+C
以停止节点旋转。