C++ YASMIN (Yet Another State MachINe)
Loading...
Searching...
No Matches
yasmin::State Class Reference

Represents a state in a state machine. More...

#include <state.hpp>

Inheritance diagram for yasmin::State:
Collaboration diagram for yasmin::State:

Public Member Functions

 State (const std::set< std::string > &outcomes)
 Constructs a State with a set of possible outcomes.
 
StateStatus get_status () const
 Gets the current status of the state.
 
bool is_idle () const
 Checks if the state is idle.
 
bool is_running () const
 Checks if the state is currently running.
 
bool is_canceled () const
 Checks if the state has been canceled.
 
bool is_completed () const
 Checks if the state has completed execution.
 
std::string operator() (std::shared_ptr< blackboard::Blackboard > blackboard)
 Executes the state and returns the outcome.
 
virtual std::string execute (std::shared_ptr< blackboard::Blackboard > blackboard)
 Executes the state's specific logic.
 
virtual void cancel_state ()
 Cancels the current state execution.
 
std::set< std::string > const & get_outcomes ()
 Gets the set of possible outcomes for this state.
 
virtual std::string to_string ()
 Converts the state to a string representation.
 

Protected Attributes

std::set< std::string > outcomes
 The possible outcomes of this state.
 

Private Attributes

std::atomic< StateStatusstatus {StateStatus::IDLE}
 Current status of the state.
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ State()

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

Constructs a State with a set of possible outcomes.

Parameters
outcomesA set of possible outcomes for this state.

Member Function Documentation

◆ cancel_state()

virtual void yasmin::State::cancel_state ( )
inlinevirtual

◆ execute()

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

◆ get_outcomes()

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

Gets the set of possible outcomes for this state.

Returns
A constant reference to the set of possible outcomes.

◆ get_status()

StateStatus State::get_status ( ) const

Gets the current status of the state.

Returns
The current StateStatus.

◆ is_canceled()

bool State::is_canceled ( ) const

Checks if the state has been canceled.

Returns
True if the state is canceled, otherwise false.

◆ is_completed()

bool State::is_completed ( ) const

Checks if the state has completed execution.

Returns
True if the state is completed, otherwise false.

◆ is_idle()

bool State::is_idle ( ) const

Checks if the state is idle.

Returns
True if the state is idle, otherwise false.

◆ is_running()

bool State::is_running ( ) const

Checks if the state is currently running.

Returns
True if the state is running, otherwise false.

◆ operator()()

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

Executes the state and returns the outcome.

Parameters
blackboardA shared pointer to the Blackboard to use during execution.
Returns
A string representing the outcome of the execution.

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.

Exceptions
std::logic_errorIf the outcome is not in the set of outcomes.

◆ to_string()

virtual std::string yasmin::State::to_string ( )
inlinevirtual

Converts the state to a string representation.

Returns
A string representation of the state.

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

Reimplemented in yasmin::Concurrence, yasmin::PyState, and yasmin::StateMachine.

Member Data Documentation

◆ outcomes

std::set<std::string> yasmin::State::outcomes
protected

The possible outcomes of this state.

◆ status

std::atomic<StateStatus> yasmin::State::status {StateStatus::IDLE}
private

Current status of the state.


The documentation for this class was generated from the following files: