Tutorial 9: communication using actions

Objective: This tutorial session is devoted to learn the ROS synchronous request/response remote procedure calls with feedback and preemption.

Contents

After this session you will be able to:

  • Understand the action files and know how to configure the package to use actions.

  • Understand the action server mechanism: the action server object and the execute and the preempt callback functions.

  • Understand the action client mechanism: the client object, the goal setting and the server preemption.

  • Write nodes able to call/offer an action service.

  • Use standard actions to control robots.

Provided packages:

This tutorial will use the following packages:

Package actions_tutorial
Package mastering_ros_demo_pkg
Package mastering_ros_robot_description_pkg

Prepare the catkin workspace to work with them:

  1. If you have not yet done so, follow the steps in Exercise 0 to:

  • clone in your ~/git-projects folder the meta-repository containing all the required packages,

  • create the catkin workspace folders (use catkin_ws9 for the current tutorial).

  1. Follow the procedure shown in Procedure to prepare the exercises to import in the intro2ros/2023/teamXX/EXERCISE6 subgroup of your GitLab account the package:

  1. In your git-projects folder clone the actions_tutorial and solution_exercise6 projects of your GitLab account inside an exercise6 subfolder (change XX by your team number). You can use https:

$ git clone https://gitlab.com/intro2ros/2023/teamXX/exercise6/actions_tutorial.git exercise6/actions_tutorial
$ git clone https://gitlab.com/intro2ros/2023/teamXX/exercise6/solution_exercise6.git exercise6/solution_exercise6

or ssh:

$ git clone git@gitlab.com:intro2ros/2023/teamXX/exercise6/actions_tutorial.git exercise6/actions_tutorial
$ git clone git@gitlab.com:intro2ros/2023/teamXX/exercise6/solution_exercise6.git exercise6/solution_exercise6
  1. In your catkin_ws9/src folder create a symbolic link to the packages to be used:

$ ln -s ~/git-projects/exercise6/actions_tutorial
$ ln -s ~/git-projects/all_introduction_to_ros_packages/mastering_ros_demo_pkg
$ ln -s ~/git-projects/all_introduction_to_ros_packages/mastering_ros_robot_description_pkg
  1. Edit the build.sh file of the solution_exercise6 package to add your credencials (token_user and token_code) and push the change.

References:

This tutorial is partially based on on chapter 1 of the book Mastering ROS for Robotics Programming from Lentin Joseph.

Complementary resources:

Working with ROS actionlib

ROS actionlib allows a request/reply interaction between two nodes, the action client and the action server, that communicate via a ROS Action Protocol, which is built on top of ROS messages. The client and server then provide a simple API for users to request goals (on the client side) or to execute goals (on the server side) via function calls and callbacks.

../_images/action_client_server_schema.png

The action client can preempt the requested goal running in the action server and start sending another one if the request is not finished on time as expected.

Like ROS services, actions are defined in text files. They have an extension .action and are usually stored in a subfolder called action in the package directory. They contain the following information:

  • Goal: This is the request sent by the action client to the action server, like “move a joint to 90 degrees”.

  • Feedback: This is the information to be fed back by the action server to the action client while the request is being processed, such as the current value of the joint being moved.

  • Result: This is the final information sent by the action server to the action client once the request has been fulfilled, and can be a computational result or a simple acknowledgement.

From the .action file, several messages are generated and used internally by actionlib to communicate between the action client and the action server. For instance, if the file is called Demo_action.action, the following messages are generated:

  • Demo_actionAction.msg

  • Demo_actionGoal.msg

  • Demo_actionResult.msg

  • Demo_actionFeedback.msg

Building and running a simple example

The package mastering_ros_demo_pkg contains a simple example. There is an action server that counts (with a step size of 1) from 0 to a given goal value set by the action client, at a 5 Hz rate. The feedback is the current count and the result the final count after the specified number of seconds has elapsed, or the goal count if it has been reached within the time limit.

The action file

The action file Demo_action.action in the action folder is:

#goal definition
int32 count
---
#result definition
int32 final_count
---
#feedback
int32 current_number

CMakeList.txt and package.xml files

The package.xml file contains the required dependecies on message generation and runtime packages as it was also required when using non-standard services and messages, as well as dependecies on actionlib and actionlib_msg, i.e. using package format 2 the following lines should be included:

<build_export_depend>message_runtime</build_export_depend>
<exec_depend>message_runtime</exec_depend>
<depend>message_generation</depend>
<depend>actionlib</depend>
<depend>actionlib_msgs</depend>

Regarding the CMakeLists.txt file, the main changes required to consider the actions are:

  • actionlib, actionlib_msgs, and message_generation are passed in find_package() and in catkin_package().

  • Boost is added as a system dependency, and to the include directory.

  • The Demo_action.action file is added in add_action_files().

  • actionlib_msgs is added in generate_messages().

  • The add_dependencies() is included with dependencies on ${catkin_EXPORTED_TARGETS} and ${${PROJECT_NAME}_EXPORTED_TARGETS} as done when defining non-standard services (see tutorial 5 ).

 1
 2
 3
 4
 5
 6
 7
 8
 9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
cmake_minimum_required(VERSION 2.8.3)
project(mastering_ros_demo_pkg)

find_package(catkin REQUIRED COMPONENTS
 roscpp
 rospy
 std_msgs
 actionlib
 actionlib_msgs
 message_generation
)

## System dependencies are found with CMake's conventions
find_package(Boost REQUIRED COMPONENTS system)

add_message_files(
 FILES
 demo_msg.msg
)

## Generate services in the 'srv' folder
add_service_files(
 FILES
 demo_srv.srv
)

## Generate actions in the 'action' folder
add_action_files(
 FILES
 Demo_action.action
)

## Generate added messages and services with any dependencies listed here
generate_messages(
 DEPENDENCIES
 std_msgs
 actionlib_msgs
)

catkin_package(
 CATKIN_DEPENDS roscpp rospy std_msgs actionlib actionlib_msgs message_runtime
)

include_directories(
 include
 ${catkin_INCLUDE_DIRS}
 ${Boost_INCLUDE_DIRS}
)

#Demo action server
add_executable(demo_action_server src/demo_action_server.cpp)
add_dependencies(demo_action_server ${catkin_EXPORTED_TARGETS} ${${PROJECT_NAME}_EXPORTED_TARGETS})
target_link_libraries(demo_action_server ${catkin_LIBRARIES} )

#Demo action client
add_executable(demo_action_client src/demo_action_client.cpp)
add_dependencies(demo_action_client  ${catkin_EXPORTED_TARGETS} ${${PROJECT_NAME}_EXPORTED_TARGETS})
target_link_libraries(demo_action_client ${catkin_LIBRARIES})

Running the demo

Build the mastering_ros_demo_pkg package and execute the launch file to run the action server and the action client. Set the arguments as to count up to 30 in a maximum allowed time of 3 s:

$ catkin build mastering_ros_demo_pkg
$ source devel/setup.bash
$ roslaunch mastering_ros_demo_pkg demo_actions.launch max_count:=30 timeout:=3

Exercise

Repeat for different goals and maximum allowed time.

The ROS action server

The action server of this simple example is implemented as a class called Demo_actionAction in the file demo_action_server.cpp. This file includes the header files simple_action_server.h and Demo_actionAction.h, the latter automatically generated from the action file Demo_action.action.

The data of the class Demo_actionAction includes:

  • A simple action server instance with the custom action message type.

  • A feedback instance for sending feedback during the operation.

  • A result instance for sending the final result.

The function of the class Demo_actionAction includes:

  • The constructor: Here the action server is created by taking as arguments the Nodehandle, the action name, and the action callback function (executed when the server receives a goal value). It also registers the preempt callback function (executed when the action is preempted) using registerPreemptCallback and starts the server with start.

  • The executeCB: The action callback is where all the processing is done. It loops until the goal value is reached or the action is preempted. If the current value reaches the goal value, then the final result is stored in the result variable and the success is advertised (using setSucceeded), otherwise the current result is stored in the feedback variable and it is published (using publishFeedback).

  • The preemptCB: The preempt callback stores in the result variable the result reached at the preemption instant, and the preemption condition is advertised (using setPreempted).

In main(), an instance of Demo_actionAction is created, which starts the action server.

 1
 2
 3
 4
 5
 6
 7
 8
 9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
#include "ros/ros.h"
#include "std_msgs/Int32.h"
#include <actionlib/server/simple_action_server.h>
#include "mastering_ros_demo_pkg/Demo_actionAction.h"
#include <iostream>
#include <sstream>

class Demo_actionAction
{
protected:
 ros::NodeHandle nh_;
 // NodeHandle instance must be created before this line. Otherwise strange error may occur.
 actionlib::SimpleActionServer<mastering_ros_demo_pkg::Demo_actionAction> as;
 // create messages that are used to published feedback/result
 mastering_ros_demo_pkg::Demo_actionFeedback feedback;
 mastering_ros_demo_pkg::Demo_actionResult result;

 std::string action_name;
 int goal;
 int progress;

public:
 Demo_actionAction(std::string name) :
   as(nh_, name, boost::bind(&Demo_actionAction::executeCB, this, _1), false),
   action_name(name)
 {
     as.registerPreemptCallback(boost::bind(&Demo_actionAction::preemptCB, this));
     as.start();
 }

 ~Demo_actionAction(void)
 {
 }

 void preemptCB()
 {
   ROS_WARN("%s got preempted!", action_name.c_str());
   result.final_count = progress;
   as.setPreempted(result,"I got Preempted");
 }

 void executeCB(const mastering_ros_demo_pkg::Demo_actionGoalConstPtr &goal)
 {
   if(!as.isActive() || as.isPreemptRequested()) return;
   ros::Rate rate(5);
   ROS_INFO("%s is processing the goal %d", action_name.c_str(), goal->count);
   for(progress = 1 ; progress <= goal->count; progress++){
     //Check for ros
     if(!ros::ok()){
       result.final_count = progress;
       as.setAborted(result,"I failed !");
       ROS_INFO("%s Shutting down",action_name.c_str());
       break;
     }

     if(!as.isActive() || as.isPreemptRequested()){
       return;
     }

     if(goal->count <= progress){
       ROS_INFO("%s Succeeded at getting to goal %d", action_name.c_str(), goal->count);
       result.final_count = progress;
       as.setSucceeded(result);
     }else{
       ROS_INFO("Setting to goal %d / %d",feedback.current_number,goal->count);
       feedback.current_number = progress;
       as.publishFeedback(feedback);
     }
     rate.sleep();
   }
 }
};

int main(int argc, char** argv)
{
 ros::init(argc, argv, "demo_action");
 ROS_INFO("Starting Demo Action Server");
 Demo_actionAction demo_action_obj(ros::this_node::getName());
 ros::spin();
 return 0;
}

Other useful functions of the simple action server are setAborted, isActive, isPreemptRequested or shutdown.

The ROS action client

The action client of this simple example is implemented in the file demo_action_client.cpp. Like the action_server, this file includes the header files simple_action_client.h and Demo_actionAction.h. It also includes the terminal_state.h header file where the different potential terminal states are defined.

In this file a simple action client instance is first created and then set to a waiting state until the server is available (using the waitForServer function). Then:

  • A goal is defined and then sent using the sendGoal function.

  • Using the waitForResult function, the action client is set to a waiting state until the server gives a positive response (the goal has been reached) or a failure (not finished before timeout).

  • Finally the goal is canceled using the cancelGoal function.

 1
 2
 3
 4
 5
 6
 7
 8
 9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
#include "ros/ros.h"
#include <iostream>
#include <actionlib/client/simple_action_client.h>
#include <actionlib/client/terminal_state.h>
#include "mastering_ros_demo_pkg/Demo_actionAction.h"

int main (int argc, char **argv)
{
 ros::init(argc, argv, "demo_action_client");

 if(argc != 3){
   ROS_INFO("%d",argc);
   ROS_WARN("Usage: demo_action_client <goal> <time_to_preempt_in_sec>");
   return 1;
 }

 // create the action client
 // true causes the client to spin its own thread
 actionlib::SimpleActionClient<mastering_ros_demo_pkg::Demo_actionAction> ac("demo_action", true);

 ROS_INFO("Waiting for action server to start.");

 // wait for the action server to start
 ac.waitForServer(); //will wait for infinite time

 ROS_INFO("Action server started, sending goal.");

 // send a goal to the action
 mastering_ros_demo_pkg::Demo_actionGoal goal;
 goal.count = atoi(argv[1]);

 ROS_INFO("Sending Goal [%d] and Preempt time of [%d]",goal.count, atoi(argv[2]));
 ac.sendGoal(goal);

 //wait for the action to return
 bool finished_before_timeout = ac.waitForResult(ros::Duration(atoi(argv[2])));
 //Preempting task
 ac.cancelGoal();

 if (finished_before_timeout){
   actionlib::SimpleClientGoalState state = ac.getState();
   ROS_INFO("Action finished: %s",state.toString().c_str());
   //Preempting the process
   ac.cancelGoal();
 }
 else{
   ROS_INFO("Action did not finish before the time out.");
 }

 //exit
 return 0;
}

Other useful functions of the simple action client are sendGoalAndWait, getResult or getState.

The pan-tilt example

Runnning the example

In this example an action server is responsible of moving one of the two joints of the pan-tilt structure to a given joint value, i.e. the goal has two fields, name and count. The action client passes the joint value in degrees, the name of the joint (“pan” or “tilt”) and the timeout threshold.

Build the actions_tutorial package and run the action server and the rviz using the launch file provided, and then the action client in a separate terminal. Ask the server to move the pan up to 30 in a maximum allowed time of 3 s:

$ catkin build actions_tutorial
$ source devel/setup.bash
$ roslaunch actions_tutorial actions_tutorial.launch
$ rosrun actions_tutorial pantilt_action_client 30 pan 3

Exercise

Repeat for different goals (pan/tilt and joint values) and maximum allowed time.

Exercise

Take a look at:

  • The pantilt_action.action file: note that the goal has two fields.

  • The pantilt_action_server.cpp file: note that the executeCB modifies the values of the joint_state vector, that is advertised by a publisher added in the main function.

  • The pantilt_action_client.cpp file: note that the two fields of the goal are filled by the function arguments.

Also, note that the sendGoal function has three functions as arguments, that are explained next.

Action client advanced features

One of the implementation of the sendGoal function of the simple action client allows to pass as parameteres three callback functions that are called:

  • Upon completion of the goal (called once). It has two parameters to store the state and the result:

    const actionlib::SimpleClientGoalState& state
    const name_of_the_actionResultConstPtr& result
  • Upon the activation of the client (called once). It has no parameters.

  • Every time feedback is received for the goal. It has one parameter to store the feedback:

    const name_of_the_actionFeedbackConstPtr& feedback

e.g., in the pan-tilt example we have:

ac.sendGoal(goal, &doneCb, &activeCb, &feedbackCb);
// Called once when the goal completes
void doneCb(const actionlib::SimpleClientGoalState& state,
           const actions_tutorial::pantilt_actionResultConstPtr& result)
{
  ROS_INFO("Finished in state [%s]", state.toString().c_str());
  ROS_INFO("Answer: Final angle is %f", result->final_count);
}

// Called once when the goal becomes active
void activeCb()
{
  ROS_INFO("Goal just went active");
}

// Called every time feedback is received for the goal
void feedbackCb(const actions_tutorial::pantilt_actionFeedbackConstPtr& feedback)
{
  ROS_INFO("Got Feedback: current angle is %f", feedback->current_number);
}

These callbacks give a flexible way to handle the execution of the action service, allowing for instance to cancel the goal according to some given feedback, or deciding different ways to proceed according to the resulting state.

The use of callbacks can also be posed as a way to avoid using the waitForResult call to block for the goal to finish, as done in the following ROS wiki advanced actionlib tutorial where the way to register those callbacks as class methods is also shown.

Actions for control

The FollowJointTrajectory action

In order to make the robot move along a trajectory, the FollowJointTrajectory action is defined by the control_msgs package.

Mainly, it specifies the goal action as a trajectory composed of list of joint configurations and some information on the tolerance in its following, defines some result states (ranging from SUCCESS to different error situations like GOAL_TOLERANCE_VIOLATED), and sets the action feedback as the desired and the actual geometry_msgs/JointTrajectoryPoint.

The control_msgs/FollowJointTrajectory.action file shows the goal, the result and the feedback sections (separated by ---).

Exercise

Use rqt to browse the control_msgs/FollowJointTrajectoryAction and all the involved messages:

  • control_msgs/FollowJointTrajectoryActionGoal

  • control_msgs/FollowJointTrajectoryActionResult

  • control_msgs/FollowJointTrajectoryActionFeedback

  • control_msgs/FollowJointTrajectoryGoal

  • control_msgs/FollowJointTrajectoryResult

  • control_msgs/FollowJointTrajectoryFeedback

  • control_msgs/JointTolerance

  • geometry_msgs/JointTrajectoryPoint

../_images/FollowJointTrajectoryAction.png

The FollowJointTrajectory action server

To move a robot, a real one or one simulated with Gazebo, using the FollowJointTrajectoryAction, the corresponding robot controller should be defined and spawned, as it will be detailed in tutorial 10, and then the FollowJointTrajectory action server will be available.

The name of the action server for the FollowJointTrajectoryAction is “follow_joint_trajectory”, as defined in joint_trajectory_controller_impl.h of the ros controllers package.

The trajectory commanded as the action goal may be composed of a single point or several points. The actual executed trajectory will include the motion from the current robot configuration toward the first point in the trajectory and uses polynomial interpolation.

A FollowJointTrajectory action client: Moving the pan-tilt

In the current tutorial, an action client example has been implemented to move the pan-tilt structure using the FollowJointTrajectory action. It specifies a sinusoidal trajectory with many points for the pan joint and sets the tilt at a fixed value. The robot is simulated with Gazebo (although the Gazebo GUI is not shown) and visualized using rviz.

Execute the launch file. A key must be pressed to start each new execution of the trajectory, as it will be prompted in the terminal.

$ roslaunch actions_tutorial pantilt_trajectory_controller.launch

Exercise

Take a look at the pantilt_follow_traj.cpp file. Note:

  • How the goal data is filled.

  • How the action service is called.

  • How is the feedback provided.

  • Which is the result data reported.

Exercise

Use the Action Type Browser of rqt to take a look at the GripperCommandAction action provided to control grippers.

EXERCISE 6

To solve Exercise 6 you must modify the actions_tutorial package that you have cloned in your git-projects folder.

Recall to keep commiting the changes when coding the solution (do small commits with good commit messages!) and write a README.md file in the solution_exercise6 package explaining your solution (Markdown Cheat Sheet).

Exercise 6a

Create a node called follow_traj_wrap_server in a follow_traj_wrap_server.cpp file, by modifying the pantilt_follow_traj.cpp file so that the node offers different services that encapsulate the main functions involved in the control of the robot using the FollowJointTrajectory action, i.e. services to:

  • set a trajectory towards a goal configuration (use the set_point_to_point_trajectory.srv file)

  • define the tolerance parameters (use the set_goal_tolerances.srv file)

  • send the goal to move the robot along the trajectory (use the move_robot_trajectory.srv file).

To test the server, a node called pantilt_follow_traj_client has been coded in the file pantilt_follow_traj_client.cpp of the actions_tutorial package.

Use a launch file called pantilt_trajectory_controller_server.launch to start all the nodes.

Exercise 6b

Add an additional service to send the goal to move the robot along the trajectory and preempt it if the position of the grasping_frame does not lie within some cartesian limits (use the move_robot_trajectory_safe.srv file and uncomment the required lines in the pantilt_follow_traj_client.cpp file).

SOLUTION EXERCISE 6

Download the zipped solution.