启动客户端发送两个数字,服务端接收到后将它们相加,再返回结果,客户端打印结果。
笔者使用了VSCode来编写代码,VSCode集成ROS的过程我不自己写,大家可以看看这位博主的博客,写的很好:【ROS】VSCODE + ROS 配置方法(保姆级教程,总结了多篇)
在创建好工作空间之后,在src右键选择Create Catkin Package,输入包名后,导入依赖的库:
roscpp rospy std_msgs message_generation message_runtime
在软件包中,新建srv文件夹,在里面新建文件addInt.srv,并进行编写:
int32 num1
int32 num2---
int32 sum
三横线上面是请求数据,下面是响应数据,中间用三个短横线隔开。
此时编译后,应该会在devel/include/包名下面看到生成的中间文件。
在src下创建接收方,发送方两个文件:publisher.cpp,subscriber.cpp,然后往里面编写代码。
#include "ros/ros.h"
#include "hw_server/addInt.h"
int main(int argc, char* argv[]){//防止中文乱码setlocale(LC_ALL,"");//初始化节点ros::init(argc,argv,"client");ros::NodeHandle nh;//创建客户端ros::ServiceClient sc = nh.serviceClient("addInt");//设置请求数据hw_server::addInt ai;ai.request.num1 = 5 ;ai.request.num2 = 10;//访问服务端bool res = sc.call(ai);if(res){ROS_INFO("请求结果%d",ai.response.sum);}else{ROS_INFO("请求失败!");return 1;}return 0;
}
#include "ros/ros.h"
#include "hw_server/addInt.h"
typedef hw_server::addInt::Request request;
typedef hw_server::addInt::Response response;
bool doReq(request& req, response& resp){resp.sum = req.num1 + req.num2;return 1;
}
int main(int argc, char* argv[]){setlocale(LC_ALL,"");ros::init(argc,argv,"server");ros::NodeHandle nh;//添加服务,使用回调函数处理请求。ros::ServiceServer ss = nh.advertiseService("addInt",doReq);ROS_INFO("服务已经启动....");ros::spin();return 0;
}
add_executable(server src/server.cpp)
add_executable(client src/client.cpp)
target_link_libraries(server${catkin_LIBRARIES}
)
target_link_libraries(client${catkin_LIBRARIES}
)
include_directories(
# include${catkin_INCLUDE_DIRS}
)
generate_messages(DEPENDENCIESstd_msgs
)
add_service_files(FILESaddInt.srv
)
编译后启动roscore,在工作空间下打开两个终端,分别输入以下两段:
source ./devel/setup.sh
rosrun 你的包名 server
source ./devel/setup.sh
rosrun 你的包名 client
就能够看到实现现象了。
本次实验进行了ROS的服务简单通讯,让我对通讯方式有了深刻认识。而且也进一步提升了我的ROS编程水平。
http://www.autolabor.com.cn/book/ROSTutorials
下一篇:在线考试系统设计