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