(!) 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.

SimpleActionState (ROS)

Description: This tutorial show how to use the SimpleActionState to directly call an action interface using SMACH

Tutorial Level: BEGINNER

Next Tutorial: ServiceState

   1 from smach_ros import SimpleActionState

You could simply call any action from a generic state, but SMACH has specific support to call actions, saving you a lot of code! SMACH provides a state class that acts as a proxy to an actionlib action. The instantiation of the state takes a topic name, action type, and some policy for generating a goal. The possible outcomes of the simple action state are 'succeeded', 'preempted' and 'aborted'.

Depending on how you get your goal, there are simple and more complex ways to use the simple action state.

Goal Message

Empty goal message

This is the trivial case, which will call an action server without filling out anything in the goal message.

   1 sm = StateMachine(['succeeded','aborted','preempted'])
   2 with sm:
   3     smach.StateMachine.add('TRIGGER_GRIPPER',
   4                            SimpleActionState('action_server_namespace',
   5                                              GripperAction),
   6                            transitions={'succeeded':'APPROACH_PLUG'})

Fixed goal message

A slightly more advanced usage let's you specify a hard-coded fixed goal that will get passed to the action server:

   1 sm = StateMachine(['succeeded','aborted','preempted'])
   2 with sm:
   3     gripper_goal = Pr2GripperCommandGoal()
   4     gripper_goal.command.position = 0.07
   5     gripper_goal.command.max_effort = 99999
   6     StateMachine.add('TRIGGER_GRIPPER',
   7                       SimpleActionState('action_server_namespace',
   8                                         GripperAction,
   9                                         goal=gripper_goal),
  10                       transitions={'succeeded':'APPROACH_PLUG'})

Goal from user data

Imagine you have a number of fields in the user data that already contain all the structs you need for your goal message. Then you can simply connect the userdata directly to the fields in the goal message. So, from the example above we learn that the gripper action has two fields in its goal: max_effort and position. Imagine our userdata contains the corresponding fields user_data_max and user_data_position. The code below connects the corresponding fields.

   1 sm = StateMachine(['succeeded','aborted','preempted'])
   2 with sm:
   3     StateMachine.add('TRIGGER_GRIPPER',
   4                       SimpleActionState('action_server_namespace',
   5                                         GripperAction,
   6                                         goal_slots=['max_effort', 
   7                                                     'position']),
   8                       transitions={'succeeded':'APPROACH_PLUG'},
   9                       remapping={'max_effort':'user_data_max',
  10                                  'position':'user_data_position'})

The same works for 'result_slots': the result fields of an action can automatically get written to your userdata. Also note that all fields you specify in 'goal_slots' and 'result_slots' are automatically put in your 'input_keys' and 'output_keys'.

Goal callback

This is the ultimate power version: you can get a callback when the action needs a goal, and you can create your own goal message on demand.

   1 sm = StateMachine(['succeeded','aborted','preempted'])
   2 with sm:
   3     def gripper_goal_cb(userdata, goal):
   4        gripper_goal = GripperGoal()
   5        gripper_goal.position.x = 2.0
   6        gripper_goal.max_effort = userdata.gripper_input
   7        return gripper_goal
   8 
   9     StateMachine.add('TRIGGER_GRIPPER',
  10                       SimpleActionState('action_server_namespace',
  11                                         GripperAction,
  12                                         goal_cb=gripper_goal_cb,
  13                                         input_keys=['gripper_input'])
  14                       transitions={'succeeded':'APPROACH_PLUG'},
  15                       remapping={'gripper_input':'userdata_input'})

In your goal callback you can use userdata, as long as you list the input_keys in the constructor. One of the arguments of the callback is the default goal. If you specified the 'goal=...' in the constructor, that object would get passed into the callback.

For more advanced callback usage, see @smach.cb_interface (API from ROS Jade) decorator.

Result Message

Result to userdata

You can write the result of the action directly to the userdata of your state.

   1 sm = StateMachine(['succeeded','aborted','preempted'])
   2 with sm:
   3     StateMachine.add('TRIGGER_GRIPPER',
   4                       SimpleActionState('action_server_namespace',
   5                                         GripperAction,
   6                                         result_slots=['max_effort', 
   7                                                       'position']),
   8                       transitions={'succeeded':'APPROACH_PLUG'},
   9                       remapping={'max_effort':'user_data_max',
  10                                  'position':'user_data_position'})

Result callback

The result callback is very similar to the goal callback. It allows you to read any data from the action result fields, and even return a different outcome than the default 'succeeded', 'preempted', 'aborted'.

   1 sm = StateMachine(['succeeded','aborted','preempted'])
   2 with sm:
   3     def gripper_result_cb(userdata, status, result):
   4        if status == GoalStatus.SUCCEEDED:
   5           userdata.gripper_output = result.num_iterations
   6           return 'my_outcome'
   7 
   8     StateMachine.add('TRIGGER_GRIPPER',
   9                       SimpleActionState('action_server_namespace',
  10                                         GripperAction,
  11                                         result_cb=gripper_result_cb,
  12                                         output_keys=['gripper_output'])
  13                       transitions={'succeeded':'APPROACH_PLUG'},
  14                       remapping={'gripper_output':'userdata_output'})

In the result callback you get the status of the action, which tells you if the action succeeded, aborted or was preempted. Plus you get access to the userdata, and the result of the action.

Optionally you can return a different outcome from the result callback. If you don't return anything, the state will return with the corresponding outcome of the action.

For more advanced callback usage, see @smach.cb_interface decorator.

Wiki: smach/Tutorials/SimpleActionState (last edited 2017-06-08 00:01:14 by IsaacSaito)