Note: This tutorial assumes that you have completed the previous tutorials: writing a simple action server using the execute callback method.
(!) 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 Client

Description: This tutorial covers using the simple_action_client library to create a Fibonacci action client. This example program creates an action client and sends a goal to the action server.

Tutorial Level: BEGINNER

The Code

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

   1 #include <ros/ros.h>
   2 #include <actionlib/client/simple_action_client.h>
   3 #include <actionlib/client/terminal_state.h>
   4 #include <actionlib_tutorials/FibonacciAction.h>
   5 
   6 int main (int argc, char **argv)
   7 {
   8   ros::init(argc, argv, "test_fibonacci");
   9 
  10   // create the action client
  11   // true causes the client to spin its own thread
  12   actionlib::SimpleActionClient<actionlib_tutorials::FibonacciAction> ac("fibonacci", true);
  13 
  14   ROS_INFO("Waiting for action server to start.");
  15   // wait for the action server to start
  16   ac.waitForServer(); //will wait for infinite time
  17 
  18   ROS_INFO("Action server started, sending goal.");
  19   // send a goal to the action
  20   actionlib_tutorials::FibonacciGoal goal;
  21   goal.order = 20;
  22   ac.sendGoal(goal);
  23 
  24   //wait for the action to return
  25   bool finished_before_timeout = ac.waitForResult(ros::Duration(30.0));
  26 
  27   if (finished_before_timeout)
  28   {
  29     actionlib::SimpleClientGoalState state = ac.getState();
  30     ROS_INFO("Action finished: %s",state.toString().c_str());
  31   }
  32   else
  33   {
  34     ROS_INFO("Action did not finish before the time out.");
  35     ac.cancelGoal();
  36   }
  37 
  38   //exit
  39   return 0;
  40 }

(Original can be found on the repository of the tutorial package)

The Code Explained

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

   1 #include <ros/ros.h>
   2 #include <actionlib/client/simple_action_client.h>
   3 #include <actionlib/client/terminal_state.h>
   4 

  • actionlib/client/simple_action_client.h is the action library used from implementing simple action clients.

  • actionlib/client/terminal_state.h defines the possible goal states.

   4 #include <actionlib_tutorials/FibonacciAction.h>
   5 

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

   6 int main (int argc, char **argv)
   7 {
   8   ros::init(argc, argv, "test_fibonacci");
   9 
  10   // create the action client
  11   // true causes the client to spin its own thread
  12   actionlib::SimpleActionClient<actionlib_tutorials::FibonacciAction> ac("fibonacci", true);

The action client is templated on the action definition, specifying what message types to communicate to the action server with. The action client constructor also takes two arguments, the server name to connect to and a boolean option to automatically spin a thread. If you prefer not to use threads (and you want actionlib to do the 'thread magic' behind the scenes), this is a good option for you. Here the action client is constructed with the server name and the auto spin option set to true.

  14   ROS_INFO("Waiting for action server to start.");
  15   // wait for the action server to start
  16   ac.waitForServer(); //will wait for infinite time
  17 

Since the action server may not be up and running, the action client will wait for the action server to start before continuing.

  17   ROS_INFO("Action server started, sending goal.");
  18   // send a goal to the action
  19   actionlib_tutorials::FibonacciGoal goal;
  20   goal.order = 20;
  21   ac.sendGoal(goal);

Here a goal message is created, the goal value is set and sent to the action server.

  24   //wait for the action to return
  25   bool finished_before_timeout = ac.waitForResult(ros::Duration(30.0));

The action client now waits for the goal to finish before continuing. The timeout on the wait is set to 30 seconds, this means after 30 seconds the function will return with false if the goal has not finished.

  26   if (finished_before_timeout)
  27   {
  28     actionlib::SimpleClientGoalState state = ac.getState();
  29     ROS_INFO("Action finished: %s",state.toString().c_str());
  30   }
  31   else
  32   {
  33     ROS_INFO("Action did not finish before the time out.");
  34     ac.cancelGoal();
  35   }
  36 
  37   //exit
  38 

If the goal finished before the time out the goal status is reported, else the user is notified that the goal did not finish in the allotted time.

Compiling

Add the following lines to your CMakeLists.txt file:

add_executable(fibonacci_client src/fibonacci_client.cpp)

target_link_libraries( 
  fibonacci_client
  ${catkin_LIBRARIES}
)

add_dependencies(
  fibonacci_client
  ${actionlib_tutorials_EXPORTED_TARGETS}
)

Then build:

cd %TOPDIR_YOUR_CATKIN_WORKSPACE%
catkin_make
source devel/setup.bash

rosbuild_add_executable(fibonacci_client src/fibonacci_client.cpp)
rosbuild_link_boost(fibonacci_client thread)

Running the Action client

After you have successfully built the executable, start a new terminal and run the client:

$ rosrun actionlib_tutorials fibonacci_client

You will see something similar to:

  • [ INFO] 1250806286.804217000: Started node [/test_fibonacci], pid [9414], bound on [aqy], xmlrpc port [35466], tcpros port [55866], logging to [~/ros/ros/log/test_fibonacci_9414.log], using [real] time
    [ INFO] 1250806287.828279000: Waiting for action server to start.

To check that your client is running properly, list ROS topics being published:

$ rostopic list -v

You will see something similar to:

  • Published topics:
     * /fibonacci/goal [actionlib_tutorials/FibonacciActionGoal] 1 publisher
     * /fibonacci/cancel [actionlib_msgs/GoalID] 1 publisher
     * /rosout [rosgraph_msgs/Log] 1 publisher
     * /rosout_agg [rosgraph_msgs/Log] 1 publisher
    
    Subscribed topics:
     * /fibonacci/feedback [actionlib_tutorials/FibonacciActionFeedback] 1 subscriber
     * /rosout [rosgraph_msgs/Log] 1 subscriber
     * /fibonacci/status [actionlib_msgs/GoalStatusArray] 1 subscriber
     * /fibonacci/result [actionlib_tutorials/FibonacciActionResult] 1 subscriber

Alternatively you can look at the nodes:

$ rxgraph

Or, starting with Groovy:

$ rqt_graph

fibonacci_client.png

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

Connecting the Server and Client

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

Wiki: actionlib_tutorials/Tutorials/SimpleActionClient (last edited 2023-03-10 13:33:42 by Hirotaka Yamada)