01 导读
C++代码必须通过编译生成可执行文件;
python代码是可执行文件,不需要编译;
开发的功能包都放在catkin_ws这样一个工作空间里;
新建的功能包取名为action_example;
工作模式的结构示意图如下:
什么是动作(action)
一种问答通信机制;
带有连续反馈;
可以在任务过程中止运行;
基于ROS的消息机制实现。
通信双方在ROS Action Protocal下进行交流通信是通过接口来实现,如下图:
Action的接口
goal:发布任务目标;
cancel:请求取消任务;
status:通知客户端当前的状态;
feedback:周期反馈任务运行的监控数据;
result:向客户端发送任务的执行结果,只发布一次。
我们可以看到,客户端会向服务器发送目标指令和取消动作指令,而服务器则可以给客户端发送实时的状态信息,结果信息,反馈信息等等,从而完成了service没法做到的部分.
02 功能包的创建
在catkin_ws/src/目录下新建功能包action_example,并在创建时显式的指明依赖roscpp和actionlib actionlib_msgs,依赖actionlib actionlib_msgs将作为基本数据类型用于定义我们的服务类型。打开命令行终端,输入命令:
$ cd ~/catkin_ws/src #创建功能包topic_example时,显式的指明依赖roscpp和std_msgs, #依赖会被默认写到功能包的CMakeLists.txt和package.xml中 $ catkin_create_pkg action_example roscpp actionlib actionlib_msgs
03 在功能包中创建action(动作)
Action的工作原理是client-server模式,也是一个双向的通信模式。通信双方在ROS Action Protocol下通过消息进行数据的交流通信。client和server为用户提供一个简单的API来请求目标(在客户端)或通过函数调用和回调来执行目标(在服务器端)。
3.1 自定义action
利用动作库进行请求响应,动作的内容格式应包含三个部分,目标、反馈、结果。
在功能包action_example目录下新建action目录,然后在action_example/action/目录中创建DoDishes.action文件
# Define the goal 定义目标信息 uint32 dishwasher_id # Specify which dishwasher we want to use --- # Define the result 定义结果信息 uint32 total_dishes_cleaned --- # Define a feedback message 定义周期反馈的信息 float32 percent_complete
3.2 在package.xml中添加功能包依赖
action文件被转换成为C++,Python和其他语言的源代码:
查看package.xml
, 确保它包含以下语句:
*部分ROS版本中的exec_depend需要改成run_depend
<build_depend>actionlib</build_depend> <build_depend>actionlib_msgs</build_depend> <exec_depend>actionlib</exec_depend> <exec_depend>actionlib_msgs</exec_depend>
3.3 在CMakeLists.txt添加编译选项
##1 Find catkin macros and libraries ##1 if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) ##1 is used, also find other catkin packages find_package(catkin REQUIRED COMPONENTS roscpp actionlib_msgs actionlib ) ##2 Generate actions in the 'action' folder add_action_files( FILES DoDishes.action ) ##3 Generate added messages and services with any dependencies listed here generate_messages( DEPENDENCIES actionlib_msgs )
04 功能包的源代码编写
在新建的功能包action_example/src目录下新建两个文件action_server.cpp和action_client.cpp,并将下面的代码分别填入。
4.1 编写action_server.cpp
如何实现一个动作服务器:
初始化ROS节点;
创建动作服务器实例;
启动服务器,等待动作请求;
在回调函数中完成动作服务功能的处理,并反馈进度信息;
动作完成,发送结束信息。
在action_example/src包中创建action_server.cpp文件:
#include <ros/ros.h> #include <actionlib/server/simple_action_server.h> #include "action_example/DoDishesAction.h" typedef actionlib::SimpleActionServer<action_example::DoDishesAction> Server; // 收到action的goal后调用该回调函数 void execute(const action_example::DoDishesGoalConstPtr& goal, Server* as) { ros::Rate r(1); action_example::DoDishesFeedback feedback; ROS_INFO("Dishwasher %d is working.", goal->dishwasher_id); // 假设洗盘子的进度,并且按照1hz的频率发布进度feedback for(int i=1; i<=10; i++) { feedback.percent_complete = i * 10; as->publishFeedback(feedback); r.sleep(); } // 当action完成后,向客户端返回结果 ROS_INFO("Dishwasher %d finish working.", goal->dishwasher_id); as->setSucceeded(); } int main(int argc, char** argv) { ros::init(argc, argv, "do_dishes_server"); ros::NodeHandle n; // 定义一个服务器 Server server(n, "do_dishes", boost::bind(&execute, _1, &server), false); // 服务器开始运行 server.start(); ros::spin(); return 0; }
4.2 编写action_client.cpp
如何实现一个动作客户端:
初始化ROS节点;
创建动作客户端实例;
连接动作服务端;
发送动作目标;
根据不同类型的服务端反馈处理回调函数。
在action_example/src包中创建action_client.cpp文件,并在其中粘贴以下內容:
#include <actionlib/client/simple_action_client.h> #include "action_example/DoDishesAction.h" typedef actionlib::SimpleActionClient<action_example::DoDishesAction> Client; // 当action完成后会调用该回调函数一次 void doneCb(const actionlib::SimpleClientGoalState& state, const action_example::DoDishesResultConstPtr& result) { ROS_INFO("Yay! The dishes are now clean"); ros::shutdown(); } // 当action激活后会调用该回调函数一次 void activeCb() { ROS_INFO("Goal just went active"); } // 收到feedback后调用该回调函数 void feedbackCb(const action_example::DoDishesFeedbackConstPtr& feedback) { ROS_INFO(" percent_complete : %f ", feedback->percent_complete); } int main(int argc, char** argv) { ros::init(argc, argv, "do_dishes_client"); // 定义一个客户端 Client client("do_dishes", true); // 等待服务器端 ROS_INFO("Waiting for action server to start."); client.waitForServer(); ROS_INFO("Action server started, sending goal."); // 创建一个action的goal action_example::DoDishesGoal goal; goal.dishwasher_id = 1; // 发送action的goal给服务器端,并且设置回调函数 client.sendGoal(goal, &doneCb, &activeCb, &feedbackCb); ros::spin(); return 0; }
05 功能包的编译配置(编译节点)
说明:
C++代码必须通过编译生成可执行文件;
python代码是可执行文件,不需要编译;
如何编译代码
设置需要编译的代码和生成的可执行文件;
设置链接库;
设置依赖。
创建功能包action_example时,显式的指明依赖roscpp和std_msgs,依赖会被默认写到功能包的CMakeLists.txt和package.xml中。
在 CMakeLists.txt 文件末尾加入几条语句:
add_executable(action_client src/action_client.cpp) target_link_libraries( action_client ${catkin_LIBRARIES}) add_dependencies(action_client ${${PROJECT_NAME}_EXPORTED_TARGETS}) add_executable(action_server src/action_server.cpp) target_link_libraries( action_server ${catkin_LIBRARIES}) add_dependencies(action_server ${${PROJECT_NAME}_EXPORTED_TARGETS})
06 功能包的编译
$ cd ~/catkin_ws $ catkin_make -DCATKIN_WHITELIST_PACKAGES="action_example" $ source ~/catkin_ws/devel/setup.bash # 刷新环境
07 测试action_server和action_client
7.1 运行action_server
第一步,打开一个命令行终端:
$ roscore
第二步,打开第二个命令行终端:
# 用rosrun <package_name> <node_name>启动功能包中的发布节点。 $ source ~/catkin_ws/devel/setup.bash # 激活catkin_ws工作空间(必须有,必不可少) $ rosrun action_example action_server
你将看到如下的输出信息:
[ INFO] [1588752334.514526874]: Dishwasher 1 is working. [ INFO] [1588752344.515033939]: Dishwasher 1 finish working. # Server节点启动后的日
7.2 运行action_client
打开第三个命令行客户端:
$ source ~/catkin_ws/devel/setup.bash # 激活catkin_ws工作空间(必须有,必不可少) $ rosrun action_example action_client
你将会看到如下的输出信息:
[ INFO] [1588752334.233231877]: Waiting for action server to start. [ INFO] [1588752334.513889608]: Action server started, sending goal. [ INFO] [1588752334.514780017]: Goal just went active [ INFO] [1588752334.515056866]: percent_complete : 10.000000 [ INFO] [1588752335.516336080]: percent_complete : 20.000000 [ INFO] [1588752336.516271562]: percent_complete : 30.000000 [ INFO] [1588752337.516315111]: percent_complete : 40.000000 [ INFO] [1588752338.515751638]: percent_complete : 50.000000 [ INFO] [1588752339.515473734]: percent_complete : 60.000000 [ INFO] [1588752340.516373053]: percent_complete : 70.000000 [ INFO] [1588752341.515448200]: percent_complete : 80.000000 [ INFO] [1588752342.515654876]: percent_complete : 90.000000 [ INFO] [1588752343.515571413]: percent_complete : 100.000000 [ INFO] [1588752344.516076162]: Yay! The dishes are now clean
现在,你已经成功地运行了你的第一个action_server和action_client程序。