smach_ros package

Submodules

Module contents

class smach_ros.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.

class smach_ros.ConditionState(*args: Any, **kwargs: Any)

Bases: RosState

A state that will check a condition function a number of times.

If max_checks > 1, it will block while the condition is false and once it has checked max_checks times, it will return false.

execute(ud)
class smach_ros.IntrospectionClient(*args: Any, **kwargs: Any)

Bases: Node

get_servers()

Get the base names that are broadcasting smach states.

set_initial_state(server, path, initial_states, initial_userdata=smach.UserData, timeout=None)

Set the initial state of a smach server.

@type server: string @param server: The name of the introspection server to which this client should connect.

@type path: string @param path: The path to the target container in the state machine.

@type initial_states: list of string @param inital_state: The state the target container should take when it starts. This is as list of at least one state label.

@type initial_userdata: UserData @param initial_userdata: The userdata to inject into the target container.

@type timeout: rclpy.time.Duration @param timeout: Timeout for this call. If this is set to None, it will not block, and the initial state may not be set before the target state machine goes active.

class smach_ros.IntrospectionServer(*args: Any, **kwargs: Any)

Bases: Node

Server for providing introspection and control for smach.

clear()

Clear all proxies in this server.

construct(server_name, state, path)

Recursively construct proxies to containers.

start()
stop()
class smach_ros.MonitorState(*args: Any, **kwargs: Any)

Bases: RosState

A state that will check a given ROS topic with a condition function.

execute(ud)
request_preempt()
class smach_ros.RosState(*args: Any, **kwargs: Any)

Bases: State

A state that can interact with a ROS node.

property node
class smach_ros.ServiceState(*args: Any, **kwargs: Any)

Bases: RosState

State for calling a service.

execute(ud)

Execute service

class smach_ros.SimpleActionState(*args: Any, **kwargs: Any)

Bases: RosState

Simple action client state. Use this class to represent an ActionClient as a state in a state machine.

execute(ud)

Called when executing a state. This calls the goal_cb if it is defined, and then dispatches the goal with a non-blocking call to the action client.

request_preempt()

Request preemption of this state and cancel the goal with a timeout.

class smach_ros.SmachNode(*args: Any, **kwargs: Any)

Bases: Node

A ROS2 Node executing a SMACH StateMachine

join()
start()
smach_ros.set_preempt_handler(sc)

Sets a ROS pre-shutdown handler to preempt a given SMACH container when ROS receives a shutdown request.

This can be attached to multiple containers, but only needs to be used on the top-level containers.

@type sc: L{smach.Container} @param sc: Container to preempt on ROS shutdown.