|
Python YASMIN (Yet Another State MachINe)
|


Public Member Functions | |
| None | __init__ (self, Set[str] outcomes) |
| str | __call__ (self, Blackboard blackboard=None) |
| str | execute (self, Blackboard blackboard) |
| str | __str__ (self) |
| None | cancel_state (self) |
| bool | is_canceled (self) |
| bool | is_running (self) |
| Set[str] | get_outcomes (self) |
Protected Attributes | |
| Set | _outcomes = set() |
| A set of valid outcomes for this state. | |
| bool | _running = False |
| A flag indicating whether the state is currently running. | |
| bool | _canceled = False |
| A flag indicating whether the state has been canceled. | |
Abstract base class representing a state in a state machine.
This class provides a framework for creating specific states with defined outcomes.
Subclasses must implement the `execute` method to define the state-specific behavior.
Attributes:
_outcomes (Set[str]): A set of valid outcomes for this state.
_running (bool): A flag indicating whether the state is currently running.
_canceled (bool): A flag indicating whether the state has been canceled.
| None yasmin.state.State.__init__ | ( | self, | |
| Set[str] | outcomes ) |
Initializes the State instance.
:param outcomes: A set of valid outcomes for this state.
Must contain at least one outcome.
:raises ValueError: If the provided outcomes set is empty.
| str yasmin.state.State.__call__ | ( | self, | |
| Blackboard | blackboard = None ) |
Executes the state and returns the outcome.
This method sets the state as running, executes the state's behavior,
and validates the outcome against the allowed outcomes.
:param blackboard: An optional Blackboard instance that can be used during execution.
If None, a new Blackboard instance will be created.
:return: The outcome of the state execution.
:raises ValueError: If the outcome is not one of the valid outcomes for this state.
| str yasmin.state.State.__str__ | ( | self | ) |
Returns the string representation of the state. :return: The name of the class representing the state.
| None yasmin.state.State.cancel_state | ( | self | ) |
Cancels the execution of the state. Sets the _canceled flag to True and logs the cancellation.
Reimplemented in yasmin.concurrence.Concurrence, yasmin.state_machine.StateMachine, and yasmin_ros.action_state.ActionState.
| str yasmin.state.State.execute | ( | self, | |
| Blackboard | blackboard ) |
Executes the specific behavior of the state. This method must be implemented by subclasses to define what happens when the state is executed. :param blackboard: An instance of Blackboard that provides the context for execution. :return: The outcome of the execution as a string. :raises NotImplementedError: If not implemented in a subclass.
Reimplemented in yasmin.cb_state.CbState, yasmin.concurrence.Concurrence, yasmin.state_machine.StateMachine, yasmin_demos.concurrence_demo.BarState, yasmin_demos.concurrence_demo.FooState, yasmin_demos.remap_demo.BarState, yasmin_demos.remap_demo.Foo, yasmin_demos.yasmin_demo.BarState, yasmin_demos.yasmin_demo.FooState, yasmin_ros.action_state.ActionState, yasmin_ros.monitor_state.MonitorState, and yasmin_ros.service_state.ServiceState.
| Set[str] yasmin.state.State.get_outcomes | ( | self | ) |
Gets the valid outcomes for this state. :return: A set of valid outcomes as strings.
| bool yasmin.state.State.is_canceled | ( | self | ) |
Checks if the state has been canceled. :return: True if the state is canceled, False otherwise.
| bool yasmin.state.State.is_running | ( | self | ) |
Checks if the state is currently running. :return: True if the state is running, False otherwise.
|
protected |
A flag indicating whether the state has been canceled.
|
protected |
A set of valid outcomes for this state.
|
protected |
A flag indicating whether the state is currently running.