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)
 

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< bool > end_
 
std::atomic< bool > initialized_
 
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 executionModel_ = executionModel;
71}
SmaccFifoScheduler * scheduler_
std::atomic< bool > initialized_

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

Member Function Documentation

◆ findUpdatableClientsAndComponents()

void smacc2::SignalDetector::findUpdatableClientsAndComponents ( )
private

findUpdatableClientsAndComponents()

Definition at line 95 of file signal_detector.cpp.

96{
97 this->updatableClients_.clear();
98 for (auto pair : this->smaccStateMachine_->getOrthogonals())
99 {
100 auto & orthogonal = pair.second;
101 auto & clients = orthogonal->getClients();
102
103 for (auto & client : clients)
104 {
105 // updatable client components
106 auto updatableClient = dynamic_cast<ISmaccUpdatable *>(client.get());
107
108 if (updatableClient != nullptr)
109 {
110 RCLCPP_DEBUG_STREAM(
111 getLogger(), "Adding updatable client: " << demangleType(typeid(updatableClient)));
112 this->updatableClients_.push_back(updatableClient);
113 }
114
115 // updatable client components
116 std::vector<std::shared_ptr<ISmaccComponent>> components;
117 client->getComponents(components);
118 for (auto & componententry : components)
119 {
120 auto updatableComponent = dynamic_cast<ISmaccUpdatable *>(componententry.get());
121 if (updatableComponent != nullptr)
122 {
123 RCLCPP_DEBUG_STREAM(
124 getLogger(),
125 "Adding updatable component: " << demangleType(typeid(*updatableComponent)));
126 this->updatableClients_.push_back(updatableComponent);
127 }
128 }
129 }
130 }
131}
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 138 of file signal_detector.cpp.

139{
140 updatableStateElements_.push_back(std::vector<ISmaccUpdatable *>());
141
142 auto & updatableElements = updatableStateElements_.back();
143
144 for (auto pair : this->smaccStateMachine_->getOrthogonals())
145 {
146 auto & orthogonal = pair.second;
147 auto & behaviors = orthogonal->getClientBehaviors().back();
148
149 for (auto & currentBehavior : behaviors)
150 {
151 ISmaccUpdatable * updatableClientBehavior =
152 dynamic_cast<ISmaccUpdatable *>(currentBehavior.get());
153
154 if (updatableClientBehavior != nullptr)
155 {
156 RCLCPP_DEBUG_STREAM(
157 getLogger(),
158 "Adding updatable behavior: " << demangleType(typeid(updatableClientBehavior)));
159 updatableElements.push_back(updatableClientBehavior);
160 }
161 }
162 }
163
164 auto updatableState = dynamic_cast<ISmaccUpdatable *>(currentState);
165 if (updatableState != nullptr)
166 {
167 updatableElements.push_back(updatableState);
168 }
169
170 auto statereactors = currentState->getStateReactors();
171 for (auto & sr : statereactors)
172 {
173 ISmaccUpdatable * updatableStateReactor = dynamic_cast<ISmaccUpdatable *>(sr.get());
174 if (updatableStateReactor != nullptr)
175 {
176 RCLCPP_DEBUG_STREAM(
177 getLogger(),
178 "Adding updatable stateReactorr: " << demangleType(typeid(updatableStateReactor)));
179 updatableElements.push_back(updatableStateReactor);
180 }
181 }
182
183 auto eventgenerators = currentState->getEventGenerators();
184 for (auto & eg : eventgenerators)
185 {
186 ISmaccUpdatable * updatableEventGenerator = dynamic_cast<ISmaccUpdatable *>(eg.get());
187 if (updatableEventGenerator != nullptr)
188 {
189 RCLCPP_DEBUG_STREAM(
190 getLogger(),
191 "Adding updatable eventGenerator: " << demangleType(typeid(updatableEventGenerator)));
192 updatableElements.push_back(updatableEventGenerator);
193 }
194 }
195}
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(), 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 73 of file signal_detector.cpp.

73{ 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 80 of file signal_detector.cpp.

81{
82 smaccStateMachine_ = stateMachine;
83 lastState_ = std::numeric_limits<int64_t>::quiet_NaN();
85 this->getNode()->declare_parameter("signal_detector_loop_freq", this->loop_rate_hz);
86
87 initialized_ = true;
88}
std::atomic< int64_t > lastState_

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

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 232 of file signal_detector.cpp.

232{ signalDetectorThread_.join(); }

References signalDetectorThread_.

◆ notifyStateConfigured()

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

Definition at line 197 of file signal_detector.cpp.

198{
199 this->findUpdatableStateElements(currentState);
200}
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 202 of file signal_detector.cpp.

203{
204 this->updatableStateElements_.pop_back();
205}

References updatableStateElements_.

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

Here is the caller graph for this function:

◆ pollingLoop()

void smacc2::SignalDetector::pollingLoop ( )

pollingLoop()

Definition at line 347 of file signal_detector.cpp.

348{
349 // rclcpp::Node::SharedPtr nh("~"); // use node name as root of the parameter server
350 rclcpp::Node::SharedPtr _;
351 rclcpp::Rate r0(20);
352
353 while (!initialized_)
354 {
355 r0.sleep();
356 }
357
358 auto nh = getNode();
359
360 if (!nh->get_parameter("signal_detector_loop_freq", this->loop_rate_hz))
361 {
362 RCLCPP_WARN(
363 getLogger(),
364 "Signal Detector frequency (ros param signal_detector_loop_freq) was not set, using default "
365 "frequency: "
366 "%lf",
367 this->loop_rate_hz);
368 }
369 else
370 {
371 RCLCPP_WARN(
372 getLogger(), "Signal Detector frequency (ros param signal_detector_loop_freq): %lf",
373 this->loop_rate_hz);
374 }
375
376 nh->set_parameter(rclcpp::Parameter("signal_detector_loop_freq", this->loop_rate_hz));
377
378 RCLCPP_INFO_STREAM(getLogger(), "[SignalDetector] Loop rate hz:" << loop_rate_hz);
379
381 {
382 RCLCPP_INFO_STREAM(getLogger(), "[SignalDetector] Running in single-threaded mode.");
383
384 rclcpp::Rate r(loop_rate_hz);
385 while (rclcpp::ok() && !end_)
386 {
387 RCLCPP_INFO_STREAM_THROTTLE(
388 getLogger(), *getNode()->get_clock(), 10000, "[SignalDetector] Heartbeat");
389 pollOnce();
390 rclcpp::spin_some(nh);
391 r.sleep();
392 }
393 }
394 else
395 {
396 RCLCPP_INFO_STREAM(getLogger(), "[SignalDetector] Running in multi-threaded mode.");
397
398 rclcpp::executors::MultiThreadedExecutor executor;
399 executor.add_node(nh);
400 executor.spin();
401 }
402}

References end_, executionModel_, getLogger(), getNode(), initialized_, loop_rate_hz, pollOnce(), 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 260 of file signal_detector.cpp.

261{
262 // precondition: smaccStateMachine_ != nullptr
263
264 //TRACEPOINT( spinOnce);
265 TRACEPOINT(spinOnce);
266
267 std::lock_guard<std::recursive_mutex> lock(smaccStateMachine_->m_mutex_);
268 try
269 {
270 //smaccStateMachine_->lockStateMachine("update behaviors");
271
273 RCLCPP_DEBUG_STREAM(getLogger(), "Updatable clients: " << this->updatableClients_.size());
274
275 if (this->updatableClients_.size())
276 {
277 auto node = getNode();
278 for (auto * updatableClient : this->updatableClients_)
279 {
280 auto updatableElementName = demangleType(typeid(*updatableClient)).c_str();
281 try
282 {
283 RCLCPP_DEBUG_STREAM(
284 node->get_logger(),
285 "[PollOnce] update client call: " << demangleType(typeid(*updatableClient)));
286
287 TRACEPOINT(smacc2_state_update_start, updatableElementName);
288 updatableClient->executeUpdate(smaccStateMachine_->getNode());
289 TRACEPOINT(smacc2_state_update_start, updatableElementName);
290 }
291 catch (const std::exception & e)
292 {
293 RCLCPP_ERROR_STREAM(
294 node->get_logger(),
295 "Error in updatable elemnent " << updatableElementName << ": " << e.what() << '\n');
296 }
297 }
298 }
299
300 // STATE UPDATABLE ELEMENTS
301 if (
304 this->smaccStateMachine_->stateMachineCurrentAction !=
306 this->smaccStateMachine_->stateMachineCurrentAction !=
308 this->smaccStateMachine_->stateMachineCurrentAction !=
310 {
311 RCLCPP_DEBUG_STREAM(
312 getLogger(), "Updatable states: " << this->updatableStateElements_.size());
313
314 for (auto stateElement : this->updatableStateElements_)
315 {
316 for (auto * udpatableStateElement : stateElement)
317 {
318 std::string updatableElementName = demangleType(typeid(*udpatableStateElement));
319 auto updatableElementNameCstr = updatableElementName.c_str();
320
321 RCLCPP_DEBUG_STREAM(
322 getLogger(), "pollOnce update client behavior call: "
323 << demangleType(typeid(*udpatableStateElement)));
324 TRACEPOINT(smacc2_state_update_start, updatableElementNameCstr);
325
326 udpatableStateElement->executeUpdate(smaccStateMachine_->getNode());
327 TRACEPOINT(smacc2_state_update_start, updatableElementNameCstr);
328 }
329 }
330 }
331 }
332 catch (std::exception & ex)
333 {
334 RCLCPP_ERROR(getLogger(), "Exception during Signal Detector update loop. %s.", ex.what());
335 }
336
337 auto nh = this->getNode();
338 rclcpp::spin_some(nh);
339 //smaccStateMachine_->unlockStateMachine("update behaviors");
340}
StateMachineInternalAction stateMachineCurrentAction
void TRACEPOINT(spinOnce)
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, TRACEPOINT(), 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 222 of file signal_detector.cpp.

223{
224 signalDetectorThread_ = boost::thread(boost::bind(&SignalDetector::pollingLoop, this));
225}

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 212 of file signal_detector.cpp.

213{
214 processorHandle_ = processorHandle;
215}

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 239 of file signal_detector.cpp.

239{ end_ = true; }

References end_.

Referenced by smacc2::onSignalShutdown().

Here is the caller graph for this function:

◆ terminateScheduler()

void smacc2::SignalDetector::terminateScheduler ( )

terminateScheduler()

Definition at line 246 of file signal_detector.cpp.

247{
248 if (scheduler_)
249 {
250 RCLCPP_INFO(getLogger(), "[SignalDetector] Terminating scheduler...");
251 scheduler_->terminate();
252 }
253}

References getLogger(), and scheduler_.

Referenced by 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 91 of file smacc_signal_detector.hpp.

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

◆ executionModel_

ExecutionModel smacc2::SignalDetector::executionModel_
private

Definition at line 105 of file smacc_signal_detector.hpp.

Referenced by pollingLoop(), and SignalDetector().

◆ initialized_

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

Definition at line 93 of file smacc_signal_detector.hpp.

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

◆ lastState_

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

Definition at line 82 of file smacc_signal_detector.hpp.

Referenced by initialize().

◆ loop_rate_hz

double smacc2::SignalDetector::loop_rate_hz
private

Definition at line 89 of file smacc_signal_detector.hpp.

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

◆ processorHandle_

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

Definition at line 101 of file smacc_signal_detector.hpp.

Referenced by postEvent(), and setProcessorHandle().

◆ scheduler_

SmaccFifoScheduler* smacc2::SignalDetector::scheduler_
private

Definition at line 99 of file smacc_signal_detector.hpp.

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

◆ signalDetectorThread_

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

Definition at line 103 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 95 of file smacc_signal_detector.hpp.

◆ updatableClients_

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

Definition at line 79 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: