Note: This tutorial assumes that you have completed the previous tutorials: ROS tutorials. |
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 Simple Action Server using the Execute Callback
Description: This tutorial covers using the simple_action_server library to create a Fibonacci action server. This example action server generates a Fibonacci sequence, the goal is the order of the sequence, the feedback is the sequence as it is computed, and the result is the final sequence.Tutorial Level: BEGINNER
Next Tutorial: Write a simple action client
Contents
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 actionlib_tutorials/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 automatically generate the message files during the make process, a few things need to be added to CMakeLists.txt.
add the actionlib_msgs package to the find_package macro's argument like this (if you used catkin_create_package to generate CMakeLists.txt, this may already have been added):
find_package(catkin REQUIRED COMPONENTS actionlib_msgs)
Note that CMake needs to find_package actionlib_msgs (message_generation does not need to be listed explicitly, it is referenced implicitly by actionlib_msgs).
use the add_action_files macro to declare the actions you want to be generated:
add_action_files( DIRECTORY action FILES Fibonacci.action )
call the generate_messages macro, not forgetting the dependencies on actionlib_msgs and other message packages like std_msgs:
generate_messages( DEPENDENCIES actionlib_msgs std_msgs # Or other packages containing msgs )
add actionlib_msgs to catkin_package macro like this:
catkin_package( CATKIN_DEPENDS actionlib_msgs )
catkin_package also specifies only CATKIN_DEPEND to actionlib_msgs. The transitive dependency on message_runtime is happening automatically.
Note: Sometimes you have to setup your package.xml, since we are generating messages you have to declare on the manifest file that at run time you have to generate messages. You could just insert the follow line.
<exec_depend>message_generation</exec_depend>
Now by following, automatically generate msg files of your action files, and also see the result.
$ cd ../.. # Go back to the top level of your catkin workspace $ catkin_make $ ls devel/share/actionlib_tutorials/msg/ FibonacciActionFeedback.msg FibonacciAction.msg FibonacciFeedback.msg FibonacciResult.msg FibonacciActionGoal.msg FibonacciActionResult.msg FibonacciGoal.msg $ ls devel/include/actionlib_tutorials/ FibonacciActionFeedback.h FibonacciAction.h FibonacciFeedback.h FibonacciResult.h FibonacciActionGoal.h FibonacciActionResult.h FibonacciGoal.h
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()
To manually generate the message files from this file, use the script genaction.py from the actionlib_msgs package.
Writing a Simple Server
The Code
First, create actionlib_tutorials/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 <actionlib_tutorials/FibonacciAction.h>
4
5 class FibonacciAction
6 {
7 protected:
8
9 ros::NodeHandle nh_;
10 actionlib::SimpleActionServer<actionlib_tutorials::FibonacciAction> as_; // NodeHandle instance must be created before this line. Otherwise strange error occurs.
11 std::string action_name_;
12 // create messages that are used to published feedback/result
13 actionlib_tutorials::FibonacciFeedback feedback_;
14 actionlib_tutorials::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 actionlib_tutorials::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("fibonacci");
80 ros::spin();
81
82 return 0;
83 }
The Code Explained
Now, let's break down the code piece by piece.
actionlib/server/simple_action_server.h is the action library used from implementing simple actions.
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<actionlib_tutorials::FibonacciAction> as_; // NodeHandle instance must be created before this line. Otherwise strange error occurs.
11 std::string action_name_;
12 // create messages that are used to published feedback/result
13 actionlib_tutorials::FibonacciFeedback feedback_;
14 actionlib_tutorials::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.
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.
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.
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.
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]);
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.
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.
Once the action has finished computing the Fibonacci sequence the action notifies the action client that the action is complete by setting succeeded.
Finally the main function, creates the action and spins the node. The action will be running and waiting to receive goals.
Compiling
Add the following lines to your CMakeLists.txt file:
add_executable(fibonacci_server src/fibonacci_server.cpp) target_link_libraries( fibonacci_server ${catkin_LIBRARIES} ) add_dependencies( fibonacci_server ${actionlib_tutorials_EXPORTED_TARGETS} )
The minimal entire CMakeLists.txt would look like this:
cmake_minimum_required(VERSION 2.8.3) project(actionlib_tutorials) find_package(catkin REQUIRED COMPONENTS roscpp actionlib actionlib_msgs) find_package(Boost REQUIRED COMPONENTS system) add_action_files( DIRECTORY action FILES Fibonacci.action ) generate_messages( DEPENDENCIES actionlib_msgs std_msgs ) catkin_package( CATKIN_DEPENDS actionlib_msgs ) include_directories(include ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS}) add_executable(fibonacci_server src/fibonacci_server.cpp) target_link_libraries( fibonacci_server ${catkin_LIBRARIES} ) add_dependencies( fibonacci_server ${actionlib_tutorials_EXPORTED_TARGETS} )
rosbuild_add_executable(fibonacci_server src/fibonacci_server.cpp)
In ROS fuerte, use the boost linking macros around rosbuild_add_executable:
rosbuild_add_boost_directories() rosbuild_add_executable(fibonacci_server src/fibonacci_server.cpp) rosbuild_link_boost(fibonacci_server thread)
Then build as usual.
$ rosmake actionlib_tutorials
Running the Action server
Start a roscore in a new terminal
$ roscore
And then run the action server:
$ rosrun actionlib_tutorials fibonacci_server
You will see something similar to:
[ INFO] 1250790662.410962000: Started node [/fibonacci], pid [29267], bound on [aqy], xmlrpc port [39746], tcpros port [49573], logging to [~/ros/ros/log/fibonacci_29267.log], using [real] time
To check that your action is running properly list topics being published:
$ rostopic list -v
You will see something similar to:
Published topics: * /fibonacci/feedback [actionlib_tutorials/FibonacciActionFeedback] 1 publisher * /fibonacci/status [actionlib_msgs/GoalStatusArray] 1 publisher * /rosout [rosgraph_msgs/Log] 1 publisher * /fibonacci/result [actionlib_tutorials/FibonacciActionResult] 1 publisher * /rosout_agg [rosgraph_msgs/Log] 1 publisher Subscribed topics: * /fibonacci/goal [actionlib_tutorials/FibonacciActionGoal] 1 subscriber * /fibonacci/cancel [actionlib_msgs/GoalID] 1 subscriber * /rosout [rosgraph_msgs/Log] 1 subscriber
Alternatively you can look at the nodes:
$ rqt_graph
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.