|
C++ YASMIN (Yet Another State MachINe)
|
Runs a series of states in parallel. More...
#include <concurrence.hpp>


Public Types | |
| typedef std::map< std::string, std::string > | StateOutcomeMap |
| typedef std::map< std::string, StateOutcomeMap > | OutcomeMap |
Public Member Functions | |
| Concurrence (const std::map< std::string, std::shared_ptr< State > > &states, const std::string &default_outcome, const OutcomeMap &outcome_map) | |
| Constructs a State with a set of possible outcomes. | |
| std::string | execute (std::shared_ptr< blackboard::Blackboard > blackboard) override |
| Executes the state's specific logic. | |
| void | cancel_state () override |
| Cancels the current state execution. | |
| const std::map< std::string, std::shared_ptr< State > > & | get_states () const |
| Returns the map of states managed by this concurrence state. | |
| const OutcomeMap & | get_outcome_map () const |
| Returns the outcome map for this concurrence state. | |
| const std::string & | get_default_outcome () const |
| Returns the default outcome for this concurrence state. | |
| std::string | to_string () override |
| Converts the state to a string representation. | |
Public Member Functions inherited from yasmin::State | |
| 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. | |
| std::set< std::string > const & | get_outcomes () |
| Gets the set of possible outcomes for this state. | |
Protected Attributes | |
| const std::map< std::string, std::shared_ptr< State > > | states |
| The states to run concurrently (name -> state) | |
| const std::string | default_outcome |
| Default outcome. | |
| OutcomeMap | outcome_map |
| std::map< std::string, std::shared_ptr< std::string > > | intermediate_outcome_map |
| Stores the intermediate outcomes of the concurrent states. | |
| std::set< std::string > | possible_outcomes |
| The set of possible outcomes. | |
Protected Attributes inherited from yasmin::State | |
| std::set< std::string > | outcomes |
| The possible outcomes of this state. | |
Static Private Member Functions | |
| static std::set< std::string > | generate_possible_outcomes (const OutcomeMap &outcome_map, const std::string &default_outcome) |
| Helper function to generate a set of possible outcomes from an outcome map. | |
Private Attributes | |
| std::mutex | intermediate_outcome_mutex |
| Mutex for intermediate outcome map. | |
Runs a series of states in parallel.
The Concurrence class runs a set of states concurrently, waiting for the termination of each, and then returns a single output according to a provided rule map, or a default outcome if no rule is satisfied.
| typedef std::map<std::string, StateOutcomeMap> yasmin::Concurrence::OutcomeMap |
| typedef std::map<std::string, std::string> yasmin::Concurrence::StateOutcomeMap |
| Concurrence::Concurrence | ( | const std::map< std::string, std::shared_ptr< State > > & | states, |
| const std::string & | default_outcome, | ||
| const OutcomeMap & | outcome_map ) |
Constructs a State with a set of possible outcomes.
| states | A map of state names to states that will run concurrently. |
| default_outcome | The default outcome to return if no outcome map rules are satisfied. |
| outcome_map | A map of outcome names to requirements for achieving that outcome. |
|
overridevirtual |
Cancels the current state execution.
This method sets the canceled flag to true and logs the action.
Reimplemented from yasmin::State.
|
overridevirtual |
Executes the state's specific logic.
| blackboard | A shared pointer to the Blackboard to use during execution. |
This method is intended to be overridden by derived classes to provide specific execution logic.
Reimplemented from yasmin::State.
|
staticprivate |
Helper function to generate a set of possible outcomes from an outcome map.
| outcome_map | |
| default_outcome |
| const std::string & Concurrence::get_default_outcome | ( | ) | const |
Returns the default outcome for this concurrence state.
| const Concurrence::OutcomeMap & Concurrence::get_outcome_map | ( | ) | const |
Returns the outcome map for this concurrence state.
| const std::map< std::string, std::shared_ptr< State > > & Concurrence::get_states | ( | ) | const |
Returns the map of states managed by this concurrence state.
|
inlineoverridevirtual |
Converts the state to a string representation.
Reimplemented from yasmin::State.
|
protected |
Default outcome.
|
protected |
Stores the intermediate outcomes of the concurrent states.
|
private |
Mutex for intermediate outcome map.
|
protected |
Specifies which combination of state outputs should produce a given overall output
|
protected |
The set of possible outcomes.
|
protected |
The states to run concurrently (name -> state)