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 if (this->eventsLogPub_)
197 {
198 this->eventsLogPub_->publish(event);
199 }
200 }
201
202 if (
203 evlifetime == EventLifeTime::CURRENT_STATE &&
206 {
207 RCLCPP_WARN_STREAM(
208 getLogger(),
209 "[ISmaccStateMachine] CURRENT STATE SCOPED EVENT DISCARDED, state is exiting/transitioning "
210 << eventtypename);
211 return;
212 // in this case we may lose/skip events, if this is not right for some cases we should create a
213 // queue to lock the events during the transitions. This issues appeared when a client
214 // asyncbehavior was posting an event meanwhile we were doing the transition, but the main
215 // thread was waiting for its correct finalization (with thread.join)
216 }
217
218 // when a postting event is requested by any component, client, or client behavior
219 // we reach this place. Now, we propagate the events to all the state state reactors to generate
220 // some more events
221
222 RCLCPP_DEBUG_STREAM(getLogger(), "[PostEvent entry point] " << eventtypename);
223 for (auto currentState : currentState_)
224 {
225 propagateEventToStateReactors(currentState, ev);
226 }
227
228 this->signalDetector_->postEvent(ev);
229}
230
231template <typename EventType>
233{
235 RCLCPP_INFO_STREAM(getLogger(), "Event: " << evname);
236 auto * ev = new EventType();
237 this->postEvent(ev, evlifetime);
238}
239
240template <typename T>
241bool ISmaccStateMachine::getGlobalSMData(std::string name, T & ret)
242{
243 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
244 // RCLCPP_WARN(getLogger(),"get SM Data lock acquire");
245 bool success = false;
246
247 if (!globalData_.count(name))
248 {
249 // RCLCPP_WARN(getLogger(),"get SM Data - data do not exist");
250 success = false;
251 }
252 else
253 {
254 // RCLCPP_WARN(getLogger(),"get SM DAta -data exist. accessing");
255 try
256 {
257 auto & v = globalData_[name];
258
259 // RCLCPP_WARN(getLogger(),"get SM DAta -data exist. any cast");
260 ret = boost::any_cast<T>(v.second);
261 success = true;
262 // RCLCPP_WARN(getLogger(),"get SM DAta -data exist. success");
263 }
264 catch (boost::bad_any_cast & ex)
265 {
266 RCLCPP_ERROR(getLogger(), "bad any cast: %s", ex.what());
267 success = false;
268 }
269 }
270
271 // RCLCPP_WARN(getLogger(),"get SM Data lock release");
272 return success;
273}
274
275template <typename T>
276void ISmaccStateMachine::setGlobalSMData(std::string name, T value)
277{
278 {
279 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
280 // RCLCPP_WARN(getLogger(),"set SM Data lock acquire");
281
282 globalData_[name] = {
283 [this, name]()
284 {
285 std::stringstream ss;
286 auto val = any_cast<T>(globalData_[name].second);
287 ss << val;
288 return ss.str();
289 },
290 value};
291 }
292
293 this->updateStatusMessage();
294}
295
296//template <typename StateField, typename BehaviorType>
297//void ISmaccStateMachine::mapBehavior()
298//{
299// std::string stateFieldName = demangleSymbol(typeid(StateField).name());
300// std::string behaviorType = demangleSymbol(typeid(BehaviorType).name());
301// RCLCPP_INFO(
302// getLogger(), "Mapping state field '%s' to stateReactor '%s'", stateFieldName.c_str(),
303// behaviorType.c_str());
304// smacc2::ISmaccClientBehavior * globalreference;
305// if (!this->getGlobalSMData(stateFieldName, globalreference))
306// {
307// // Using the requires component approach, we force a unique existence
308// // of this component
309// BehaviorType * behavior;
310// this->requiresComponent(behavior);
311// globalreference = dynamic_cast<smacc2::ISmaccClientBehavior *>(behavior);
312//
313// this->setGlobalSMData(stateFieldName, globalreference);
314// }
315//}
316
317namespace utils
318{
319template <int arity>
320struct Bind
321{
322 template <typename TSmaccSignal, typename TMemberFunctionPrototype, typename TSmaccObjectType>
323 boost::signals2::connection bindaux(
324 TSmaccSignal & signal, TMemberFunctionPrototype callback, TSmaccObjectType * object,
325 std::shared_ptr<CallbackCounterSemaphore> callbackCounter);
326};
327
328template <>
329struct Bind<1>
330{
331 template <typename TSmaccSignal, typename TMemberFunctionPrototype, typename TSmaccObjectType>
332 boost::signals2::connection bindaux(
333 TSmaccSignal & signal, TMemberFunctionPrototype callback, TSmaccObjectType * object,
334 std::shared_ptr<CallbackCounterSemaphore> callbackCounter)
335 {
336 return signal.connect(
337
338 [=]()
339 {
340 if (callbackCounter == nullptr)
341 {
342 (object->*callback)();
343 }
344 else if (callbackCounter->acquire())
345 {
346 (object->*callback)();
347 callbackCounter->release();
348 }
349 });
350 }
351};
352
353template <>
354struct Bind<2>
355{
356 template <typename TSmaccSignal, typename TMemberFunctionPrototype, typename TSmaccObjectType>
357 boost::signals2::connection bindaux(
358 TSmaccSignal & signal, TMemberFunctionPrototype callback, TSmaccObjectType * object,
359 std::shared_ptr<CallbackCounterSemaphore> callbackCounter)
360 {
361 return signal.connect(
362 [=](auto a1)
363 {
364 if (callbackCounter == nullptr)
365 {
366 return (object->*callback)(a1);
367 }
368 else if (callbackCounter->acquire())
369 {
370 (object->*callback)(a1);
371 callbackCounter->release();
372 }
373 });
374 }
375};
376
377template <>
378struct Bind<3>
379{
380 template <typename TSmaccSignal, typename TMemberFunctionPrototype, typename TSmaccObjectType>
381 boost::signals2::connection bindaux(
382 TSmaccSignal & signal, TMemberFunctionPrototype callback, TSmaccObjectType * object,
383 std::shared_ptr<CallbackCounterSemaphore> callbackCounter)
384 {
385 return signal.connect(
386 [=](auto a1, auto a2)
387 {
388 if (callbackCounter == nullptr)
389 {
390 return (object->*callback)(a1, a2);
391 }
392 else if (callbackCounter->acquire())
393 {
394 (object->*callback)(a1, a2);
395 callbackCounter->release();
396 }
397 });
398 }
399};
400
401template <>
402struct Bind<4>
403{
404 template <typename TSmaccSignal, typename TMemberFunctionPrototype, typename TSmaccObjectType>
405 boost::signals2::connection bindaux(
406 TSmaccSignal & signal, TMemberFunctionPrototype callback, TSmaccObjectType * object,
407 std::shared_ptr<CallbackCounterSemaphore> callbackCounter)
408 {
409 return signal.connect(
410 [=](auto a1, auto a2, auto a3)
411 {
412 if (callbackCounter == nullptr)
413 {
414 return (object->*callback)(a1, a2, a3);
415 }
416 else if (callbackCounter->acquire())
417 {
418 (object->*callback)(a1, a2, a3);
419 callbackCounter->release();
420 }
421 });
422 }
423};
424} // namespace utils
425using namespace smacc2::utils;
426
427template <typename TSmaccSignal, typename TMemberFunctionPrototype, typename TSmaccObjectType>
429 TSmaccSignal & signal, TMemberFunctionPrototype callback, TSmaccObjectType * object)
430{
431 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
432
433 static_assert(
434 std::is_base_of<ISmaccState, TSmaccObjectType>::value ||
435 std::is_base_of<ISmaccClient, TSmaccObjectType>::value ||
436 std::is_base_of<ISmaccClientBehavior, TSmaccObjectType>::value ||
437 std::is_base_of<StateReactor, TSmaccObjectType>::value ||
438 std::is_base_of<ISmaccComponent, TSmaccObjectType>::value,
439 "Only are accepted smacc types as subscribers for smacc signals");
440
441 typedef decltype(callback) ft;
443 boost::signals2::connection connection;
444
445 // long life-time objects
446 if (
447 std::is_base_of<ISmaccComponent, TSmaccObjectType>::value ||
448 std::is_base_of<ISmaccClient, TSmaccObjectType>::value ||
449 std::is_base_of<ISmaccOrthogonal, TSmaccObjectType>::value ||
450 std::is_base_of<ISmaccStateMachine, TSmaccObjectType>::value)
451 {
452 RCLCPP_INFO(
453 getLogger(),
454 "[StateMachine] Long life-time SMACC signal subscription created. Subscriber is %s. Callback "
455 "is: %s",
457 demangleSymbol(typeid(callback).name()).c_str());
458
459 connection = binder.bindaux(signal, callback, object, nullptr);
460 }
461 else if (
462 std::is_base_of<ISmaccState, TSmaccObjectType>::value ||
463 std::is_base_of<StateReactor, TSmaccObjectType>::value ||
464 std::is_base_of<ISmaccClientBehavior, TSmaccObjectType>::value)
465 {
466 RCLCPP_INFO(
467 getLogger(),
468 "[StateMachine] Life-time constrained SMACC signal subscription created. Subscriber is %s",
470
471 std::shared_ptr<CallbackCounterSemaphore> callbackCounterSemaphore;
472 if (stateCallbackConnections.count(object))
473 {
474 callbackCounterSemaphore = stateCallbackConnections[object];
475 }
476 else
477 {
478 callbackCounterSemaphore =
479 std::make_shared<CallbackCounterSemaphore>(demangledTypeName<TSmaccObjectType>().c_str());
480 stateCallbackConnections[object] = callbackCounterSemaphore;
481 }
482
483 connection = binder.bindaux(signal, callback, object, callbackCounterSemaphore);
484 callbackCounterSemaphore->addConnection(connection);
485 }
486 else // state life-time objects
487 {
488 RCLCPP_WARN(
489 getLogger(),
490 "[StateMachine] Connecting signal to an unknown object with unknown lifetime "
491 "behavior. An exception may occur if the object is destroyed during the execution.");
492
493 connection = binder.bindaux(signal, callback, object, nullptr);
494 }
495
496 return connection;
497}
498
499template <typename StateType>
501{
502 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
503
504 RCLCPP_DEBUG(
505 getLogger(),
506 "[State Machine] Initializing a new state '%s' and updating current state. Getting state "
507 "meta-information. number of orthogonals: %ld",
508 demangleSymbol(typeid(StateType).name()).c_str(), this->orthogonals_.size());
509
511 currentState_.push_back(state);
512 currentStateInfo_ = stateMachineInfo_->getState<StateType>();
513}
514
515template <typename StateType>
517{
518 RCLCPP_INFO(
519 getLogger(), "[%s] State OnEntry code finished.",
520 demangleSymbol(typeid(StateType).name()).c_str());
521
522 auto currentState = this->currentState_.back();
523 for (auto pair : this->orthogonals_)
524 {
525 RCLCPP_DEBUG(getLogger(), "Orthogonal onEntry: %s.", pair.second->getName().c_str());
526 auto & orthogonal = pair.second;
527 try
528 {
529 orthogonal->onEntry();
530 }
531 catch (const std::exception & e)
532 {
533 RCLCPP_ERROR(
534 getLogger(),
535 "[Orthogonal %s] Exception on Entry - continuing with next orthogonal. Exception info: %s",
536 pair.second->getName().c_str(), e.what());
537 }
538 }
539
540 for (auto & sr : currentState->getStateReactors())
541 {
542 auto srname = smacc2::demangleSymbol(typeid(*sr).name());
543 RCLCPP_INFO_STREAM(getLogger(), "State reactor onEntry: " << srname);
544 try
545 {
546 sr->onEntry();
547 }
548 catch (const std::exception & e)
549 {
550 RCLCPP_ERROR(
551 getLogger(),
552 "[State Reactor %s] Exception on Entry - continuing with next state reactor. Exception "
553 "info: %s",
554 srname.c_str(), e.what());
555 }
556 }
557
558 for (auto & eg : currentState->getEventGenerators())
559 {
560 auto egname = smacc2::demangleSymbol(typeid(*eg).name());
561 RCLCPP_INFO_STREAM(getLogger(), "Event generator onEntry: " << egname);
562 try
563 {
564 eg->onEntry();
565 }
566 catch (const std::exception & e)
567 {
568 RCLCPP_ERROR(
569 getLogger(),
570 "[Event generator %s] Exception on Entry - continuing with next state reactor. Exception "
571 "info: %s",
572 egname.c_str(), e.what());
573 }
574 }
575
576 {
577 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
578 this->updateStatusMessage();
580 }
581}
582
583template <typename StateType>
585{
586 for (auto pair : this->orthogonals_)
587 {
588 // RCLCPP_INFO(getLogger(),"ortho onruntime configure: %s", pair.second->getName().c_str());
589 auto & orthogonal = pair.second;
590 orthogonal->runtimeConfigure();
591 }
592
593 {
594 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
595 this->updateStatusMessage();
597
599 }
600}
601
602template <typename StateType>
607
608template <typename StateType>
610{
612 auto fullname = demangleSymbol(typeid(StateType).name());
613 RCLCPP_WARN_STREAM(getLogger(), "Exiting state: " << fullname);
614 // this->set_parameter("destroyed", true);
615
616 RCLCPP_INFO_STREAM(getLogger(), "Notification state exit: leaving state " << state);
617 for (auto pair : this->orthogonals_)
618 {
619 auto & orthogonal = pair.second;
620 try
621 {
622 orthogonal->onExit();
623 }
624 catch (const std::exception & e)
625 {
626 RCLCPP_ERROR(
627 getLogger(),
628 "[Orthogonal %s] Exception onExit - continuing with next orthogonal. Exception info: %s",
629 pair.second->getName().c_str(), e.what());
630 }
631 }
632
633 for (auto & sr : state->getStateReactors())
634 {
635 auto srname = smacc2::demangleSymbol(typeid(*sr).name());
636 RCLCPP_INFO_STREAM(getLogger(), "State reactor OnExit: " << srname);
637 try
638 {
639 sr->onExit();
640 }
641 catch (const std::exception & e)
642 {
643 RCLCPP_ERROR(
644 getLogger(),
645 "[State Reactor %s] Exception on OnExit - continuing with next state reactor. Exception "
646 "info: %s",
647 srname.c_str(), e.what());
648 }
649 }
650
651 for (auto & eg : state->getEventGenerators())
652 {
653 auto egname = smacc2::demangleSymbol(typeid(*eg).name());
654 RCLCPP_INFO_STREAM(getLogger(), "Event generator OnExit: " << egname);
655 try
656 {
657 eg->onExit();
658 }
659 catch (const std::exception & e)
660 {
661 RCLCPP_ERROR(
662 getLogger(),
663 "[State Reactor %s] Exception on OnExit - continuing with next state reactor. Exception "
664 "info: %s",
665 egname.c_str(), e.what());
666 }
667 }
668}
669
670template <typename StateType>
672{
673 this->lockStateMachine("state exit");
674
676
677 auto fullname = demangleSymbol(typeid(StateType).name());
678 RCLCPP_WARN_STREAM(getLogger(), "Exiting state: " << fullname);
679
680 RCLCPP_INFO_STREAM(getLogger(), "Notification state disposing: leaving state" << state);
681 for (auto pair : this->orthogonals_)
682 {
683 auto & orthogonal = pair.second;
684 try
685 {
686 orthogonal->onDispose();
687 }
688 catch (const std::exception & e)
689 {
690 RCLCPP_ERROR(
691 getLogger(),
692 "[Orthogonal %s] Exception onDispose - continuing with next orthogonal. Exception info: %s",
693 pair.second->getName().c_str(), e.what());
694 }
695 }
696
697 for (auto & sr : state->getStateReactors())
698 {
699 auto srname = smacc2::demangleSymbol(typeid(*sr).name()).c_str();
700 RCLCPP_INFO(getLogger(), "State reactor disposing: %s", srname);
701 try
702 {
703 this->disconnectSmaccSignalObject(sr.get());
704 }
705 catch (const std::exception & e)
706 {
707 RCLCPP_ERROR(
708 getLogger(),
709 "[State Reactor %s] Exception on OnDispose - continuing with next state reactor. Exception "
710 "info: %s",
711 srname, e.what());
712 }
713 }
714
715 for (auto & eg : state->getEventGenerators())
716 {
717 auto egname = smacc2::demangleSymbol(typeid(*eg).name()).c_str();
718 RCLCPP_INFO(getLogger(), "Event generator disposing: %s", egname);
719 try
720 {
721 this->disconnectSmaccSignalObject(eg.get());
722 }
723 catch (const std::exception & e)
724 {
725 RCLCPP_ERROR(
726 getLogger(),
727 "[State Reactor %s] Exception on OnDispose - continuing with next state reactor. Exception "
728 "info: %s",
729 egname, e.what());
730 }
731 }
732
733 this->stateCallbackConnections.clear();
734 currentState_.pop_back();
735
736 // then call exit state
737 RCLCPP_WARN_STREAM(getLogger(), "State exit: " << fullname);
738
740 this->unlockStateMachine("state exit");
741}
742//------------------------------------------------------------------------------------------------
743template <typename EventType>
745{
746 RCLCPP_DEBUG(
747 getLogger(), "PROPAGATING EVENT [%s] TO SRs [%s]: ", demangleSymbol<EventType>().c_str(),
748 st->getClassName().c_str());
749 for (auto & sb : st->getStateReactors())
750 {
751 sb->notifyEvent(ev);
752 }
753
754 auto * pst = st->getParentState();
755 if (pst != nullptr)
756 {
758 }
759}
760
761template <typename InitialStateType>
763{
764 this->stateMachineInfo_ = std::make_shared<SmaccStateMachineInfo>(this->getNode());
765 this->stateMachineInfo_->buildStateMachineInfo<InitialStateType>();
766 this->stateMachineInfo_->assembleSMStructureMessage(this);
768}
769
771
773
778
779} // 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