SMACC2
Loading...
Searching...
No Matches
smacc_state_machine_impl.hpp
Go to the documentation of this file.
1// Copyright 2021 RobosoftAI Inc.
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15/**************************************************************************************************
16 *
17 * Authors: Pablo Inigo Blasco, Brett Aldrich
18 *
19 **************************************************************************************************/
20
21#pragma once
22
23#include <memory>
24#include <sstream>
25#include <string>
26
35
43
44#include <boost/function_types/function_arity.hpp>
45#include <boost/function_types/function_type.hpp>
46#include <boost/function_types/parameter_types.hpp>
48#include <smacc2_msgs/msg/smacc_status.hpp>
49
50namespace smacc2
51{
52using namespace smacc2::introspection;
53
54template <typename TOrthogonal>
56{
57 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
58
59 std::string orthogonalkey = demangledTypeName<TOrthogonal>();
60 TOrthogonal * ret;
61
62 auto it = orthogonals_.find(orthogonalkey);
63
64 if (it != orthogonals_.end())
65 {
66 RCLCPP_DEBUG(
67 getLogger(),
68 "Orthogonal %s resource is being required from some state, client or component. Found "
69 "resource in "
70 "cache.",
71 orthogonalkey.c_str());
72 ret = dynamic_cast<TOrthogonal *>(it->second.get());
73 return ret;
74 }
75 else
76 {
77 std::stringstream ss;
78 ss << "Orthogonal not found " << orthogonalkey.c_str() << std::endl;
79 ss << "The existing orthogonals are the following: " << std::endl;
80 for (auto & orthogonal : orthogonals_)
81 {
82 ss << " - " << orthogonal.first << std::endl;
83 }
84
85 RCLCPP_WARN_STREAM(getLogger(), ss.str());
86
87 return nullptr;
88 }
89}
90
91//-------------------------------------------------------------------------------------------------------
92template <typename TOrthogonal>
94{
95 //this->lockStateMachine("create orthogonal");
96 std::lock_guard<std::recursive_mutex> guard(m_mutex_);
97 std::string orthogonalkey = demangledTypeName<TOrthogonal>();
98
99 if (orthogonals_.count(orthogonalkey) == 0)
100 {
101 auto ret = std::make_shared<TOrthogonal>();
102 orthogonals_[orthogonalkey] = dynamic_pointer_cast<smacc2::ISmaccOrthogonal>(ret);
103
104 ret->setStateMachine(this);
105
106 RCLCPP_INFO(getLogger(), "%s Orthogonal is created", orthogonalkey.c_str());
107 }
108 else
109 {
110 RCLCPP_WARN_STREAM(
111 getLogger(), "There were already one existing orthogonal of type "
112 << orthogonalkey.c_str() << ". Skipping creation orthogonal request. ");
113 std::stringstream ss;
114 ss << "The existing orthogonals are the following: " << std::endl;
115 for (auto & orthogonal : orthogonals_)
116 {
117 ss << " - " << orthogonal.first << std::endl;
118 }
119 RCLCPP_WARN_STREAM(getLogger(), ss.str());
120 }
121 //this->unlockStateMachine("create orthogonal");
122}
123
124//-------------------------------------------------------------------------------------------------------
125template <typename SmaccComponentType>
126void ISmaccStateMachine::requiresComponent(SmaccComponentType *& storage, bool throwsException)
127{
128 RCLCPP_DEBUG(
129 getLogger(), "component %s is required",
130 demangleSymbol(typeid(SmaccComponentType).name()).c_str());
131 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
132
133 for (auto ortho : this->orthogonals_)
134 {
135 for (auto & client : ortho.second->clients_)
136 {
137 storage = client->getComponent<SmaccComponentType>();
138 if (storage != nullptr)
139 {
140 return;
141 }
142 }
143 }
144
145 RCLCPP_WARN(
146 getLogger(), "component %s is required but it was not found in any orthogonal",
147 demangleSymbol(typeid(SmaccComponentType).name()).c_str());
148
149 if (throwsException)
150 throw std::runtime_error("component is required but it was not found in any orthogonal");
151
152 // std::string componentkey = demangledTypeName<SmaccComponentType>();
153 // SmaccComponentType *ret;
154
155 // auto it = components_.find(componentkey);
156
157 // if (it == components_.end())
158 // {
159 // RCLCPP_DEBUG(getLogger(),"%s smacc component is required. Creating a new instance.",
160 // componentkey.c_str());
161
162 // ret = new SmaccComponentType();
163 // ret->setStateMachine(this);
164 // components_[componentkey] = static_cast<smacc2::ISmaccComponent *>(ret);
165 // RCLCPP_DEBUG(getLogger(),"%s resource is required. Done.", componentkey.c_str());
166 // }
167 // else
168 // {
169 // RCLCPP_DEBUG(getLogger(),"%s resource is required. Found resource in cache.",
170 // componentkey.c_str()); ret = dynamic_cast<SmaccComponentType *>(it->second);
171 // }
172
173 // storage = ret;
174}
175//-------------------------------------------------------------------------------------------------------
176template <typename EventType>
177void ISmaccStateMachine::postEvent(EventType * ev, EventLifeTime evlifetime)
178{
179 std::lock_guard<std::recursive_mutex> guard(eventQueueMutex_);
180
181#define eventtypename demangleSymbol<EventType>().c_str()
182
184
185 if (
186 evlifetime == EventLifeTime::CURRENT_STATE &&
189 {
190 RCLCPP_WARN_STREAM(
191 getLogger(),
192 "[ISmaccStateMachine] CURRENT STATE SCOPED EVENT DISCARDED, state is exiting/transitioning "
193 << eventtypename);
194 return;
195 // in this case we may lose/skip events, if this is not right for some cases we should create a
196 // queue to lock the events during the transitions. This issues appeared when a client
197 // asyncbehavior was posting an event meanwhile we were doing the transition, but the main
198 // thread was waiting for its correct finalization (with thread.join)
199 }
200
201 // when a postting event is requested by any component, client, or client behavior
202 // we reach this place. Now, we propagate the events to all the state state reactors to generate
203 // some more events
204
205 RCLCPP_DEBUG_STREAM(getLogger(), "[PostEvent entry point] " << eventtypename);
206 for (auto currentState : currentState_)
207 {
208 propagateEventToStateReactors(currentState, ev);
209 }
210
211 this->signalDetector_->postEvent(ev);
212}
213
214template <typename EventType>
216{
217 auto evname = smacc2::introspection::demangleSymbol<EventType>();
218 RCLCPP_INFO_STREAM(getLogger(), "Event " << evname);
219 auto * ev = new EventType();
220 this->postEvent(ev, evlifetime);
221}
222
223template <typename T>
224bool ISmaccStateMachine::getGlobalSMData(std::string name, T & ret)
225{
226 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
227 // RCLCPP_WARN(getLogger(),"get SM Data lock acquire");
228 bool success = false;
229
230 if (!globalData_.count(name))
231 {
232 // RCLCPP_WARN(getLogger(),"get SM Data - data do not exist");
233 success = false;
234 }
235 else
236 {
237 // RCLCPP_WARN(getLogger(),"get SM DAta -data exist. accessing");
238 try
239 {
240 auto & v = globalData_[name];
241
242 // RCLCPP_WARN(getLogger(),"get SM DAta -data exist. any cast");
243 ret = boost::any_cast<T>(v.second);
244 success = true;
245 // RCLCPP_WARN(getLogger(),"get SM DAta -data exist. success");
246 }
247 catch (boost::bad_any_cast & ex)
248 {
249 RCLCPP_ERROR(getLogger(), "bad any cast: %s", ex.what());
250 success = false;
251 }
252 }
253
254 // RCLCPP_WARN(getLogger(),"get SM Data lock release");
255 return success;
256}
257
258template <typename T>
259void ISmaccStateMachine::setGlobalSMData(std::string name, T value)
260{
261 {
262 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
263 // RCLCPP_WARN(getLogger(),"set SM Data lock acquire");
264
265 globalData_[name] = {
266 [this, name]()
267 {
268 std::stringstream ss;
269 auto val = any_cast<T>(globalData_[name].second);
270 ss << val;
271 return ss.str();
272 },
273 value};
274 }
275
276 this->updateStatusMessage();
277}
278
279template <typename StateField, typename BehaviorType>
281{
282 std::string stateFieldName = demangleSymbol(typeid(StateField).name());
283 std::string behaviorType = demangleSymbol(typeid(BehaviorType).name());
284 RCLCPP_INFO(
285 getLogger(), "Mapping state field '%s' to stateReactor '%s'", stateFieldName.c_str(),
286 behaviorType.c_str());
287 SmaccClientBehavior * globalreference;
288 if (!this->getGlobalSMData(stateFieldName, globalreference))
289 {
290 // Using the requires component approach, we force a unique existence
291 // of this component
292 BehaviorType * behavior;
293 this->requiresComponent(behavior);
294 globalreference = dynamic_cast<ISmaccClientBehavior *>(behavior);
295
296 this->setGlobalSMData(stateFieldName, globalreference);
297 }
298}
299
300namespace utils
301{
302template <int arity>
303struct Bind
304{
305 template <typename TSmaccSignal, typename TMemberFunctionPrototype, typename TSmaccObjectType>
306 boost::signals2::connection bindaux(
307 TSmaccSignal & signal, TMemberFunctionPrototype callback, TSmaccObjectType * object,
308 std::shared_ptr<CallbackCounterSemaphore> callbackCounter);
309};
310
311template <>
312struct Bind<1>
313{
314 template <typename TSmaccSignal, typename TMemberFunctionPrototype, typename TSmaccObjectType>
315 boost::signals2::connection bindaux(
316 TSmaccSignal & signal, TMemberFunctionPrototype callback, TSmaccObjectType * object,
317 std::shared_ptr<CallbackCounterSemaphore> callbackCounter)
318 {
319 return signal.connect(
320
321 [=]()
322 {
323 if (callbackCounter == nullptr)
324 {
325 (object->*callback)();
326 }
327 else if (callbackCounter->acquire())
328 {
329 (object->*callback)();
330 callbackCounter->release();
331 }
332 });
333 }
334};
335
336template <>
337struct Bind<2>
338{
339 template <typename TSmaccSignal, typename TMemberFunctionPrototype, typename TSmaccObjectType>
340 boost::signals2::connection bindaux(
341 TSmaccSignal & signal, TMemberFunctionPrototype callback, TSmaccObjectType * object,
342 std::shared_ptr<CallbackCounterSemaphore> callbackCounter)
343 {
344 return signal.connect(
345 [=](auto a1)
346 {
347 if (callbackCounter == nullptr)
348 {
349 return (object->*callback)(a1);
350 }
351 else if (callbackCounter->acquire())
352 {
353 (object->*callback)(a1);
354 callbackCounter->release();
355 }
356 });
357 }
358};
359
360template <>
361struct Bind<3>
362{
363 template <typename TSmaccSignal, typename TMemberFunctionPrototype, typename TSmaccObjectType>
364 boost::signals2::connection bindaux(
365 TSmaccSignal & signal, TMemberFunctionPrototype callback, TSmaccObjectType * object,
366 std::shared_ptr<CallbackCounterSemaphore> callbackCounter)
367 {
368 return signal.connect(
369 [=](auto a1, auto a2)
370 {
371 if (callbackCounter == nullptr)
372 {
373 return (object->*callback)(a1, a2);
374 }
375 else if (callbackCounter->acquire())
376 {
377 (object->*callback)(a1, a2);
378 callbackCounter->release();
379 }
380 });
381 }
382};
383
384template <>
385struct Bind<4>
386{
387 template <typename TSmaccSignal, typename TMemberFunctionPrototype, typename TSmaccObjectType>
388 boost::signals2::connection bindaux(
389 TSmaccSignal & signal, TMemberFunctionPrototype callback, TSmaccObjectType * object,
390 std::shared_ptr<CallbackCounterSemaphore> callbackCounter)
391 {
392 return signal.connect(
393 [=](auto a1, auto a2, auto a3)
394 {
395 if (callbackCounter == nullptr)
396 {
397 return (object->*callback)(a1, a2, a3);
398 }
399 else if (callbackCounter->acquire())
400 {
401 (object->*callback)(a1, a2, a3);
402 callbackCounter->release();
403 }
404 });
405 }
406};
407} // namespace utils
408using namespace smacc2::utils;
409
410template <typename TSmaccSignal, typename TMemberFunctionPrototype, typename TSmaccObjectType>
412 TSmaccSignal & signal, TMemberFunctionPrototype callback, TSmaccObjectType * object)
413{
414 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
415
416 static_assert(
417 std::is_base_of<ISmaccState, TSmaccObjectType>::value ||
418 std::is_base_of<ISmaccClient, TSmaccObjectType>::value ||
419 std::is_base_of<ISmaccClientBehavior, TSmaccObjectType>::value ||
420 std::is_base_of<StateReactor, TSmaccObjectType>::value ||
421 std::is_base_of<ISmaccComponent, TSmaccObjectType>::value,
422 "Only are accepted smacc types as subscribers for smacc signals");
423
424 typedef decltype(callback) ft;
426 boost::signals2::connection connection;
427
428 // long life-time objects
429 if (
430 std::is_base_of<ISmaccComponent, TSmaccObjectType>::value ||
431 std::is_base_of<ISmaccClient, TSmaccObjectType>::value ||
432 std::is_base_of<ISmaccOrthogonal, TSmaccObjectType>::value ||
433 std::is_base_of<ISmaccStateMachine, TSmaccObjectType>::value)
434 {
435 connection = binder.bindaux(signal, callback, object, nullptr);
436 }
437 else if (
438 std::is_base_of<ISmaccState, TSmaccObjectType>::value ||
439 std::is_base_of<StateReactor, TSmaccObjectType>::value ||
440 std::is_base_of<ISmaccClientBehavior, TSmaccObjectType>::value)
441 {
442 RCLCPP_INFO(
443 getLogger(),
444 "[StateMachine] life-time constrained smacc signal subscription created. Subscriber is %s",
445 demangledTypeName<TSmaccObjectType>().c_str());
446
447 std::shared_ptr<CallbackCounterSemaphore> callbackCounterSemaphore;
448 if (stateCallbackConnections.count(object))
449 {
450 callbackCounterSemaphore = stateCallbackConnections[object];
451 }
452 else
453 {
454 callbackCounterSemaphore =
455 std::make_shared<CallbackCounterSemaphore>(demangledTypeName<TSmaccObjectType>().c_str());
456 stateCallbackConnections[object] = callbackCounterSemaphore;
457 }
458
459 connection = binder.bindaux(signal, callback, object, callbackCounterSemaphore);
460 callbackCounterSemaphore->addConnection(connection);
461 }
462 else // state life-time objects
463 {
464 RCLCPP_WARN(
465 getLogger(),
466 "[StateMachine] connecting signal to an unknown object with life-time unknown "
467 "behavior. It might provoke "
468 "an exception if the object is destroyed during the execution.");
469
470 connection = binder.bindaux(signal, callback, object, nullptr);
471 }
472
473 return connection;
474}
475
476template <typename StateType>
478{
479 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
480
481 RCLCPP_DEBUG(
482 getLogger(),
483 "[State Machne] Initializing a new state '%s' and updating current state. Getting state "
484 "meta-information. number of orthogonals: %ld",
485 demangleSymbol(typeid(StateType).name()).c_str(), this->orthogonals_.size());
486
488 currentState_.push_back(state);
489 currentStateInfo_ = stateMachineInfo_->getState<StateType>();
490}
491
492template <typename StateType>
494{
495 RCLCPP_INFO(
496 getLogger(), "[%s] State OnEntry code finished",
497 demangleSymbol(typeid(StateType).name()).c_str());
498
499 auto currentState = this->currentState_.back();
500 for (auto pair : this->orthogonals_)
501 {
502 RCLCPP_DEBUG(getLogger(), "ortho onentry: %s", pair.second->getName().c_str());
503 auto & orthogonal = pair.second;
504 try
505 {
506 orthogonal->onEntry();
507 }
508 catch (const std::exception & e)
509 {
510 RCLCPP_ERROR(
511 getLogger(),
512 "[Orthogonal %s] Exception on Entry - continuing with next orthogonal. Exception info: %s",
513 pair.second->getName().c_str(), e.what());
514 }
515 }
516
517 for (auto & sr : currentState->getStateReactors())
518 {
519 auto srname = smacc2::demangleSymbol(typeid(*sr).name());
520 RCLCPP_INFO_STREAM(getLogger(), "state reactor onEntry: " << srname);
521 try
522 {
523 sr->onEntry();
524 }
525 catch (const std::exception & e)
526 {
527 RCLCPP_ERROR(
528 getLogger(),
529 "[State Reactor %s] Exception on Entry - continuing with next state reactor. Exception "
530 "info: %s",
531 srname.c_str(), e.what());
532 }
533 }
534
535 for (auto & eg : currentState->getEventGenerators())
536 {
537 auto egname = smacc2::demangleSymbol(typeid(*eg).name());
538 RCLCPP_INFO_STREAM(getLogger(), "event generator onEntry: " << egname);
539 try
540 {
541 eg->onEntry();
542 }
543 catch (const std::exception & e)
544 {
545 RCLCPP_ERROR(
546 getLogger(),
547 "[Event generator %s] Exception on Entry - continuing with next state reactor. Exception "
548 "info: %s",
549 egname.c_str(), e.what());
550 }
551 }
552
553 {
554 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
555 this->updateStatusMessage();
557 }
558}
559
560template <typename StateType>
562{
563 for (auto pair : this->orthogonals_)
564 {
565 // RCLCPP_INFO(getLogger(),"ortho onruntime configure: %s", pair.second->getName().c_str());
566 auto & orthogonal = pair.second;
567 orthogonal->runtimeConfigure();
568 }
569
570 {
571 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
572 this->updateStatusMessage();
574
576 }
577}
578
579template <typename StateType>
581{
583}
584
585template <typename StateType>
587{
589 auto fullname = demangleSymbol(typeid(StateType).name());
590 RCLCPP_WARN_STREAM(getLogger(), "exiting state: " << fullname);
591 // this->set_parameter("destroyed", true);
592
593 RCLCPP_INFO_STREAM(getLogger(), "Notification State Exit: leaving state " << state);
594 for (auto pair : this->orthogonals_)
595 {
596 auto & orthogonal = pair.second;
597 try
598 {
599 orthogonal->onExit();
600 }
601 catch (const std::exception & e)
602 {
603 RCLCPP_ERROR(
604 getLogger(),
605 "[Orthogonal %s] Exception onExit - continuing with next orthogonal. Exception info: %s",
606 pair.second->getName().c_str(), e.what());
607 }
608 }
609
610 for (auto & sr : state->getStateReactors())
611 {
612 auto srname = smacc2::demangleSymbol(typeid(*sr).name());
613 RCLCPP_INFO_STREAM(getLogger(), "state reactor OnExit: " << srname);
614 try
615 {
616 sr->onExit();
617 }
618 catch (const std::exception & e)
619 {
620 RCLCPP_ERROR(
621 getLogger(),
622 "[State Reactor %s] Exception on OnExit - continuing with next state reactor. Exception "
623 "info: %s",
624 srname.c_str(), e.what());
625 }
626 }
627
628 for (auto & eg : state->getEventGenerators())
629 {
630 auto egname = smacc2::demangleSymbol(typeid(*eg).name());
631 RCLCPP_INFO_STREAM(getLogger(), "event generator OnExit: " << egname);
632 try
633 {
634 eg->onExit();
635 }
636 catch (const std::exception & e)
637 {
638 RCLCPP_ERROR(
639 getLogger(),
640 "[State Reactor %s] Exception on OnExit - continuing with next state reactor. Exception "
641 "info: %s",
642 egname.c_str(), e.what());
643 }
644 }
645}
646
647template <typename StateType>
649{
650 this->lockStateMachine("state exit");
651
653
654 auto fullname = demangleSymbol(typeid(StateType).name());
655 RCLCPP_WARN_STREAM(getLogger(), "exiting state: " << fullname);
656
657 RCLCPP_INFO_STREAM(getLogger(), "Notification State Disposing: leaving state" << state);
658 for (auto pair : this->orthogonals_)
659 {
660 auto & orthogonal = pair.second;
661 try
662 {
663 orthogonal->onDispose();
664 }
665 catch (const std::exception & e)
666 {
667 RCLCPP_ERROR(
668 getLogger(),
669 "[Orthogonal %s] Exception onDispose - continuing with next orthogonal. Exception info: %s",
670 pair.second->getName().c_str(), e.what());
671 }
672 }
673
674 for (auto & sr : state->getStateReactors())
675 {
676 auto srname = smacc2::demangleSymbol(typeid(*sr).name()).c_str();
677 RCLCPP_INFO(getLogger(), "state reactor disposing: %s", srname);
678 try
679 {
680 this->disconnectSmaccSignalObject(sr.get());
681 }
682 catch (const std::exception & e)
683 {
684 RCLCPP_ERROR(
685 getLogger(),
686 "[State Reactor %s] Exception on OnDispose - continuing with next state reactor. Exception "
687 "info: %s",
688 srname, e.what());
689 }
690 }
691
692 for (auto & eg : state->getEventGenerators())
693 {
694 auto egname = smacc2::demangleSymbol(typeid(*eg).name()).c_str();
695 RCLCPP_INFO(getLogger(), "state reactor disposing: %s", egname);
696 try
697 {
698 this->disconnectSmaccSignalObject(eg.get());
699 }
700 catch (const std::exception & e)
701 {
702 RCLCPP_ERROR(
703 getLogger(),
704 "[State Reactor %s] Exception on OnDispose - continuing with next state reactor. Exception "
705 "info: %s",
706 egname, e.what());
707 }
708 }
709
710 this->stateCallbackConnections.clear();
711 currentState_.pop_back();
712
713 // then call exit state
714 RCLCPP_WARN_STREAM(getLogger(), "state exit: " << fullname);
715
717 this->unlockStateMachine("state exit");
718}
719//------------------------------------------------------------------------------------------------
720template <typename EventType>
722{
723 RCLCPP_DEBUG(
724 getLogger(), "PROPAGATING EVENT [%s] TO SRs [%s]: ", demangleSymbol<EventType>().c_str(),
725 st->getClassName().c_str());
726 for (auto & sb : st->getStateReactors())
727 {
728 sb->notifyEvent(ev);
729 }
730
731 auto * pst = st->getParentState();
732 if (pst != nullptr)
733 {
735 }
736}
737
738template <typename InitialStateType>
740{
741 this->stateMachineInfo_ = std::make_shared<SmaccStateMachineInfo>(this->getNode());
742 this->stateMachineInfo_->buildStateMachineInfo<InitialStateType>();
743 this->stateMachineInfo_->assembleSMStructureMessage(this);
745}
746
748
750
752{
753 return *this->stateMachineInfo_;
754}
755
756} // namespace smacc2
std::map< std::string, std::shared_ptr< smacc2::ISmaccOrthogonal > > orthogonals_
std::vector< ISmaccState * > currentState_
std::recursive_mutex eventQueueMutex_
bool getGlobalSMData(std::string name, T &ret)
boost::signals2::connection createSignalConnection(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object)
StateMachineInternalAction stateMachineCurrentAction
std::shared_ptr< SmaccStateInfo > currentStateInfo_
rclcpp::Node::SharedPtr getNode()
std::map< std::string, std::pair< std::function< std::string()>, boost::any > > globalData_
void notifyOnStateExitting(StateType *state)
void setGlobalSMData(std::string name, T value)
void notifyOnRuntimeConfigurationFinished(StateType *state)
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()
void unlockStateMachine(std::string msg)
std::map< void *, std::shared_ptr< CallbackCounterSemaphore > > stateCallbackConnections
void notifyOnRuntimeConfigured(StateType *state)
std::shared_ptr< SmaccStateMachineInfo > stateMachineInfo_
void postEvent(EventType *ev, EventLifeTime evlifetime=EventLifeTime::ABSOLUTE)
void requiresComponent(SmaccComponentType *&storage, bool throwsException=false)
void notifyOnStateEntryStart(StateType *state)
ISmaccState * getParentState()
Definition: smacc_state.hpp:32
virtual std::string getClassName()
Definition: smacc_state.cpp:26
std::vector< std::shared_ptr< StateReactor > > & getStateReactors()
Definition: smacc_state.hpp:80
void postEvent(EventType *ev)
void notifyStateExited(ISmaccState *currentState)
void notifyStateConfigured(ISmaccState *currentState)
std::string demangleSymbol()
#define eventtypename
void TRACEPOINT(spinOnce)
boost::signals2::connection bindaux(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object, std::shared_ptr< CallbackCounterSemaphore > callbackCounter)
boost::signals2::connection bindaux(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object, std::shared_ptr< CallbackCounterSemaphore > callbackCounter)
boost::signals2::connection bindaux(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object, std::shared_ptr< CallbackCounterSemaphore > callbackCounter)
boost::signals2::connection bindaux(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object, std::shared_ptr< CallbackCounterSemaphore > callbackCounter)
boost::signals2::connection bindaux(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object, std::shared_ptr< CallbackCounterSemaphore > callbackCounter)
smacc2_event