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
98 std::string orthogonalkey = demangledTypeName<TOrthogonal>();
99
100 if (orthogonals_.count(orthogonalkey) == 0)
101 {
102 auto ret = std::make_shared<TOrthogonal>();
103 orthogonals_[orthogonalkey] = dynamic_pointer_cast<smacc2::ISmaccOrthogonal>(ret);
104
105 ret->setStateMachine(this);
106
107 RCLCPP_INFO(getLogger(), "%s Orthogonal is created", orthogonalkey.c_str());
108 }
109 else
110 {
111 RCLCPP_WARN_STREAM(
112 getLogger(), "There were already one existing orthogonal of type "
113 << orthogonalkey.c_str() << ". Skipping creation orthogonal request. ");
114 std::stringstream ss;
115 ss << "The existing orthogonals are the following: " << std::endl;
116 for (auto & orthogonal : orthogonals_)
117 {
118 ss << " - " << orthogonal.first << std::endl;
119 }
120 RCLCPP_WARN_STREAM(getLogger(), ss.str());
121 }
122 //this->unlockStateMachine("create orthogonal");
123}
124
125//-------------------------------------------------------------------------------------------------------
126template <typename SmaccComponentType>
127void ISmaccStateMachine::requiresComponent(SmaccComponentType *& storage, bool throwsException)
128{
129 RCLCPP_DEBUG(
130 getLogger(), "component %s is required",
131 demangleSymbol(typeid(SmaccComponentType).name()).c_str());
132 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
133
134 for (auto ortho : this->orthogonals_)
135 {
136 for (auto & client : ortho.second->clients_)
137 {
138 storage = client->getComponent<SmaccComponentType>();
139 if (storage != nullptr)
140 {
141 return;
142 }
143 }
144 }
145
146 RCLCPP_WARN(
147 getLogger(), "component %s is required but it was not found in any orthogonal",
148 demangleSymbol(typeid(SmaccComponentType).name()).c_str());
149
150 if (throwsException)
151 throw std::runtime_error("component is required but it was not found in any orthogonal");
152
153 // std::string componentkey = demangledTypeName<SmaccComponentType>();
154 // SmaccComponentType *ret;
155
156 // auto it = components_.find(componentkey);
157
158 // if (it == components_.end())
159 // {
160 // RCLCPP_DEBUG(getLogger(),"%s smacc component is required. Creating a new instance.",
161 // componentkey.c_str());
162
163 // ret = new SmaccComponentType();
164 // ret->setStateMachine(this);
165 // components_[componentkey] = static_cast<smacc2::ISmaccComponent *>(ret);
166 // RCLCPP_DEBUG(getLogger(),"%s resource is required. Done.", componentkey.c_str());
167 // }
168 // else
169 // {
170 // RCLCPP_DEBUG(getLogger(),"%s resource is required. Found resource in cache.",
171 // componentkey.c_str()); ret = dynamic_cast<SmaccComponentType *>(it->second);
172 // }
173
174 // storage = ret;
175}
176//-------------------------------------------------------------------------------------------------------
177template <typename EventType>
178void ISmaccStateMachine::postEvent(EventType * ev, EventLifeTime evlifetime)
179{
180 std::lock_guard<std::recursive_mutex> guard(eventQueueMutex_);
181
182#define eventtypename demangleSymbol<EventType>().c_str()
183
185
186 {
188 EventLabel<EventType>(evinfo.label);
189
190 smacc2_msgs::msg::SmaccEvent event;
191 event.event_type = evinfo.getEventTypeName();
192 event.event_source = evinfo.getEventSourceName();
193 event.event_object_tag = evinfo.getOrthogonalName();
194 event.label = evinfo.label;
195
196 this->eventsLogPub_->publish(event);
197 }
198
199 if (
200 evlifetime == EventLifeTime::CURRENT_STATE &&
203 {
204 RCLCPP_WARN_STREAM(
205 getLogger(),
206 "[ISmaccStateMachine] CURRENT STATE SCOPED EVENT DISCARDED, state is exiting/transitioning "
207 << eventtypename);
208 return;
209 // in this case we may lose/skip events, if this is not right for some cases we should create a
210 // queue to lock the events during the transitions. This issues appeared when a client
211 // asyncbehavior was posting an event meanwhile we were doing the transition, but the main
212 // thread was waiting for its correct finalization (with thread.join)
213 }
214
215 // when a postting event is requested by any component, client, or client behavior
216 // we reach this place. Now, we propagate the events to all the state state reactors to generate
217 // some more events
218
219 RCLCPP_DEBUG_STREAM(getLogger(), "[PostEvent entry point] " << eventtypename);
220 for (auto currentState : currentState_)
221 {
222 propagateEventToStateReactors(currentState, ev);
223 }
224
225 this->signalDetector_->postEvent(ev);
226}
227
228template <typename EventType>
230{
232 RCLCPP_INFO_STREAM(getLogger(), "Event: " << evname);
233 auto * ev = new EventType();
234 this->postEvent(ev, evlifetime);
235}
236
237template <typename T>
238bool ISmaccStateMachine::getGlobalSMData(std::string name, T & ret)
239{
240 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
241 // RCLCPP_WARN(getLogger(),"get SM Data lock acquire");
242 bool success = false;
243
244 if (!globalData_.count(name))
245 {
246 // RCLCPP_WARN(getLogger(),"get SM Data - data do not exist");
247 success = false;
248 }
249 else
250 {
251 // RCLCPP_WARN(getLogger(),"get SM DAta -data exist. accessing");
252 try
253 {
254 auto & v = globalData_[name];
255
256 // RCLCPP_WARN(getLogger(),"get SM DAta -data exist. any cast");
257 ret = boost::any_cast<T>(v.second);
258 success = true;
259 // RCLCPP_WARN(getLogger(),"get SM DAta -data exist. success");
260 }
261 catch (boost::bad_any_cast & ex)
262 {
263 RCLCPP_ERROR(getLogger(), "bad any cast: %s", ex.what());
264 success = false;
265 }
266 }
267
268 // RCLCPP_WARN(getLogger(),"get SM Data lock release");
269 return success;
270}
271
272template <typename T>
273void ISmaccStateMachine::setGlobalSMData(std::string name, T value)
274{
275 {
276 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
277 // RCLCPP_WARN(getLogger(),"set SM Data lock acquire");
278
279 globalData_[name] = {
280 [this, name]()
281 {
282 std::stringstream ss;
283 auto val = any_cast<T>(globalData_[name].second);
284 ss << val;
285 return ss.str();
286 },
287 value};
288 }
289
290 this->updateStatusMessage();
291}
292
293//template <typename StateField, typename BehaviorType>
294//void ISmaccStateMachine::mapBehavior()
295//{
296// std::string stateFieldName = demangleSymbol(typeid(StateField).name());
297// std::string behaviorType = demangleSymbol(typeid(BehaviorType).name());
298// RCLCPP_INFO(
299// getLogger(), "Mapping state field '%s' to stateReactor '%s'", stateFieldName.c_str(),
300// behaviorType.c_str());
301// smacc2::ISmaccClientBehavior * globalreference;
302// if (!this->getGlobalSMData(stateFieldName, globalreference))
303// {
304// // Using the requires component approach, we force a unique existence
305// // of this component
306// BehaviorType * behavior;
307// this->requiresComponent(behavior);
308// globalreference = dynamic_cast<smacc2::ISmaccClientBehavior *>(behavior);
309//
310// this->setGlobalSMData(stateFieldName, globalreference);
311// }
312//}
313
314namespace utils
315{
316template <int arity>
317struct Bind
318{
319 template <typename TSmaccSignal, typename TMemberFunctionPrototype, typename TSmaccObjectType>
320 boost::signals2::connection bindaux(
321 TSmaccSignal & signal, TMemberFunctionPrototype callback, TSmaccObjectType * object,
322 std::shared_ptr<CallbackCounterSemaphore> callbackCounter);
323};
324
325template <>
326struct Bind<1>
327{
328 template <typename TSmaccSignal, typename TMemberFunctionPrototype, typename TSmaccObjectType>
329 boost::signals2::connection bindaux(
330 TSmaccSignal & signal, TMemberFunctionPrototype callback, TSmaccObjectType * object,
331 std::shared_ptr<CallbackCounterSemaphore> callbackCounter)
332 {
333 return signal.connect(
334
335 [=]()
336 {
337 if (callbackCounter == nullptr)
338 {
339 (object->*callback)();
340 }
341 else if (callbackCounter->acquire())
342 {
343 (object->*callback)();
344 callbackCounter->release();
345 }
346 });
347 }
348};
349
350template <>
351struct Bind<2>
352{
353 template <typename TSmaccSignal, typename TMemberFunctionPrototype, typename TSmaccObjectType>
354 boost::signals2::connection bindaux(
355 TSmaccSignal & signal, TMemberFunctionPrototype callback, TSmaccObjectType * object,
356 std::shared_ptr<CallbackCounterSemaphore> callbackCounter)
357 {
358 return signal.connect(
359 [=](auto a1)
360 {
361 if (callbackCounter == nullptr)
362 {
363 return (object->*callback)(a1);
364 }
365 else if (callbackCounter->acquire())
366 {
367 (object->*callback)(a1);
368 callbackCounter->release();
369 }
370 });
371 }
372};
373
374template <>
375struct Bind<3>
376{
377 template <typename TSmaccSignal, typename TMemberFunctionPrototype, typename TSmaccObjectType>
378 boost::signals2::connection bindaux(
379 TSmaccSignal & signal, TMemberFunctionPrototype callback, TSmaccObjectType * object,
380 std::shared_ptr<CallbackCounterSemaphore> callbackCounter)
381 {
382 return signal.connect(
383 [=](auto a1, auto a2)
384 {
385 if (callbackCounter == nullptr)
386 {
387 return (object->*callback)(a1, a2);
388 }
389 else if (callbackCounter->acquire())
390 {
391 (object->*callback)(a1, a2);
392 callbackCounter->release();
393 }
394 });
395 }
396};
397
398template <>
399struct Bind<4>
400{
401 template <typename TSmaccSignal, typename TMemberFunctionPrototype, typename TSmaccObjectType>
402 boost::signals2::connection bindaux(
403 TSmaccSignal & signal, TMemberFunctionPrototype callback, TSmaccObjectType * object,
404 std::shared_ptr<CallbackCounterSemaphore> callbackCounter)
405 {
406 return signal.connect(
407 [=](auto a1, auto a2, auto a3)
408 {
409 if (callbackCounter == nullptr)
410 {
411 return (object->*callback)(a1, a2, a3);
412 }
413 else if (callbackCounter->acquire())
414 {
415 (object->*callback)(a1, a2, a3);
416 callbackCounter->release();
417 }
418 });
419 }
420};
421} // namespace utils
422using namespace smacc2::utils;
423
424template <typename TSmaccSignal, typename TMemberFunctionPrototype, typename TSmaccObjectType>
426 TSmaccSignal & signal, TMemberFunctionPrototype callback, TSmaccObjectType * object)
427{
428 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
429
430 static_assert(
431 std::is_base_of<ISmaccState, TSmaccObjectType>::value ||
432 std::is_base_of<ISmaccClient, TSmaccObjectType>::value ||
433 std::is_base_of<ISmaccClientBehavior, TSmaccObjectType>::value ||
434 std::is_base_of<StateReactor, TSmaccObjectType>::value ||
435 std::is_base_of<ISmaccComponent, TSmaccObjectType>::value,
436 "Only are accepted smacc types as subscribers for smacc signals");
437
438 typedef decltype(callback) ft;
440 boost::signals2::connection connection;
441
442 // long life-time objects
443 if (
444 std::is_base_of<ISmaccComponent, TSmaccObjectType>::value ||
445 std::is_base_of<ISmaccClient, TSmaccObjectType>::value ||
446 std::is_base_of<ISmaccOrthogonal, TSmaccObjectType>::value ||
447 std::is_base_of<ISmaccStateMachine, TSmaccObjectType>::value)
448 {
449 RCLCPP_INFO(
450 getLogger(),
451 "[StateMachine] Long life-time SMACC signal subscription created. Subscriber is %s. Callback "
452 "is: %s",
454 demangleSymbol(typeid(callback).name()).c_str());
455
456 connection = binder.bindaux(signal, callback, object, nullptr);
457 }
458 else if (
459 std::is_base_of<ISmaccState, TSmaccObjectType>::value ||
460 std::is_base_of<StateReactor, TSmaccObjectType>::value ||
461 std::is_base_of<ISmaccClientBehavior, TSmaccObjectType>::value)
462 {
463 RCLCPP_INFO(
464 getLogger(),
465 "[StateMachine] Life-time constrained SMACC signal subscription created. Subscriber is %s",
467
468 std::shared_ptr<CallbackCounterSemaphore> callbackCounterSemaphore;
469 if (stateCallbackConnections.count(object))
470 {
471 callbackCounterSemaphore = stateCallbackConnections[object];
472 }
473 else
474 {
475 callbackCounterSemaphore =
476 std::make_shared<CallbackCounterSemaphore>(demangledTypeName<TSmaccObjectType>().c_str());
477 stateCallbackConnections[object] = callbackCounterSemaphore;
478 }
479
480 connection = binder.bindaux(signal, callback, object, callbackCounterSemaphore);
481 callbackCounterSemaphore->addConnection(connection);
482 }
483 else // state life-time objects
484 {
485 RCLCPP_WARN(
486 getLogger(),
487 "[StateMachine] Connecting signal to an unknown object with unknown lifetime "
488 "behavior. An exception may occur if the object is destroyed during the execution.");
489
490 connection = binder.bindaux(signal, callback, object, nullptr);
491 }
492
493 return connection;
494}
495
496template <typename StateType>
498{
499 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
500
501 RCLCPP_DEBUG(
502 getLogger(),
503 "[State Machine] Initializing a new state '%s' and updating current state. Getting state "
504 "meta-information. number of orthogonals: %ld",
505 demangleSymbol(typeid(StateType).name()).c_str(), this->orthogonals_.size());
506
508 currentState_.push_back(state);
509 currentStateInfo_ = stateMachineInfo_->getState<StateType>();
510}
511
512template <typename StateType>
514{
515 RCLCPP_INFO(
516 getLogger(), "[%s] State OnEntry code finished.",
517 demangleSymbol(typeid(StateType).name()).c_str());
518
519 auto currentState = this->currentState_.back();
520 for (auto pair : this->orthogonals_)
521 {
522 RCLCPP_DEBUG(getLogger(), "Orthogonal onEntry: %s.", pair.second->getName().c_str());
523 auto & orthogonal = pair.second;
524 try
525 {
526 orthogonal->onEntry();
527 }
528 catch (const std::exception & e)
529 {
530 RCLCPP_ERROR(
531 getLogger(),
532 "[Orthogonal %s] Exception on Entry - continuing with next orthogonal. Exception info: %s",
533 pair.second->getName().c_str(), e.what());
534 }
535 }
536
537 for (auto & sr : currentState->getStateReactors())
538 {
539 auto srname = smacc2::demangleSymbol(typeid(*sr).name());
540 RCLCPP_INFO_STREAM(getLogger(), "State reactor onEntry: " << srname);
541 try
542 {
543 sr->onEntry();
544 }
545 catch (const std::exception & e)
546 {
547 RCLCPP_ERROR(
548 getLogger(),
549 "[State Reactor %s] Exception on Entry - continuing with next state reactor. Exception "
550 "info: %s",
551 srname.c_str(), e.what());
552 }
553 }
554
555 for (auto & eg : currentState->getEventGenerators())
556 {
557 auto egname = smacc2::demangleSymbol(typeid(*eg).name());
558 RCLCPP_INFO_STREAM(getLogger(), "Event generator onEntry: " << egname);
559 try
560 {
561 eg->onEntry();
562 }
563 catch (const std::exception & e)
564 {
565 RCLCPP_ERROR(
566 getLogger(),
567 "[Event generator %s] Exception on Entry - continuing with next state reactor. Exception "
568 "info: %s",
569 egname.c_str(), e.what());
570 }
571 }
572
573 {
574 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
575 this->updateStatusMessage();
577 }
578}
579
580template <typename StateType>
582{
583 for (auto pair : this->orthogonals_)
584 {
585 // RCLCPP_INFO(getLogger(),"ortho onruntime configure: %s", pair.second->getName().c_str());
586 auto & orthogonal = pair.second;
587 orthogonal->runtimeConfigure();
588 }
589
590 {
591 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
592 this->updateStatusMessage();
594
596 }
597}
598
599template <typename StateType>
604
605template <typename StateType>
607{
609 auto fullname = demangleSymbol(typeid(StateType).name());
610 RCLCPP_WARN_STREAM(getLogger(), "Exiting state: " << fullname);
611 // this->set_parameter("destroyed", true);
612
613 RCLCPP_INFO_STREAM(getLogger(), "Notification state exit: leaving state " << state);
614 for (auto pair : this->orthogonals_)
615 {
616 auto & orthogonal = pair.second;
617 try
618 {
619 orthogonal->onExit();
620 }
621 catch (const std::exception & e)
622 {
623 RCLCPP_ERROR(
624 getLogger(),
625 "[Orthogonal %s] Exception onExit - continuing with next orthogonal. Exception info: %s",
626 pair.second->getName().c_str(), e.what());
627 }
628 }
629
630 for (auto & sr : state->getStateReactors())
631 {
632 auto srname = smacc2::demangleSymbol(typeid(*sr).name());
633 RCLCPP_INFO_STREAM(getLogger(), "State reactor OnExit: " << srname);
634 try
635 {
636 sr->onExit();
637 }
638 catch (const std::exception & e)
639 {
640 RCLCPP_ERROR(
641 getLogger(),
642 "[State Reactor %s] Exception on OnExit - continuing with next state reactor. Exception "
643 "info: %s",
644 srname.c_str(), e.what());
645 }
646 }
647
648 for (auto & eg : state->getEventGenerators())
649 {
650 auto egname = smacc2::demangleSymbol(typeid(*eg).name());
651 RCLCPP_INFO_STREAM(getLogger(), "Event generator OnExit: " << egname);
652 try
653 {
654 eg->onExit();
655 }
656 catch (const std::exception & e)
657 {
658 RCLCPP_ERROR(
659 getLogger(),
660 "[State Reactor %s] Exception on OnExit - continuing with next state reactor. Exception "
661 "info: %s",
662 egname.c_str(), e.what());
663 }
664 }
665}
666
667template <typename StateType>
669{
670 this->lockStateMachine("state exit");
671
673
674 auto fullname = demangleSymbol(typeid(StateType).name());
675 RCLCPP_WARN_STREAM(getLogger(), "Exiting state: " << fullname);
676
677 RCLCPP_INFO_STREAM(getLogger(), "Notification state disposing: leaving state" << state);
678 for (auto pair : this->orthogonals_)
679 {
680 auto & orthogonal = pair.second;
681 try
682 {
683 orthogonal->onDispose();
684 }
685 catch (const std::exception & e)
686 {
687 RCLCPP_ERROR(
688 getLogger(),
689 "[Orthogonal %s] Exception onDispose - continuing with next orthogonal. Exception info: %s",
690 pair.second->getName().c_str(), e.what());
691 }
692 }
693
694 for (auto & sr : state->getStateReactors())
695 {
696 auto srname = smacc2::demangleSymbol(typeid(*sr).name()).c_str();
697 RCLCPP_INFO(getLogger(), "State reactor disposing: %s", srname);
698 try
699 {
700 this->disconnectSmaccSignalObject(sr.get());
701 }
702 catch (const std::exception & e)
703 {
704 RCLCPP_ERROR(
705 getLogger(),
706 "[State Reactor %s] Exception on OnDispose - continuing with next state reactor. Exception "
707 "info: %s",
708 srname, e.what());
709 }
710 }
711
712 for (auto & eg : state->getEventGenerators())
713 {
714 auto egname = smacc2::demangleSymbol(typeid(*eg).name()).c_str();
715 RCLCPP_INFO(getLogger(), "Event generator disposing: %s", egname);
716 try
717 {
718 this->disconnectSmaccSignalObject(eg.get());
719 }
720 catch (const std::exception & e)
721 {
722 RCLCPP_ERROR(
723 getLogger(),
724 "[State Reactor %s] Exception on OnDispose - continuing with next state reactor. Exception "
725 "info: %s",
726 egname, e.what());
727 }
728 }
729
730 this->stateCallbackConnections.clear();
731 currentState_.pop_back();
732
733 // then call exit state
734 RCLCPP_WARN_STREAM(getLogger(), "State exit: " << fullname);
735
737 this->unlockStateMachine("state exit");
738}
739//------------------------------------------------------------------------------------------------
740template <typename EventType>
742{
743 RCLCPP_DEBUG(
744 getLogger(), "PROPAGATING EVENT [%s] TO SRs [%s]: ", demangleSymbol<EventType>().c_str(),
745 st->getClassName().c_str());
746 for (auto & sb : st->getStateReactors())
747 {
748 sb->notifyEvent(ev);
749 }
750
751 auto * pst = st->getParentState();
752 if (pst != nullptr)
753 {
755 }
756}
757
758template <typename InitialStateType>
760{
761 this->stateMachineInfo_ = std::make_shared<SmaccStateMachineInfo>(this->getNode());
762 this->stateMachineInfo_->buildStateMachineInfo<InitialStateType>();
763 this->stateMachineInfo_->assembleSMStructureMessage(this);
765}
766
768
770
775
776} // 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)
void requiresComponent(SmaccComponentType *&storage, bool throwsExceptionIfNotExist=false)
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)
rclcpp::Publisher< smacc2_msgs::msg::SmaccEvent >::SharedPtr eventsLogPub_
void notifyOnStateEntryStart(StateType *state)
ISmaccState * getParentState()
virtual std::string getClassName()
std::vector< std::shared_ptr< StateReactor > > & getStateReactors()
void notifyStateExited(ISmaccState *currentState)
void notifyStateConfigured(ISmaccState *currentState)
static TypeInfo::Ptr getTypeInfoFromType()
std::enable_if< HasEventLabel< T >::value, void >::type EventLabel(std::string &label)
std::string demangleSymbol()
std::string demangledTypeName()
#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