[Documentation] [TitleIndex] [WordIndex

Creating the Action Messages

Before writing an action it is important to define the goal, result, and feedback messages. The action messages are generated automatically from the .action file, for more information on action files see the actionlib documentation. This file defines the type and format of the goal, result, and feedback topics for the action. Create learning_actionlib/action/Fibonacci.action in your favorite editor, and place the following inside it:

#goal definition
int32 order
---
#result definition
int32[] sequence
---
#feedback
int32[] sequence

To manually generate the message files from this file:

$ roscd learning_actionlib
$ rosrun actionlib_msgs genaction.py . Fibonacci.action

You will see:

To automatically generate the message files during the make process, add the following to CMakeLists.txt (before the rosbuild_init call)

rosbuild_find_ros_package(actionlib_msgs)
include(${actionlib_msgs_PACKAGE_PATH}/cmake/actionbuild.cmake)
genaction()

You'll also need to make sure to generate header files from the message files generated by the genaction.py script. To do this, uncomment the following line at the bottom your CMakeLists.txt file if you have not already.

rosbuild_genmsg()

Writing a Simple Server

The Code

First, create learning_actionlib/src/fibonacci_server.cpp in your favorite editor, and place the following inside it:

   1 #include <ros/ros.h>
   2 #include <actionlib/server/simple_action_server.h>
   3 #include <learning_actionlib/FibonacciAction.h>
   4 
   5 class FibonacciAction
   6 {
   7 protected:
   8 
   9   ros::NodeHandle nh_;
  10   actionlib::SimpleActionServer<learning_actionlib::FibonacciAction> as_;
  11   std::string action_name_;
  12   // create messages that are used to published feedback/result
  13   learning_actionlib::FibonacciFeedback feedback_;
  14   learning_actionlib::FibonacciResult result_;
  15 
  16 public:
  17 
  18   FibonacciAction(std::string name) :
  19     as_(nh_, name, boost::bind(&FibonacciAction::executeCB, this, _1), false),
  20     action_name_(name)
  21   {
  22     as_.start();
  23   }
  24 
  25   ~FibonacciAction(void)
  26   {
  27   }
  28 
  29   void executeCB(const learning_actionlib::FibonacciGoalConstPtr &goal)
  30   {
  31     // helper variables
  32     ros::Rate r(1);
  33     bool success = true;
  34 
  35     // push_back the seeds for the fibonacci sequence
  36     feedback_.sequence.clear();
  37     feedback_.sequence.push_back(0);
  38     feedback_.sequence.push_back(1);
  39 
  40     // publish info to the console for the user
  41     ROS_INFO("%s: Executing, creating fibonacci sequence of order %i with seeds %i, %i", action_name_.c_str(), goal->order, feedback_.sequence[0], feedback_.sequence[1]);
  42 
  43     // start executing the action
  44     for(int i=1; i<=goal->order; i++)
  45     {
  46       // check that preempt has not been requested by the client
  47       if (as_.isPreemptRequested() || !ros::ok())
  48       {
  49         ROS_INFO("%s: Preempted", action_name_.c_str());
  50         // set the action state to preempted
  51         as_.setPreempted();
  52         success = false;
  53         break;
  54       }
  55       feedback_.sequence.push_back(feedback_.sequence[i] + feedback_.sequence[i-1]);
  56       // publish the feedback
  57       as_.publishFeedback(feedback_);
  58       // this sleep is not necessary, the sequence is computed at 1 Hz for demonstration purposes
  59       r.sleep();
  60     }
  61 
  62     if(success)
  63     {
  64       result_.sequence = feedback_.sequence;
  65       ROS_INFO("%s: Succeeded", action_name_.c_str());
  66       // set the action state to succeeded
  67       as_.setSucceeded(result_);
  68     }
  69   }
  70 
  71 
  72 };
  73 
  74 
  75 int main(int argc, char** argv)
  76 {
  77   ros::init(argc, argv, "fibonacci");
  78 
  79   FibonacciAction fibonacci(ros::this_node::getName());
  80   ros::spin();
  81 
  82   return 0;
  83 }

The Code Explained

Now, let's break down the code piece by piece.

   1 #include <ros/ros.h>
   2 #include <actionlib/server/simple_action_server.h>
   3 

actionlib/server/simple_action_server.h is the action library used from implementing simple actions.

   3 #include <learning_actionlib/FibonacciAction.h>
   4 

This includes the action message generated from the Fibonacci.action file show above. This is a header generated automatically from the FibonacciAction.msg file. For more information on message definitions, see the msg page.

   7 protected:
   8 
   9   ros::NodeHandle nh_;
  10   actionlib::SimpleActionServer<learning_actionlib::FibonacciAction> as_;
  11   std::string action_name_;
  12   // create messages that are used to published feedback/result
  13   learning_actionlib::FibonacciFeedback feedback_;
  14   learning_actionlib::FibonacciResult result_;

These are the protected variables of the action class. The node handle is constructed and passed into the action server during construction of the action. The action server is constructed in the constructor of the action and has been discussed below. The feedback and result messages are created for publishing in the action.

  18   FibonacciAction(std::string name) :
  19     as_(nh_, name, boost::bind(&FibonacciAction::executeCB, this, _1), false),
  20     action_name_(name)
  21   {
  22     as_.start();
  23   }

In the action constructor, an action server is created. The action server takes arguments of a node handle, name of the action, and optionally an executeCB. In this example the action server is created with the arguments for the executeCB.

  29   void executeCB(const learning_actionlib::FibonacciGoalConstPtr &goal)

Now the executeCB function referenced in the constructor is created. The callback function is passed a pointer to the goal message. Note: This is a boost shared pointer, given by appending "ConstPtr" to the end of the goal message type.

  31     // helper variables
  32     ros::Rate r(1);
  33     bool success = true;
  34 
  35     // push_back the seeds for the fibonacci sequence
  36     feedback_.sequence.clear();
  37     feedback_.sequence.push_back(0);
  38     feedback_.sequence.push_back(1);
  39 
  40     // publish info to the console for the user
  41     ROS_INFO("%s: Executing, creating fibonacci sequence of order %i with seeds %i, %i", action_name_.c_str(), goal->order, feedback_.sequence[0], feedback_.sequence[1]);

Here the internals of the action are created. In this example ROS_INFO is being published to let the user know that the action is executing.

  42     // start executing the action
  43     for(int i=1; i<=goal->order; i++)
  44     {
  45       // check that preempt has not been requested by the client
  46       if (as_.isPreemptRequested() || !ros::ok())
  47       {
  48         ROS_INFO("%s: Preempted", action_name_.c_str());
  49         // set the action state to preempted
  50         as_.setPreempted();
  51         success = false;
  52         break;
  53       }

An important component of an action server is the ability to allow an action client to request that the current goal execution be cancelled. When a client requests that the current goal be preempted the action server should cancel the goal, perform necessary clean-up, and call the function setPreempted(), which signals that the action has been preempted by user request. Setting the rate at which the action server checks for preemption requests is left to the implementor of the server.

  55       feedback_.sequence.push_back(feedback_.sequence[i] + feedback_.sequence[i-1]);
  56       // publish the feedback
  57       as_.publishFeedback(feedback_);
  58       // this sleep is not necessary, the sequence is computed at 1 Hz for demonstration purposes
  59       r.sleep();
  60     }

Here the Fibonacci sequence is put into the feedback variable and then published on the feedback channel provided by the action server. Then the action continues on looping and publishing feedback.

  61     if(success)
  62     {
  63       result_.sequence = feedback_.sequence;
  64       ROS_INFO("%s: Succeeded", action_name_.c_str());
  65       // set the action state to succeeded
  66       as_.setSucceeded(result_);
  67     }
  68   }

Once the action has finished computing the Fibonacci sequence the action notifies the action client that the action is complete by setting succeeded.

  74 int main(int argc, char** argv)
  75 {
  76   ros::init(argc, argv, "fibonacci");
  77 
  78   FibonacciAction fibonacci(ros::this_node::getName());
  79   ros::spin();
  80 
  81   return 0;
  82 }

Finally the main function, creates the action and spins the node. The action will be running and waiting to receive goals.

Compiling and Running the Action

Add the following lines to your CMakeLists.txt file:

rosbuild_add_executable(fibonacci_server src/fibonacci_server.cpp)

After you have made the executable (rosmake), start a roscore in a new terminal

$ roscore

And then run the action server:

$ rosrun learning_actionlib fibonacci_server

You will see something similar to:

To check that your action is running properly list topics being published:

$ rostopic list -v

You will see something similar to:

Alternatively you can look at the nodes:

$ rxgraph

fibonacci_server.png

This shows that your action server is publishing the feedback, status, and result channels as expected and subscribed to the goal and cancel channels as expected. The action server is up and running properly.

Sending a Goal to the Action Server

For the next step in using your action, you need to Ctrl-C the action server and write a simple action client.


2024-02-24 12:24