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