#include <ros/ros.h> #include <actionlib/server/simple_action_server.h> #include "learning_communication/DoDishesAction.h" typedef actionlib::SimpleActionServer<learning_communication::DoDishesAction> Server; // 收到action的goal后调用该回调函数 void execute(const learning_communication::DoDishesGoalConstPtr& goal, Server* as) { ros::Rate r(1); learning_communication::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; }
#include <actionlib/client/simple_action_client.h> #include "learning_communication/DoDishesAction.h" typedef actionlib::SimpleActionClient<learning_communication::DoDishesAction> Client; // 当action完成后会调用该回调函数一次 void doneCb(const actionlib::SimpleClientGoalState& state, const learning_communication::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 learning_communication::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 learning_communication::DoDishesGoal goal; goal.dishwasher_id = 1; // 发送action的goal给服务器端,并且设置回调函数 client.sendGoal(goal, &doneCb, &activeCb, &feedbackCb); ros::spin(); return 0; }