C++ YASMIN (Yet Another State MachINe)
|
Represents a state in a state machine. More...
#include <state.hpp>
Public Member Functions | |
State (std::set< std::string > outcomes) | |
Constructs a State with a set of possible outcomes. | |
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. | |
bool | is_canceled () const |
Checks if the state has been canceled. | |
bool | is_running () const |
Checks if the state is currently running. | |
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_bool | canceled {false} |
Indicates if the state has been canceled. | |
std::atomic_bool | running {false} |
Indicates if the state is currently running. | |
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 (running or canceled) and the possible outcomes of its execution.
State::State | ( | std::set< std::string > | outcomes | ) |
Constructs a State with a set of possible outcomes.
outcomes | A set of possible outcomes for this state. |
|
inlinevirtual |
Cancels the current state execution.
This method sets the canceled flag to true and logs the action.
Reimplemented in yasmin::StateMachine, yasmin_ros::ActionState< ActionT >, and yasmin_ros::ActionState< Fibonacci >.
|
inlinevirtual |
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 in BarState, FooState, yasmin::CbState, yasmin::StateMachine, yasmin_ros::ActionState< ActionT >, yasmin_ros::ActionState< Fibonacci >, yasmin_ros::MonitorState< MsgT >, yasmin_ros::MonitorState< nav_msgs::msg::Odometry >, yasmin_ros::ServiceState< ServiceT >, and yasmin_ros::ServiceState< example_interfaces::srv::AddTwoInts >.
std::set< std::string > const & State::get_outcomes | ( | ) |
Gets the set of possible outcomes for this state.
bool State::is_canceled | ( | ) | const |
Checks if the state has been canceled.
bool State::is_running | ( | ) | const |
Checks if the state is currently running.
std::string State::operator() | ( | std::shared_ptr< blackboard::Blackboard > | blackboard | ) |
Executes the state and returns the outcome.
blackboard | A shared pointer to the Blackboard to use during 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.
std::logic_error | If the outcome is not in the set of outcomes. |
|
inlinevirtual |
Converts the state to a string representation.
This method retrieves the demangled name of the class for a readable string representation.
Reimplemented in yasmin::StateMachine.
|
private |
Indicates if the state has been canceled.
|
protected |
The possible outcomes of this state.
|
private |
Indicates if the state is currently running.