Class State

Inheritance Relationships

Derived Types

Class Documentation

class State

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.

Subclassed by yasmin::CbState, yasmin::Concurrence, yasmin::StateMachine

Public Functions

State(const std::set<std::string> &outcomes)

Constructs a State with a set of possible outcomes.

Parameters:

outcomes – A set of possible outcomes for this state.

virtual ~State() = default

Virtual destructor for proper polymorphic destruction.

bool is_idle() const noexcept

Checks if the state is idle.

Returns:

True if the state is idle, otherwise false.

bool is_running() const noexcept

Checks if the state is currently running.

Returns:

True if the state is running, otherwise false.

bool is_canceled() const noexcept

Checks if the state has been canceled.

Returns:

True if the state is canceled, otherwise false.

bool is_completed() const noexcept

Checks if the state has completed execution.

Returns:

True if the state is completed, otherwise false.

std::string operator()(std::shared_ptr<yasmin::Blackboard> blackboard)

Executes the state and returns the outcome.

This function stores the state as running, invokes the execute method, and checks if the returned outcome is valid. If the outcome is not valid, a std::logic_error is thrown.

Parameters:

blackboard – A shared pointer to the Blackboard to use during execution.

Throws:

std::logic_error – If the outcome is not in the set of outcomes.

Returns:

A string representing the outcome of the execution.

inline virtual std::string execute(std::shared_ptr<yasmin::Blackboard> blackboard)

Executes the state’s specific logic.

This method is intended to be overridden by derived classes to provide specific execution logic.

Parameters:

blackboard – A shared pointer to the Blackboard to use during execution.

Returns:

A string representing the outcome of the execution.

inline virtual void cancel_state()

Cancels the current state execution.

This method sets the status to CANCELED and logs the action.

std::set<std::string> const &get_outcomes() const noexcept

Gets the set of possible outcomes for this state.

Returns:

A constant reference to the set of possible outcomes.

virtual std::string to_string() const

Converts the state to a string representation.

This method retrieves the demangled name of the class for a readable string representation.

Returns:

A string representation of the state.

Protected Attributes

std::set<std::string> outcomes

The possible outcomes of this state.