引用在《ROS2 入门应用 创建自定义接口》中自定义的服务AddThreeInts.srv
ros2 interface show tutorial_interfaces/srv/AddThreeInts# int64 a
# int64 b
# int64 c
# ---
# int64 sum
需要对《ROS2 入门应用 请求和应答(C++)》中创建的服务端/客户端功能包稍作修改
cd ~/ros2_ws/src/cpp_srvcli/src
将把两个整数求和更改为三个整数求和
修改add_two_ints_server.cpp
服务端源文件,涉及服务类型变更和应用变化
#include "rclcpp/rclcpp.hpp"
#include "tutorial_interfaces/srv/add_three_ints.hpp" // CHANGE#include /* 求和函数 */
void add(const std::shared_ptr request, // CHANGEstd::shared_ptr response) // CHANGE
{/* 从请求中添加两个整数,并将总和提供给响应 */response->sum = request->a + request->b + request->c; // CHANGE/* 使用日志通知控制台其服务状态 */RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Incoming request\na: %ld" " b: %ld" " c: %ld", request->a, request->b, request->c); // CHANGERCLCPP_INFO(rclcpp::get_logger("rclcpp"), "sending back response: [%ld]", (long int)response->sum);
}int main(int argc, char **argv)
{/* 初始化ROS2 */rclcpp::init(argc, argv);/* 定义服务端节点add_three_ints_server */std::shared_ptr node = rclcpp::Node::make_shared("add_three_ints_server"); // CHANGE/* 创建服务名为add_three_ints,服务函数为add的service服务端 */rclcpp::Service::SharedPtr service = // CHANGEnode->create_service("add_three_ints", &add); // CHANGE/* 通知准备就绪 */RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Ready to add three ints."); // CHANGE/* 运行节点 */rclcpp::spin(node);/* 退出ROS2 */rclcpp::shutdown();
}
修改add_two_ints_client.cpp
客户端源文件,涉及服务类型变更和应用变化
#include "rclcpp/rclcpp.hpp"
#include "tutorial_interfaces/srv/add_three_ints.hpp" // CHANGE#include
#include
#include /* 方便表示时间 */
using namespace std::chrono_literals;int main(int argc, char **argv)
{/* 初始化ROS2 */rclcpp::init(argc, argv);/* 校验 */if (argc != 4) { // CHANGERCLCPP_INFO(rclcpp::get_logger("rclcpp"), "usage: add_three_ints_client X Y Z"); // CHANGEreturn 1;}/* 定义客户端节点add_three_ints_client*/std::shared_ptr node = rclcpp::Node::make_shared("add_three_ints_client"); // CHANGE/* 创建服务名为add_three_ints的client客户端 */rclcpp::Client::SharedPtr client = // CHANGEnode->create_client("add_three_ints"); // CHANGE/* 创建请求request */auto request = std::make_shared(); // CHANGErequest->a = atoll(argv[1]);request->b = atoll(argv[2]);request->c = atoll(argv[3]); // CHANGE/* 搜索服务节点,间隔1s */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_three_ints"); // CHANGE}/* 退出ROS2 */rclcpp::shutdown();return 0;
}
在package.xml
清单文件中,添加对自定义服务的依赖项的声明
tutorial_interfaces
在CMakeLists.txt
编译文件中
tutorial_interfaces
tutorial_interfaces
#...find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(tutorial_interfaces REQUIRED) # CHANGEadd_executable(server src/add_two_ints_server.cpp)
ament_target_dependencies(server rclcpp tutorial_interfaces) # CHANGEadd_executable(client src/add_two_ints_client.cpp)
ament_target_dependencies(client rclcpp tutorial_interfaces) # CHANGEinstall(TARGETSserverclientDESTINATION lib/${PROJECT_NAME})ament_package()
进入工作空间根目录
cd ~/ros2_ws
编译:
colcon build --packages-select cpp_srvcli
打开一个新终端,运行服务端节点:
ros2 run cpp_srvcli server# [INFO] [rclcpp]: Ready to add three ints.
打开一个新终端,运行客户端节点:
ros2 run cpp_srvcli client 1 2 3# [INFO] [rclcpp]: Sum: 6
谢谢