[ROS] [笔记(2)] 第二个例子:Check Robot(服务、服务器与客户端)
本例程包含如下内容:
1)自定义服务;
2)服务器与客户端;
3)launch 文件。
0、Check Robot 的场景:
我们想要完成这样一个场景:
1)因为机器人有好有坏,因此有一个服务 checkRobotSrv ,这一服务就是你告诉它 Robot 的 name 和 id 它会告诉你这个 robot 是好是坏。
2)该管理员调用 checkRobotSrv 服务来检查 Robot 是好(Good Robot)还是坏(Bad Robot)并且输出。
可以看到上面的1)和2)都是我们在 Hello Robot 教程 里面完成的工作。
要完成以上的功能,我们需要创建消息(robotID)、发送消息的发送者(publisher)、接收消息的订阅者(subscriber),这些工作我们在 Hello Robot 中已经完成了。为了实现 check robot 服务,我们还需要创建服务(checkRobotSrv)、服务器(server)、客户端(client)。
1、创建 workspace 和 package:
1)进入 例子:Hello Robot 中创建的 hellorobot_ws :
1 | cd hellorobot_ws/src |
2)创建 package:
我们在该 hellorobot_ws 下创建一个名为 checkrobot 的 package:
1 | catkin_create_pkg checkrobot std_msgs rospy roscpp |
这里面 std_msgs rospy roscpp 是我们通常一个最基本的C++包之中需要的依赖项。后面这些依赖项均可以通过配置 package.xml 进行更改。
3)编译 package:
即使什么都不写我们已经可以编译这个包了。编译包需要在 workspace 路径下
1 2 | cd .. catkin_make |
编译成功后在 ROS_PTAH/hellorobot_ws 下就可以看到如下目录结构已经生成了:
build
devel
src
其实这些目录在教程(1)中我们已经生成,不过这次编译又添加了新的package到workspace下,编译时可以看到如下内容:
-- ~~ traversing 2 packages in topological order:
-- ~~ - checkrobot
-- ~~ - hellorobot
3、创建自定义服务:
1)创建服务文件 checkRobotSrv.srv:
在这里我们需要一个执行服务(checkRobot)的服务器(checkRobotServer),该服务很简单,输入机器人的id的请求(Request),返回这个机器人是好还是坏的的结果result响应(Response)。我们在 ROS_PTAH/hellorobot_ws/src/hellorobot 路径下创建 srv 文件夹,然后新建 checkRobotSrv.srv 文件:
1 2 3 | mkdir srv cd srv vi checkRobotSrv.srv |
文件内容如下:
1 2 3 | int32 id --- string result |
其中 Request在上面Response在下面,中间用---进行分割。
2)在 package.xml 添加 message 依赖:
在 package.xml 中找到如下两行代码并且取消注释:
1 2 | message_generation message_runtime |
这两行分别表示在编译和运行时的 message 依赖。
3)在 CMakeList.txt 添加编译依赖:
找到 find_package 添加 message_generation,结果如下:
1 2 3 4 5 6 | find_package(catkin REQUIRED COMPONENTS roscpp rospy std_msgs message_generation ) |
找到 add_service_files ,去掉注释并添加checkRobotSrv.srv 服务文件:
1 2 3 4 5 6 | ## Generate services in the 'srv' folder add_service_files( FILES checkRobotSrv.srv # Service2.srv ) |
找到 generate_messages 函数去掉注释,结果如下:
1 2 3 4 5 | ## Generate added messages and services with any dependencies listed here generate_messages( DEPENDENCIES std_msgs ) |
找到 catkin_package 添加如下行并启用该部分,结果如下:
1 2 3 4 5 6 7 | catkin_package( # INCLUDE_DIRS include # LIBRARIES checkrobot # CATKIN_DEPENDS roscpp rospy std_msgs # DEPENDS system_lib CATKIN_DEPENDS message_runtime ) |
4、创建服务器 server:
我们在 ROS_PTAH/hellorobot_ws/src/checkrobot/src 目录下创建 server.cpp 文件,代码内容如下:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 | #include "ros/ros.h" #include "checkrobot/checkRobotSrv.h" bool checkRobot(checkrobot::checkRobotSrv::Request &req, checkrobot::checkRobotSrv::Response &res) { int32_t id = req.id; if (id % 5 == 0) { res.result = "Bad robot"; } else { res.result = "Good robot"; } ROS_INFO("request: Robot id=%d", req.id); ROS_INFO("sending back response: [%s]", res.result.c_str()); return true; } int main(int argc, char **argv) { ros::init(argc, argv, "checkRobotServer"); ros::NodeHandle n; ros::ServiceServer service = n.advertiseService("checkRobot", checkRobot); ROS_INFO("Ready to check robot."); ros::spin(); return 0; } |
其中最关键的其实只有几行:
1 | ros::init(argc, argv, "checkRobotServer"); |
这一行声明了我们的 Node 名字叫 “checkRobotServer”。
1 2 3 | ros::NodeHandle n; ros::ServiceServer service = n.advertiseService("checkRobot", checkRobot); |
这一行创建了一个 Node 句柄和 Server,它的服务是 “checkRobot”,执行函数是 checkRobot。
1 | ros::spin(); |
这一行与之前我们使用的 spinOnce 区别是,这里会进入一个循环,不停保持对 callback 的处理,因为我们这里是需要保持一直接收消息的,所以这里用 spin。
1 2 | bool checkRobot(checkrobot::checkRobotSrv::Request &req, checkrobot::checkRobotSrv::Response &res) |
这一部分就是我们的服务处理函数,其中 req 是请求的字段,res 是返回结果。如果服务正常工作这一函数就应返回 true。
5、创建客户端 client:
我们在 ROS_PTAH/hellorobot_ws/src/checkrobot/src 目录下创建 client.cpp 文件,代码内容如下:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 | #include "ros/ros.h" #include "checkrobot/checkRobotSrv.h" #include int main(int argc, char **argv) { ros::init(argc, argv, "client"); if (argc != 2) { ROS_INFO("usage: client [id]"); return 1; } ros::NodeHandle n; ros::ServiceClient client = n.serviceClient("checkRobot"); checkrobot::checkRobotSrv srv; srv.request.id = atoll(argv[1]); if (client.call(srv)) { ROS_INFO("Result: %s", srv.response.result.c_str()); } else { ROS_ERROR("Failed to call service checkRobot"); return 0; } return 0; } |
其中最关键的其实只有几行:
1 2 | ros::NodeHandle n; ros::ServiceClient client = n.serviceClient("checkRobot"); |
这里创建了一个基于 checkRobotSrv 的 client,其中服务名称为 checkRobot。
1 2 | checkrobot::checkRobotSrv srv; srv.request.id = atoll(argv[1]); |
这里构造了我们定义的 checkRobotSrv 服务,并把我们从命令行输入第一个参数作为request.id。
1 | client.call(srv) |
这里是真正调用服务的地方,如果之前我们的服务那里返回 true 就表示调用成功,我们输出相关的 result。
6、编译:
1)修改 CMakeList.txt 添加 Server 和 Client 编译项:
在 CMakeList.txt 文件结尾添加如下几行:
1 2 3 4 5 6 7 | add_executable(server src/server.cpp) target_link_libraries(server ${catkin_LIBRARIES}) add_dependencies(server checkrobot_gencpp) add_executable(client src/client.cpp) target_link_libraries(client ${catkin_LIBRARIES}) add_dependencies(client checkrobot_gencpp) |
2)运行编译命令:
在 ROS_PTAH/hellorobot_ws/ 目录下运行 catkin 编译:
1 | catkin_make |
如果没有问题整个工程就编译完成了。
7、运行测试:
1)首先运行 roscore:
1 | roscore |
2)其次进入 workspace 目录配置环境:
1 2 | cd ROS_PTAH/hellorobot_ws source ./devel/setup.bash |
3)运行 Server :
1 | rosrun checkrobot server |
将会看到类似输出:
1 | [ INFO] [1446623323.928237720]: Ready to check robot. |
4)新开一个 Terminal (Ctrl+Alt+T)运行 client:
首先重复步骤2)配置环境。然后运行:
1 | rosrun checkrobot client 3 |
将会看到类似输出:
1 | [ INFO] [1446623328.059565698]: Result: Good robot |
当然我们可以再次运行:
1 | rosrun checkrobot client 5 |
将会看到类似输出:
1 | [ INFO] [1446623333.004074424]: Result: Bad robot |
错误提示:
1、错误:Failed to contact master
如果看到如下错误:
[ERROR] [1446531999.044935824]: [registerPublisher] Failed to contact master at [localhost:11311]. Retrying...
请检查 roscore 是否正常打开。
源码下载:
checkrobot
参考文献:
[1] http://wiki.ros.org/ROS/Tutorials/WritingPublisherSubscriber%28c%2B%2B%29
有一个地方貌似有错。就是client.cpp 里面第15行
ros::ServiceClient client = n.serviceClient("checkRobot");
应该改为
ros::ServiceClient client = n.serviceClient("checkRobot");