Class ISmaccStateMachine

Inheritance Relationships

Derived Type

Class Documentation

class ISmaccStateMachine

Subclassed by smacc2::SmaccStateMachineBase< DerivedStateMachine, InitialStateType >

Public Functions

ISmaccStateMachine(std::string stateMachineName, SignalDetector *signalDetector, rclcpp::NodeOptions nodeOptions = rclcpp::NodeOptions())
virtual ~ISmaccStateMachine()
virtual void reset()
virtual void stop()
virtual void eStop()
template<typename TOrthogonal>
TOrthogonal *getOrthogonal()
template<typename TOrthogonal, typename TClientBehavior>
inline TClientBehavior *getClientBehavior(int index = 0)
const std::map<std::string, std::shared_ptr<smacc2::ISmaccOrthogonal>> &getOrthogonals() const
template<typename SmaccComponentType>
void requiresComponent(SmaccComponentType *&storage, bool throwsExceptionIfNotExist = false)
template<typename EventType>
void postEvent(EventType *ev, EventLifeTime evlifetime = EventLifeTime::ABSOLUTE)
template<typename EventType>
void postEvent(EventLifeTime evlifetime = EventLifeTime::ABSOLUTE)
template<typename T>
bool getGlobalSMData(std::string name, T &ret)
template<typename T>
void setGlobalSMData(std::string name, T value)
template<typename StateField, typename BehaviorType>
void mapBehavior()
std::string getStateMachineName()
void state_machine_visualization()
inline std::shared_ptr<SmaccStateInfo> getCurrentStateInfo()
void publishTransition(const SmaccTransitionInfo &transitionInfo)
virtual void onInitialize()

this function should be implemented by the user to create the orthogonals

void getTransitionLogHistory(const std::shared_ptr<rmw_request_id_t> request_header, const std::shared_ptr<smacc2_msgs::srv::SmaccGetTransitionHistory::Request> req, std::shared_ptr<smacc2_msgs::srv::SmaccGetTransitionHistory::Response> res)
template<typename TSmaccSignal, typename TMemberFunctionPrototype, typename TSmaccObjectType>
boost::signals2::connection createSignalConnection(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object)
void disconnectSmaccSignalObject(void *object)
template<typename StateType>
void notifyOnStateEntryStart(StateType *state)
template<typename StateType>
void notifyOnStateEntryEnd(StateType *state)
template<typename StateType>
void notifyOnRuntimeConfigured(StateType *state)
template<typename StateType>
void notifyOnStateExitting(StateType *state)
template<typename StateType>
void notifyOnStateExited(StateType *state)
template<typename StateType>
void notifyOnRuntimeConfigurationFinished(StateType *state)
inline int64_t getCurrentStateCounter() const
inline ISmaccState *getCurrentState() const
inline const SmaccStateMachineInfo &getStateMachineInfo()
template<typename InitialStateType>
void buildStateMachineInfo()
rclcpp::Node::SharedPtr getNode()
inline rclcpp::Logger getLogger()
inline std::recursive_mutex &getMutex()

Protected Functions

void checkStateMachineConsistence()
void initializeROS(std::string smshortname)
void onInitialized()
template<typename TOrthogonal>
void createOrthogonal()

Protected Attributes

rclcpp::Node::SharedPtr nh_
rclcpp::TimerBase::SharedPtr timer_
rclcpp::Publisher<smacc2_msgs::msg::SmaccStateMachine>::SharedPtr stateMachinePub_
rclcpp::Publisher<smacc2_msgs::msg::SmaccStatus>::SharedPtr stateMachineStatusPub_
rclcpp::Publisher<smacc2_msgs::msg::SmaccTransitionLogEntry>::SharedPtr transitionLogPub_
rclcpp::Service<smacc2_msgs::srv::SmaccGetTransitionHistory>::SharedPtr transitionHistoryService_
std::vector<ISmaccState*> currentState_
std::shared_ptr<SmaccStateInfo> currentStateInfo_
smacc2_msgs::msg::SmaccStatus status_msg_
std::map<std::string, std::shared_ptr<smacc2::ISmaccOrthogonal>> orthogonals_
std::vector<boost::signals2::scoped_connection> longLivedSignalConnections_
std::shared_ptr<SmaccStateMachineInfo> stateMachineInfo_