8#include <boost/any.hpp>
19#include <smacc_msgs/SmaccStateMachine.h>
20#include <smacc_msgs/SmaccTransitionLogEntry.h>
21#include <smacc_msgs/SmaccStatus.h>
22#include <smacc_msgs/SmaccGetTransitionHistory.h>
66 template <
typename TOrthogonal>
69 const std::map<std::string, std::shared_ptr<smacc::ISmaccOrthogonal>> &
getOrthogonals()
const;
71 template <
typename SmaccComponentType>
74 template <
typename EventType>
77 template <
typename EventType>
88 template <
typename StateField,
typename BehaviorType>
102 bool getTransitionLogHistory(smacc_msgs::SmaccGetTransitionHistory::Request &req, smacc_msgs::SmaccGetTransitionHistory::Response &res);
104 template <
typename TSmaccSignal,
typename TMemberFunctionPrototype,
typename TSmaccObjectType>
105 boost::signals2::connection
createSignalConnection(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *
object);
109 template <
typename StateType>
112 template <
typename StateType>
115 template <
typename StateType>
118 template <
typename StateType>
121 template <
typename StateType>
124 template <
typename StateType>
133 template <
typename InitialStateType>
148 template <
typename TOrthogonal>
152 template <
typename T>
153 bool getParam(std::string param_name, T ¶m_storage);
156 template <
typename T>
157 void setParam(std::string param_name, T param_val);
160 template <
typename T>
161 bool param(std::string param_name, T ¶m_val,
const T &default_val)
const;
182 std::map<std::string, std::shared_ptr<smacc::ISmaccOrthogonal>>
orthogonals_;
193 std::map<std::string, std::pair<std::function<std::string()>, boost::any>>
globalData_;
208 template <
typename EventType>
void publishTransition(const SmaccTransitionInfo &transitionInfo)
std::shared_ptr< SmaccStateMachineInfo > stateMachineInfo_
void notifyOnRuntimeConfigurationFinished(StateType *state)
ros::NodeHandle getNode()
void initializeROS(std::string smshortname)
std::shared_ptr< SmaccStateInfo > getCurrentStateInfo()
bool param(std::string param_name, T ¶m_val, const T &default_val) const
std::string getStateMachineName()
TOrthogonal * getOrthogonal()
SignalDetector * signalDetector_
const SmaccStateMachineInfo & getStateMachineInfo()
void propagateEventToStateReactors(ISmaccState *st, EventType *ev)
std::vector< ISmaccState * > currentState_
std::recursive_mutex eventQueueMutex_
smacc_msgs::SmaccStatus status_msg_
virtual ~ISmaccStateMachine()
ros::Publisher stateMachineStatusPub_
void lockStateMachine(std::string msg)
ISmaccState * getCurrentState() const
StateMachineInternalAction stateMachineCurrentAction
void notifyOnStateExitting(StateType *state)
void notifyOnRuntimeConfigured(StateType *state)
ros::ServiceServer transitionHistoryService_
const std::map< std::string, std::shared_ptr< smacc::ISmaccOrthogonal > > & getOrthogonals() const
void notifyOnStateEntryEnd(StateType *state)
void setGlobalSMData(std::string name, T value)
uint64_t getCurrentStateCounter() const
void buildStateMachineInfo()
std::shared_ptr< SmaccStateInfo > currentStateInfo_
ros::NodeHandle private_nh_
smacc::SMRunMode runMode_
std::map< void *, std::shared_ptr< CallbackCounterSemaphore > > stateCallbackConnections
void requiresComponent(SmaccComponentType *&storage)
std::recursive_mutex m_mutex_
void state_machine_visualization(const ros::TimerEvent &)
virtual void onInitialize()
this function should be implemented by the user to create the orthogonals
void notifyOnStateExited(StateType *state)
bool getParam(std::string param_name, T ¶m_storage)
ros::Publisher transitionLogPub_
std::map< std::string, std::shared_ptr< smacc::ISmaccOrthogonal > > orthogonals_
void updateStatusMessage()
std::map< std::string, std::pair< std::function< std::string()>, boost::any > > globalData_
boost::signals2::connection createSignalConnection(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object)
void unlockStateMachine(std::string msg)
void disconnectSmaccSignalObject(void *object)
uint64_t stateSeqCounter_
void getTransitionLogHistory()
bool getGlobalSMData(std::string name, T &ret)
void notifyOnStateEntryStart(StateType *state)
void checkStateMachineConsistence()
ros::Publisher stateMachinePub_
std::vector< smacc_msgs::SmaccTransitionLogEntry > transitionLogHistory_
void setParam(std::string param_name, T param_val)
void postEvent(EventType *ev, EventLifeTime evlifetime=EventLifeTime::ABSOLUTE)
StateMachineInternalAction