22#include <boost/any.hpp>
32#include <smacc2_msgs/msg/smacc_state_machine.hpp>
33#include <smacc2_msgs/msg/smacc_status.hpp>
34#include <smacc2_msgs/msg/smacc_transition_log_entry.hpp>
35#include <smacc2_msgs/srv/smacc_get_transition_history.hpp>
76 template <
typename TOrthogonal>
79 const std::map<std::string, std::shared_ptr<smacc2::ISmaccOrthogonal>> &
getOrthogonals()
const;
81 template <
typename SmaccComponentType>
84 template <
typename EventType>
87 template <
typename EventType>
98 template <
typename StateField,
typename BehaviorType>
113 const std::shared_ptr<rmw_request_id_t> request_header,
114 const std::shared_ptr<smacc2_msgs::srv::SmaccGetTransitionHistory::Request> req,
115 std::shared_ptr<smacc2_msgs::srv::SmaccGetTransitionHistory::Response> res);
117 template <
typename TSmaccSignal,
typename TMemberFunctionPrototype,
typename TSmaccObjectType>
119 TSmaccSignal & signal, TMemberFunctionPrototype
callback, TSmaccObjectType *
object);
124 template <
typename StateType>
127 template <
typename StateType>
130 template <
typename StateType>
133 template <
typename StateType>
136 template <
typename StateType>
141 template <
typename StateType>
150 template <
typename InitialStateType>
153 rclcpp::Node::SharedPtr
getNode();
166 template <
typename TOrthogonal>
170 rclcpp::Node::SharedPtr
nh_;
187 std::map<std::string, std::shared_ptr<smacc2::ISmaccOrthogonal>>
orthogonals_;
201 std::map<std::string, std::pair<std::function<std::string()>, boost::any>>
globalData_;
217 template <
typename EventType>
std::map< std::string, std::shared_ptr< smacc2::ISmaccOrthogonal > > orthogonals_
smacc2::SMRunMode runMode_
std::recursive_mutex eventQueueMutex_
virtual ~ISmaccStateMachine()
std::string getStateMachineName()
bool getGlobalSMData(std::string name, T &ret)
void publishTransition(const SmaccTransitionInfo &transitionInfo)
boost::signals2::connection createSignalConnection(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object)
StateMachineInternalAction stateMachineCurrentAction
rclcpp::Publisher< smacc2_msgs::msg::SmaccStateMachine >::SharedPtr stateMachinePub_
std::shared_ptr< SmaccStateInfo > currentStateInfo_
rclcpp::Node::SharedPtr getNode()
std::map< std::string, std::pair< std::function< std::string()>, boost::any > > globalData_
unsigned long stateSeqCounter_
void notifyOnStateExitting(StateType *state)
rclcpp::Service< smacc2_msgs::srv::SmaccGetTransitionHistory >::SharedPtr transitionHistoryService_
void setGlobalSMData(std::string name, T value)
virtual void onInitialize()
this function should be implemented by the user to create the orthogonals
void disposeStateAndDisconnectSignals()
TOrthogonal * getOrthogonal()
std::vector< smacc2_msgs::msg::SmaccTransitionLogEntry > transitionLogHistory_
void buildStateMachineInfo()
void notifyOnRuntimeConfigurationFinished(StateType *state)
const std::map< std::string, std::shared_ptr< smacc2::ISmaccOrthogonal > > & getOrthogonals() const
std::recursive_mutex m_mutex_
rclcpp::Publisher< smacc2_msgs::msg::SmaccStatus >::SharedPtr stateMachineStatusPub_
ISmaccStateMachine(std::string stateMachineName, SignalDetector *signalDetector)
void notifyOnStateExited(StateType *state)
void notifyOnStateEntryEnd(StateType *state)
void propagateEventToStateReactors(ISmaccState *st, EventType *ev)
ISmaccState * currentState_
const SmaccStateMachineInfo & getStateMachineInfo()
rclcpp::Node::SharedPtr nh_
void requiresComponent(SmaccComponentType *&storage)
unsigned long getCurrentStateCounter() const
std::shared_ptr< SmaccStateInfo > getCurrentStateInfo()
rclcpp::TimerBase::SharedPtr timer_
rclcpp::Publisher< smacc2_msgs::msg::SmaccTransitionLogEntry >::SharedPtr transitionLogPub_
ISmaccState * getCurrentState() const
void checkStateMachineConsistence()
SignalDetector * signalDetector_
rclcpp::Logger getLogger()
void notifyOnRuntimeConfigured(StateType *state)
void initializeROS(std::string smshortname)
smacc2_msgs::msg::SmaccStatus status_msg_
std::list< boost::signals2::connection > stateCallbackConnections
void state_machine_visualization()
std::shared_ptr< SmaccStateMachineInfo > stateMachineInfo_
void postEvent(EventType *ev, EventLifeTime evlifetime=EventLifeTime::ABSOLUTE)
void updateStatusMessage()
std::recursive_mutex & getMutex()
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)
void notifyOnStateEntryStart(StateType *state)
StateMachineInternalAction
void callback(const image_tools::ROSCvMatContainer &img)