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