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>
77 template <
typename TOrthogonal>
82 template <
typename TOrthogonal,
typename TClientBehavior>
85 auto orthogonal = this->
template getOrthogonal<TOrthogonal>();
87 return orthogonal->template getClientBehavior<TClientBehavior>(index);
90 const std::map<std::string, std::shared_ptr<smacc2::ISmaccOrthogonal>> &
getOrthogonals()
const;
92 template <
typename SmaccComponentType>
93 void requiresComponent(SmaccComponentType *& storage,
bool throwsExceptionIfNotExist =
false);
95 template <
typename EventType>
98 template <
typename EventType>
102 template <
typename T>
106 template <
typename T>
109 template <
typename StateField,
typename BehaviorType>
124 const std::shared_ptr<rmw_request_id_t> request_header,
125 const std::shared_ptr<smacc2_msgs::srv::SmaccGetTransitionHistory::Request> req,
126 std::shared_ptr<smacc2_msgs::srv::SmaccGetTransitionHistory::Response> res);
128 template <
typename TSmaccSignal,
typename TMemberFunctionPrototype,
typename TSmaccObjectType>
130 TSmaccSignal & signal, TMemberFunctionPrototype callback, TSmaccObjectType *
object);
134 template <
typename StateType>
137 template <
typename StateType>
140 template <
typename StateType>
143 template <
typename StateType>
146 template <
typename StateType>
149 template <
typename StateType>
158 template <
typename InitialStateType>
161 rclcpp::Node::SharedPtr
getNode();
174 template <
typename TOrthogonal>
178 rclcpp::Node::SharedPtr
nh_;
195 std::map<std::string, std::shared_ptr<smacc2::ISmaccOrthogonal>>
orthogonals_;
211 std::map<std::string, std::pair<std::function<std::string()>, boost::any>>
globalData_;
227 template <
typename EventType>
std::map< std::string, std::shared_ptr< smacc2::ISmaccOrthogonal > > orthogonals_
smacc2::SMRunMode runMode_
std::vector< ISmaccState * > currentState_
std::recursive_mutex eventQueueMutex_
virtual ~ISmaccStateMachine()
std::string getStateMachineName()
uint64_t stateSeqCounter_
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_
TClientBehavior * getClientBehavior(int index=0)
rclcpp::Node::SharedPtr getNode()
std::map< std::string, std::pair< std::function< std::string()>, boost::any > > globalData_
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
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_
void notifyOnStateExited(StateType *state)
void lockStateMachine(std::string msg)
void notifyOnStateEntryEnd(StateType *state)
void propagateEventToStateReactors(ISmaccState *st, EventType *ev)
void disconnectSmaccSignalObject(void *object)
const SmaccStateMachineInfo & getStateMachineInfo()
rclcpp::Node::SharedPtr nh_
uint64_t getCurrentStateCounter() const
std::shared_ptr< SmaccStateInfo > getCurrentStateInfo()
void unlockStateMachine(std::string msg)
rclcpp::TimerBase::SharedPtr timer_
rclcpp::Publisher< smacc2_msgs::msg::SmaccTransitionLogEntry >::SharedPtr transitionLogPub_
void requiresComponent(SmaccComponentType *&storage, bool throwsExceptionIfNotExist=false)
ISmaccState * getCurrentState() const
void checkStateMachineConsistence()
SignalDetector * signalDetector_
std::vector< boost::signals2::scoped_connection > longLivedSignalConnections_
std::map< void *, std::shared_ptr< CallbackCounterSemaphore > > stateCallbackConnections
rclcpp::Logger getLogger()
void notifyOnRuntimeConfigured(StateType *state)
void initializeROS(std::string smshortname)
smacc2_msgs::msg::SmaccStatus status_msg_
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