(!) 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.

Writing a Callback Based SimpleActionClient

Description: Example of using callbacks for program flow that's more complicated than a simple, linear script.

Tutorial Level: ADVANCED

Example

In some cases, blocking until a goal completes doesn't provide enough flexibility. Instead, event based execution might make more sense. Below is an example of how to use callbacks to avoid using a waitForResult() call to block for the goal to finish.

https://raw.githubusercontent.com/ros/common_tutorials/noetic-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 }

But I want to use Classes!

The syntax for registering goal, active, and feedback callbacks isn't the most convenient when trying to register class methods. However, this can be done using the "super useful yet sometimes hard to get the syntax right" boost::bind (See boost docs).

Below is an example of another Fibonnaci ActionClient, but this time, classes are used:

https://raw.githubusercontent.com/ros/common_tutorials/noetic-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 }

The crux of this example is the call to sendGoal which uses boost::bind.

We're not registering active or feedback callbacks, so we're instead passing in null function pointers. We could have also left these two arguments blank, since by default the callbacks are null.

Wiki: actionlib_tutorials/Tutorials/Writing a Callback Based Simple Action Client (last edited 2023-03-10 14:10:35 by Hirotaka Yamada)