SMACC
Loading...
Searching...
No Matches
Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes | Friends | List of all members
smacc::ISmaccStateMachine Class Reference

#include <smacc_state_machine.h>

Inheritance diagram for smacc::ISmaccStateMachine:
Inheritance graph
Collaboration diagram for smacc::ISmaccStateMachine:
Collaboration graph

Public Member Functions

 ISmaccStateMachine (SignalDetector *signalDetector)
 
virtual ~ISmaccStateMachine ()
 
virtual void reset ()
 
virtual void stop ()
 
virtual void eStop ()
 
template<typename TOrthogonal >
TOrthogonal * getOrthogonal ()
 
const std::map< std::string, std::shared_ptr< smacc::ISmaccOrthogonal > > & getOrthogonals () const
 
template<typename SmaccComponentType >
void requiresComponent (SmaccComponentType *&storage)
 
template<typename EventType >
void postEvent (EventType *ev, EventLifeTime evlifetime=EventLifeTime::ABSOLUTE)
 
template<typename EventType >
void postEvent (EventLifeTime evlifetime=EventLifeTime::ABSOLUTE)
 
void getTransitionLogHistory ()
 
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 (const ros::TimerEvent &)
 
std::shared_ptr< SmaccStateInfogetCurrentStateInfo ()
 
void publishTransition (const SmaccTransitionInfo &transitionInfo)
 
virtual void onInitialize ()
 this function should be implemented by the user to create the orthogonals More...
 
bool getTransitionLogHistory (smacc_msgs::SmaccGetTransitionHistory::Request &req, smacc_msgs::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)
 
uint64_t getCurrentStateCounter () const
 
ISmaccStategetCurrentState () const
 
const SmaccStateMachineInfogetStateMachineInfo ()
 
template<typename InitialStateType >
void buildStateMachineInfo ()
 
ros::NodeHandle getNode ()
 

Protected Member Functions

void checkStateMachineConsistence ()
 
void initializeROS (std::string smshortname)
 
void onInitialized ()
 
template<typename TOrthogonal >
void createOrthogonal ()
 
template<typename T >
bool getParam (std::string param_name, T &param_storage)
 
template<typename T >
void setParam (std::string param_name, T param_val)
 
template<typename T >
bool param (std::string param_name, T &param_val, const T &default_val) const
 

Protected Attributes

ros::NodeHandle nh_
 
ros::NodeHandle private_nh_
 
ros::Timer timer_
 
ros::Publisher stateMachinePub_
 
ros::Publisher stateMachineStatusPub_
 
ros::Publisher transitionLogPub_
 
ros::ServiceServer transitionHistoryService_
 
std::vector< ISmaccState * > currentState_
 
std::shared_ptr< SmaccStateInfocurrentStateInfo_
 
smacc_msgs::SmaccStatus status_msg_
 
std::map< std::string, std::shared_ptr< smacc::ISmaccOrthogonal > > orthogonals_
 

Private Member Functions

void lockStateMachine (std::string msg)
 
void unlockStateMachine (std::string msg)
 
template<typename EventType >
void propagateEventToStateReactors (ISmaccState *st, EventType *ev)
 
void updateStatusMessage ()
 

Private Attributes

std::recursive_mutex m_mutex_
 
std::recursive_mutex eventQueueMutex_
 
StateMachineInternalAction stateMachineCurrentAction
 
std::map< void *, std::shared_ptr< CallbackCounterSemaphore > > stateCallbackConnections
 
std::map< std::string, std::pair< std::function< std::string()>, boost::any > > globalData_
 
std::vector< smacc_msgs::SmaccTransitionLogEntry > transitionLogHistory_
 
smacc::SMRunMode runMode_
 
SignalDetectorsignalDetector_
 
uint64_t stateSeqCounter_
 
std::shared_ptr< SmaccStateMachineInfostateMachineInfo_
 

Friends

class ISmaccState
 
class SignalDetector
 

Detailed Description

Definition at line 53 of file smacc_state_machine.h.

Constructor & Destructor Documentation

◆ ISmaccStateMachine()

smacc::ISmaccStateMachine::ISmaccStateMachine ( SignalDetector signalDetector)

Definition at line 15 of file smacc_state_machine.cpp.

17{
18 ROS_INFO("Creating State Machine Base");
19 signalDetector_ = signalDetector;
21
22 std::string runMode;
23 if (nh_.getParam("run_mode", runMode))
24 {
25 if (runMode == "debug")
26 {
28 }
29 else if (runMode == "release")
30 {
32 }
33 else
34 {
35 ROS_ERROR("Incorrect run_mode value: %s", runMode.c_str());
36 }
37 }
38 else
39 {
41 }
42}
void initialize(ISmaccStateMachine *stateMachine)

References smacc::DEBUG, smacc::SignalDetector::initialize(), nh_, smacc::RELEASE, runMode_, and signalDetector_.

Here is the call graph for this function:

◆ ~ISmaccStateMachine()

smacc::ISmaccStateMachine::~ISmaccStateMachine ( )
virtual

Definition at line 59 of file smacc_state_machine.cpp.

60{
61 ROS_INFO("Finishing State Machine");
62}

Member Function Documentation

◆ buildStateMachineInfo()

template<typename InitialStateType >
void smacc::ISmaccStateMachine::buildStateMachineInfo

Definition at line 656 of file smacc_state_machine_impl.h.

657 {
658 this->stateMachineInfo_ = std::make_shared<SmaccStateMachineInfo>();
659 this->stateMachineInfo_->buildStateMachineInfo<InitialStateType>();
660 this->stateMachineInfo_->assembleSMStructureMessage(this);
662 }
std::shared_ptr< SmaccStateMachineInfo > stateMachineInfo_

References checkStateMachineConsistence(), and stateMachineInfo_.

Here is the call graph for this function:

◆ checkStateMachineConsistence()

void smacc::ISmaccStateMachine::checkStateMachineConsistence ( )
protected

Definition at line 184 of file smacc_state_machine.cpp.

185{
186 // transition from an orthogonal that doesn’t exist.
187 // transition from a source that doesn’t exist.
188
189 // std::stringstream errorbuffer;
190 // bool errorFound = false;
191
192 // for (auto &stentry : this->stateMachineInfo_->states)
193 // {
194 // auto stinfo = stentry.second;
195
196 // for (auto &transition : stinfo->transitions_)
197 // {
198 // auto evinfo = transition.eventInfo;
199 // bool found = false;
200 // for (auto &orthogonal : orthogonals_)
201 // {
202 // if (orthogonal.first == evinfo->getOrthogonalName())
203 // {
204 // found = true;
205 // break;
206 // }
207 // }
208
209 // if (!found)
210 // {
211 // errorbuffer << "---------" << std::endl
212 // << "[Consistency Checking] Transition event refers not existing orthogonal." << std::endl
213 // << "State: " << demangleType(*stinfo->tid_) << std::endl
214 // << "Transition: " << transition.transitionTypeInfo->getFullName() << std::endl
215 // << "Orthogonal: " << evinfo->getOrthogonalName() << std::endl
216 // << "---------" << std::endl;
217
218 // errorFound = true;
219 // }
220 // //std::string getEventSourceName();
221 // //std::string getOrthogonalName();
222 // }
223 // }
224
225 // if (errorFound)
226 // {
227 // ROS_WARN_STREAM("== STATE MACHINE CONSISTENCY CHECK: ==" << std::endl
228 // << errorbuffer.str() << std::endl
229 // << "=================");
230 // }
231 // cb from a client that doesn’t exist – don’t worry about making clients dynamically.
232}

Referenced by buildStateMachineInfo().

Here is the caller graph for this function:

◆ createOrthogonal()

template<typename TOrthogonal >
void smacc::ISmaccStateMachine::createOrthogonal
protected

Definition at line 63 of file smacc_state_machine_impl.h.

64 {
65 this->lockStateMachine("create orthogonal");
66 std::string orthogonalkey = demangledTypeName<TOrthogonal>();
67
68 if (orthogonals_.count(orthogonalkey) == 0)
69 {
70 auto ret = std::make_shared<TOrthogonal>();
71 orthogonals_[orthogonalkey] = dynamic_pointer_cast<smacc::ISmaccOrthogonal>(ret);
72
73 ret->setStateMachine(this);
74
75 ROS_INFO("%s Orthogonal is created", orthogonalkey.c_str());
76 }
77 else
78 {
79 ROS_WARN_STREAM("There were already one existing orthogonal of type "
80 << orthogonalkey.c_str() << ". Skipping creation orthogonal request. ");
81 std::stringstream ss;
82 ss << "The existing orthogonals are the following: " << std::endl;
83 for (auto &orthogonal : orthogonals_)
84 {
85 ss << " - " << orthogonal.first << std::endl;
86 }
87 ROS_WARN_STREAM(ss.str());
88 }
89 this->unlockStateMachine("create orthogonal");
90 }
void lockStateMachine(std::string msg)
std::map< std::string, std::shared_ptr< smacc::ISmaccOrthogonal > > orthogonals_
void unlockStateMachine(std::string msg)

References lockStateMachine(), orthogonals_, and unlockStateMachine().

Here is the call graph for this function:

◆ createSignalConnection()

template<typename TSmaccSignal , typename TMemberFunctionPrototype , typename TSmaccObjectType >
boost::signals2::connection smacc::ISmaccStateMachine::createSignalConnection ( TSmaccSignal &  signal,
TMemberFunctionPrototype  callback,
TSmaccObjectType *  object 
)

Definition at line 345 of file smacc_state_machine_impl.h.

348 {
349 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
350
351 static_assert(std::is_base_of<ISmaccState, TSmaccObjectType>::value ||
352 std::is_base_of<ISmaccClient, TSmaccObjectType>::value ||
353 std::is_base_of<ISmaccClientBehavior, TSmaccObjectType>::value ||
354 std::is_base_of<StateReactor, TSmaccObjectType>::value ||
355 std::is_base_of<ISmaccComponent, TSmaccObjectType>::value,
356 "Only are accepted smacc types as subscribers for smacc signals");
357
358 typedef decltype(callback) ft;
359 Bind<boost::function_types::function_arity<ft>::value> binder;
360
361 boost::signals2::connection connection;
362
363 // long life-time objects
364 if (std::is_base_of<ISmaccComponent, TSmaccObjectType>::value ||
365 std::is_base_of<ISmaccClient, TSmaccObjectType>::value ||
366 std::is_base_of<ISmaccOrthogonal, TSmaccObjectType>::value ||
367 std::is_base_of<ISmaccStateMachine, TSmaccObjectType>::value)
368 {
369 connection = binder.bindaux(signal, callback, object, nullptr);
370 }
371 else if (std::is_base_of<ISmaccState, TSmaccObjectType>::value ||
372 std::is_base_of<StateReactor, TSmaccObjectType>::value ||
373 std::is_base_of<ISmaccClientBehavior, TSmaccObjectType>::value)
374 {
375 ROS_INFO("[StateMachine] life-time constrained smacc signal subscription created. Subscriber is %s",
376 demangledTypeName<TSmaccObjectType>().c_str());
377
378 std::shared_ptr<CallbackCounterSemaphore> callbackCounterSemaphore;
379 if(stateCallbackConnections.count(object))
380 {
381 callbackCounterSemaphore = stateCallbackConnections[object];
382 }
383 else
384 {
385 callbackCounterSemaphore = std::make_shared<CallbackCounterSemaphore>(demangledTypeName<TSmaccObjectType>().c_str());
386 stateCallbackConnections[object] = callbackCounterSemaphore;
387 }
388
389 connection = binder.bindaux(signal, callback, object, callbackCounterSemaphore);
390 callbackCounterSemaphore->addConnection(connection);
391
392 }
393 else // state life-time objects
394 {
395 ROS_WARN("[StateMachine] connecting signal to an unknown object with life-time unknown behavior. It might provoke "
396 "an exception if the object is destroyed during the execution.");
397
398 connection = binder.bindaux(signal, callback, object, nullptr);
399 }
400
401 return connection;
402 }
std::map< void *, std::shared_ptr< CallbackCounterSemaphore > > stateCallbackConnections
std::recursive_mutex m_mutex_

References smacc::utils::Bind< arity >::bindaux(), m_mutex_, and stateCallbackConnections.

Referenced by smacc::ISmaccClient::connectSignal(), smacc::client_bases::SmaccActionClientBase< ActionType >::onAborted(), smacc::SmaccAsyncClientBehavior::onFailure(), smacc::SmaccAsyncClientBehavior::onFinished(), smacc::client_bases::SmaccSubscriberClient< MessageType >::onFirstMessageReceived(), cl_keyboard::ClKeyboard::OnKeyPress(), smacc::client_bases::SmaccSubscriberClient< MessageType >::onMessageReceived(), cl_multirole_sensor::ClMultiroleSensor< MessageType >::onMessageTimeout(), cl_move_group_interface::ClMoveGroup::onMotionExecutionFailed(), cl_move_group_interface::ClMoveGroup::onMotionExecutionSuccedded(), smacc::client_bases::SmaccActionClientBase< ActionType >::onPreempted(), smacc::client_bases::SmaccActionClientBase< ActionType >::onRejected(), smacc::client_bases::SmaccServiceServerClient< TService >::onServiceRequestReceived(), smacc::client_bases::SmaccActionClientBase< ActionType >::onSucceeded(), smacc::SmaccAsyncClientBehavior::onSuccess(), cl_ros_timer::ClRosTimer::onTimerTick(), cl_ros_timer::CbTimerCountdownLoop::onTimerTick(), and cl_ros_timer::CbTimerCountdownOnce::onTimerTick().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ disconnectSmaccSignalObject()

void smacc::ISmaccStateMachine::disconnectSmaccSignalObject ( void *  object)

Definition at line 44 of file smacc_state_machine.cpp.

45{
46 ROS_INFO("[SmaccSignals] object signal disconnecting %ld", (long)object_ptr);
47 if(stateCallbackConnections.count(object_ptr) > 0)
48 {
49 auto callbackSemaphore = stateCallbackConnections[object_ptr];
50 callbackSemaphore->finalize();
51 stateCallbackConnections.erase(object_ptr);
52 }
53 else
54 {
55 ROS_INFO("[SmaccSignals] no signals found %ld", (long)object_ptr);
56 }
57}

References stateCallbackConnections.

Referenced by notifyOnStateExited(), and smacc::ISmaccOrthogonal::onDispose().

Here is the caller graph for this function:

◆ eStop()

void smacc::ISmaccStateMachine::eStop ( )
virtual

Reimplemented in smacc::SmaccStateMachineBase< DerivedStateMachine, InitialStateType >.

Definition at line 72 of file smacc_state_machine.cpp.

73{
74}

Referenced by smacc::SmaccStateMachineBase< DerivedStateMachine, InitialStateType >::eStop().

Here is the caller graph for this function:

◆ getCurrentState()

ISmaccState * smacc::ISmaccStateMachine::getCurrentState ( ) const
inline

Definition at line 669 of file smacc_state_machine_impl.h.

670 {
671 return this->currentState_.back();
672 }
std::vector< ISmaccState * > currentState_

References currentState_.

◆ getCurrentStateCounter()

uint64_t smacc::ISmaccStateMachine::getCurrentStateCounter ( ) const
inline

Definition at line 664 of file smacc_state_machine_impl.h.

665 {
666 return this->stateSeqCounter_;
667 }

References stateSeqCounter_.

◆ getCurrentStateInfo()

std::shared_ptr< SmaccStateInfo > smacc::ISmaccStateMachine::getCurrentStateInfo ( )
inline

Definition at line 95 of file smacc_state_machine.h.

95{ return currentStateInfo_; }
std::shared_ptr< SmaccStateInfo > currentStateInfo_

References currentStateInfo_.

◆ getGlobalSMData()

template<typename T >
bool smacc::ISmaccStateMachine::getGlobalSMData ( std::string  name,
T &  ret 
)

Definition at line 173 of file smacc_state_machine_impl.h.

174 {
175 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
176 // ROS_WARN("get SM Data lock acquire");
177 bool success = false;
178
179 if (!globalData_.count(name))
180 {
181 // ROS_WARN("get SM Data - data do not exist");
182 success = false;
183 }
184 else
185 {
186 // ROS_WARN("get SM DAta -data exist. accessing");
187 try
188 {
189 auto &v = globalData_[name];
190
191 // ROS_WARN("get SM DAta -data exist. any cast");
192 ret = boost::any_cast<T>(v.second);
193 success = true;
194 // ROS_WARN("get SM DAta -data exist. success");
195 }
196 catch (boost::bad_any_cast &ex)
197 {
198 ROS_ERROR("bad any cast: %s", ex.what());
199 success = false;
200 }
201 }
202
203 // ROS_WARN("get SM Data lock release");
204 return success;
205 }
std::map< std::string, std::pair< std::function< std::string()>, boost::any > > globalData_

References globalData_, and m_mutex_.

Referenced by smacc::ISmaccOrthogonal::getGlobalSMData(), smacc::ISmaccState::getGlobalSMData(), and mapBehavior().

Here is the caller graph for this function:

◆ getNode()

ros::NodeHandle smacc::ISmaccStateMachine::getNode ( )
inline

Definition at line 136 of file smacc_state_machine.h.

136 {
137 return nh_;
138 };

References nh_.

Referenced by smacc::ISmaccClientBehavior::getNode().

Here is the caller graph for this function:

◆ getOrthogonal()

template<typename TOrthogonal >
TOrthogonal * smacc::ISmaccStateMachine::getOrthogonal

Definition at line 30 of file smacc_state_machine_impl.h.

31 {
32 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
33
34 std::string orthogonalkey = demangledTypeName<TOrthogonal>();
35 TOrthogonal *ret;
36
37 auto it = orthogonals_.find(orthogonalkey);
38
39 if (it != orthogonals_.end())
40 {
41 ROS_DEBUG("Orthogonal %s resource is being required from some state, client or component. Found resource in cache.", orthogonalkey.c_str());
42 ret = dynamic_cast<TOrthogonal *>(it->second.get());
43 return ret;
44 }
45 else
46 {
47 std::stringstream ss;
48 ss << "Orthogonal not found " << orthogonalkey.c_str() << std::endl;
49 ss << "The existing orthogonals are the following: " << std::endl;
50 for (auto &orthogonal : orthogonals_)
51 {
52 ss << " - " << orthogonal.first << std::endl;
53 }
54
55 ROS_WARN_STREAM(ss.str());
56
57 return nullptr;
58 }
59 }

References m_mutex_, and orthogonals_.

Referenced by smacc::ISmaccState::getOrthogonal().

Here is the caller graph for this function:

◆ getOrthogonals()

const std::map< std::string, std::shared_ptr< smacc::ISmaccOrthogonal > > & smacc::ISmaccStateMachine::getOrthogonals ( ) const

◆ getParam()

template<typename T >
bool smacc::ISmaccStateMachine::getParam ( std::string  param_name,
T &  param_storage 
)
protected

Definition at line 405 of file smacc_state_machine_impl.h.

406 {
407 return nh_.getParam(param_name, param_storage);
408 }

References nh_.

◆ getStateMachineInfo()

const smacc::introspection::SmaccStateMachineInfo & smacc::ISmaccStateMachine::getStateMachineInfo ( )
inline

Definition at line 674 of file smacc_state_machine_impl.h.

675 {
676 return *this->stateMachineInfo_;
677 }

References stateMachineInfo_.

Referenced by smacc::SmaccState< MostDerived, Context, InnerInitial, historyMode >::getStateInfo().

Here is the caller graph for this function:

◆ getStateMachineName()

std::string smacc::ISmaccStateMachine::getStateMachineName ( )

Definition at line 179 of file smacc_state_machine.cpp.

180{
181 return demangleSymbol(typeid(*this).name());
182}
std::string demangleSymbol()
Definition: introspection.h:75

References smacc::introspection::demangleSymbol().

Here is the call graph for this function:

◆ getTransitionLogHistory() [1/2]

void smacc::ISmaccStateMachine::getTransitionLogHistory ( )

Referenced by initializeROS().

Here is the caller graph for this function:

◆ getTransitionLogHistory() [2/2]

bool smacc::ISmaccStateMachine::getTransitionLogHistory ( smacc_msgs::SmaccGetTransitionHistory::Request &  req,
smacc_msgs::SmaccGetTransitionHistory::Response &  res 
)

Definition at line 148 of file smacc_state_machine.cpp.

149{
150 ROS_WARN("Requesting Transition Log History, current size: %ld", this->transitionLogHistory_.size());
151 res.history = this->transitionLogHistory_;
152 return true;
153}
std::vector< smacc_msgs::SmaccTransitionLogEntry > transitionLogHistory_

References transitionLogHistory_.

◆ initializeROS()

void smacc::ISmaccStateMachine::initializeROS ( std::string  smshortname)
protected

Definition at line 136 of file smacc_state_machine.cpp.

137{
138 ROS_WARN_STREAM("State machine base creation:" << shortname);
139 // STATE MACHINE TOPICS
140 stateMachinePub_ = nh_.advertise<smacc_msgs::SmaccStateMachine>(shortname + "/smacc/state_machine_description", 1);
141 stateMachineStatusPub_ = nh_.advertise<smacc_msgs::SmaccStatus>(shortname + "/smacc/status", 1);
142 transitionLogPub_ = nh_.advertise<smacc_msgs::SmaccTransitionLogEntry>(shortname + "/smacc/transition_log", 1);
143
144 // STATE MACHINE SERVICES
145 transitionHistoryService_ = nh_.advertiseService(shortname + "/smacc/transition_log_history", &ISmaccStateMachine::getTransitionLogHistory, this);
146}
ros::ServiceServer transitionHistoryService_

References getTransitionLogHistory(), nh_, stateMachinePub_, stateMachineStatusPub_, transitionHistoryService_, and transitionLogPub_.

Referenced by smacc::SmaccStateMachineBase< DerivedStateMachine, InitialStateType >::initiate_impl().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ lockStateMachine()

void smacc::ISmaccStateMachine::lockStateMachine ( std::string  msg)
private

Definition at line 167 of file smacc_state_machine.cpp.

168{
169 ROS_DEBUG("locking state machine: %s", msg.c_str());
170 m_mutex_.lock();
171}

References m_mutex_.

Referenced by createOrthogonal(), notifyOnStateExited(), and smacc::SignalDetector::pollOnce().

Here is the caller graph for this function:

◆ mapBehavior()

template<typename StateField , typename BehaviorType >
void smacc::ISmaccStateMachine::mapBehavior

Definition at line 227 of file smacc_state_machine_impl.h.

228 {
229 std::string stateFieldName = demangleSymbol(typeid(StateField).name());
230 std::string behaviorType = demangleSymbol(typeid(BehaviorType).name());
231 ROS_INFO("Mapping state field '%s' to stateReactor '%s'", stateFieldName.c_str(), behaviorType.c_str());
232 SmaccClientBehavior *globalreference;
233 if (!this->getGlobalSMData(stateFieldName, globalreference))
234 {
235 // Using the requires component approach, we force a unique existence
236 // of this component
237 BehaviorType *behavior;
238 this->requiresComponent(behavior);
239 globalreference = dynamic_cast<ISmaccClientBehavior *>(behavior);
240
241 this->setGlobalSMData(stateFieldName, globalreference);
242 }
243 }
void setGlobalSMData(std::string name, T value)
void requiresComponent(SmaccComponentType *&storage)
bool getGlobalSMData(std::string name, T &ret)

References smacc::introspection::demangleSymbol(), getGlobalSMData(), requiresComponent(), and setGlobalSMData().

Here is the call graph for this function:

◆ notifyOnRuntimeConfigurationFinished()

template<typename StateType >
void smacc::ISmaccStateMachine::notifyOnRuntimeConfigurationFinished ( StateType *  state)

Definition at line 495 of file smacc_state_machine_impl.h.

496 {
497 for (auto pair : this->orthogonals_)
498 {
499 //ROS_INFO("ortho onruntime configure: %s", pair.second->getName().c_str());
500 auto &orthogonal = pair.second;
501 orthogonal->runtimeConfigure();
502 }
503
504 {
505 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
506 this->updateStatusMessage();
508
510 }
511 }
StateMachineInternalAction stateMachineCurrentAction
void notifyStateConfigured(ISmaccState *currentState)

References currentState_, m_mutex_, smacc::SignalDetector::notifyStateConfigured(), orthogonals_, signalDetector_, smacc::STATE_ENTERING, stateMachineCurrentAction, and updateStatusMessage().

Referenced by smacc::SmaccState< MostDerived, Context, InnerInitial, historyMode >::entryStateInternal().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ notifyOnRuntimeConfigured()

template<typename StateType >
void smacc::ISmaccStateMachine::notifyOnRuntimeConfigured ( StateType *  state)

◆ notifyOnStateEntryEnd()

template<typename StateType >
void smacc::ISmaccStateMachine::notifyOnStateEntryEnd ( StateType *  state)

Definition at line 437 of file smacc_state_machine_impl.h.

438 {
439 ROS_INFO("[%s] State OnEntry code finished", demangleSymbol(typeid(StateType).name()).c_str());
440
441 auto currentState = this->currentState_.back();
442 for (auto pair : this->orthogonals_)
443 {
444 //ROS_INFO("ortho onentry: %s", pair.second->getName().c_str());
445 auto &orthogonal = pair.second;
446 try
447 {
448 orthogonal->onEntry();
449 }
450 catch (const std::exception &e)
451 {
452 ROS_ERROR("[Orthogonal %s] Exception on Entry - continuing with next orthogonal. Exception info: %s",
453 pair.second->getName().c_str(), e.what());
454 }
455 }
456
457 for (auto &sr : currentState->getStateReactors())
458 {
459 auto srname = smacc::demangleSymbol(typeid(*sr).name()).c_str();
460 ROS_INFO("state reactor onEntry: %s", srname);
461 try
462 {
463 sr->onEntry();
464 }
465 catch (const std::exception &e)
466 {
467 ROS_ERROR("[State Reactor %s] Exception on Entry - continuing with next state reactor. Exception info: %s",
468 srname, e.what());
469 }
470 }
471
472 for (auto &eg : currentState->getEventGenerators())
473 {
474 auto egname = smacc::demangleSymbol(typeid(*eg).name()).c_str();
475 ROS_INFO("state reactor onEntry: %s", egname);
476 try
477 {
478 eg->onEntry();
479 }
480 catch (const std::exception &e)
481 {
482 ROS_ERROR("[Event generator %s] Exception on Entry - continuing with next state reactor. Exception info: %s",
483 egname, e.what());
484 }
485 }
486
487 {
488 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
489 this->updateStatusMessage();
491 }
492 }

References currentState_, smacc::introspection::demangleSymbol(), m_mutex_, orthogonals_, smacc::STATE_STEADY, stateMachineCurrentAction, and updateStatusMessage().

Referenced by smacc::SmaccState< MostDerived, Context, InnerInitial, historyMode >::entryStateInternal().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ notifyOnStateEntryStart()

template<typename StateType >
void smacc::ISmaccStateMachine::notifyOnStateEntryStart ( StateType *  state)

Definition at line 425 of file smacc_state_machine_impl.h.

426 {
427 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
428
429 ROS_DEBUG("[State Machne] Initializating a new state '%s' and updating current state. Getting state meta-information. number of orthogonals: %ld", demangleSymbol(typeid(StateType).name()).c_str(), this->orthogonals_.size());
430
432 currentState_.push_back(state);
433 currentStateInfo_ = stateMachineInfo_->getState<StateType>();
434 }

References currentState_, currentStateInfo_, smacc::introspection::demangleSymbol(), m_mutex_, orthogonals_, stateMachineInfo_, and stateSeqCounter_.

Referenced by smacc::SmaccState< MostDerived, Context, InnerInitial, historyMode >::entryStateInternal().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ notifyOnStateExited()

template<typename StateType >
void smacc::ISmaccStateMachine::notifyOnStateExited ( StateType *  state)

Definition at line 575 of file smacc_state_machine_impl.h.

576 {
577 this->lockStateMachine("state exit");
578
580
581 auto fullname = demangleSymbol(typeid(StateType).name());
582 ROS_WARN_STREAM("exiting state: " << fullname);
583
584 ROS_INFO_STREAM("Notification State Disposing: leaving state" << state);
585 for (auto pair : this->orthogonals_)
586 {
587 auto &orthogonal = pair.second;
588 try
589 {
590 orthogonal->onDispose();
591 }
592 catch (const std::exception &e)
593 {
594 ROS_ERROR("[Orthogonal %s] Exception onDispose - continuing with next orthogonal. Exception info: %s",
595 pair.second->getName().c_str(), e.what());
596 }
597 }
598
599 for (auto &sr : state->getStateReactors())
600 {
601 auto srname = smacc::demangleSymbol(typeid(*sr).name()).c_str();
602 ROS_INFO("state reactor disposing: %s", srname);
603 try
604 {
605 this->disconnectSmaccSignalObject(sr.get());
606 }
607 catch (const std::exception &e)
608 {
609 ROS_ERROR("[State Reactor %s] Exception on OnDispose - continuing with next state reactor. Exception info: %s",
610 srname, e.what());
611 }
612 }
613
614 for (auto &eg : state->getEventGenerators())
615 {
616 auto egname = smacc::demangleSymbol(typeid(*eg).name()).c_str();
617 ROS_INFO("state reactor disposing: %s", egname);
618 try
619 {
620 this->disconnectSmaccSignalObject(eg.get());
621 }
622 catch (const std::exception &e)
623 {
624 ROS_ERROR("[State Reactor %s] Exception on OnDispose - continuing with next state reactor. Exception info: %s",
625 egname, e.what());
626 }
627 }
628
629 this->stateCallbackConnections.clear();
630 currentState_.pop_back();
631
632 // then call exit state
633 ROS_WARN_STREAM("state exit: " << fullname);
634
636 this->unlockStateMachine("state exit");
637 }
void disconnectSmaccSignalObject(void *object)
void notifyStateExited(ISmaccState *currentState)

References currentState_, smacc::introspection::demangleSymbol(), disconnectSmaccSignalObject(), lockStateMachine(), smacc::SignalDetector::notifyStateExited(), orthogonals_, signalDetector_, stateCallbackConnections, stateMachineCurrentAction, smacc::TRANSITIONING, and unlockStateMachine().

Referenced by smacc::SmaccState< MostDerived, Context, InnerInitial, historyMode >::exit().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ notifyOnStateExitting()

template<typename StateType >
void smacc::ISmaccStateMachine::notifyOnStateExitting ( StateType *  state)

Definition at line 520 of file smacc_state_machine_impl.h.

521 {
523
524 auto fullname = demangleSymbol(typeid(StateType).name());
525 ROS_WARN_STREAM("exiting state: " << fullname);
526 //this->setParam("destroyed", true);
527
528 ROS_INFO_STREAM("Notification State Exit: leaving state" << state);
529 for (auto pair : this->orthogonals_)
530 {
531 auto &orthogonal = pair.second;
532 try
533 {
534 orthogonal->onExit();
535 }
536 catch (const std::exception &e)
537 {
538 ROS_ERROR("[Orthogonal %s] Exception onExit - continuing with next orthogonal. Exception info: %s",
539 pair.second->getName().c_str(), e.what());
540 }
541 }
542
543 for (auto &sr : state->getStateReactors())
544 {
545 auto srname = smacc::demangleSymbol(typeid(*sr).name()).c_str();
546 ROS_INFO("state reactor OnExit: %s", srname);
547 try
548 {
549 sr->onExit();
550 }
551 catch (const std::exception &e)
552 {
553 ROS_ERROR("[State Reactor %s] Exception on OnExit - continuing with next state reactor. Exception info: %s",
554 srname, e.what());
555 }
556 }
557
558 for (auto &eg : state->getEventGenerators())
559 {
560 auto egname = smacc::demangleSymbol(typeid(*eg).name()).c_str();
561 ROS_INFO("state reactor OnExit: %s", egname);
562 try
563 {
564 eg->onExit();
565 }
566 catch (const std::exception &e)
567 {
568 ROS_ERROR("[State Reactor %s] Exception on OnExit - continuing with next state reactor. Exception info: %s",
569 egname, e.what());
570 }
571 }
572 }

References smacc::introspection::demangleSymbol(), orthogonals_, smacc::STATE_EXITING, and stateMachineCurrentAction.

Referenced by smacc::SmaccState< MostDerived, Context, InnerInitial, historyMode >::exit().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ onInitialize()

void smacc::ISmaccStateMachine::onInitialize ( )
virtual

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

Definition at line 127 of file smacc_state_machine.cpp.

128{
129}

Referenced by smacc::SmaccStateMachineBase< DerivedStateMachine, InitialStateType >::initiate_impl().

Here is the caller graph for this function:

◆ onInitialized()

void smacc::ISmaccStateMachine::onInitialized ( )
protected

Definition at line 131 of file smacc_state_machine.cpp.

132{
133 timer_ = nh_.createTimer(ros::Duration(0.5), &ISmaccStateMachine::state_machine_visualization, this);
134}
void state_machine_visualization(const ros::TimerEvent &)

References nh_, state_machine_visualization(), and timer_.

Referenced by smacc::SmaccStateMachineBase< DerivedStateMachine, InitialStateType >::initiate_impl().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ param()

template<typename T >
bool smacc::ISmaccStateMachine::param ( std::string  param_name,
T &  param_val,
const T &  default_val 
) const
protected

Definition at line 419 of file smacc_state_machine_impl.h.

420 {
421 return nh_.param(param_name, param_val, default_val);
422 }

References nh_.

◆ postEvent() [1/2]

template<typename EventType >
void smacc::ISmaccStateMachine::postEvent ( EventLifeTime  evlifetime = EventLifeTime::ABSOLUTE)

Definition at line 166 of file smacc_state_machine_impl.h.

167 {
168 auto *ev = new EventType();
169 this->postEvent(ev, evlifetime);
170 }
void postEvent(EventType *ev, EventLifeTime evlifetime=EventLifeTime::ABSOLUTE)

References postEvent().

Here is the call graph for this function:

◆ postEvent() [2/2]

template<typename EventType >
void smacc::ISmaccStateMachine::postEvent ( EventType *  ev,
EventLifeTime  evlifetime = EventLifeTime::ABSOLUTE 
)

Definition at line 138 of file smacc_state_machine_impl.h.

139 {
140 std::lock_guard<std::recursive_mutex> guard(eventQueueMutex_);
143 {
144 ROS_WARN_STREAM("CURRENT STATE SCOPED EVENT SKIPPED, state is exiting/transitioning " << demangleSymbol<EventType>());
145 return;
146 // in this case we may lose/skip events, if this is not right for some cases we should create a queue
147 // to lock the events during the transitions. This issues appeared when a client asyncbehavior was posting an event
148 // meanwhile we were doing the transition, but the main thread was waiting for its correct finalization (with thread.join)
149 }
150
151 // when a postting event is requested by any component, client, or client behavior
152 // we reach this place. Now, we propagate the events to all the state state reactors to generate
153 // some more events
154
155 ROS_DEBUG_STREAM("[PostEvent entry point] " << demangleSymbol<EventType>());
156
157 for (auto currentState : currentState_)
158 {
159 propagateEventToStateReactors(currentState, ev);
160 }
161
162 this->signalDetector_->postEvent(ev);
163 }
void propagateEventToStateReactors(ISmaccState *st, EventType *ev)
std::recursive_mutex eventQueueMutex_
void postEvent(EventType *ev)

References smacc::CURRENT_STATE, currentState_, eventQueueMutex_, smacc::SignalDetector::postEvent(), propagateEventToStateReactors(), signalDetector_, smacc::STATE_EXITING, stateMachineCurrentAction, and smacc::TRANSITIONING.

Referenced by smacc::ISmaccComponent::postEvent(), smacc::ISmaccClient::postEvent(), smacc::ISmaccClientBehavior::postEvent(), smacc::ISmaccState::postEvent(), postEvent(), and smacc::StateReactor::setOutputEvent().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ propagateEventToStateReactors()

template<typename EventType >
void smacc::ISmaccStateMachine::propagateEventToStateReactors ( ISmaccState st,
EventType *  ev 
)
private

Definition at line 640 of file smacc_state_machine_impl.h.

641 {
642 ROS_DEBUG("PROPAGATING EVENT [%s] TO LUs [%s]: ", demangleSymbol<EventType>().c_str(), st->getClassName().c_str());
643 for (auto &sb : st->getStateReactors())
644 {
645 sb->notifyEvent(ev);
646 }
647
648 auto *pst = st->getParentState();
649 if (pst != nullptr)
650 {
652 }
653 }

References smacc::ISmaccState::getClassName(), smacc::ISmaccState::getParentState(), smacc::ISmaccState::getStateReactors(), and propagateEventToStateReactors().

Referenced by postEvent(), and propagateEventToStateReactors().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ publishTransition()

void smacc::ISmaccStateMachine::publishTransition ( const SmaccTransitionInfo transitionInfo)

Definition at line 117 of file smacc_state_machine.cpp.

118{
119 smacc_msgs::SmaccTransitionLogEntry transitionLogEntry;
120 transitionLogEntry.timestamp = ros::Time::now();
121 transitionInfoToMsg(transitionInfo, transitionLogEntry.transition);
122 this->transitionLogHistory_.push_back(transitionLogEntry);
123
124 transitionLogPub_.publish(transitionLogEntry);
125}
void transitionInfoToMsg(const SmaccTransitionInfo &transition, smacc_msgs::SmaccTransition &transitionMsg)
Definition: reflection.cpp:9

References smacc::introspection::transitionInfoToMsg(), transitionLogHistory_, and transitionLogPub_.

Referenced by smacc::ISmaccState::notifyTransitionFromTransitionTypeInfo().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ requiresComponent()

template<typename SmaccComponentType >
void smacc::ISmaccStateMachine::requiresComponent ( SmaccComponentType *&  storage)

Definition at line 94 of file smacc_state_machine_impl.h.

95 {
96 ROS_DEBUG("component %s is required", demangleSymbol(typeid(SmaccComponentType).name()).c_str());
97 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
98
99 for (auto ortho : this->orthogonals_)
100 {
101 for (auto &client : ortho.second->clients_)
102 {
103
104 storage = client->getComponent<SmaccComponentType>();
105 if (storage != nullptr)
106 {
107 return;
108 }
109 }
110 }
111
112 ROS_WARN("component %s is required but it was not found in any orthogonal", demangleSymbol(typeid(SmaccComponentType).name()).c_str());
113
114 // std::string componentkey = demangledTypeName<SmaccComponentType>();
115 // SmaccComponentType *ret;
116
117 // auto it = components_.find(componentkey);
118
119 // if (it == components_.end())
120 // {
121 // ROS_DEBUG("%s smacc component is required. Creating a new instance.", componentkey.c_str());
122
123 // ret = new SmaccComponentType();
124 // ret->setStateMachine(this);
125 // components_[componentkey] = static_cast<smacc::ISmaccComponent *>(ret);
126 // ROS_DEBUG("%s resource is required. Done.", componentkey.c_str());
127 // }
128 // else
129 // {
130 // ROS_DEBUG("%s resource is required. Found resource in cache.", componentkey.c_str());
131 // ret = dynamic_cast<SmaccComponentType *>(it->second);
132 // }
133
134 // storage = ret;
135 }

References smacc::introspection::demangleSymbol(), m_mutex_, and orthogonals_.

Referenced by mapBehavior(), smacc::ISmaccClientBehavior::requiresComponent(), smacc::ISmaccOrthogonal::requiresComponent(), and smacc::ISmaccState::requiresComponent().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ reset()

void smacc::ISmaccStateMachine::reset ( )
virtual

Reimplemented in smacc::SmaccStateMachineBase< DerivedStateMachine, InitialStateType >.

Definition at line 64 of file smacc_state_machine.cpp.

65{
66}

Referenced by smacc::SmaccStateMachineBase< DerivedStateMachine, InitialStateType >::reset().

Here is the caller graph for this function:

◆ setGlobalSMData()

template<typename T >
void smacc::ISmaccStateMachine::setGlobalSMData ( std::string  name,
value 
)

Definition at line 208 of file smacc_state_machine_impl.h.

209 {
210 {
211 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
212 // ROS_WARN("set SM Data lock acquire");
213
214 globalData_[name] = {[this, name]() {
215 std::stringstream ss;
216 auto val = any_cast<T>(globalData_[name].second);
217 ss << val;
218 return ss.str();
219 },
220 value};
221 }
222
223 this->updateStatusMessage();
224 }

References globalData_, m_mutex_, and updateStatusMessage().

Referenced by cl_move_base_z::CbNavigateGlobalPosition::execute(), mapBehavior(), smacc::ISmaccOrthogonal::setGlobalSMData(), and smacc::ISmaccState::setGlobalSMData().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setParam()

template<typename T >
void smacc::ISmaccStateMachine::setParam ( std::string  param_name,
param_val 
)
protected

Definition at line 412 of file smacc_state_machine_impl.h.

413 {
414 return nh_.setParam(param_name, param_val);
415 }

References nh_.

◆ state_machine_visualization()

void smacc::ISmaccStateMachine::state_machine_visualization ( const ros::TimerEvent &  )

Definition at line 155 of file smacc_state_machine.cpp.

156{
157 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
158
159 smacc_msgs::SmaccStateMachine state_machine_msg;
160 state_machine_msg.states = stateMachineInfo_->stateMsgs;
161 this->stateMachinePub_.publish(state_machine_msg);
162
163 status_msg_.header.stamp = ros::Time::now();
164 this->stateMachineStatusPub_.publish(status_msg_);
165}
smacc_msgs::SmaccStatus status_msg_

References m_mutex_, stateMachineInfo_, stateMachinePub_, stateMachineStatusPub_, and status_msg_.

Referenced by onInitialized().

Here is the caller graph for this function:

◆ stop()

void smacc::ISmaccStateMachine::stop ( )
virtual

Reimplemented in smacc::SmaccStateMachineBase< DerivedStateMachine, InitialStateType >.

Definition at line 68 of file smacc_state_machine.cpp.

69{
70}

Referenced by smacc::SmaccStateMachineBase< DerivedStateMachine, InitialStateType >::stop().

Here is the caller graph for this function:

◆ unlockStateMachine()

void smacc::ISmaccStateMachine::unlockStateMachine ( std::string  msg)
private

Definition at line 173 of file smacc_state_machine.cpp.

174{
175 ROS_DEBUG("unlocking state machine: %s", msg.c_str());
176 m_mutex_.unlock();
177}

References m_mutex_.

Referenced by createOrthogonal(), notifyOnStateExited(), and smacc::SignalDetector::pollOnce().

Here is the caller graph for this function:

◆ updateStatusMessage()

void smacc::ISmaccStateMachine::updateStatusMessage ( )
private

Definition at line 81 of file smacc_state_machine.cpp.

82{
83 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
84
85 if (currentStateInfo_ != nullptr)
86 {
87 ROS_WARN_STREAM("[StateMachine] setting state active "
88 << ": " << currentStateInfo_->getFullPath());
89
90 if (this->runMode_ == SMRunMode::DEBUG)
91 {
92 status_msg_.current_states.clear();
93 std::list<const SmaccStateInfo *> ancestorList;
94 currentStateInfo_->getAncestors(ancestorList);
95
96 for (auto &ancestor : ancestorList)
97 {
98 status_msg_.current_states.push_back(ancestor->toShortName());
99 }
100
101 status_msg_.global_variable_names.clear();
102 status_msg_.global_variable_values.clear();
103
104 for (auto entry : this->globalData_)
105 {
106 status_msg_.global_variable_names.push_back(entry.first);
107 status_msg_.global_variable_values.push_back(entry.second.first()); // <- invoke to_string()
108 }
109
110 status_msg_.header.stamp = ros::Time::now();
111 status_msg_.header.frame_id = "odom";
112 this->stateMachineStatusPub_.publish(status_msg_);
113 }
114 }
115}

References currentStateInfo_, smacc::DEBUG, globalData_, m_mutex_, runMode_, stateMachineStatusPub_, and status_msg_.

Referenced by notifyOnRuntimeConfigurationFinished(), notifyOnStateEntryEnd(), and setGlobalSMData().

Here is the caller graph for this function:

Friends And Related Function Documentation

◆ ISmaccState

friend class ISmaccState
friend

Definition at line 215 of file smacc_state_machine.h.

◆ SignalDetector

friend class SignalDetector
friend

Definition at line 216 of file smacc_state_machine.h.

Member Data Documentation

◆ currentState_

std::vector<ISmaccState*> smacc::ISmaccStateMachine::currentState_
protected

◆ currentStateInfo_

std::shared_ptr<SmaccStateInfo> smacc::ISmaccStateMachine::currentStateInfo_
protected

◆ eventQueueMutex_

std::recursive_mutex smacc::ISmaccStateMachine::eventQueueMutex_
private

Definition at line 186 of file smacc_state_machine.h.

Referenced by postEvent().

◆ globalData_

std::map<std::string, std::pair<std::function<std::string()>, boost::any> > smacc::ISmaccStateMachine::globalData_
private

Definition at line 193 of file smacc_state_machine.h.

Referenced by getGlobalSMData(), setGlobalSMData(), and updateStatusMessage().

◆ m_mutex_

std::recursive_mutex smacc::ISmaccStateMachine::m_mutex_
private

◆ nh_

ros::NodeHandle smacc::ISmaccStateMachine::nh_
protected

◆ orthogonals_

std::map<std::string, std::shared_ptr<smacc::ISmaccOrthogonal> > smacc::ISmaccStateMachine::orthogonals_
protected

◆ private_nh_

ros::NodeHandle smacc::ISmaccStateMachine::private_nh_
protected

Definition at line 165 of file smacc_state_machine.h.

◆ runMode_

smacc::SMRunMode smacc::ISmaccStateMachine::runMode_
private

Definition at line 197 of file smacc_state_machine.h.

Referenced by ISmaccStateMachine(), and updateStatusMessage().

◆ signalDetector_

SignalDetector* smacc::ISmaccStateMachine::signalDetector_
private

◆ stateCallbackConnections

std::map<void*, std::shared_ptr<CallbackCounterSemaphore> > smacc::ISmaccStateMachine::stateCallbackConnections
private

◆ stateMachineCurrentAction

StateMachineInternalAction smacc::ISmaccStateMachine::stateMachineCurrentAction
private

◆ stateMachineInfo_

std::shared_ptr<SmaccStateMachineInfo> smacc::ISmaccStateMachine::stateMachineInfo_
private

◆ stateMachinePub_

ros::Publisher smacc::ISmaccStateMachine::stateMachinePub_
protected

Definition at line 168 of file smacc_state_machine.h.

Referenced by initializeROS(), and state_machine_visualization().

◆ stateMachineStatusPub_

ros::Publisher smacc::ISmaccStateMachine::stateMachineStatusPub_
protected

◆ stateSeqCounter_

uint64_t smacc::ISmaccStateMachine::stateSeqCounter_
private

Definition at line 202 of file smacc_state_machine.h.

Referenced by getCurrentStateCounter(), and notifyOnStateEntryStart().

◆ status_msg_

smacc_msgs::SmaccStatus smacc::ISmaccStateMachine::status_msg_
protected

Definition at line 179 of file smacc_state_machine.h.

Referenced by state_machine_visualization(), and updateStatusMessage().

◆ timer_

ros::Timer smacc::ISmaccStateMachine::timer_
protected

Definition at line 167 of file smacc_state_machine.h.

Referenced by onInitialized().

◆ transitionHistoryService_

ros::ServiceServer smacc::ISmaccStateMachine::transitionHistoryService_
protected

Definition at line 171 of file smacc_state_machine.h.

Referenced by initializeROS().

◆ transitionLogHistory_

std::vector<smacc_msgs::SmaccTransitionLogEntry> smacc::ISmaccStateMachine::transitionLogHistory_
private

Definition at line 195 of file smacc_state_machine.h.

Referenced by getTransitionLogHistory(), and publishTransition().

◆ transitionLogPub_

ros::Publisher smacc::ISmaccStateMachine::transitionLogPub_
protected

Definition at line 170 of file smacc_state_machine.h.

Referenced by initializeROS(), and publishTransition().


The documentation for this class was generated from the following files: