yasmin.state module
- class yasmin.state.State(outcomes: Set[str])
Bases:
ABC
Represents a state in a state machine.
The State class defines a state that can execute actions and manage outcomes. It maintains information about its execution status and the possible outcomes of its execution.
- Attributes:
_outcomes (Set[str]): The possible outcomes of this state. __status (StateStatus): Current status of the state. __status_lock (threading.Lock): Lock for thread-safe status operations.
- cancel_state() None
Cancels the current state execution.
This method sets the status to CANCELED and logs the action.
- abstractmethod execute(blackboard: Blackboard) str
Executes the state’s specific logic.
This method is intended to be overridden by derived classes to provide specific execution logic.
- Args:
blackboard (Blackboard): A shared pointer to the Blackboard to use during execution.
- Returns:
str: A string representing the outcome of the execution.
- get_outcomes() Set[str]
Gets the set of possible outcomes for this state.
- Returns:
Set[str]: A constant reference to the set of possible outcomes.
- get_status() StateStatus
Gets the current status of the State.
- Returns:
StateStatus: The current status of the state.
- is_canceled() bool
Checks if the State is canceled.
- Returns:
bool: True if the state is canceled, otherwise False.
- is_completed() bool
Checks if the State is completed.
- Returns:
bool: True if the state is completed, otherwise False.
- is_idle() bool
Checks if the State is idle.
- Returns:
bool: True if the state is idle, otherwise False.
- is_running() bool
Checks if the State is running.
- Returns:
bool: True if the state is running, otherwise False.
- set_status(status: StateStatus) None
Sets the status of the State.
- Args:
status (StateStatus): The new status for the state.