服务通信的目的
1, 服务通信,可以用最简单的一张图来表示:
2, 用最简单的话来说,就是,你问,我答。
3, 应用场景, 比如人脸识别,你给我一张脸的图片,我识别出人脸后给你反馈。
ROS中服务通信的实现
1, 那么,当一个复杂的系统,需要进行话题通信时,需要进行管理.就像银行的咨询处。银行的每个专员(Server)都有一个窗口号,假设每个窗口办理的业务都不一样,每个专员都把自己服务内容(服务名)告诉(注册)给咨询处, 包括窗口号。当用户(client)来银行办理业务时,首先去咨询处询问某个业务去哪办理,咨询处进行服务查询,咨询处告诉(Server)某个客户(client)需要向他办理业务,然后(client)去某某窗口(建立连接), 然后(client)开始和(Server)进行你问我答。
ROS中的实现
1, 注册Server(RPC);
2, 注册Client(RPC);
3, ROS Master查找Server,并发送Client的TCP信息。(RPC);
4, Server接受到之后,用Tcp与Client建立连接(TCP);
5, 开始执行服务功能(TCP)。
注: 如果不明白什么是RPC通信和TCP通信,请自行百度.
代码实现
创建自定义服务
1, 在src同级目录, 创建srv文件夹.
2, 在srv文件夹中新建calRectArea.srv文件.并粘贴以下代码
float32 w #请求
float32 h
---
float32 s #回复
3, 修改CMakeLists.txt文件.
find_package处添加:
find_package(catkin REQUIRED COMPONENTS
roscpp
std_msgs
message_generation #自定义消息类型依赖 自定义重点
)
add_service_files处添加:
add_service_files(
FILES
calRectArea.srv
)
generate_messages处添加
generate_messages(
DEPENDENCIES
std_msgs #自定义重点
)
catkin_package处添加
catkin_package(
INCLUDE_DIRS include
LIBRARIES ros_test
CATKIN_DEPENDS roscpp std_msgs message_runtime #自定义重点
DEPENDS system_lib
)
4, 在package.xml的<-package>节点中添加, 用于自动生成服务.
<!--自定义消息类型,功能包依赖-->
<build_depend>message_generation</build_depend>
<exec_depend>message_runtime</exec_depend>
5, 在vscode的终端中使用catkin_make
,生成calRectArea服务.生成完成后, 可以在devel/include/ros_test
文件夹下, 查看生成的calRectAreaRequest.h
和calRectAreaResponse.h
文件.
创建Server和Client
1, 在src文件夹下创建, calRectAreaReq.cpp和calRectAreaRes.cpp两个文件.
2, 在calRectAreaReq.cpp(client)文件中粘贴以下代码:
#include <cstdlib>
#include "ros/ros.h"
#include "ros_test/calRectArea.h" //在devel的include文件夹中生成
#include <iostream>
int main(int argc, char **argv)
{
//ros中文支持
setlocale(LC_ALL, "");
// ROS节点初始化
ros::init(argc, argv, "rectAreaClient");
// 创建节点句柄
ros::NodeHandle n;
// 创建一个client,请求rectArea service
// service消息类型是ros_test::calRectArea
ros::ServiceClient client = n.serviceClient<ros_test::calRectArea>("rectArea");
// 创建ros_test::calRectArea类型的service消息
ros_test::calRectArea srv;
ros::Rate rate(10);
while (ros::ok())
{
float w = 0.0f;
float h = 0.0f;
ROS_INFO("请输入w");
std::cin>>w;
ROS_INFO("请输入h");
std::cin>>h;
ROS_INFO("w=%f,h=%f",w,h);
// 发布service请求,等待运算的应答结果
srv.request.w = w;
srv.request.h = h;
if (client.call(srv))
{
ROS_INFO("面积: %f", srv.response.s);
}
else
{
ROS_ERROR("Failed");
return 1;
}
ros::spinOnce();
rate.sleep();
}
return 0;
}
3, 在calRectAreaRes.cpp(server)文件中粘贴以下代码:
#include "ros/ros.h"
#include "ros_test/calRectArea.h" //在devel的include文件夹中生成
bool calArea(ros_test::calRectArea::Request &req,
ros_test::calRectArea::Response &res)
{
res.s = req.w * req.h;
ROS_INFO("接受到一个请求,面积[%f]",res.s);
return true;
}
int main(int argc, char **argv)
{
//ros中文支持
setlocale(LC_ALL, "");
// ROS节点初始化
ros::init(argc,argv,"rectAreaSrv");
// 创建节点句柄
ros::NodeHandle n;
// 创建一个名为rectArea的server,注册回调函数calArea()
ros::ServiceServer service = n.advertiseService("rectArea",calArea);
// 循环等待回调函数
ROS_INFO("Ready...");
ros::spin();
return 0;
}
4, 具体释义, 请查看注释.
5, 修改CMakeLists.txt文件,(末尾添加)
add_executable(calRectAreaRes src/calRectAreaRes.cpp)
target_link_libraries(calRectAreaRes ${catkin_LIBRARIES})
add_dependencies(calRectAreaRes ${PROJECT_NAME}_gen_cpp) #包含自定义服务类型 自定义重点
add_executable(calRectAreaReq src/calRectAreaReq.cpp)
target_link_libraries(calRectAreaReq ${catkin_LIBRARIES})
add_dependencies(calRectAreaReq ${PROJECT_NAME}_gen_cpp) #包含自定义服务类型 自定义重点
编译和运行
在vscode的终端中使用catkin_make
,编译整个工程, 使用快捷键Ctrl + Shift + T , 弹出系统终端, 启动roscore, 运行calRectAreaRes和calRectAreaReq节点, 测试结果:
获取源码
公-众-号搜索 ”机器人小站"。后台回复 190918R即可.