Note: This tutorial assumes that you have completed the previous tutorials: writing a simple action server using the goal 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 Threaded Simple Action Client

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

Tutorial Level: INTERMEDIATE

Next Tutorial: Running an action server and client with other nodes

  Show EOL distros: 

The Code

First, create actionlib_tutorials/src/averaging_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/AveragingAction.h>
   5 #include <boost/thread.hpp>
   6 
   7 void spinThread()
   8 {
   9   ros::spin();
  10 }
  11 
  12 int main (int argc, char **argv)
  13 {
  14   ros::init(argc, argv, "test_averaging");
  15 
  16   // create the action client
  17   actionlib::SimpleActionClient<actionlib_tutorials::AveragingAction> ac("averaging");
  18   boost::thread spin_thread(&spinThread);
  19 
  20   ROS_INFO("Waiting for action server to start.");
  21   ac.waitForServer();
  22 
  23   ROS_INFO("Action server started, sending goal.");
  24   // send a goal to the action
  25   actionlib_tutorials::AveragingGoal goal;
  26   goal.samples = 100;
  27   ac.sendGoal(goal);
  28 
  29   //wait for the action to return
  30   bool finished_before_timeout = ac.waitForResult(ros::Duration(30.0));
  31 
  32   if (finished_before_timeout)
  33   {
  34     actionlib::SimpleClientGoalState state = ac.getState();
  35     ROS_INFO("Action finished: %s",state.toString().c_str());
  36   }
  37   else
  38     ROS_INFO("Action did not finish before the time out.");
  39 
  40   // shutdown the node and join the thread back before exiting
  41   ros::shutdown();
  42   spin_thread.join();
  43 
  44   //exit
  45   return 0;
  46 }

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/server/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/AveragingAction.h>
   5 

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

   5 #include <boost/thread.hpp>
   6 

This includes the boost thread library for spinning the thread in this example.

   7 void spinThread()
   8 {
   9   ros::spin();
  10 }

Here is a simple function for spinning a thread that will be used later in the code. This thread will spin the ros node in the background.

  12 int main (int argc, char **argv)
  13 {
  14   ros::init(argc, argv, "test_averaging");
  15 
  16   // create the action client
  17   actionlib::SimpleActionClient<actionlib_tutorials::AveragingAction> ac("averaging");

The action client is template 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. Here the action client is constructed with the server name and the auto spin option set to false, which means a thread must be created.

  18   boost::thread spin_thread(&spinThread);

Here the thread is created and the ros node is started spinning in the background. By using this method you can create multiple threads for your action client if needed.

  20   ROS_INFO("Waiting for action server to start.");
  21   ac.waitForServer();

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

  23   ROS_INFO("Action server started, sending goal.");
  24   // send a goal to the action
  25   actionlib_tutorials::AveragingGoal goal;
  26   goal.samples = 100;
  27   ac.sendGoal(goal);

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

  29   //wait for the action to return
  30   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.

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

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.

  40   // shutdown the node and join the thread back before exiting
  41   ros::shutdown();
  42   spin_thread.join();
  43 
  44   //exit
  45   return 0;
  46 }

Now that the goal is completed and we have reported the goal status, we need to shutdown the ros node and join our thread back before exiting.

Compiling and Running the Client

Add the following line to your CMakeLists.txt file:

rosbuild_add_executable(averaging_client src/averaging_client.cpp)

add_executable(averaging_client src/averaging_client.cpp)
target_link_libraries(averaging_client ${catkin_LIBRARIES})

After you have made the executable by catkin_make, start a roscore in a new terminal:

$ roscore

And then run the client:

$ rosrun actionlib_tutorials averaging_client

You will see something similar to:

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

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

$ rostopic list -v

You will see something similar to:

  • Published topics:
     * /averaging/goal [actionlib_tutorials/AveragingActionGoal] 1 publisher
     * /averaging/cancel [actionlib/GoalID] 1 publisher
     * /rosout [roslib/Log] 1 publisher
     * /rosout_agg [roslib/Log] 1 publisher
    
    Subscribed topics:
     * /time [unknown type] 2 subscribers
     * /rosout [roslib/Log] 1 subscriber
     * /averaging/feedback [unknown type] 1 subscriber
     * /averaging/status [unknown type] 1 subscriber
     * /averaging/result [unknown type] 1 subscriber

Alternatively you can look at the nodes:

$ rxgraph &

$ rosrun rqt_graph rqt_graph &

averaging_action_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 an action server and client with other nodes.

Wiki: actionlib_tutorials/Tutorials/SimpleActionClient(Threaded) (last edited 2016-12-10 02:54:51 by IsaacSaito)