SMACC2
Loading...
Searching...
No Matches
smacc2::SignalDetector Class Reference

#include <smacc_signal_detector.hpp>

Collaboration diagram for smacc2::SignalDetector:
Collaboration graph

Public Member Functions

 SignalDetector (SmaccFifoScheduler *scheduler, ExecutionModel executionModel=ExecutionModel::SINGLE_THREAD_SPINNER)
 
void initialize (ISmaccStateMachine *stateMachine)
 
void setProcessorHandle (SmaccFifoScheduler::processor_handle processorHandle)
 
void runThread ()
 
void join ()
 
void stop ()
 
void terminateScheduler ()
 
void pollingLoop ()
 
template<typename EventType >
void postEvent (EventType *ev)
 
rclcpp::Node::SharedPtr getNode ()
 
rclcpp::Logger getLogger ()
 
void notifyStateConfigured (ISmaccState *currentState)
 
void notifyStateExited (ISmaccState *currentState)
 
void notifyRosInitialized ()
 

Private Member Functions

void pollOnce ()
 
void findUpdatableClientsAndComponents ()
 
void findUpdatableStateElements (ISmaccState *currentState)
 

Private Attributes

ISmaccStateMachinesmaccStateMachine_
 
std::vector< ISmaccUpdatable * > updatableClients_
 
std::vector< std::vector< ISmaccUpdatable * > > updatableStateElements_
 
std::atomic< int64_t > lastState_
 
double loop_rate_hz
 
std::atomic< boolend_
 
std::atomic< boolinitialized_
 
std::atomic< boolrosInitialized_
 
rclcpp::Publisher< smacc2_msgs::msg::SmaccStatus >::SharedPtr statusPub_
 
SmaccFifoSchedulerscheduler_
 
SmaccFifoScheduler::processor_handle processorHandle_
 
boost::thread signalDetectorThread_
 
ExecutionModel executionModel_
 

Detailed Description

Definition at line 37 of file smacc_signal_detector.hpp.

Constructor & Destructor Documentation

◆ SignalDetector()

smacc2::SignalDetector::SignalDetector ( SmaccFifoScheduler * scheduler,
ExecutionModel executionModel = ExecutionModel::SINGLE_THREAD_SPINNER )

SignalDetector()

Definition at line 64 of file signal_detector.cpp.

65{
66 scheduler_ = scheduler;
67 loop_rate_hz = 20.0;
68 end_ = false;
69 initialized_ = false;
70 rosInitialized_ = false;
71 executionModel_ = executionModel;
72}
SmaccFifoScheduler * scheduler_
std::atomic< bool > rosInitialized_
std::atomic< bool > initialized_

References end_, executionModel_, initialized_, loop_rate_hz, rosInitialized_, and scheduler_.

Member Function Documentation

◆ findUpdatableClientsAndComponents()

void smacc2::SignalDetector::findUpdatableClientsAndComponents ( )
private

findUpdatableClientsAndComponents()

Definition at line 104 of file signal_detector.cpp.

105{
106 this->updatableClients_.clear();
107 for (auto pair : this->smaccStateMachine_->getOrthogonals())
108 {
109 auto & orthogonal = pair.second;
110 auto & clients = orthogonal->getClients();
111
112 for (auto & client : clients)
113 {
114 // updatable client components
115 auto updatableClient = dynamic_cast<ISmaccUpdatable *>(client.get());
116
117 if (updatableClient != nullptr)
118 {
119 RCLCPP_DEBUG_STREAM(
120 getLogger(), "Adding updatable client: " << demangleType(typeid(updatableClient)));
121 this->updatableClients_.push_back(updatableClient);
122 }
123
124 // updatable client components
125 std::vector<std::shared_ptr<ISmaccComponent>> components;
126 client->getComponents(components);
127 for (auto & componententry : components)
128 {
129 auto updatableComponent = dynamic_cast<ISmaccUpdatable *>(componententry.get());
130 if (updatableComponent != nullptr)
131 {
132 RCLCPP_DEBUG_STREAM(
133 getLogger(),
134 "Adding updatable component: " << demangleType(typeid(*updatableComponent)));
135 this->updatableClients_.push_back(updatableComponent);
136 }
137 }
138 }
139 }
140}
const std::map< std::string, std::shared_ptr< smacc2::ISmaccOrthogonal > > & getOrthogonals() const
std::vector< ISmaccUpdatable * > updatableClients_
ISmaccStateMachine * smaccStateMachine_
std::string demangleType(const std::type_info *tinfo)

References smacc2::introspection::demangleType(), getLogger(), smacc2::ISmaccStateMachine::getOrthogonals(), smaccStateMachine_, and updatableClients_.

Referenced by initialize(), and pollOnce().

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

◆ findUpdatableStateElements()

void smacc2::SignalDetector::findUpdatableStateElements ( ISmaccState * currentState)
private

findUpdatableClientBehaviors()

Definition at line 147 of file signal_detector.cpp.

148{
149 updatableStateElements_.push_back(std::vector<ISmaccUpdatable *>());
150
151 auto & updatableElements = updatableStateElements_.back();
152
153 for (auto pair : this->smaccStateMachine_->getOrthogonals())
154 {
155 auto & orthogonal = pair.second;
156 auto & behaviors = orthogonal->getClientBehaviors().back();
157
158 for (auto & currentBehavior : behaviors)
159 {
160 ISmaccUpdatable * updatableClientBehavior =
161 dynamic_cast<ISmaccUpdatable *>(currentBehavior.get());
162
163 if (updatableClientBehavior != nullptr)
164 {
165 RCLCPP_DEBUG_STREAM(
166 getLogger(),
167 "Adding updatable behavior: " << demangleType(typeid(updatableClientBehavior)));
168 updatableElements.push_back(updatableClientBehavior);
169 }
170 }
171 }
172
173 auto updatableState = dynamic_cast<ISmaccUpdatable *>(currentState);
174 if (updatableState != nullptr)
175 {
176 updatableElements.push_back(updatableState);
177 }
178
179 auto statereactors = currentState->getStateReactors();
180 for (auto & sr : statereactors)
181 {
182 ISmaccUpdatable * updatableStateReactor = dynamic_cast<ISmaccUpdatable *>(sr.get());
183 if (updatableStateReactor != nullptr)
184 {
185 RCLCPP_DEBUG_STREAM(
186 getLogger(),
187 "Adding updatable stateReactorr: " << demangleType(typeid(updatableStateReactor)));
188 updatableElements.push_back(updatableStateReactor);
189 }
190 }
191
192 auto eventgenerators = currentState->getEventGenerators();
193 for (auto & eg : eventgenerators)
194 {
195 ISmaccUpdatable * updatableEventGenerator = dynamic_cast<ISmaccUpdatable *>(eg.get());
196 if (updatableEventGenerator != nullptr)
197 {
198 RCLCPP_DEBUG_STREAM(
199 getLogger(),
200 "Adding updatable eventGenerator: " << demangleType(typeid(updatableEventGenerator)));
201 updatableElements.push_back(updatableEventGenerator);
202 }
203 }
204}
std::vector< std::vector< ISmaccUpdatable * > > updatableStateElements_

References smacc2::introspection::demangleType(), smacc2::ISmaccState::getEventGenerators(), getLogger(), smacc2::ISmaccStateMachine::getOrthogonals(), smacc2::ISmaccState::getStateReactors(), smaccStateMachine_, and updatableStateElements_.

Referenced by notifyStateConfigured().

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

◆ getLogger()

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

Definition at line 68 of file smacc_signal_detector.hpp.

68{ return getNode()->get_logger(); }
rclcpp::Node::SharedPtr getNode()

References getNode().

Referenced by findUpdatableClientsAndComponents(), findUpdatableStateElements(), notifyRosInitialized(), pollingLoop(), pollOnce(), and terminateScheduler().

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

◆ getNode()

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

Definition at line 74 of file signal_detector.cpp.

74{ return this->smaccStateMachine_->getNode(); }
rclcpp::Node::SharedPtr getNode()

References smacc2::ISmaccStateMachine::getNode(), and smaccStateMachine_.

Referenced by getLogger(), initialize(), pollingLoop(), and pollOnce().

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

◆ initialize()

void smacc2::SignalDetector::initialize ( ISmaccStateMachine * stateMachine)

initialize()

Definition at line 81 of file signal_detector.cpp.

82{
83 smaccStateMachine_ = stateMachine;
84 lastState_ = std::numeric_limits<int64_t>::quiet_NaN();
86 this->getNode()->declare_parameter("signal_detector_loop_freq", this->loop_rate_hz);
87
88 auto context = getNode()->get_node_base_interface()->get_context();
89 context->on_shutdown(
90 [this]()
91 {
92 this->stop();
93 this->terminateScheduler();
94 });
95
96 initialized_ = true;
97}
std::atomic< int64_t > lastState_

References findUpdatableClientsAndComponents(), getNode(), initialized_, lastState_, loop_rate_hz, smaccStateMachine_, stop(), and terminateScheduler().

Referenced by smacc2::ISmaccStateMachine::ISmaccStateMachine().

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

◆ join()

void smacc2::SignalDetector::join ( )

join()

Definition at line 247 of file signal_detector.cpp.

247{ signalDetectorThread_.join(); }

References signalDetectorThread_.

◆ notifyRosInitialized()

void smacc2::SignalDetector::notifyRosInitialized ( )

Definition at line 216 of file signal_detector.cpp.

217{
218 RCLCPP_INFO(getLogger(), "[SignalDetector] ROS initialization complete, enabling polling loop");
219 rosInitialized_ = true;
220}

References getLogger(), and rosInitialized_.

Referenced by smacc2::ISmaccStateMachine::initializeROS().

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

◆ notifyStateConfigured()

void smacc2::SignalDetector::notifyStateConfigured ( ISmaccState * currentState)

Definition at line 206 of file signal_detector.cpp.

207{
208 this->findUpdatableStateElements(currentState);
209}
void findUpdatableStateElements(ISmaccState *currentState)

References findUpdatableStateElements().

Referenced by smacc2::ISmaccStateMachine::notifyOnRuntimeConfigurationFinished().

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

◆ notifyStateExited()

void smacc2::SignalDetector::notifyStateExited ( ISmaccState * currentState)

Definition at line 211 of file signal_detector.cpp.

212{
213 this->updatableStateElements_.pop_back();
214}

References updatableStateElements_.

Referenced by smacc2::ISmaccStateMachine::notifyOnStateExited().

Here is the caller graph for this function:

◆ pollingLoop()

void smacc2::SignalDetector::pollingLoop ( )

pollingLoop()

Definition at line 359 of file signal_detector.cpp.

360{
361 // rclcpp::Node::SharedPtr nh("~"); // use node name as root of the parameter server
362 rclcpp::Node::SharedPtr _;
363 rclcpp::Rate r0(20);
364
365 // Wait for both SignalDetector::initialize() (called from ISmaccStateMachine constructor)
366 // and ROS initialization to complete (initializeROS called from initiate_impl).
367 // This ensures orthogonals, clients, and ROS objects are fully initialized
368 // before we start polling and accessing them.
369 while ((!initialized_ || !rosInitialized_) && rclcpp::ok() && !end_)
370 {
371 r0.sleep();
372 }
373
374 if (!rclcpp::ok() || end_)
375 {
376 RCLCPP_INFO(getLogger(), "[SignalDetector] Shutdown requested before initialization completed");
377 return;
378 }
379
380 auto nh = getNode();
381
382 if (!nh->get_parameter("signal_detector_loop_freq", this->loop_rate_hz))
383 {
384 RCLCPP_WARN(
385 getLogger(),
386 "Signal Detector frequency (ros param signal_detector_loop_freq) was not set, using default "
387 "frequency: "
388 "%lf",
389 this->loop_rate_hz);
390 }
391 else
392 {
393 RCLCPP_WARN(
394 getLogger(), "Signal Detector frequency (ros param signal_detector_loop_freq): %lf",
395 this->loop_rate_hz);
396 }
397
398 nh->set_parameter(rclcpp::Parameter("signal_detector_loop_freq", this->loop_rate_hz));
399
400 RCLCPP_INFO_STREAM(getLogger(), "[SignalDetector] Loop rate hz:" << loop_rate_hz);
401
403 {
404 RCLCPP_INFO_STREAM(getLogger(), "[SignalDetector] Running in single-threaded mode.");
405
406 rclcpp::Rate r(loop_rate_hz);
407 while (rclcpp::ok() && !end_)
408 {
409 RCLCPP_INFO_STREAM_THROTTLE(
410 getLogger(), *getNode()->get_clock(), 10000, "[SignalDetector] Heartbeat");
411 pollOnce();
412 rclcpp::spin_some(nh);
413 r.sleep();
414 }
415 }
416 else
417 {
418 RCLCPP_INFO_STREAM(getLogger(), "[SignalDetector] Running in multi-threaded mode.");
419
420 rclcpp::executors::MultiThreadedExecutor executor;
421 executor.add_node(nh);
422 executor.spin();
423 }
424}

References end_, executionModel_, getLogger(), getNode(), initialized_, loop_rate_hz, pollOnce(), rosInitialized_, and smacc2::SINGLE_THREAD_SPINNER.

Referenced by smacc2::run(), smacc2::run_async(), and runThread().

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

◆ pollOnce()

void smacc2::SignalDetector::pollOnce ( )
private

poll()

Definition at line 275 of file signal_detector.cpp.

276{
277 // precondition: smaccStateMachine_ != nullptr
278
279 //TRACETOOLS_TRACEPOINT( spinOnce);
280 TRACETOOLS_TRACEPOINT(spinOnce);
281
282 std::lock_guard<std::recursive_mutex> lock(smaccStateMachine_->m_mutex_);
283 try
284 {
285 //smaccStateMachine_->lockStateMachine("update behaviors");
286
288 RCLCPP_DEBUG_STREAM(getLogger(), "Updatable clients: " << this->updatableClients_.size());
289
290 if (this->updatableClients_.size())
291 {
292 auto node = getNode();
293 for (auto * updatableClient : this->updatableClients_)
294 {
295 auto updatableElementName = demangleType(typeid(*updatableClient)).c_str();
296 try
297 {
298 RCLCPP_DEBUG_STREAM(
299 node->get_logger(),
300 "[PollOnce] update client call: " << demangleType(typeid(*updatableClient)));
301
302 TRACETOOLS_TRACEPOINT(smacc2_state_update_start, updatableElementName);
303 updatableClient->executeUpdate(smaccStateMachine_->getNode());
304 TRACETOOLS_TRACEPOINT(smacc2_state_update_start, updatableElementName);
305 }
306 catch (const std::exception & e)
307 {
308 RCLCPP_ERROR_STREAM(
309 node->get_logger(),
310 "Error in updatable elemnent " << updatableElementName << ": " << e.what() << '\n');
311 }
312 }
313 }
314
315 // STATE UPDATABLE ELEMENTS
316 if (
319 this->smaccStateMachine_->stateMachineCurrentAction !=
321 this->smaccStateMachine_->stateMachineCurrentAction !=
323 this->smaccStateMachine_->stateMachineCurrentAction !=
325 {
326 RCLCPP_DEBUG_STREAM(
327 getLogger(), "Updatable states: " << this->updatableStateElements_.size());
328
329 for (auto stateElement : this->updatableStateElements_)
330 {
331 for (auto * udpatableStateElement : stateElement)
332 {
333 std::string updatableElementName = demangleType(typeid(*udpatableStateElement));
334 auto updatableElementNameCstr = updatableElementName.c_str();
335
336 RCLCPP_DEBUG_STREAM(
337 getLogger(), "pollOnce update client behavior call: "
338 << demangleType(typeid(*udpatableStateElement)));
339 TRACETOOLS_TRACEPOINT(smacc2_state_update_start, updatableElementNameCstr);
340
341 udpatableStateElement->executeUpdate(smaccStateMachine_->getNode());
342 TRACETOOLS_TRACEPOINT(smacc2_state_update_start, updatableElementNameCstr);
343 }
344 }
345 }
346 }
347 catch (std::exception & ex)
348 {
349 RCLCPP_ERROR(getLogger(), "Exception during Signal Detector update loop. %s.", ex.what());
350 }
351 //smaccStateMachine_->unlockStateMachine("update behaviors");
352}
StateMachineInternalAction stateMachineCurrentAction
smacc2_state_update_start

References smacc2::introspection::demangleType(), findUpdatableClientsAndComponents(), getLogger(), smacc2::ISmaccStateMachine::getNode(), getNode(), smacc2::ISmaccStateMachine::m_mutex_, smacc2_state_update_start, smaccStateMachine_, smacc2::STATE_CONFIGURING, smacc2::STATE_ENTERING, smacc2::STATE_EXITING, smacc2::ISmaccStateMachine::stateMachineCurrentAction, smacc2::TRANSITIONING, updatableClients_, and updatableStateElements_.

Referenced by pollingLoop().

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

◆ postEvent()

template<typename EventType >
void smacc2::SignalDetector::postEvent ( EventType * ev)
inline

Definition at line 61 of file smacc_signal_detector.hpp.

62 {
63 boost::intrusive_ptr<EventType> weakPtrEvent = ev;
64 this->scheduler_->queue_event(processorHandle_, weakPtrEvent);
65 }
SmaccFifoScheduler::processor_handle processorHandle_

References processorHandle_, and scheduler_.

Referenced by smacc2::ISmaccStateMachine::postEvent().

Here is the caller graph for this function:

◆ runThread()

void smacc2::SignalDetector::runThread ( )

runThread()

Definition at line 237 of file signal_detector.cpp.

238{
239 signalDetectorThread_ = boost::thread(boost::bind(&SignalDetector::pollingLoop, this));
240}

References pollingLoop(), and signalDetectorThread_.

Here is the call graph for this function:

◆ setProcessorHandle()

void smacc2::SignalDetector::setProcessorHandle ( SmaccFifoScheduler::processor_handle processorHandle)

setProcessorHandle()

Definition at line 227 of file signal_detector.cpp.

228{
229 processorHandle_ = processorHandle;
230}

References processorHandle_.

Referenced by smacc2::run(), and smacc2::run_async().

Here is the caller graph for this function:

◆ stop()

void smacc2::SignalDetector::stop ( )

stop()

Definition at line 254 of file signal_detector.cpp.

254{ end_ = true; }

References end_.

Referenced by initialize(), and smacc2::onSignalShutdown().

Here is the caller graph for this function:

◆ terminateScheduler()

void smacc2::SignalDetector::terminateScheduler ( )

terminateScheduler()

Definition at line 261 of file signal_detector.cpp.

262{
263 if (scheduler_)
264 {
265 RCLCPP_INFO(getLogger(), "[SignalDetector] Terminating scheduler...");
266 scheduler_->terminate();
267 }
268}

References getLogger(), and scheduler_.

Referenced by initialize(), and smacc2::run().

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

Member Data Documentation

◆ end_

std::atomic<bool> smacc2::SignalDetector::end_
private

Definition at line 95 of file smacc_signal_detector.hpp.

Referenced by pollingLoop(), SignalDetector(), and stop().

◆ executionModel_

ExecutionModel smacc2::SignalDetector::executionModel_
private

Definition at line 112 of file smacc_signal_detector.hpp.

Referenced by pollingLoop(), and SignalDetector().

◆ initialized_

std::atomic<bool> smacc2::SignalDetector::initialized_
private

Definition at line 97 of file smacc_signal_detector.hpp.

Referenced by initialize(), pollingLoop(), and SignalDetector().

◆ lastState_

std::atomic<int64_t> smacc2::SignalDetector::lastState_
private

Definition at line 86 of file smacc_signal_detector.hpp.

Referenced by initialize().

◆ loop_rate_hz

double smacc2::SignalDetector::loop_rate_hz
private

Definition at line 93 of file smacc_signal_detector.hpp.

Referenced by initialize(), pollingLoop(), and SignalDetector().

◆ processorHandle_

SmaccFifoScheduler::processor_handle smacc2::SignalDetector::processorHandle_
private

Definition at line 108 of file smacc_signal_detector.hpp.

Referenced by postEvent(), and setProcessorHandle().

◆ rosInitialized_

std::atomic<bool> smacc2::SignalDetector::rosInitialized_
private

Definition at line 100 of file smacc_signal_detector.hpp.

Referenced by notifyRosInitialized(), pollingLoop(), and SignalDetector().

◆ scheduler_

SmaccFifoScheduler* smacc2::SignalDetector::scheduler_
private

Definition at line 106 of file smacc_signal_detector.hpp.

Referenced by postEvent(), SignalDetector(), and terminateScheduler().

◆ signalDetectorThread_

boost::thread smacc2::SignalDetector::signalDetectorThread_
private

Definition at line 110 of file smacc_signal_detector.hpp.

Referenced by join(), and runThread().

◆ smaccStateMachine_

ISmaccStateMachine* smacc2::SignalDetector::smaccStateMachine_
private

◆ statusPub_

rclcpp::Publisher<smacc2_msgs::msg::SmaccStatus>::SharedPtr smacc2::SignalDetector::statusPub_
private

Definition at line 102 of file smacc_signal_detector.hpp.

◆ updatableClients_

std::vector<ISmaccUpdatable *> smacc2::SignalDetector::updatableClients_
private

Definition at line 83 of file smacc_signal_detector.hpp.

Referenced by findUpdatableClientsAndComponents(), and pollOnce().

◆ updatableStateElements_

std::vector<std::vector<ISmaccUpdatable *> > smacc2::SignalDetector::updatableStateElements_
private

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