1、创建目录、工具包
# 创建文件夹:工作空间、srcmkdir-p ros2_ws/src# 进入 srccdros2_ws/src# src 目录下:创建功能包ros2 pkg create demo_cpp_service --build-type ament_cmake --dependencies rclcpp std_msgs
2、创建srv文件:服务接口定义
# src目录下:创建 srv 目录mkdir-p demo_cpp_service/srv# src目录下:创建 .srv 服务文件touchdemo_cpp_service/srv/AddThreeInts.srv
# 请求部分(客户端发送)int64 a int64 b int64 c ---# 响应部分(服务端返回)int64sum
3、创建:客户端
// client.cpp #include "rclcpp/rclcpp.hpp" #include "demo_cpp_service/srv/add_three_ints.hpp" #include <chrono> #include <cstdlib> #include <memory> #include <thread> using namespace std::chrono_literals; int main(int argc, char **argv) { // 初始化 ROS 2 rclcpp::init(argc, argv); // 检查命令行参数:需要传入3个整数 if (argc != 4) { RCLCPP_ERROR( rclcpp::get_logger("client"), "用法: client A B C (A、B、C 为整数)" ); return 1; } // 将命令行参数转为整数 long a = std::stol(argv[1]); long b = std::stol(argv[2]); long c = std::stol(argv[3]); // 创建临时节点(用于发起服务请求) auto node = std::make_shared<rclcpp::Node>("add_three_ints_client"); // 创建客户端,连接到名为 "add_three_ints" 的服务 auto client = node->create_client<demo_cpp_service::srv::AddThreeInts>("add_three_ints"); // 等待服务可用(最多等待5秒) while (!client->wait_for_service(1s)) { if (!rclcpp::ok()) { RCLCPP_ERROR(node->get_logger(), "中断等待,服务不可用。"); return 1; } RCLCPP_INFO(node->get_logger(), "等待服务 'add_three_ints' 可用..."); } // 构造请求对象 auto request = std::make_shared<demo_cpp_service::srv::AddThreeInts::Request>(); request->a = a; request->b = b; request->c = c; // 异步发送请求 auto result_future = client->async_send_request(request); // 等待响应(最多10秒) if (rclcpp::spin_until_future_complete(node, result_future, 10s) == rclcpp::FutureReturnCode::SUCCESS) { // 获取响应结果 auto response = result_future.get(); RCLCPP_INFO( node->get_logger(), "服务返回结果: %ld + %ld + %ld = %ld", a, b, c, response->sum ); } else { RCLCPP_ERROR(node->get_logger(), "服务调用失败或超时。"); } rclcpp::shutdown(); return 0; }
4、创建:服务端
// server.cpp #include "rclcpp/rclcpp.hpp" // 包含我们自定义的服务类型头文件 #include "demo_cpp_service/srv/add_three_ints.hpp" #include <memory> // 服务回调函数:当客户端发起请求时被调用 void handle_add_three_ints( const std::shared_ptr<demo_cpp_service::srv::AddThreeInts::Request> request, std::shared_ptr<demo_cpp_service::srv::AddThreeInts::Response> response) { // 计算三个整数的和 response->sum = request->a + request->b + request->c; // 打印日志(可在终端看到) RCLCPP_INFO( rclcpp::get_logger("server"), "收到请求: %ld + %ld + %ld = %ld", request->a, request->b, request->c, response->sum ); } int main(int argc, char **argv) { // 初始化 ROS 2 rclcpp::init(argc, argv); // 创建一个节点 auto node = std::make_shared<rclcpp::Node>("add_three_ints_server"); // 创建服务 // 参数说明: // - 服务名称:"add_three_ints" // - 回调函数:handle_add_three_ints auto service = node->create_service<demo_cpp_service::srv::AddThreeInts>( "add_three_ints", &handle_add_three_ints ); RCLCPP_INFO(node->get_logger(), "服务 'add_three_ints' 已启动,等待请求..."); // 进入事件循环,等待客户端请求 rclcpp::spin(node); // 关闭 ROS 2 rclcpp::shutdown(); return 0; }
5、修改:CMakeLists.txt 文件
cmake_minimum_required(VERSION3.8)project(demo_cpp_service)if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES"Clang")add_compile_options(-Wall -Wextra -Wpedantic)endif()# 查找依赖find_package(ament_cmake REQUIRED)find_package(rclcpp REQUIRED)find_package(rosidl_default_generators REQUIRED)# 声明服务文件rosidl_generate_interfaces(${PROJECT_NAME}"srv/AddThreeInts.srv"# 你的服务文件路径DEPENDENCIES# 如果服务依赖其他接口(如std_msgs),这里添加,无则留空)# 编译服务器/客户端节点add_executable(server src/server.cpp)ament_target_dependencies(server rclcpp)# 链接接口库(关键:让节点能访问生成的服务接口)rosidl_get_typesupport_target(cpp_typesupport_target${PROJECT_NAME}rosidl_typesupport_cpp)target_link_libraries(server"${cpp_typesupport_target}")add_executable(client src/client.cpp)ament_target_dependencies(client rclcpp)rosidl_get_typesupport_target(cpp_typesupport_target${PROJECT_NAME}rosidl_typesupport_cpp)target_link_libraries(client"${cpp_typesupport_target}")# 安装可执行文件install(TARGETS server client DESTINATION lib/${PROJECT_NAME})if(BUILD_TESTING)find_package(ament_lint_auto REQUIRED)ament_lint_auto_find_test_dependencies()endif()ament_package()
6、修改:package.xml 文件
<?xml version="1.0"?><?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?><packageformat="3"><name>demo_cpp_service</name><version>0.0.0</version><description>ROS2 C++ service demo</description><maintaineremail="rabbit@example.com">rabbit</maintainer><license>Apache-2.0</license><!-- 原有依赖 --><buildtool_depend>ament_cmake</buildtool_depend><buildtool_depend>rosidl_default_generators</buildtool_depend><depend>rclcpp</depend><depend>rosidl_default_runtime</depend><member_of_group>rosidl_interface_packages</member_of_group><!-- 新增这行 --><test_depend>ament_lint_auto</test_depend><test_depend>ament_lint_common</test_depend><export><build_type>ament_cmake</build_type></export></package>
7、colcon build 编译
# 回到工作目录执行:ros2_wscolcon build --packages-select demo_cpp_service
sourceinstall/setup.bash ros2 run demo_cpp_service server
sourceinstall/setup.bash ros2 run demo_cpp_service client102030