文章目录
- 1.服务通信的概念及应用场景
- 1.1概念
- 1.2 应用场景
- 2.准备工作
- 3.服务通信的实现
- 3.1 服务通信接口消息
- 3.2 服务端实现
- 3.3 客户端实现
- 3.4 编译及运行
- 3.4.1 修改CMakeLists
- 3.4.2 服务端运行结果
- 3.4.2 客户端运行结果
1.服务通信的概念及应用场景
1.1概念
服务通信也是ROS中一种极其常用的通信模式,服务通信是基于请求响应模式的,是一种应答机制。也即:一个节点A向另一个节点B发送请求,B接收处理请求并产生响应结果返回给A。
服务端只能有一个,客户端可以有多个:
1.2 应用场景
机器人巡逻过程中,控制系统分析传感器数据发现可疑物体或人… 此时需要拍摄照片并留存。
也就是数据分析节点A需要向相机相关节点B发送图片存储请求,节点B处理请求,并返回处理结果。
2.准备工作
3.服务通信的实现
3.1 服务通信接口消息
定义服务接口消息与定义话题接口消息流程类似,主要步骤如下:
①创建并编辑 .srv文件;
②编辑配置文件;
③编译;
④测试。
3.2 服务端实现
// 1.包含头文件
#include "rclcpp/rclcpp.hpp"
#include "base_interfaces_demo/srv/add_ints.hpp"
using base_interfaces_demo::srv::AddInts;
using std::placeholders::_1;
using std::placeholders::_2;// 3.定义节点类;
class MinimalService: public rclcpp::Node{ public: MinimalService():Node("minimal_service"){ // 3-1.创建服务端; server = this->create_service<AddInts>("add_ints", std::bind(&MinimalService::add, this, _1, _2));RCLCPP_INFO(this->get_logger(),"add_ints 服务端启动完毕,等待请求提交..."); } private: rclcpp::Service<AddInts>::SharedPtr server; // 3-2.处理请求数据并响应结果。 void add(const AddInts::Request::SharedPtr req, const AddInts::Response::SharedPtr res){ res->sum = req->num1 + req->num2; RCLCPP_INFO(this->get_logger(),"请求数据:(%d,%d),响应结果:%d", req->num1, req->num2, res->sum); }
};int main(int argc, char const *argv[])
{ // 2.初始化 ROS2 客户端; rclcpp::init(argc,argv); // 4.调用spin函数,并传入节点对象指针; auto server = std::make_shared<MinimalService>(); rclcpp::spin(server); // 5.释放资源。 rclcpp::shutdown(); return 0;
}
代码分析:
3.3 客户端实现
// 1.包含头文件;
#include "rclcpp/rclcpp.hpp"
#include "base_interfaces_demo/srv/add_ints.hpp"
using base_interfaces_demo::srv::AddInts;using namespace std::chrono_literals;
// 3.定义节点类;
class MinimalClient: public rclcpp::Node{
public:
MinimalClient():Node("minimal_client"){
// 3-1.创建客户端;
client = this->create_client<AddInts>("add_ints");
RCLCPP_INFO(this->get_logger(),"客户端创建, 等待连接服务端! ");
}
// 3-2.等待服务连接;
bool connect_server(){
while (!client->wait_for_service(1s))
{
if (!rclcpp::ok())
{
RCLCPP_INFO(rclcpp::get_logger("rclcpp"),"强制退出! ");
return false;
}
RCLCPP_INFO(this->get_logger(),"服务连接中, 请稍候...");
}
return true;
}
// 3-3.组织请求数据并发送;
rclcpp::Client<AddInts>::FutureAndRequestId send_request(int32_t num1, int32_t num2){
auto request = std::make_shared<AddInts::Request>();
request->num1 = num1;
request->num2 = num2;
return client->async_send_request(request);
}
private:
rclcpp::Client<AddInts>::SharedPtr client;
};
int main(int argc, char ** argv){
if (argc != 3){
RCLCPP_INFO(rclcpp::get_logger("rclcpp"),"请提交两个整型数据! ");
return 1;
}
// 2.初始化 ROS2 客户端;
rclcpp::init(argc,argv);
// 4.创建对象指针并调用其功能;
auto client = std::make_shared<MinimalClient>();
bool flag = client->connect_server();
if (!flag)
{
RCLCPP_INFO(rclcpp::get_logger("rclcpp"),"服务连接失败! ");
return 0;
}
auto response = client->send_request(atoi(argv[1]),atoi(argv[2]));
// 处理响应
if (rclcpp::spin_until_future_complete(client,response) ==
rclcpp::FutureReturnCode::SUCCESS)
{
RCLCPP_INFO(client->get_logger(),"请求正常处理");
RCLCPP_INFO(client->get_logger(),"响应结果:%d!", response.get()->sum);
}
else {
RCLCPP_INFO(client->get_logger(),"请求异常");
}
// 5.释放资源。
rclcpp::shutdown();
return 0;
}
代码分析:
3.4 编译及运行
3.4.1 修改CMakeLists
别忘了修改CMakeLists文件
3.4.2 服务端运行结果
3.4.2 客户端运行结果
提示:这里对文章进行总结: