(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

编写一个基于SimpleActionClient的回调函数

Description: 相比一个简单的线性脚本,使用回调函数的示例程序流会更复杂。

Tutorial Level: ADVANCED

示例

在一些情况下,阻塞直到一个目标完成不会提供足够的灵活。相反的,基于事件运行或许需要更多场景。在以下例程中,提供如何使用回调来避免调用waitForResult()来阻塞用于目标完成。

https://raw.githubusercontent.com/ros/common_tutorials/hydro-devel/actionlib_tutorials/src/fibonacci_callback_client.cpp

   1 #include <ros/ros.h>
   2 #include <actionlib/client/simple_action_client.h>
   3 #include <actionlib_tutorials/FibonacciAction.h>
   4 
   5 using namespace actionlib_tutorials;
   6 typedef actionlib::SimpleActionClient<FibonacciAction> Client;
   7 
   8 // Called once when the goal completes
   9 void doneCb(const actionlib::SimpleClientGoalState& state,
  10             const FibonacciResultConstPtr& result)
  11 {
  12   ROS_INFO("Finished in state [%s]", state.toString().c_str());
  13   ROS_INFO("Answer: %i", result->sequence.back());
  14   ros::shutdown();
  15 }
  16 
  17 // Called once when the goal becomes active
  18 void activeCb()
  19 {
  20   ROS_INFO("Goal just went active");
  21 }
  22 
  23 // Called every time feedback is received for the goal
  24 void feedbackCb(const FibonacciFeedbackConstPtr& feedback)
  25 {
  26   ROS_INFO("Got Feedback of length %lu", feedback->sequence.size());
  27 }
  28 
  29 int main (int argc, char **argv)
  30 {
  31   ros::init(argc, argv, "test_fibonacci_callback");
  32 
  33   // Create the action client
  34   Client ac("fibonacci", true);
  35 
  36   ROS_INFO("Waiting for action server to start.");
  37   ac.waitForServer();
  38   ROS_INFO("Action server started, sending goal.");
  39 
  40   // Send Goal
  41   FibonacciGoal goal;
  42   goal.order = 20;
  43   ac.sendGoal(goal, &doneCb, &activeCb, &feedbackCb);
  44 
  45   ros::spin();
  46   return 0;
  47 }

但我想要使用类!

当尝试注册类方法时,注册目标、活跃和反馈回调的语法并不是很方便。然而,这已经完成了,通过"超级有用但有时很难得到正确的语法" boost::bind (查看boost 文档).

以下是一个其他Fibonnaci ActionClient的示例,使用到类:

https://raw.githubusercontent.com/ros/common_tutorials/hydro-devel/actionlib_tutorials/src/fibonacci_class_client.cpp

   1 #include <ros/ros.h>
   2 #include <actionlib/client/simple_action_client.h>
   3 #include <actionlib_tutorials/FibonacciAction.h>
   4 
   5 using namespace actionlib_tutorials;
   6 typedef actionlib::SimpleActionClient<FibonacciAction> Client;
   7 
   8 class MyNode
   9 {
  10 public:
  11   MyNode() : ac("fibonacci", true)
  12   {
  13     ROS_INFO("Waiting for action server to start.");
  14     ac.waitForServer();
  15     ROS_INFO("Action server started, sending goal.");
  16   }
  17 
  18   void doStuff(int order)
  19   {
  20     FibonacciGoal goal;
  21     goal.order = order;
  22 
  23     // Need boost::bind to pass in the 'this' pointer
  24     ac.sendGoal(goal,
  25                 boost::bind(&MyNode::doneCb, this, _1, _2),
  26                 Client::SimpleActiveCallback(),
  27                 Client::SimpleFeedbackCallback());
  28 
  29   }
  30 
  31   void doneCb(const actionlib::SimpleClientGoalState& state,
  32               const FibonacciResultConstPtr& result)
  33   {
  34     ROS_INFO("Finished in state [%s]", state.toString().c_str());
  35     ROS_INFO("Answer: %i", result->sequence.back());
  36     ros::shutdown();
  37   }
  38 
  39 private:
  40   Client ac;
  41 };
  42 
  43 int main (int argc, char **argv)
  44 {
  45   ros::init(argc, argv, "test_fibonacci_class_client");
  46   MyNode my_node;
  47   my_node.doStuff(10);
  48   ros::spin();
  49   return 0;
  50 }

这个示例的关键所在是调用sendGoal ,该函数使用boost::bindhttps://raw.githubusercontent.com/ros/common_tutorials/hydro-devel/actionlib_tutorials/src/fibonacci_class_client.cpp

   1 #include <ros/ros.h>
   2 #include <actionlib/client/simple_action_client.h>
   3 #include <actionlib_tutorials/FibonacciAction.h>
   4 
   5 using namespace actionlib_tutorials;
   6 typedef actionlib::SimpleActionClient<FibonacciAction> Client;
   7 
   8 class MyNode
   9 {
  10 public:
  11   MyNode() : ac("fibonacci", true)
  12   {
  13     ROS_INFO("Waiting for action server to start.");
  14     ac.waitForServer();
  15     ROS_INFO("Action server started, sending goal.");
  16   }
  17 
  18   void doStuff(int order)
  19   {
  20     FibonacciGoal goal;
  21     goal.order = order;
  22 
  23     // Need boost::bind to pass in the 'this' pointer
  24     ac.sendGoal(goal,
  25                 boost::bind(&MyNode::doneCb, this, _1, _2),
  26                 Client::SimpleActiveCallback(),
  27                 Client::SimpleFeedbackCallback());
  28 
  29   }
  30 
  31   void doneCb(const actionlib::SimpleClientGoalState& state,
  32               const FibonacciResultConstPtr& result)
  33   {
  34     ROS_INFO("Finished in state [%s]", state.toString().c_str());
  35     ROS_INFO("Answer: %i", result->sequence.back());
  36     ros::shutdown();
  37   }
  38 
  39 private:
  40   Client ac;
  41 };
  42 
  43 int main (int argc, char **argv)
  44 {
  45   ros::init(argc, argv, "test_fibonacci_class_client");
  46   MyNode my_node;
  47   my_node.doStuff(10);
  48   ros::spin();
  49   return 0;
  50 }

我们不注册活跃或反馈回调函数,因此我们可以使用传递null函数指针来代替。我们也可以通过设置两个参数为空来使用,因为默认的回调函数为null

Wiki: cn/actionlib_tutorials/Tutorials/Writing a Callback Based Simple Action Client (last edited 2017-03-19 07:36:54 by Playfish)