1.创建服务提供者service_server_01.cpp
#include "example_interfaces/srv/add_two_ints.hpp"
#include "rclcpp/rclcpp.hpp"
class ServiceServer01 : public rclcpp::Node {
public:
ServiceServer01(std::string name) : Node(name) {
RCLCPP_INFO(this->get_logger(), "节点已启动:%s.", name.c_str());
// 创建服务
add_ints_server_ =
this->create_service<example_interfaces::srv::AddTwoInts>(
"add_two_ints_srv",
std::bind(&ServiceServer01::handle_add_two_ints, this,
std::placeholders::_1, std::placeholders::_2));
}
private:
// 声明一个服务
rclcpp::Service<example_interfaces::srv::AddTwoInts>::SharedPtr
add_ints_server_;
// 收到请求的处理函数
void handle_add_two_ints(
const std::shared_ptr<example_interfaces::srv::AddTwoInts::Request> request,
std::shared_ptr<example_interfaces::srv::AddTwoInts::Response> response) {
RCLCPP_INFO(this->get_logger(), "收到a: %ld b: %ld", request->a,
request->b);
response->sum = request->a + request->b;
};
};
int main(int argc, char** argv) {
rclcpp::init(argc, argv);
auto node = std::make_shared<ServiceServer01>("service_server_01");
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}
2.创建服务消费者service_client_01.cpp
#include "rclcpp/rclcpp.hpp"
#include "example_interfaces/srv/add_two_ints.hpp"
class ServiceClient01 : public rclcpp::Node {
public:
// 构造函数,有一个参数为节点名称
ServiceClient01(std::string name) : Node(name) {
RCLCPP_INFO(this->get_logger(), "节点已启动:%s.", name.c_str());
// 创建客户端
client_ = this->create_client<example_interfaces::srv::AddTwoInts>("add_two_ints_srv");
}
void send_request(int a, int b) {
RCLCPP_INFO(this->get_logger(), "计算%d+%d", a, b);
// 1.等待服务端上线
while (!client_->wait_for_service(std::chrono::seconds(1))) {
//等待时检测rclcpp的状态
if (!rclcpp::ok()) {
RCLCPP_ERROR(this->get_logger(), "等待服务的过程中被打断...");
return;
}
RCLCPP_INFO(this->get_logger(), "等待服务端上线中");
}
// 2.构造请求的
auto request =
std::make_shared<example_interfaces::srv::AddTwoInts_Request>();
request->a = a;
request->b = b;
// 3.发送异步请求,然后等待返回,返回时调用回调函数
client_->async_send_request(
request, std::bind(&ServiceClient01::result_callback_, this,
std::placeholders::_1));
};
private:
// 声明客户端
rclcpp::Client<example_interfaces::srv::AddTwoInts>::SharedPtr client_;
void result_callback_(
rclcpp::Client<example_interfaces::srv::AddTwoInts>::SharedFuture
result_future) {
auto response = result_future.get();
RCLCPP_INFO(this->get_logger(), "计算结果:%ld", response->sum);
}
};
int main(int argc, char** argv) {
rclcpp::init(argc, argv);
/*创建对应节点的共享指针对象*/
auto node = std::make_shared<ServiceClient01>("service_client_01");
/* 运行节点,并检测退出信号*/
//增加这一行,node->send_request(5, 6);,计算5+6结果
node->send_request(5, 6);
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}
3.初始化链接应用
导入接口的三个步骤不知道你是否还记得。
ament_cmake类型功能包导入消息接口分为三步:
在CMakeLists.txt中导入,具体是先find_packages再ament_target_dependencies。
在packages.xml中导入,具体是添加depend标签并将消息接口写入。
在代码中导入,C++中是#include"消息功能包/xxx/xxx.hpp"。
CMakeLists.txt
find_package(example_interfaces REQUIRED)
add_executable(service_client_01 src/service_client_01.cpp)
ament_target_dependencies(service_client_01 rclcpp example_interfaces)
add_executable(service_server_01 src/service_server_01.cpp)
ament_target_dependencies(service_server_01 rclcpp example_interfaces)
install(TARGETS
service_server_01
service_client_01
DESTINATION lib/${PROJECT_NAME}
)
packages.xml
<depend>example_interfaces</depend>
4.编译、运行应用
cd chapt3/chapt3_ws/
colcon build --packages-select example_service_rclcpp
# 运行 service_server_01
source install/setup.bash
ros2 run example_service_rclcpp service_server_01
# 打开新终端运行 service_client_01
source install/setup.bash
ros2 run example_service_rclcpp service_client_01
5.两数相加我们需要利用ROS2自带的example_interfaces
接口,使用命令行可以查看这个接口的定义
ros2 interface show example_interfaces/srv/AddTwoInts
# 查看声明的服务
ros2 service list
# 使用命令行调用服务两数之和接口
ros2 service call /add_two_ints_srv example_interfaces/srv/AddTwoInts "{a: 5,b: 10}"