Package smach_ros :: Module action_server_wrapper :: Class ActionServerWrapper

Class ActionServerWrapper

source code

SMACH container wrapper with actionlib ActionServer.

Use this class to associate an action server with a smach StateMachine. This allows invocation of the state machine over the actionlib API/protocol.

This class delegates to a provided SMACH container and associates it with an action server. The user can specify lists of outcomes which correspond to different action result statuses (SUCCEEDED, ABORTED, PREEMPTED). Once the delegate state machine leaves one of these outcomes, this wrapper class will cause the state machine to terminate, and cause the action server to return a result.

Note that this class does not inherit from smach.State and can only be used as a top-level container.

Instance Methods
 
__init__(self, server_name, action_spec, wrapped_container, succeeded_outcomes=[], aborted_outcomes=[], preempted_outcomes=[], goal_key='action_goal', feedback_key='action_feedback', result_key='action_result', goal_slots_map={}, feedback_slots_map={}, result_slots_map={}, expand_goal_slots=False, pack_result_slots=False)
Constructor.
source code
 
run_server(self)
Run the state machine as an action server.
source code
 
transition_cb(self, userdata, active_states)
Transition callback passed to state machine.
source code
 
termination_cb(self, userdata, terminal_states, container_outcome)
Termination callback passed to state machine.
source code
 
publish_feedback(self, userdata)
Publish the feedback message in the userdata db.
source code
 
execute_cb(self, goal)
Action server goal callback This method is called when the action server associated with this state machine receives a goal.
source code
 
preempt_cb(self)
Action server preempt callback.
source code
Instance Variables
  wrapped_container
State machine that this wrapper talks to.
Method Details

__init__(self, server_name, action_spec, wrapped_container, succeeded_outcomes=[], aborted_outcomes=[], preempted_outcomes=[], goal_key='action_goal', feedback_key='action_feedback', result_key='action_result', goal_slots_map={}, feedback_slots_map={}, result_slots_map={}, expand_goal_slots=False, pack_result_slots=False)
(Constructor)

source code 

Constructor.

Parameters:
  • server_name (string) - The name of the action server that this container will present.
  • action_spec (actionlib action msg) - The type of action this server will present
  • wrapped_container (StateMachine) - The state machine to manipulate
  • succeeded_outcomes (array of strings) - Array of terminal state labels which, when left, should cause the action server to return SUCCEEDED as a result status.
  • aborted_outcomes (array of strings) - Array of terminal state labels which, when left, should cause the action server to return ABORTED as a result status.
  • preempted_outcomes (array of strings) - Array of terminal state labels which, when left, should cause the action server to return PREEMPTED as a result status.
  • goal_key (string) - The userdata key into which the action goal should be stuffed when the action server receives one.
  • feedback_key (string) - The userdata key into which the SMACH container can put feedback information relevant to the action.
  • result_key (string) - The userdata key into which the SMACH container can put result information from this action.

run_server(self)

source code 

Run the state machine as an action server. Note that this method does not block.

transition_cb(self, userdata, active_states)

source code 

Transition callback passed to state machine. This method is called each time the state machine transitions.

termination_cb(self, userdata, terminal_states, container_outcome)

source code 

Termination callback passed to state machine. This callback receives the final state and state machine outcome as specified by the state-outcome map given to the delegate container on construction (see ActionServerWrapper.__init__).

Remember that in this context, the SMACH container is just a single state object, which has an outcome like any other state; it is this outcome on which we switch here. This method will determine from the state machine outcome which result should be returned to the action client for this goal.

publish_feedback(self, userdata)

source code 

Publish the feedback message in the userdata db. Note that this feedback is independent of smach.

execute_cb(self, goal)

source code 

Action server goal callback This method is called when the action server associated with this state machine receives a goal. This puts the goal into the userdata, which is the userdata of the contained state.

preempt_cb(self)

source code 

Action server preempt callback. This method is called when the action client preempts an active goal.

In this case, the StateMachine needs to propagate said preemption to the currently active delegate action (the current state).