SMACC2
Loading...
Searching...
No Matches
Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes | Friends | List of all members
smacc2::ISmaccStateMachine Class Reference

#include <smacc_state_machine.hpp>

Inheritance diagram for smacc2::ISmaccStateMachine:
Inheritance graph
Collaboration diagram for smacc2::ISmaccStateMachine:
Collaboration graph

Public Member Functions

 ISmaccStateMachine (std::string stateMachineName, SignalDetector *signalDetector, rclcpp::NodeOptions nodeOptions=rclcpp::NodeOptions())
 
virtual ~ISmaccStateMachine ()
 
virtual void reset ()
 
virtual void stop ()
 
virtual void eStop ()
 
template<typename TOrthogonal >
TOrthogonalgetOrthogonal ()
 
template<typename TOrthogonal , typename TClientBehavior >
TClientBehaviorgetClientBehavior (int index=0)
 
const std::map< std::string, std::shared_ptr< smacc2::ISmaccOrthogonal > > & getOrthogonals () const
 
template<typename SmaccComponentType >
void requiresComponent (SmaccComponentType *&storage, bool throwsExceptionIfNotExist=false)
 
template<typename EventType >
void postEvent (EventType *ev, EventLifeTime evlifetime=EventLifeTime::ABSOLUTE)
 
template<typename EventType >
void postEvent (EventLifeTime evlifetime=EventLifeTime::ABSOLUTE)
 
template<typename T >
bool getGlobalSMData (std::string name, T &ret)
 
template<typename T >
void setGlobalSMData (std::string name, T value)
 
template<typename StateField , typename BehaviorType >
void mapBehavior ()
 
std::string getStateMachineName ()
 
void state_machine_visualization ()
 
std::shared_ptr< SmaccStateInfogetCurrentStateInfo ()
 
void publishTransition (const SmaccTransitionInfo &transitionInfo)
 
virtual void onInitialize ()
 this function should be implemented by the user to create the orthogonals
 
void getTransitionLogHistory (const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< smacc2_msgs::srv::SmaccGetTransitionHistory::Request > req, std::shared_ptr< smacc2_msgs::srv::SmaccGetTransitionHistory::Response > res)
 
template<typename TSmaccSignal , typename TMemberFunctionPrototype , typename TSmaccObjectType >
boost::signals2::connection createSignalConnection (TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object)
 
void disconnectSmaccSignalObject (void *object)
 
template<typename StateType >
void notifyOnStateEntryStart (StateType *state)
 
template<typename StateType >
void notifyOnStateEntryEnd (StateType *state)
 
template<typename StateType >
void notifyOnRuntimeConfigured (StateType *state)
 
template<typename StateType >
void notifyOnStateExitting (StateType *state)
 
template<typename StateType >
void notifyOnStateExited (StateType *state)
 
template<typename StateType >
void notifyOnRuntimeConfigurationFinished (StateType *state)
 
int64_t getCurrentStateCounter () const
 
ISmaccStategetCurrentState () const
 
const SmaccStateMachineInfogetStateMachineInfo ()
 
template<typename InitialStateType >
void buildStateMachineInfo ()
 
rclcpp::Node::SharedPtr getNode ()
 
rclcpp::Logger getLogger ()
 
std::recursive_mutex & getMutex ()
 

Protected Member Functions

void checkStateMachineConsistence ()
 
void initializeROS (std::string smshortname)
 
void onInitialized ()
 
template<typename TOrthogonal >
void createOrthogonal ()
 

Protected Attributes

rclcpp::Node::SharedPtr nh_
 
rclcpp::TimerBase::SharedPtr timer_
 
rclcpp::Publisher< smacc2_msgs::msg::SmaccStateMachine >::SharedPtr stateMachinePub_
 
rclcpp::Publisher< smacc2_msgs::msg::SmaccStatus >::SharedPtr stateMachineStatusPub_
 
rclcpp::Publisher< smacc2_msgs::msg::SmaccTransitionLogEntry >::SharedPtr transitionLogPub_
 
rclcpp::Service< smacc2_msgs::srv::SmaccGetTransitionHistory >::SharedPtr transitionHistoryService_
 
std::vector< ISmaccState * > currentState_
 
std::shared_ptr< SmaccStateInfocurrentStateInfo_
 
smacc2_msgs::msg::SmaccStatus status_msg_
 
std::map< std::string, std::shared_ptr< smacc2::ISmaccOrthogonal > > orthogonals_
 
std::vector< boost::signals2::scoped_connection > longLivedSignalConnections_
 
std::shared_ptr< SmaccStateMachineInfostateMachineInfo_
 

Private Member Functions

void lockStateMachine (std::string msg)
 
void unlockStateMachine (std::string msg)
 
template<typename EventType >
void propagateEventToStateReactors (ISmaccState *st, EventType *ev)
 
void updateStatusMessage ()
 

Private Attributes

std::recursive_mutex m_mutex_
 
std::recursive_mutex eventQueueMutex_
 
StateMachineInternalAction stateMachineCurrentAction
 
std::map< void *, std::shared_ptr< CallbackCounterSemaphore > > stateCallbackConnections
 
std::map< std::string, std::pair< std::function< std::string()>, boost::any > > globalData_
 
std::vector< smacc2_msgs::msg::SmaccTransitionLogEntry > transitionLogHistory_
 
smacc2::SMRunMode runMode_
 
SignalDetectorsignalDetector_
 
int64_t stateSeqCounter_
 

Friends

class ISmaccState
 
class SignalDetector
 

Detailed Description

Definition at line 64 of file smacc_state_machine.hpp.

Constructor & Destructor Documentation

◆ ISmaccStateMachine()

smacc2::ISmaccStateMachine::ISmaccStateMachine ( std::string  stateMachineName,
SignalDetector signalDetector,
rclcpp::NodeOptions  nodeOptions = rclcpp::NodeOptions() 
)

Definition at line 35 of file smacc_state_machine.cpp.

37: nh_(nullptr), stateSeqCounter_(0)
38{
39 // This enables loading arbitrary parameters
40 // However, best practice would be to declare parameters in the corresponding classes
41 // and provide descriptions about expected use
42 // TODO(henningkayser): remove once all parameters are declared inside the components
43 // node_options.automatically_declare_parameters_from_overrides(true);
44
45 nh_ = rclcpp::Node::make_shared(stateMachineName, nodeOptions); //
46 RCLCPP_INFO_STREAM(
47 nh_->get_logger(), "Creating State Machine Base: " << nh_->get_fully_qualified_name());
48
49 signalDetector_ = signalDetector;
51
52 std::string runMode;
53 if (nh_->get_parameter("run_mode", runMode))
54 {
55 if (runMode == "debug")
56 {
58 }
59 else if (runMode == "release")
60 {
62 }
63 else
64 {
65 RCLCPP_ERROR(nh_->get_logger(), "Incorrect run_mode value: %s", runMode.c_str());
66 }
67 }
68 else
69 {
71 }
72}
void initialize(ISmaccStateMachine *stateMachine)

References smacc2::DEBUG, smacc2::SignalDetector::initialize(), nh_, smacc2::RELEASE, runMode_, and signalDetector_.

Here is the call graph for this function:

◆ ~ISmaccStateMachine()

smacc2::ISmaccStateMachine::~ISmaccStateMachine ( )
virtual

Definition at line 74 of file smacc_state_machine.cpp.

75{
76 RCLCPP_INFO(nh_->get_logger(), "Finishing State Machine");
77}

References nh_.

Member Function Documentation

◆ buildStateMachineInfo()

void smacc2::ISmaccStateMachine::buildStateMachineInfo ( )

Definition at line 747 of file smacc_state_machine_impl.hpp.

748{
749 this->stateMachineInfo_ = std::make_shared<SmaccStateMachineInfo>(this->getNode());
750 this->stateMachineInfo_->buildStateMachineInfo<InitialStateType>();
751 this->stateMachineInfo_->assembleSMStructureMessage(this);
753}
rclcpp::Node::SharedPtr getNode()
std::shared_ptr< SmaccStateMachineInfo > stateMachineInfo_

References checkStateMachineConsistence(), getNode(), and stateMachineInfo_.

Here is the call graph for this function:

◆ checkStateMachineConsistence()

void smacc2::ISmaccStateMachine::checkStateMachineConsistence ( )
protected

Definition at line 228 of file smacc_state_machine.cpp.

229{
230 // transition from an orthogonal that doesn’t exist.
231 // transition from a source that doesn’t exist.
232
233 // std::stringstream errorbuffer;
234 // bool errorFound = false;
235
236 // for (auto &stentry : this->stateMachineInfo_->states)
237 // {
238 // auto stinfo = stentry.second;
239
240 // for (auto &transition : stinfo->transitions_)
241 // {
242 // auto evinfo = transition.eventInfo;
243 // bool found = false;
244 // for (auto &orthogonal : orthogonals_)
245 // {
246 // if (orthogonal.first == evinfo->getOrthogonalName())
247 // {
248 // found = true;
249 // break;
250 // }
251 // }
252
253 // if (!found)
254 // {
255 // errorbuffer << "---------" << std::endl
256 // << "[Consistency Checking] Transition event refers not existing orthogonal." << std::endl
257 // << "State: " << demangleType(*stinfo->tid_) << std::endl
258 // << "Transition: " << transition.transitionTypeInfo->getFullName() << std::endl
259 // << "Orthogonal: " << evinfo->getOrthogonalName() << std::endl
260 // << "---------" << std::endl;
261
262 // errorFound = true;
263 // }
264 // //std::string getEventSourceName();
265 // //std::string getOrthogonalName();
266 // }
267 // }
268
269 // if (errorFound)
270 // {
271 // RCLCPP_WARN_STREAM(nh_->get_logger(),"== STATE MACHINE CONSISTENCY CHECK: ==" << std::endl
272 // << errorbuffer.str() << std::endl
273 // << "=================");
274 // }
275 // cb from a client that doesn’t exist – don’t worry about making clients dynamically.
276}

Referenced by buildStateMachineInfo().

Here is the caller graph for this function:

◆ createOrthogonal()

template<typename TOrthogonal >
void smacc2::ISmaccStateMachine::createOrthogonal ( )
protected

Definition at line 93 of file smacc_state_machine_impl.hpp.

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}
std::map< std::string, std::shared_ptr< smacc2::ISmaccOrthogonal > > orthogonals_

References getLogger(), m_mutex_, and orthogonals_.

Here is the call graph for this function:

◆ createSignalConnection()

boost::signals2::connection smacc2::ISmaccStateMachine::createSignalConnection ( TSmaccSignal signal,
TMemberFunctionPrototype  callback,
TSmaccObjectType object 
)

Definition at line 412 of file smacc_state_machine_impl.hpp.

414{
415 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
416
417 static_assert(
418 std::is_base_of<ISmaccState, TSmaccObjectType>::value ||
419 std::is_base_of<ISmaccClient, TSmaccObjectType>::value ||
420 std::is_base_of<ISmaccClientBehavior, TSmaccObjectType>::value ||
421 std::is_base_of<StateReactor, TSmaccObjectType>::value ||
422 std::is_base_of<ISmaccComponent, TSmaccObjectType>::value,
423 "Only are accepted smacc types as subscribers for smacc signals");
424
425 typedef decltype(callback) ft;
426 Bind<boost::function_types::function_arity<ft>::value> binder;
427 boost::signals2::connection connection;
428
429 // long life-time objects
430 if (
431 std::is_base_of<ISmaccComponent, TSmaccObjectType>::value ||
432 std::is_base_of<ISmaccClient, TSmaccObjectType>::value ||
433 std::is_base_of<ISmaccOrthogonal, TSmaccObjectType>::value ||
434 std::is_base_of<ISmaccStateMachine, TSmaccObjectType>::value)
435 {
436 RCLCPP_INFO(
437 getLogger(),
438 "[StateMachine] long life-time smacc signal subscription created. Subscriber is %s. Callback "
439 "is: %s",
440 demangledTypeName<TSmaccObjectType>().c_str(),
441 demangleSymbol(typeid(callback).name()).c_str());
442
443 connection = binder.bindaux(signal, callback, object, nullptr);
444 }
445 else if (
446 std::is_base_of<ISmaccState, TSmaccObjectType>::value ||
447 std::is_base_of<StateReactor, TSmaccObjectType>::value ||
448 std::is_base_of<ISmaccClientBehavior, TSmaccObjectType>::value)
449 {
450 RCLCPP_INFO(
451 getLogger(),
452 "[StateMachine] life-time constrained smacc signal subscription created. Subscriber is %s",
453 demangledTypeName<TSmaccObjectType>().c_str());
454
455 std::shared_ptr<CallbackCounterSemaphore> callbackCounterSemaphore;
456 if (stateCallbackConnections.count(object))
457 {
458 callbackCounterSemaphore = stateCallbackConnections[object];
459 }
460 else
461 {
462 callbackCounterSemaphore =
463 std::make_shared<CallbackCounterSemaphore>(demangledTypeName<TSmaccObjectType>().c_str());
464 stateCallbackConnections[object] = callbackCounterSemaphore;
465 }
466
467 connection = binder.bindaux(signal, callback, object, callbackCounterSemaphore);
468 callbackCounterSemaphore->addConnection(connection);
469 }
470 else // state life-time objects
471 {
472 RCLCPP_WARN(
473 getLogger(),
474 "[StateMachine] connecting signal to an unknown object with life-time unknown "
475 "behavior. It might provoke "
476 "an exception if the object is destroyed during the execution.");
477
478 connection = binder.bindaux(signal, callback, object, nullptr);
479 }
480
481 return connection;
482}
std::map< void *, std::shared_ptr< CallbackCounterSemaphore > > stateCallbackConnections
std::string demangleSymbol()

References smacc2::introspection::demangleSymbol(), getLogger(), m_mutex_, and stateCallbackConnections.

Referenced by smacc2::ISmaccClient::connectSignal(), smacc2::client_bases::SmaccActionClientBase< ActionType >::onAborted(), smacc2::client_bases::SmaccActionClientBase< ActionType >::onAborted(), smacc2::client_bases::SmaccActionClientBase< ActionType >::onCancelled(), smacc2::client_bases::SmaccActionClientBase< ActionType >::onCancelled(), cl_nav2z::CbNavigateNextWaypoint::onEntry(), smacc2::SmaccAsyncClientBehavior::onFailure(), smacc2::SmaccAsyncClientBehavior::onFinished(), smacc2::components::CpTopicSubscriber< MessageType >::onFirstMessageReceived(), smacc2::client_bases::SmaccSubscriberClient< MessageType >::onFirstMessageReceived(), cl_keyboard::ClKeyboard::OnKeyPress(), smacc2::components::CpTopicSubscriber< MessageType >::onMessageReceived(), smacc2::client_bases::SmaccSubscriberClient< MessageType >::onMessageReceived(), cl_multirole_sensor::ClMultiroleSensor< MessageType >::onMessageTimeout(), cl_moveit2z::ClMoveit2z::onMotionExecutionFailed(), cl_moveit2z::ClMoveit2z::onMotionExecutionSuccedded(), smacc2::client_bases::SmaccServiceServerClient< TService >::onServiceRequestReceived(), smacc2::client_bases::SmaccActionClientBase< ActionType >::onSucceeded(), smacc2::client_bases::SmaccActionClientBase< ActionType >::onSucceeded(), smacc2::SmaccAsyncClientBehavior::onSuccess(), cl_ros_timer::ClRosTimer::onTimerTick(), cl_ros_timer::CbTimerCountdownLoop::onTimerTick(), cl_ros_timer::CbTimerCountdownOnce::onTimerTick(), cl_nav2z::CbNav2ZClientBehaviorBase::sendGoal(), and cl_nav2z::CpWaypointNavigator::sendNextGoal().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ disconnectSmaccSignalObject()

void smacc2::ISmaccStateMachine::disconnectSmaccSignalObject ( void object)

Definition at line 79 of file smacc_state_machine.cpp.

80{
81 RCLCPP_INFO(
82 nh_->get_logger(), "[SmaccSignals] object signal disconnecting %ld", (long)object_ptr);
83 if (stateCallbackConnections.count(object_ptr) > 0)
84 {
85 auto callbackSemaphore = stateCallbackConnections[object_ptr];
86 callbackSemaphore->finalize();
87 stateCallbackConnections.erase(object_ptr);
88 }
89 else
90 {
91 RCLCPP_INFO(nh_->get_logger(), "[SmaccSignals] no signals found %ld", (long)object_ptr);
92 }
93}

References nh_, and stateCallbackConnections.

Referenced by notifyOnStateExited(), and smacc2::ISmaccOrthogonal::onDispose().

Here is the caller graph for this function:

◆ eStop()

void smacc2::ISmaccStateMachine::eStop ( )
virtual

◆ getClientBehavior()

TClientBehavior * smacc2::ISmaccStateMachine::getClientBehavior ( int  index = 0)
inline

Definition at line 85 of file smacc_state_machine.hpp.

86 {
87 auto orthogonal = this->template getOrthogonal<TOrthogonal>();
88
89 return orthogonal->template getClientBehavior<TClientBehavior>(index);
90 }

◆ getCurrentState()

ISmaccState * smacc2::ISmaccStateMachine::getCurrentState ( ) const
inline

Definition at line 757 of file smacc_state_machine_impl.hpp.

757{ return this->currentState_.back(); }
std::vector< ISmaccState * > currentState_

References currentState_.

Referenced by cl_nav2z::CpWaypointNavigator::sendNextGoal().

Here is the caller graph for this function:

◆ getCurrentStateCounter()

int64_t smacc2::ISmaccStateMachine::getCurrentStateCounter ( ) const
inline

Definition at line 755 of file smacc_state_machine_impl.hpp.

755{ return this->stateSeqCounter_; }

References stateSeqCounter_.

◆ getCurrentStateInfo()

std::shared_ptr< SmaccStateInfo > smacc2::ISmaccStateMachine::getCurrentStateInfo ( )
inline

Definition at line 118 of file smacc_state_machine.hpp.

118{ return currentStateInfo_; }
std::shared_ptr< SmaccStateInfo > currentStateInfo_

References currentStateInfo_.

◆ getGlobalSMData()

template<typename T >
bool smacc2::ISmaccStateMachine::getGlobalSMData ( std::string  name,
T ret 
)

Definition at line 225 of file smacc_state_machine_impl.hpp.

226{
227 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
228 // RCLCPP_WARN(getLogger(),"get SM Data lock acquire");
229 bool success = false;
230
231 if (!globalData_.count(name))
232 {
233 // RCLCPP_WARN(getLogger(),"get SM Data - data do not exist");
234 success = false;
235 }
236 else
237 {
238 // RCLCPP_WARN(getLogger(),"get SM DAta -data exist. accessing");
239 try
240 {
241 auto & v = globalData_[name];
242
243 // RCLCPP_WARN(getLogger(),"get SM DAta -data exist. any cast");
244 ret = boost::any_cast<T>(v.second);
245 success = true;
246 // RCLCPP_WARN(getLogger(),"get SM DAta -data exist. success");
247 }
248 catch (boost::bad_any_cast & ex)
249 {
250 RCLCPP_ERROR(getLogger(), "bad any cast: %s", ex.what());
251 success = false;
252 }
253 }
254
255 // RCLCPP_WARN(getLogger(),"get SM Data lock release");
256 return success;
257}
std::map< std::string, std::pair< std::function< std::string()>, boost::any > > globalData_

References getLogger(), globalData_, and m_mutex_.

Referenced by smacc2::ISmaccOrthogonal::getGlobalSMData(), and mapBehavior().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getLogger()

rclcpp::Logger smacc2::ISmaccStateMachine::getLogger ( )
inline

◆ getMutex()

std::recursive_mutex & smacc2::ISmaccStateMachine::getMutex ( )
inline

Definition at line 167 of file smacc_state_machine.hpp.

167{ return this->m_mutex_; }

References m_mutex_.

◆ getNode()

rclcpp::Node::SharedPtr smacc2::ISmaccStateMachine::getNode ( )

◆ getOrthogonal()

template<typename TOrthogonal >
TOrthogonal * smacc2::ISmaccStateMachine::getOrthogonal ( )

Definition at line 55 of file smacc_state_machine_impl.hpp.

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}

References getLogger(), m_mutex_, and orthogonals_.

Here is the call graph for this function:

◆ getOrthogonals()

const std::map< std::string, std::shared_ptr< smacc2::ISmaccOrthogonal > > & smacc2::ISmaccStateMachine::getOrthogonals ( ) const

◆ getStateMachineInfo()

const smacc2::introspection::SmaccStateMachineInfo & smacc2::ISmaccStateMachine::getStateMachineInfo ( )
inline

Definition at line 759 of file smacc_state_machine_impl.hpp.

760{
761 return *this->stateMachineInfo_;
762}

References stateMachineInfo_.

◆ getStateMachineName()

std::string smacc2::ISmaccStateMachine::getStateMachineName ( )

Definition at line 223 of file smacc_state_machine.cpp.

224{
225 return demangleSymbol(typeid(*this).name());
226}

References smacc2::introspection::demangleSymbol().

Here is the call graph for this function:

◆ getTransitionLogHistory()

void smacc2::ISmaccStateMachine::getTransitionLogHistory ( const std::shared_ptr< rmw_request_id_t request_header,
const std::shared_ptr< smacc2_msgs::srv::SmaccGetTransitionHistory::Request >  req,
std::shared_ptr< smacc2_msgs::srv::SmaccGetTransitionHistory::Response >  res 
)

Definition at line 184 of file smacc_state_machine.cpp.

188{
189 RCLCPP_WARN(
190 nh_->get_logger(), "Requesting Transition Log History, current size: %ld",
191 this->transitionLogHistory_.size());
192 res->history = this->transitionLogHistory_;
193}
std::vector< smacc2_msgs::msg::SmaccTransitionLogEntry > transitionLogHistory_

References nh_, and transitionLogHistory_.

Referenced by initializeROS().

Here is the caller graph for this function:

◆ initializeROS()

void smacc2::ISmaccStateMachine::initializeROS ( std::string  smshortname)
protected

Definition at line 165 of file smacc_state_machine.cpp.

166{
167 RCLCPP_WARN_STREAM(nh_->get_logger(), "State machine base creation:" << shortname);
168 // STATE MACHINE TOPICS
169 stateMachinePub_ = nh_->create_publisher<smacc2_msgs::msg::SmaccStateMachine>(
170 shortname + "/smacc/state_machine_description", rclcpp::QoS(1));
171 stateMachineStatusPub_ = nh_->create_publisher<smacc2_msgs::msg::SmaccStatus>(
172 shortname + "/smacc/status", rclcpp::QoS(1));
173 transitionLogPub_ = nh_->create_publisher<smacc2_msgs::msg::SmaccTransitionLogEntry>(
174 shortname + "/smacc/transition_log", rclcpp::QoS(1));
175
176 // STATE MACHINE SERVICES
177 transitionHistoryService_ = nh_->create_service<smacc2_msgs::srv::SmaccGetTransitionHistory>(
178 shortname + "/smacc/transition_log_history",
179 std::bind(
180 &ISmaccStateMachine::getTransitionLogHistory, this, std::placeholders::_1,
181 std::placeholders::_2, std::placeholders::_3));
182}
rclcpp::Publisher< smacc2_msgs::msg::SmaccStateMachine >::SharedPtr stateMachinePub_
rclcpp::Service< smacc2_msgs::srv::SmaccGetTransitionHistory >::SharedPtr transitionHistoryService_
rclcpp::Publisher< smacc2_msgs::msg::SmaccStatus >::SharedPtr stateMachineStatusPub_
rclcpp::Publisher< smacc2_msgs::msg::SmaccTransitionLogEntry >::SharedPtr transitionLogPub_
void getTransitionLogHistory(const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< smacc2_msgs::srv::SmaccGetTransitionHistory::Request > req, std::shared_ptr< smacc2_msgs::srv::SmaccGetTransitionHistory::Response > res)

References getTransitionLogHistory(), nh_, stateMachinePub_, stateMachineStatusPub_, transitionHistoryService_, and transitionLogPub_.

Referenced by smacc2::SmaccStateMachineBase< DerivedStateMachine, InitialStateType >::initiate_impl().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ lockStateMachine()

void smacc2::ISmaccStateMachine::lockStateMachine ( std::string  msg)
private

Definition at line 211 of file smacc_state_machine.cpp.

212{
213 RCLCPP_DEBUG(nh_->get_logger(), "-- locking SM: %s", msg.c_str());
214 m_mutex_.lock();
215}

References m_mutex_, and nh_.

Referenced by notifyOnStateExited().

Here is the caller graph for this function:

◆ mapBehavior()

void smacc2::ISmaccStateMachine::mapBehavior ( )

Definition at line 281 of file smacc_state_machine_impl.hpp.

282{
283 std::string stateFieldName = demangleSymbol(typeid(StateField).name());
284 std::string behaviorType = demangleSymbol(typeid(BehaviorType).name());
285 RCLCPP_INFO(
286 getLogger(), "Mapping state field '%s' to stateReactor '%s'", stateFieldName.c_str(),
287 behaviorType.c_str());
288 SmaccClientBehavior * globalreference;
289 if (!this->getGlobalSMData(stateFieldName, globalreference))
290 {
291 // Using the requires component approach, we force a unique existence
292 // of this component
293 BehaviorType * behavior;
294 this->requiresComponent(behavior);
295 globalreference = dynamic_cast<ISmaccClientBehavior *>(behavior);
296
297 this->setGlobalSMData(stateFieldName, globalreference);
298 }
299}
bool getGlobalSMData(std::string name, T &ret)
void setGlobalSMData(std::string name, T value)
void requiresComponent(SmaccComponentType *&storage, bool throwsExceptionIfNotExist=false)

References smacc2::introspection::demangleSymbol(), getGlobalSMData(), getLogger(), requiresComponent(), and setGlobalSMData().

Here is the call graph for this function:

◆ notifyOnRuntimeConfigurationFinished()

template<typename StateType >
void smacc2::ISmaccStateMachine::notifyOnRuntimeConfigurationFinished ( StateType state)

Definition at line 569 of file smacc_state_machine_impl.hpp.

570{
571 for (auto pair : this->orthogonals_)
572 {
573 // RCLCPP_INFO(getLogger(),"ortho onruntime configure: %s", pair.second->getName().c_str());
574 auto & orthogonal = pair.second;
575 orthogonal->runtimeConfigure();
576 }
577
578 {
579 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
580 this->updateStatusMessage();
582
584 }
585}
StateMachineInternalAction stateMachineCurrentAction
void notifyStateConfigured(ISmaccState *currentState)

References currentState_, m_mutex_, smacc2::SignalDetector::notifyStateConfigured(), orthogonals_, signalDetector_, smacc2::STATE_ENTERING, stateMachineCurrentAction, and updateStatusMessage().

Here is the call graph for this function:

◆ notifyOnRuntimeConfigured()

template<typename StateType >
void smacc2::ISmaccStateMachine::notifyOnRuntimeConfigured ( StateType state)

◆ notifyOnStateEntryEnd()

template<typename StateType >
void smacc2::ISmaccStateMachine::notifyOnStateEntryEnd ( StateType state)

Definition at line 501 of file smacc_state_machine_impl.hpp.

502{
503 RCLCPP_INFO(
504 getLogger(), "[%s] State OnEntry code finished",
505 demangleSymbol(typeid(StateType).name()).c_str());
506
507 auto currentState = this->currentState_.back();
508 for (auto pair : this->orthogonals_)
509 {
510 RCLCPP_DEBUG(getLogger(), "ortho onentry: %s", pair.second->getName().c_str());
511 auto & orthogonal = pair.second;
512 try
513 {
514 orthogonal->onEntry();
515 }
516 catch (const std::exception & e)
517 {
518 RCLCPP_ERROR(
519 getLogger(),
520 "[Orthogonal %s] Exception on Entry - continuing with next orthogonal. Exception info: %s",
521 pair.second->getName().c_str(), e.what());
522 }
523 }
524
525 for (auto & sr : currentState->getStateReactors())
526 {
527 auto srname = smacc2::demangleSymbol(typeid(*sr).name());
528 RCLCPP_INFO_STREAM(getLogger(), "state reactor onEntry: " << srname);
529 try
530 {
531 sr->onEntry();
532 }
533 catch (const std::exception & e)
534 {
535 RCLCPP_ERROR(
536 getLogger(),
537 "[State Reactor %s] Exception on Entry - continuing with next state reactor. Exception "
538 "info: %s",
539 srname.c_str(), e.what());
540 }
541 }
542
543 for (auto & eg : currentState->getEventGenerators())
544 {
545 auto egname = smacc2::demangleSymbol(typeid(*eg).name());
546 RCLCPP_INFO_STREAM(getLogger(), "event generator onEntry: " << egname);
547 try
548 {
549 eg->onEntry();
550 }
551 catch (const std::exception & e)
552 {
553 RCLCPP_ERROR(
554 getLogger(),
555 "[Event generator %s] Exception on Entry - continuing with next state reactor. Exception "
556 "info: %s",
557 egname.c_str(), e.what());
558 }
559 }
560
561 {
562 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
563 this->updateStatusMessage();
565 }
566}

References currentState_, smacc2::introspection::demangleSymbol(), getLogger(), m_mutex_, orthogonals_, smacc2::STATE_RUNNING, stateMachineCurrentAction, and updateStatusMessage().

Here is the call graph for this function:

◆ notifyOnStateEntryStart()

template<typename StateType >
void smacc2::ISmaccStateMachine::notifyOnStateEntryStart ( StateType state)

Definition at line 485 of file smacc_state_machine_impl.hpp.

486{
487 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
488
489 RCLCPP_DEBUG(
490 getLogger(),
491 "[State Machne] Initializating a new state '%s' and updating current state. Getting state "
492 "meta-information. number of orthogonals: %ld",
493 demangleSymbol(typeid(StateType).name()).c_str(), this->orthogonals_.size());
494
496 currentState_.push_back(state);
497 currentStateInfo_ = stateMachineInfo_->getState<StateType>();
498}

References currentState_, currentStateInfo_, smacc2::introspection::demangleSymbol(), getLogger(), m_mutex_, orthogonals_, stateMachineInfo_, and stateSeqCounter_.

Here is the call graph for this function:

◆ notifyOnStateExited()

template<typename StateType >
void smacc2::ISmaccStateMachine::notifyOnStateExited ( StateType state)

Definition at line 656 of file smacc_state_machine_impl.hpp.

657{
658 this->lockStateMachine("state exit");
659
661
662 auto fullname = demangleSymbol(typeid(StateType).name());
663 RCLCPP_WARN_STREAM(getLogger(), "exiting state: " << fullname);
664
665 RCLCPP_INFO_STREAM(getLogger(), "Notification State Disposing: leaving state" << state);
666 for (auto pair : this->orthogonals_)
667 {
668 auto & orthogonal = pair.second;
669 try
670 {
671 orthogonal->onDispose();
672 }
673 catch (const std::exception & e)
674 {
675 RCLCPP_ERROR(
676 getLogger(),
677 "[Orthogonal %s] Exception onDispose - continuing with next orthogonal. Exception info: %s",
678 pair.second->getName().c_str(), e.what());
679 }
680 }
681
682 for (auto & sr : state->getStateReactors())
683 {
684 auto srname = smacc2::demangleSymbol(typeid(*sr).name()).c_str();
685 RCLCPP_INFO(getLogger(), "state reactor disposing: %s", srname);
686 try
687 {
688 this->disconnectSmaccSignalObject(sr.get());
689 }
690 catch (const std::exception & e)
691 {
692 RCLCPP_ERROR(
693 getLogger(),
694 "[State Reactor %s] Exception on OnDispose - continuing with next state reactor. Exception "
695 "info: %s",
696 srname, e.what());
697 }
698 }
699
700 for (auto & eg : state->getEventGenerators())
701 {
702 auto egname = smacc2::demangleSymbol(typeid(*eg).name()).c_str();
703 RCLCPP_INFO(getLogger(), "state reactor disposing: %s", egname);
704 try
705 {
706 this->disconnectSmaccSignalObject(eg.get());
707 }
708 catch (const std::exception & e)
709 {
710 RCLCPP_ERROR(
711 getLogger(),
712 "[State Reactor %s] Exception on OnDispose - continuing with next state reactor. Exception "
713 "info: %s",
714 egname, e.what());
715 }
716 }
717
718 this->stateCallbackConnections.clear();
719 currentState_.pop_back();
720
721 // then call exit state
722 RCLCPP_WARN_STREAM(getLogger(), "state exit: " << fullname);
723
725 this->unlockStateMachine("state exit");
726}
void lockStateMachine(std::string msg)
void disconnectSmaccSignalObject(void *object)
void unlockStateMachine(std::string msg)
void notifyStateExited(ISmaccState *currentState)

References currentState_, smacc2::introspection::demangleSymbol(), disconnectSmaccSignalObject(), getLogger(), lockStateMachine(), smacc2::SignalDetector::notifyStateExited(), orthogonals_, signalDetector_, stateCallbackConnections, stateMachineCurrentAction, smacc2::TRANSITIONING, and unlockStateMachine().

Here is the call graph for this function:

◆ notifyOnStateExitting()

template<typename StateType >
void smacc2::ISmaccStateMachine::notifyOnStateExitting ( StateType state)

Definition at line 594 of file smacc_state_machine_impl.hpp.

595{
597 auto fullname = demangleSymbol(typeid(StateType).name());
598 RCLCPP_WARN_STREAM(getLogger(), "exiting state: " << fullname);
599 // this->set_parameter("destroyed", true);
600
601 RCLCPP_INFO_STREAM(getLogger(), "Notification State Exit: leaving state " << state);
602 for (auto pair : this->orthogonals_)
603 {
604 auto & orthogonal = pair.second;
605 try
606 {
607 orthogonal->onExit();
608 }
609 catch (const std::exception & e)
610 {
611 RCLCPP_ERROR(
612 getLogger(),
613 "[Orthogonal %s] Exception onExit - continuing with next orthogonal. Exception info: %s",
614 pair.second->getName().c_str(), e.what());
615 }
616 }
617
618 for (auto & sr : state->getStateReactors())
619 {
620 auto srname = smacc2::demangleSymbol(typeid(*sr).name());
621 RCLCPP_INFO_STREAM(getLogger(), "state reactor OnExit: " << srname);
622 try
623 {
624 sr->onExit();
625 }
626 catch (const std::exception & e)
627 {
628 RCLCPP_ERROR(
629 getLogger(),
630 "[State Reactor %s] Exception on OnExit - continuing with next state reactor. Exception "
631 "info: %s",
632 srname.c_str(), e.what());
633 }
634 }
635
636 for (auto & eg : state->getEventGenerators())
637 {
638 auto egname = smacc2::demangleSymbol(typeid(*eg).name());
639 RCLCPP_INFO_STREAM(getLogger(), "event generator OnExit: " << egname);
640 try
641 {
642 eg->onExit();
643 }
644 catch (const std::exception & e)
645 {
646 RCLCPP_ERROR(
647 getLogger(),
648 "[State Reactor %s] Exception on OnExit - continuing with next state reactor. Exception "
649 "info: %s",
650 egname.c_str(), e.what());
651 }
652 }
653}

References smacc2::introspection::demangleSymbol(), getLogger(), orthogonals_, smacc2::STATE_EXITING, and stateMachineCurrentAction.

Here is the call graph for this function:

◆ onInitialize()

void smacc2::ISmaccStateMachine::onInitialize ( )
virtual

this function should be implemented by the user to create the orthogonals

Definition at line 156 of file smacc_state_machine.cpp.

156{}

Referenced by smacc2::SmaccStateMachineBase< DerivedStateMachine, InitialStateType >::initiate_impl().

Here is the caller graph for this function:

◆ onInitialized()

void smacc2::ISmaccStateMachine::onInitialized ( )
protected

Definition at line 158 of file smacc_state_machine.cpp.

159{
160 auto ros_clock = rclcpp::Clock::make_shared();
161 timer_ =
162 rclcpp::create_timer(nh_, ros_clock, 0.5s, [=]() { this->state_machine_visualization(); });
163}
rclcpp::TimerBase::SharedPtr timer_

References nh_, state_machine_visualization(), and timer_.

Referenced by smacc2::SmaccStateMachineBase< DerivedStateMachine, InitialStateType >::initiate_impl().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ postEvent() [1/2]

template<typename EventType >
void smacc2::ISmaccStateMachine::postEvent ( EventLifeTime  evlifetime = EventLifeTime::ABSOLUTE)

Definition at line 216 of file smacc_state_machine_impl.hpp.

217{
218 auto evname = smacc2::introspection::demangleSymbol<EventType>();
219 RCLCPP_INFO_STREAM(getLogger(), "Event " << evname);
220 auto * ev = new EventType();
221 this->postEvent(ev, evlifetime);
222}
void postEvent(EventType *ev, EventLifeTime evlifetime=EventLifeTime::ABSOLUTE)

References getLogger(), and postEvent().

Here is the call graph for this function:

◆ postEvent() [2/2]

template<typename EventType >
void smacc2::ISmaccStateMachine::postEvent ( EventType ev,
EventLifeTime  evlifetime = EventLifeTime::ABSOLUTE 
)

Definition at line 178 of file smacc_state_machine_impl.hpp.

179{
180 std::lock_guard<std::recursive_mutex> guard(eventQueueMutex_);
181
182#define eventtypename demangleSymbol<EventType>().c_str()
183
185
186 if (
187 evlifetime == EventLifeTime::CURRENT_STATE &&
190 {
191 RCLCPP_WARN_STREAM(
192 getLogger(),
193 "[ISmaccStateMachine] CURRENT STATE SCOPED EVENT DISCARDED, state is exiting/transitioning "
194 << eventtypename);
195 return;
196 // in this case we may lose/skip events, if this is not right for some cases we should create a
197 // queue to lock the events during the transitions. This issues appeared when a client
198 // asyncbehavior was posting an event meanwhile we were doing the transition, but the main
199 // thread was waiting for its correct finalization (with thread.join)
200 }
201
202 // when a postting event is requested by any component, client, or client behavior
203 // we reach this place. Now, we propagate the events to all the state state reactors to generate
204 // some more events
205
206 RCLCPP_DEBUG_STREAM(getLogger(), "[PostEvent entry point] " << eventtypename);
207 for (auto currentState : currentState_)
208 {
209 propagateEventToStateReactors(currentState, ev);
210 }
211
212 this->signalDetector_->postEvent(ev);
213}
std::recursive_mutex eventQueueMutex_
void propagateEventToStateReactors(ISmaccState *st, EventType *ev)
#define eventtypename
void TRACEPOINT(spinOnce)
smacc2_event

References smacc2::CURRENT_STATE, currentState_, eventQueueMutex_, eventtypename, getLogger(), smacc2::SignalDetector::postEvent(), propagateEventToStateReactors(), signalDetector_, smacc2_event, smacc2::STATE_EXITING, stateMachineCurrentAction, TRACEPOINT(), and smacc2::TRANSITIONING.

Referenced by smacc2::ISmaccComponent::postEvent(), smacc2::ISmaccClient::postEvent(), smacc2::ISmaccComponent::postEvent(), smacc2::ISmaccClient::postEvent(), smacc2::ISmaccClientBehavior::postEvent(), and postEvent().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ propagateEventToStateReactors()

template<typename EventType >
void smacc2::ISmaccStateMachine::propagateEventToStateReactors ( ISmaccState st,
EventType ev 
)
private

Definition at line 729 of file smacc_state_machine_impl.hpp.

730{
731 RCLCPP_DEBUG(
732 getLogger(), "PROPAGATING EVENT [%s] TO SRs [%s]: ", demangleSymbol<EventType>().c_str(),
733 st->getClassName().c_str());
734 for (auto & sb : st->getStateReactors())
735 {
736 sb->notifyEvent(ev);
737 }
738
739 auto * pst = st->getParentState();
740 if (pst != nullptr)
741 {
743 }
744}

References getLogger(), and propagateEventToStateReactors().

Referenced by postEvent(), and propagateEventToStateReactors().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ publishTransition()

void smacc2::ISmaccStateMachine::publishTransition ( const SmaccTransitionInfo transitionInfo)

Definition at line 146 of file smacc_state_machine.cpp.

147{
148 smacc2_msgs::msg::SmaccTransitionLogEntry transitionLogEntry;
149 transitionLogEntry.timestamp = this->nh_->now();
150 transitionInfoToMsg(transitionInfo, transitionLogEntry.transition);
151 this->transitionLogHistory_.push_back(transitionLogEntry);
152
153 transitionLogPub_->publish(transitionLogEntry);
154}
void transitionInfoToMsg(const SmaccTransitionInfo &transition, smacc2_msgs::msg::SmaccTransition &transitionMsg)

References nh_, smacc2::introspection::transitionInfoToMsg(), transitionLogHistory_, and transitionLogPub_.

Referenced by smacc2::SmaccStateMachineBase< DerivedStateMachine, InitialStateType >::initiate_impl().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ requiresComponent()

void smacc2::ISmaccStateMachine::requiresComponent ( SmaccComponentType *&  storage,
bool  throwsExceptionIfNotExist = false 
)

Definition at line 127 of file smacc_state_machine_impl.hpp.

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}

References smacc2::introspection::demangleSymbol(), getLogger(), m_mutex_, and orthogonals_.

Referenced by mapBehavior(), smacc2::ISmaccOrthogonal::requiresComponent(), and smacc2::ISmaccClientBehavior::requiresComponent().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ reset()

void smacc2::ISmaccStateMachine::reset ( )
virtual

◆ setGlobalSMData()

template<typename T >
void smacc2::ISmaccStateMachine::setGlobalSMData ( std::string  name,
T  value 
)

Definition at line 260 of file smacc_state_machine_impl.hpp.

261{
262 {
263 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
264 // RCLCPP_WARN(getLogger(),"set SM Data lock acquire");
265
266 globalData_[name] = {
267 [this, name]()
268 {
269 std::stringstream ss;
270 auto val = any_cast<T>(globalData_[name].second);
271 ss << val;
272 return ss.str();
273 },
274 value};
275 }
276
277 this->updateStatusMessage();
278}

References globalData_, m_mutex_, and updateStatusMessage().

Referenced by mapBehavior(), and smacc2::ISmaccOrthogonal::setGlobalSMData().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ state_machine_visualization()

void smacc2::ISmaccStateMachine::state_machine_visualization ( )

Definition at line 195 of file smacc_state_machine.cpp.

196{
197 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
198
199 smacc2_msgs::msg::SmaccStateMachine state_machine_msg;
200 state_machine_msg.states = stateMachineInfo_->stateMsgs;
201
202 std::sort(
203 state_machine_msg.states.begin(), state_machine_msg.states.end(),
204 [](auto & a, auto & b) { return a.index < b.index; });
205 stateMachinePub_->publish(state_machine_msg);
206
207 status_msg_.header.stamp = this->nh_->now();
209}
smacc2_msgs::msg::SmaccStatus status_msg_

References m_mutex_, nh_, stateMachineInfo_, stateMachinePub_, stateMachineStatusPub_, and status_msg_.

Referenced by onInitialized().

Here is the caller graph for this function:

◆ stop()

void smacc2::ISmaccStateMachine::stop ( )
virtual

◆ unlockStateMachine()

void smacc2::ISmaccStateMachine::unlockStateMachine ( std::string  msg)
private

Definition at line 217 of file smacc_state_machine.cpp.

218{
219 RCLCPP_DEBUG(nh_->get_logger(), "-- unlocking SM: %s", msg.c_str());
220 m_mutex_.unlock();
221}

References m_mutex_, and nh_.

Referenced by notifyOnStateExited().

Here is the caller graph for this function:

◆ updateStatusMessage()

void smacc2::ISmaccStateMachine::updateStatusMessage ( )
private

Definition at line 109 of file smacc_state_machine.cpp.

110{
111 std::lock_guard<std::recursive_mutex> lock(m_mutex_);
112
113 if (currentStateInfo_ != nullptr)
114 {
115 RCLCPP_WARN_STREAM(
116 nh_->get_logger(), "[StateMachine] setting state active "
117 << ": " << currentStateInfo_->getFullPath());
118
120 {
121 status_msg_.current_states.clear();
122 std::list<const SmaccStateInfo *> ancestorList;
123 currentStateInfo_->getAncestors(ancestorList);
124
125 for (auto & ancestor : ancestorList)
126 {
127 status_msg_.current_states.push_back(ancestor->toShortName());
128 }
129
130 status_msg_.global_variable_names.clear();
131 status_msg_.global_variable_values.clear();
132
133 for (auto entry : this->globalData_)
134 {
135 status_msg_.global_variable_names.push_back(entry.first);
136 status_msg_.global_variable_values.push_back(
137 entry.second.first()); // <- invoke to_string()
138 }
139
140 status_msg_.header.stamp = this->nh_->now();
142 }
143 }
144}

References currentStateInfo_, smacc2::DEBUG, globalData_, m_mutex_, nh_, runMode_, stateMachineStatusPub_, and status_msg_.

Referenced by notifyOnRuntimeConfigurationFinished(), notifyOnStateEntryEnd(), and setGlobalSMData().

Here is the caller graph for this function:

Friends And Related Symbol Documentation

◆ ISmaccState

friend class ISmaccState
friend

Definition at line 234 of file smacc_state_machine.hpp.

◆ SignalDetector

friend class SignalDetector
friend

Definition at line 235 of file smacc_state_machine.hpp.

Member Data Documentation

◆ currentState_

std::vector<ISmaccState *> smacc2::ISmaccStateMachine::currentState_
protected

◆ currentStateInfo_

std::shared_ptr<SmaccStateInfo> smacc2::ISmaccStateMachine::currentStateInfo_
protected

◆ eventQueueMutex_

std::recursive_mutex smacc2::ISmaccStateMachine::eventQueueMutex_
private

Definition at line 206 of file smacc_state_machine.hpp.

Referenced by postEvent().

◆ globalData_

std::map<std::string, std::pair<std::function<std::string()>, boost::any> > smacc2::ISmaccStateMachine::globalData_
private

Definition at line 213 of file smacc_state_machine.hpp.

Referenced by getGlobalSMData(), setGlobalSMData(), and updateStatusMessage().

◆ longLivedSignalConnections_

std::vector<boost::signals2::scoped_connection> smacc2::ISmaccStateMachine::longLivedSignalConnections_
protected

Definition at line 199 of file smacc_state_machine.hpp.

◆ m_mutex_

std::recursive_mutex smacc2::ISmaccStateMachine::m_mutex_
private

◆ nh_

rclcpp::Node::SharedPtr smacc2::ISmaccStateMachine::nh_
protected

◆ orthogonals_

std::map<std::string, std::shared_ptr<smacc2::ISmaccOrthogonal> > smacc2::ISmaccStateMachine::orthogonals_
protected

◆ runMode_

smacc2::SMRunMode smacc2::ISmaccStateMachine::runMode_
private

Definition at line 218 of file smacc_state_machine.hpp.

Referenced by ISmaccStateMachine(), and updateStatusMessage().

◆ signalDetector_

SignalDetector* smacc2::ISmaccStateMachine::signalDetector_
private

◆ stateCallbackConnections

std::map<void *, std::shared_ptr<CallbackCounterSemaphore> > smacc2::ISmaccStateMachine::stateCallbackConnections
private

◆ stateMachineCurrentAction

StateMachineInternalAction smacc2::ISmaccStateMachine::stateMachineCurrentAction
private

◆ stateMachineInfo_

std::shared_ptr<SmaccStateMachineInfo> smacc2::ISmaccStateMachine::stateMachineInfo_
protected

◆ stateMachinePub_

rclcpp::Publisher<smacc2_msgs::msg::SmaccStateMachine>::SharedPtr smacc2::ISmaccStateMachine::stateMachinePub_
protected

Definition at line 183 of file smacc_state_machine.hpp.

Referenced by initializeROS(), and state_machine_visualization().

◆ stateMachineStatusPub_

rclcpp::Publisher<smacc2_msgs::msg::SmaccStatus>::SharedPtr smacc2::ISmaccStateMachine::stateMachineStatusPub_
protected

◆ stateSeqCounter_

int64_t smacc2::ISmaccStateMachine::stateSeqCounter_
private

Definition at line 223 of file smacc_state_machine.hpp.

Referenced by getCurrentStateCounter(), and notifyOnStateEntryStart().

◆ status_msg_

smacc2_msgs::msg::SmaccStatus smacc2::ISmaccStateMachine::status_msg_
protected

Definition at line 194 of file smacc_state_machine.hpp.

Referenced by state_machine_visualization(), and updateStatusMessage().

◆ timer_

rclcpp::TimerBase::SharedPtr smacc2::ISmaccStateMachine::timer_
protected

Definition at line 182 of file smacc_state_machine.hpp.

Referenced by onInitialized().

◆ transitionHistoryService_

rclcpp::Service<smacc2_msgs::srv::SmaccGetTransitionHistory>::SharedPtr smacc2::ISmaccStateMachine::transitionHistoryService_
protected

Definition at line 186 of file smacc_state_machine.hpp.

Referenced by initializeROS().

◆ transitionLogHistory_

std::vector<smacc2_msgs::msg::SmaccTransitionLogEntry> smacc2::ISmaccStateMachine::transitionLogHistory_
private

Definition at line 216 of file smacc_state_machine.hpp.

Referenced by getTransitionLogHistory(), and publishTransition().

◆ transitionLogPub_

rclcpp::Publisher<smacc2_msgs::msg::SmaccTransitionLogEntry>::SharedPtr smacc2::ISmaccStateMachine::transitionLogPub_
protected

Definition at line 185 of file smacc_state_machine.hpp.

Referenced by initializeROS(), and publishTransition().


The documentation for this class was generated from the following files: