编写一个简单的服务和客户端(C++) [4887]
目标: 使用C++创建和运行服务和客户端节点。 [4888]
教程级别: 初学者 [3951]
内容 [16422]
背景 [16410]
当使用:doc:services <../Beginner-CLI-Tools/Understanding-ROS2-Services/Understanding-ROS2-Services>`的方式进行通信时,发送请求数据的节点称为客户端节点,而响应请求的节点则是服务节点。请求和响应的结构由`
.srv``文件确定。 [4889]
这里使用的示例是一个简单的整数加法系统;一个节点请求两个整数的和,另一个节点返回结果。 [4890]
任务 [16427]
1 创建一个包 [3283]
在一个新的终端中 源化你的 ROS 2 安装,这样 ros2
命令才能正常工作。 [16429]
进入在 上一个教程 中创建的 ros2_ws
目录。 [4837]
请记住,包应该在“src”目录中创建,而不是工作区的根目录。进入“ros2_ws/src”并创建一个新的包: [4776]
ros2 pkg create --build-type ament_cmake cpp_srvcli --dependencies rclcpp example_interfaces
您的终端将返回一个消息,验证您的包``cpp_srvcli``及其所有必要的文件和文件夹的创建。 [4891]
``--dependencies``参数将自动向``package.xml``和``CMakeLists.txt``中添加必要的依赖项。``example_interfaces``是包含你需要构造请求和响应的`.srv文件 <https://github.com/ros2/example_interfaces/blob/humble/srv/AddTwoInts.srv>`__的包: [4892]
int64 a
int64 b
---
int64 sum
前两行是请求的参数,在破折号以下是响应。 [4893]
1.1 更新 package.xml
[16432]
因为您在包创建过程中使用了“--dependencies”选项,所以无需手动添加依赖项到“package.xml”或“CMakeLists.txt”中。 [4779]
同样,确保将描述、维护者电子邮件和姓名以及许可证信息添加到 package.xml
中。 [4780]
<description>C++ client server tutorial</description>
<maintainer email="you@email.com">Your Name</maintainer>
<license>Apache License 2.0</license>
2 编写服务节点 [4894]
在``ros2_ws/src/cpp_srvcli/src``目录中,创建一个名为``add_two_ints_server.cpp``的新文件,并粘贴以下代码: [4895]
#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();
}
2.1 检查代码 [16436]
前两个``#include``语句是你的包依赖项。 [4896]
``add``函数从请求中添加两个整数,并将和发送到响应中,同时使用日志通知控制台其状态。 [4897]
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);
}
初始化ROS 2 C++客户端库: [4899]
rclcpp::init(argc, argv);
创建一个名为``add_two_ints_server``的节点: [4900]
std::shared_ptr<rclcpp::Node> node = rclcpp::Node::make_shared("add_two_ints_server");
为该节点创建一个名为``add_two_ints``的服务,并使用``&add``方法自动在网络上进行广告发布: [4901]
rclcpp::Service<example_interfaces::srv::AddTwoInts>::SharedPtr service = node->create_service<example_interfaces::srv::AddTwoInts>("add_two_ints", &add);
当准备好时打印一条日志消息: [4902]
RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Ready to add two ints.");
旋转节点,使服务可用。 [4903]
rclcpp::spin(node);
2.2 添加可执行文件 [16446]
``add_executable``宏会生成一个可通过``ros2 run``运行的可执行文件。将以下代码块添加到``CMakeLists.txt``中以创建一个名为``server``的可执行文件: [4904]
add_executable(server src/add_two_ints_server.cpp)
ament_target_dependencies(server rclcpp example_interfaces)
为了使``ros2 run``能够找到可执行文件,请在文件末尾,在``ament_package()``之前添加以下行: [4905]
install(TARGETS
server
DESTINATION lib/${PROJECT_NAME})
现在,您可以构建软件包、源化本地设置文件并运行它,但是让我们先创建客户端节点,以便您可以看到整个系统的运行情况。 [4906]
3.编写客户端节点 [4907]
在``ros2_ws/src/cpp_srvcli/src``目录中,创建一个名为``add_two_ints_client.cpp``的新文件,并将以下代码粘贴到其中: [4908]
#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;
}
3.1 检查代码 [4869]
与服务节点类似,以下代码行创建节点,然后为该节点创建客户端: [4909]
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``文件定义。 [4910]
auto request = std::make_shared<example_interfaces::srv::AddTwoInts::Request>();
request->a = atoll(argv[1]);
request->b = atoll(argv[2]);
``while``循环给客户端1秒的时间在网络中搜索服务节点。如果找不到任何节点,将继续等待。 [4911]
RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "service not available, waiting again...");
如果客户端被取消(例如你在终端中输入``Ctrl+C``),它将返回一个错误日志消息,说明它被中断了。 [4912]
RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "Interrupted while waiting for the service. Exiting.");
然后客户端发送请求,节点会一直等待直到接收到响应或失败。 [4913]
3.2 添加可执行文件 [4914]
返回到``CMakeLists.txt``,为新节点添加可执行文件和目标。在自动生成的文件中删除一些不必要的样板代码后,你的``CMakeLists.txt``应该如下所示: [4915]
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()
4 构建和运行 [16752]
在构建之前,最好在工作空间的根目录(ros2_ws
)中运行``rosdep``来检查是否缺少依赖项: [4791]
rosdep install -i --from-path src --rosdistro humble -y
rosdep 只能在 Linux 上运行,所以您可以跳过下一步。 [4792]
rosdep 只能在 Linux 上运行,所以您可以跳过下一步。 [4792]
返回到您的工作空间的根目录 ros2_ws
,并构建您的新包: [4793]
colcon build --packages-select cpp_srvcli
colcon build --packages-select cpp_srvcli
colcon build --merge-install --packages-select cpp_srvcli
打开一个新的终端,导航到 ros2_ws
,并加载设置文件: [4794]
source install/setup.bash
. install/setup.bash
call install/setup.bat
现在运行服务节点: [4916]
ros2 run cpp_srvcli server
终端应该返回以下消息,然后等待: [4917]
[INFO] [rclcpp]: Ready to add two ints.
打开另一个终端,再次在``ros2_ws``目录内源化设置文件。启动客户端节点,然后输入两个整数,用空格分隔: [4918]
ros2 run cpp_srvcli client 2 3
例如,如果你选择了``2``和``3``,客户端将会收到如下响应: [4919]
[INFO] [rclcpp]: Sum: 5
返回运行服务节点的终端。您将看到当服务节点收到请求、接收到的数据以及发送回的响应时,它会发布日志消息: [4920]
[INFO] [rclcpp]: Incoming request
a: 2 b: 3
[INFO] [rclcpp]: sending back response: [5]
在服务器终端中输入``Ctrl+C``以停止节点的运行。 [4921]