smach_ros.action_server_wrapper module

class smach_ros.action_server_wrapper.ActionServerWrapper(node, 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)

Bases: object

SMACH container wrapper with actionlib ActionServer.

Use this class to associate an action server with a smach L{StateMachine<smach.state_machine.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 L{smach.State<smach.State>} and can only be used as a top-level container.

action_server_wrapper_cancel_callback(cancel_request)
execute_cb(goal_handle)

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

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

preempt_check()
publish_feedback(userdata)

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

termination_cb(userdata, terminal_states, container_outcome)

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 L{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.

transition_cb(userdata, active_states)

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

wrapped_container

State machine that this wrapper talks to.