SMACC
Loading...
Searching...
No Matches
smacc_state_machine.h
Go to the documentation of this file.
1/*****************************************************************************************************************
2 * ReelRobotix Inc. - Software License Agreement Copyright (c) 2018
3 * Authors: Pablo Inigo Blasco, Brett Aldrich
4 *
5 ******************************************************************************************************************/
6#pragma once
7
8#include <boost/any.hpp>
9#include <map>
10#include <mutex>
11#include <stack>
12
13#include <smacc/common.h>
17#include <smacc/smacc_signal.h>
18
19#include <smacc_msgs/SmaccStateMachine.h>
20#include <smacc_msgs/SmaccTransitionLogEntry.h>
21#include <smacc_msgs/SmaccStatus.h>
22#include <smacc_msgs/SmaccGetTransitionHistory.h>
23
24#include <smacc/smacc_state.h>
26//#include <smacc/smacc_event_generator.h>
28
29namespace smacc
30{
31
32using namespace smacc::introspection;
33
34enum class EventLifeTime{
36 CURRENT_STATE /*events are discarded if we are leaving the state it were created. I is used for client behaviors whose lifetime is associated to state*/
37};
38
40{
46};
47
48
49
50// This class describes the concept of Smacc State Machine in an abastract way.
51// The SmaccStateMachineBase inherits from this state machine and from
52// statechart::StateMachine<> (via multiple inheritance)
54{
55public:
56 ISmaccStateMachine(SignalDetector *signalDetector);
57
58 virtual ~ISmaccStateMachine();
59
60 virtual void reset();
61
62 virtual void stop();
63
64 virtual void eStop();
65
66 template <typename TOrthogonal>
67 TOrthogonal *getOrthogonal();
68
69 const std::map<std::string, std::shared_ptr<smacc::ISmaccOrthogonal>> &getOrthogonals() const;
70
71 template <typename SmaccComponentType>
72 void requiresComponent(SmaccComponentType *&storage);
73
74 template <typename EventType>
75 void postEvent(EventType *ev, EventLifeTime evlifetime = EventLifeTime::ABSOLUTE);
76
77 template <typename EventType>
79
81
82 template <typename T>
83 bool getGlobalSMData(std::string name, T &ret);
84
85 template <typename T>
86 void setGlobalSMData(std::string name, T value);
87
88 template <typename StateField, typename BehaviorType>
89 void mapBehavior();
90
91 std::string getStateMachineName();
92
93 void state_machine_visualization(const ros::TimerEvent &);
94
95 inline std::shared_ptr<SmaccStateInfo> getCurrentStateInfo() { return currentStateInfo_; }
96
97 void publishTransition(const SmaccTransitionInfo &transitionInfo);
98
100 virtual void onInitialize();
101
102 bool getTransitionLogHistory(smacc_msgs::SmaccGetTransitionHistory::Request &req, smacc_msgs::SmaccGetTransitionHistory::Response &res);
103
104 template <typename TSmaccSignal, typename TMemberFunctionPrototype, typename TSmaccObjectType>
105 boost::signals2::connection createSignalConnection(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object);
106
107 void disconnectSmaccSignalObject(void *object);
108
109 template <typename StateType>
110 void notifyOnStateEntryStart(StateType *state);
111
112 template <typename StateType>
113 void notifyOnStateEntryEnd(StateType *state);
114
115 template <typename StateType>
116 void notifyOnRuntimeConfigured(StateType *state);
117
118 template <typename StateType>
119 void notifyOnStateExitting(StateType *state);
120
121 template <typename StateType>
122 void notifyOnStateExited(StateType *state);
123
124 template <typename StateType>
125 void notifyOnRuntimeConfigurationFinished(StateType *state);
126
127 inline uint64_t getCurrentStateCounter() const;
128
129 inline ISmaccState *getCurrentState() const;
130
132
133 template <typename InitialStateType>
135
136 inline ros::NodeHandle getNode(){
137 return nh_;
138 };
139
140
141protected:
143
144 void initializeROS(std::string smshortname);
145
146 void onInitialized();
147
148 template <typename TOrthogonal>
149 void createOrthogonal();
150
151 // Delegates to ROS param access with the current NodeHandle
152 template <typename T>
153 bool getParam(std::string param_name, T &param_storage);
154
155 // Delegates to ROS param access with the current NodeHandle
156 template <typename T>
157 void setParam(std::string param_name, T param_val);
158
159 // Delegates to ROS param access with the current NodeHandle
160 template <typename T>
161 bool param(std::string param_name, T &param_val, const T &default_val) const;
162
163 // The node handle for this state
164 ros::NodeHandle nh_;
165 ros::NodeHandle private_nh_;
166
167 ros::Timer timer_;
168 ros::Publisher stateMachinePub_;
170 ros::Publisher transitionLogPub_;
171 ros::ServiceServer transitionHistoryService_;
172
173 // if it is null, you may be located in a transition. There is a small gap of time where internally
174 // this currentState_ is null. This may change in the future.
175 std::vector<ISmaccState*> currentState_;
176
177 std::shared_ptr<SmaccStateInfo> currentStateInfo_;
178
179 smacc_msgs::SmaccStatus status_msg_;
180
181 // orthogonals
182 std::map<std::string, std::shared_ptr<smacc::ISmaccOrthogonal>> orthogonals_;
183
184private:
185 std::recursive_mutex m_mutex_;
186 std::recursive_mutex eventQueueMutex_;
187
189
190 std::map<void*, std::shared_ptr<CallbackCounterSemaphore>> stateCallbackConnections;
191
192 // shared variables
193 std::map<std::string, std::pair<std::function<std::string()>, boost::any>> globalData_;
194
195 std::vector<smacc_msgs::SmaccTransitionLogEntry> transitionLogHistory_;
196
198
199 // Event to notify to the signaldetection thread that a request has been created...
201
203
204 void lockStateMachine(std::string msg);
205
206 void unlockStateMachine(std::string msg);
207
208 template <typename EventType>
209 void propagateEventToStateReactors(ISmaccState *st, EventType *ev);
210
211 std::shared_ptr<SmaccStateMachineInfo> stateMachineInfo_;
212
213 void updateStatusMessage();
214
215 friend class ISmaccState;
216 friend class SignalDetector;
217};
218} // namespace smacc
219
void publishTransition(const SmaccTransitionInfo &transitionInfo)
std::shared_ptr< SmaccStateMachineInfo > stateMachineInfo_
void notifyOnRuntimeConfigurationFinished(StateType *state)
void initializeROS(std::string smshortname)
std::shared_ptr< SmaccStateInfo > getCurrentStateInfo()
bool param(std::string param_name, T &param_val, const T &default_val) const
const SmaccStateMachineInfo & getStateMachineInfo()
void propagateEventToStateReactors(ISmaccState *st, EventType *ev)
std::vector< ISmaccState * > currentState_
std::recursive_mutex eventQueueMutex_
smacc_msgs::SmaccStatus status_msg_
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)
std::shared_ptr< SmaccStateInfo > currentStateInfo_
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 &param_storage)
std::map< std::string, std::shared_ptr< smacc::ISmaccOrthogonal > > orthogonals_
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)
bool getGlobalSMData(std::string name, T &ret)
void notifyOnStateEntryStart(StateType *state)
std::vector< smacc_msgs::SmaccTransitionLogEntry > transitionLogHistory_
void setParam(std::string param_name, T param_val)
void postEvent(EventType *ev, EventLifeTime evlifetime=EventLifeTime::ABSOLUTE)
StateMachineInternalAction
SMRunMode
Definition: common.h:44