Show EOL distros: 

common: actionlib | bfl | bond | bondcpp | bondpy | filters | nodelet | nodelet_topic_tools | pluginlib | smclib | tinyxml | xacro | yaml_cpp

Package Summary

The actionlib package provides a standardized interface for interfacing with preemptible tasks. Examples of this include moving the base to a target location, performing a laser scan and returning the resulting point cloud, detecting the handle of a door, etc.

common: actionlib | bfl | tinyxml | yaml_cpp

Package Summary

The actionlib package provides a standardized interface for interfacing with preemptible tasks. Examples of this include moving the base to a target location, performing a laser scan and returning the resulting point cloud, detecting the handle of a door, etc.

actionlib

Package Summary

The actionlib package provides a standardized interface for interfacing with preemptible tasks. Examples of this include moving the base to a target location, performing a laser scan and returning the resulting point cloud, detecting the handle of a door, etc.

Package Summary

The actionlib stack provides a standardized interface for interfacing with preemptable tasks. Examples of this include moving the base to a target location, performing a laser scan and returning the resulting point cloud, detecting the handle of a door, etc.

  • Maintainer status: maintained
  • Maintainer: Dirk Thomas <dthomas AT osrfoundation DOT org>
  • Author: Eitan Marder-Eppstein, Vijay Pradeep
  • License: BSD
  • Source: git https://github.com/ros/actionlib.git (branch: groovy-devel)

Package Summary

The actionlib stack provides a standardized interface for interfacing with preemptable tasks. Examples of this include moving the base to a target location, performing a laser scan and returning the resulting point cloud, detecting the handle of a door, etc.

  • Maintainer status: maintained
  • Maintainer: Esteve Fernandez <esteve AT osrfoundation DOT org>
  • Author: Eitan Marder-Eppstein, Vijay Pradeep
  • License: BSD
  • Source: git https://github.com/ros/actionlib.git (branch: hydro-devel)
ros_base: actionlib | bond_core | class_loader | dynamic_reconfigure | nodelet_core | pluginlib | ros_core

Package Summary

The actionlib stack provides a standardized interface for interfacing with preemptable tasks. Examples of this include moving the base to a target location, performing a laser scan and returning the resulting point cloud, detecting the handle of a door, etc.

ros_base: actionlib | bond_core | class_loader | dynamic_reconfigure | nodelet_core | pluginlib | ros_core

Package Summary

The actionlib stack provides a standardized interface for interfacing with preemptable tasks. Examples of this include moving the base to a target location, performing a laser scan and returning the resulting point cloud, detecting the handle of a door, etc.

ros_base: actionlib | bond_core | class_loader | dynamic_reconfigure | nodelet_core | pluginlib | ros_core

Package Summary

The actionlib stack provides a standardized interface for interfacing with preemptable tasks. Examples of this include moving the base to a target location, performing a laser scan and returning the resulting point cloud, detecting the handle of a door, etc.

ros_base: actionlib | bond_core | class_loader | dynamic_reconfigure | nodelet_core | pluginlib | ros_core

Package Summary

The actionlib stack provides a standardized interface for interfacing with preemptable tasks. Examples of this include moving the base to a target location, performing a laser scan and returning the resulting point cloud, detecting the handle of a door, etc.

ros_base: actionlib | bond_core | dynamic_reconfigure | nodelet_core | ros_core

Package Summary

The actionlib stack provides a standardized interface for interfacing with preemptable tasks. Examples of this include moving the base to a target location, performing a laser scan and returning the resulting point cloud, detecting the handle of a door, etc.

ros_base: actionlib | bond_core | dynamic_reconfigure | nodelet_core | ros_core

Package Summary

The actionlib stack provides a standardized interface for interfacing with preemptable tasks. Examples of this include moving the base to a target location, performing a laser scan and returning the resulting point cloud, detecting the handle of a door, etc.

English

简体中文

Overview

In any large ROS based system, there are cases when someone would like to send a request to a node to perform some task, and also receive a reply to the request. This can currently be achieved via ROS services.

In some cases, however, if the service takes a long time to execute, the user might want the ability to cancel the request during execution or get periodic feedback about how the request is progressing. The actionlib package provides tools to create servers that execute long-running goals that can be preempted. It also provides a client interface in order to send requests to the server.

Detailed Description

For a full discussion of how actionlib operates "under the hood", please see the Detailed Description.

Client-Server Interaction

The ActionClient and ActionServer 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.

client_server_interaction.png

Action Specification: Goal, Feedback, & Result

In order for the client and server to communicate, we need to define a few messages on which they communicate. This is with an action specification. This defines the Goal, Feedback, and Result messages with which clients and servers communicate:

Goal
To accomplish tasks using actions, we introduce the notion of a goal that can be sent to an ActionServer by an ActionClient. In the case of moving the base, the goal would be a PoseStamped message that contains information about where the robot should move to in the world. For controlling the tilting laser scanner, the goal would contain the scan parameters (min angle, max angle, speed, etc).

Feedback
Feedback provides server implementers a way to tell an ActionClient about the incremental progress of a goal. For moving the base, this might be the robot's current pose along the path. For controlling the tilting laser scanner, this might be the time left until the scan completes.

Result
A result is sent from the ActionServer to the ActionClient upon completion of the goal. This is different than feedback, since it is sent exactly once. This is extremely useful when the purpose of the action is to provide some sort of information. For move base, the result isn't very important, but it might contain the final pose of the robot. For controlling the tilting laser scanner, the result might contain a point cloud generated from the requested scan.

.action File

The action specification is defined using a .action file. The .action file has the goal definition, followed by the result definition, followed by the feedback definition, with each section separated by 3 hyphens (---).

These files are placed in a package's ./action directory, and look extremely similar to a service's .srv file. An action specification for doing the dishes might look like the following:

./action/DoDishes.action

# Define the goal
uint32 dishwasher_id  # Specify which dishwasher we want to use
---
# Define the result
uint32 total_dishes_cleaned
---
# Define a feedback message
float32 percent_complete

Based on this .action file, 6 messages need to be generated in order for the client and server to communicate. This generation can be automatically triggered during the make process:

Build a package by Catkin

Build a package that contains .action file

Add the following to your CMakeLists.txt file before catkin_package().

find_package(catkin REQUIRED genmsg actionlib_msgs)
add_action_files(DIRECTORY action FILES DoDishes.action)
generate_messages(DEPENDENCIES actionlib_msgs)

Additionally, the package.xml of the package that includes .action files must include the following dependencies:

<build_depend>actionlib_msgs</build_depend>
<exec_depend>actionlib_msgs</exec_depend>

Build a package that depends on actionlib API

Package that depends on actionlib API to implement an action server or use an action client needs another dependency on actionlib.

CMakeLists.txt

find_package(catkin REQUIRED genmsg actionlib_msgs actionlib)
add_action_files(DIRECTORY action FILES DoDishes.action)
generate_messages(DEPENDENCIES actionlib_msgs)

package.xml

<build_depend>actionlib</build_depend>
<build_depend>actionlib_msgs</build_depend>
<exec_depend>actionlib</exec_depend>
<exec_depend>actionlib_msgs</exec_depend>

Results

For the DoDishes.action, the following messages are generated by genaction.py:

  • DoDishesAction.msg

  • DoDishesActionGoal.msg

  • DoDishesActionResult.msg

  • DoDishesActionFeedback.msg

  • DoDishesGoal.msg

  • DoDishesResult.msg

  • DoDishesFeedback.msg

These messages are then used internally by actionlib to communicate between the ActionClient and ActionServer.

Using the ActionClient

C++ SimpleActionClient

Full API Reference for the C++ SimpleActionClient

Quickstart Guide:
Suppose you have defined DoDishes.action in the chores package. The following snippet shows how to send a goal to a DoDishes ActionServer called "do_dishes".

   1 #include <chores/DoDishesAction.h> // Note: "Action" is appended
   2 #include <actionlib/client/simple_action_client.h>
   3 
   4 typedef actionlib::SimpleActionClient<chores::DoDishesAction> Client;
   5 
   6 int main(int argc, char** argv)
   7 {
   8   ros::init(argc, argv, "do_dishes_client");
   9   Client client("do_dishes", true); // true -> don't need ros::spin()
  10   client.waitForServer();
  11   chores::DoDishesGoal goal;
  12   // Fill in goal here
  13   client.sendGoal(goal);
  14   client.waitForResult(ros::Duration(5.0));
  15   if (client.getState() == actionlib::SimpleClientGoalState::SUCCEEDED)
  16     printf("Yay! The dishes are now clean");
  17   printf("Current State: %s\n", client.getState().toString().c_str());
  18   return 0;
  19 }

Note: For the C++ SimpleActionClient, the waitForServer method will only work if a separate thread is servicing the client's callback queue. This requires passing in true for the spin_thread option of the client's constructor, running with a multi-threaded spinner, or using your own thread to service ROS callback queues.

Python SimpleActionClient

Full API reference for the Python SimpleActionClient

Suppose the DoDishes.action exists in the chores package. The following snippet shows how to send a goal to a DoDishes ActionServer called "do_dishes" using Python.

   1 #! /usr/bin/env python
   2 
   3 import roslib
   4 roslib.load_manifest('my_pkg_name')
   5 import rospy
   6 import actionlib
   7 
   8 from chores.msg import DoDishesAction, DoDishesGoal
   9 
  10 if __name__ == '__main__':
  11     rospy.init_node('do_dishes_client')
  12     client = actionlib.SimpleActionClient('do_dishes', DoDishesAction)
  13     client.wait_for_server()
  14 
  15     goal = DoDishesGoal()
  16     # Fill in the goal here
  17     client.send_goal(goal)
  18     client.wait_for_result(rospy.Duration.from_sec(5.0))

Implementing an ActionServer

C++ SimpleActionServer

Full API Reference for the C++ SimpleActionServer

Quickstart Guide:
Suppose you have defined DoDishes.action in the chores package. The following snippet shows how to write a DoDishes ActionServer called "do_dishes".

   1 #include <chores/DoDishesAction.h>  // Note: "Action" is appended
   2 #include <actionlib/server/simple_action_server.h>
   3 
   4 typedef actionlib::SimpleActionServer<chores::DoDishesAction> Server;
   5 
   6 void execute(const chores::DoDishesGoalConstPtr& goal, Server* as)  // Note: "Action" is not appended to DoDishes here
   7 {
   8   // Do lots of awesome groundbreaking robot stuff here
   9   as->setSucceeded();
  10 }
  11 
  12 int main(int argc, char** argv)
  13 {
  14   ros::init(argc, argv, "do_dishes_server");
  15   ros::NodeHandle n;
  16   Server server(n, "do_dishes", boost::bind(&execute, _1, &server), false);
  17   server.start();
  18   ros::spin();
  19   return 0;
  20 }

Python SimpleActionServer

Full API Reference for the Python SimpleActionServer

Quickstart Guide:
Suppose you have defined DoDishes.action in the chores package. The following snippet shows how to write a DoDishes ActionServer called "do_dishes".

   1 #! /usr/bin/env python
   2 
   3 import roslib
   4 roslib.load_manifest('my_pkg_name')
   5 import rospy
   6 import actionlib
   7 
   8 from chores.msg import DoDishesAction
   9 
  10 class DoDishesServer:
  11   def __init__(self):
  12     self.server = actionlib.SimpleActionServer('do_dishes', DoDishesAction, self.execute, False)
  13     self.server.start()
  14 
  15   def execute(self, goal):
  16     # Do lots of awesome groundbreaking robot stuff here
  17     self.server.set_succeeded()
  18 
  19 
  20 if __name__ == '__main__':
  21   rospy.init_node('do_dishes_server')
  22   server = DoDishesServer()
  23   rospy.spin()

SimpleActionServer Goal Policies

The SimpleActionServer implements a single goal policy on top of the ActionServer class. The specification of the policy is as follows:

  • Only one goal can have an active status at a time
  • New goals preempt previous goals based on the stamp in their GoalID field (later goals preempt earlier ones)
  • An explicit preempt goal preempts all goals with timestamps that are less than or equal to the stamp associated with the preempt
  • Accepting a new goal implies successful preemption of any old goal and the status of the old goal will be changed automatically to reflect this

Calling acceptNewGoal accepts a new goal when one is available. The status of this goal is set to active upon acceptance, and the status of any previously active goal is set to preempted. Preempts received for the new goal between checking if isNewGoalAvailable or invocation of a goal callback and the acceptNewGoal call will not trigger a preempt callback. This means, isPreemptRequested should be called after accepting the goal even for callback-based implementations to make sure the new goal does not have a pending preempt request.

Tutorials

Please refer to the Tutorials page

Report a Bug

Please report any bugs on the actionlib GitHub repository Issues page by detailing your environment (OS, ROS Distro) and a minimal example how how to replicate the issue.

Wiki: actionlib (last edited 2024-01-09 09:16:20 by Martin Pecka)