本文最后更新于:2022年5月29日 上午
什么是动作(action)
一种问答通信机制;
带有连续反馈;
可以在任务过程中止运行;
给予ROS的消息机制实现。
Action的接口
goal:发布任务目标;
cancel:请求取消任务;
status:通知客户端当前的状态;
feedback:周期反馈任务运行的监控数据;
result:向客服端发送任务的执行结果,只发布一次。
1,创建程序包 在工作空间的src目录下:
1 2 cd ~/catkin_ws/src/ catkin_create_pkg action_demo roscpp std_msgs
2,定义action文件 1 2 3 cd ~/catkin_ws/src/action_demo mkdir action gedit DoDishes.action
DoDishes.action文件内容:
1 2 3 4 5 6 7 8 uint32 dishwasher_id --- uint32 total_dishes_cleaned --- float32 percent_complete
3,修改package.xml 在package.xml中添加功能包依赖
1 2 3 4 <build_depend > actionlib</build_depend > <build_depend > actionlib_msgs</build_depend > <exec_depend > actionlib</exec_depend > <exec_depend > actionlib_msgs</exec_depend >
4,修改CMakeLists.txt文件 1)在find_packag函数的COMPONENTS的列表里增加actionlib_msgs actionlib,就像这样:
1 2 3 4 5 6 find_package(catkin REQUIRED COMPONENTS roscpp std_msgs actionlib_msgs actionlib )
2)在文件尾添加编译选项
1 2 add_action_files(DIRECTORY action FILES DoDishes.action) generate_messages(DEPENDENCIES actionlib_msgs)
5,编译检查action文件是否正确 在工作空间执行命令:
将会看到编译完成信息。
6,实现一个动作服务器
初始化ROS节点;
创建动作服务器实例;
启动服务器,等待动作请求;
在回调函数中完成动作服务功能的处理,并反馈进度信息;
动作完成,发送结束信息。
创建动作服务器文件:
1 2 roscd action_demo/src gedit DoDishes_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 35 36 37 38 39 40 41 42 #include <ros/ros.h> #include <actionlib/server/simple_action_server.h> #include "action_demo/DoDishesAction.h" typedef actionlib::SimpleActionServer<action_demo::DoDishesAction> Server;void execute (const action_demo::DoDishesGoalConstPtr& goal, Server* as) { ros::Rate r (1 ) ; action_demo::DoDishesFeedback feedback; ROS_INFO ("Dishwasher %d is working." , goal->dishwasher_id); for (int i=1 ; i<=10 ; i++) { feedback.percent_complete = i * 10 ; as->publishFeedback (feedback); r.sleep (); } 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 ; }
7,实现一个动作客户端
初始化ROS节点;
创建动作客户端实例;
连接动作服务端;
发送动作目标;
根据不同类型的服务反馈处理回调函数。
创建动作服务器文件:
1 2 roscd action_demo/src gedit DoDishes_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 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 #include <actionlib/client/simple_action_client.h> #include "action_demo/DoDishesAction.h" typedef actionlib::SimpleActionClient<action_demo::DoDishesAction> Client;void doneCb (const actionlib::SimpleClientGoalState& state, const action_demo::DoDishesResultConstPtr& result) { ROS_INFO ("Yay! The dishes are now clean" ); ros::shutdown (); }void activeCb () { ROS_INFO ("Goal just went active" ); }void feedbackCb (const action_demo::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_demo::DoDishesGoal goal; goal.dishwasher_id = 1 ; client.sendGoal (goal, &doneCb, &activeCb, &feedbackCb); ros::spin (); return 0 ; }
8,设置相关的依赖 修改CMakeLists.txt文件:
设置需要编译的代码和生成的可执行文件;
设置链接库;
设置依赖。
1 2 3 4 5 6 7 add_executable (DoDishes_client src/DoDishes_client.cpp) target_link_libraries ( DoDishes_client ${catkin_LIBRARIES}) add_dependencies (DoDishes_client ${${PROJECT_NAME}_EXPORTED_TARGETS}) add_executable (DoDishes_server src/DoDishes_server.cpp) target_link_libraries ( DoDishes_server ${catkin_LIBRARIES}) add_dependencies (DoDishes_server ${${PROJECT_NAME}_EXPORTED_TARGETS})
9,编译运行 1 2 cd ~/catkin_ws catkin_make
编译完成直接运行: