ROS Message:
catkin_create_pkg dodishes roscpp actionlib actionlib_msgs
cd dodishes mkdir action
<build_depend>message_generation</build_depend> <exec_depend>message_runtime</exec_depend>
例如:./action/DoDishes.action
./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
基于这个 .action 文件,需要生成 6 条消息,以便客户端和服务器进行通信
package.xml
<build_depend>actionlib</build_depend> <build_depend>actionlib_msgs</build_depend> <exec_depend>actionlib</exec_depend> <exec_depend>actionlib_msgs</exec_depend>
CMakeLists.txt
find_package(catkin REQUIRED COMPONENTS actionlib_msgs actionlib ) add_action_files(DIRECTORY action FILES DoDishes.action ) generate_messages( DEPENDENCIES actionlib_msgs ) catkin_package( CATKIN_DEPENDS actionlib_msgs )
#include <ros/ros.h> #include <actionlib/server/simple_action_server.h> // 这是一个library里面一个做好的包(simple_action_server)里面的头文件 #include "dodishes/DoDishesAction.h" // 这个头文件是重点,在上一部分生成的action消息的头文件 // 为服务端数据类型定义别名 typedef actionlib::SimpleActionServer<dodishes::DoDishesAction> Server; // 收到action的goal后调用该回调函数 void execute(const dodishes::DoDishesGoalConstPtr & goal, Server * as) { ros::Rate r(1); dodishes::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; // 发布feedback 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); // 其中的参数n,就是NodeHandle。而“do_dishes”,是你给server起的名字 // boost::bind(&execute, _1, &server)是当收到新的goal时候需要的返回函数 // false的意思是暂时不启动这个server server.start(); // 服务器开始运行 ros::spin(); return 0; }
总结:
#include <ros/ros.h> #include <actionlib/client/simple_action_client.h> // 这是一个library里面一个做好的包(simple_action_server)里面的头文件 #include "dodishes/DoDishesAction.h" // 这个头文件是重点,在上一部分生成的action消息的头文件 // 为客户端数据类型定义一个别名 typedef actionlib::SimpleActionClient<dodishes::DoDishesAction> Client; // 当服务器完成后会调用该回调函数一次 void doneCb(const actionlib::SimpleClientGoalState & state, const dodishes::DoDishesResultConstPtr & result) { ROS_INFO("Yay! The dishes are now clean"); ros::shutdown(); } // 当服务器激活后会调用该回调函数一次 void activeCb() { ROS_INFO("Goal just went active"); } // 收到feedback后调用该回调函数 void feedbackCb(const dodishes::DoDishesFeedbackConstPtr & feedback) { ROS_INFO(" percent_complete : %f ", feedback->percent_complete); } int main(int argc, char **argv) { ros::init(argc, argv, "do_dishes_client"); // 定义一个客户端,连接名为do_dishes的服务器,开启自循环线程 Client client("do_dishes", true); ROS_INFO("Waiting for action server to start."); client.waitForServer(); // 客户端等待服务器函数 // 可以传递一个ros::Duration作为最大等待值,程序进入到这个函数开始挂起等待 // 服务器就位或者达到等待最大时间退出,前者返回true,后者返回false ROS_INFO("Action server started, sending goal."); dodishes::DoDishesGoal goal; // 创建一个action的goal goal.dishwasher_id = 1; // 定义盘子的目标,也就是洗一个盘子 // 发送action的goal给服务器端,并且设置回调函数 client.sendGoal(goal, &doneCb, &activeCb, &feedbackCb); ros::spin(); return 0; }
总结:
CMakeLists.txt
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})