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

50{
51 scheduler_ = scheduler;
52 loop_rate_hz = 20.0;
53 end_ = false;
54 initialized_ = false;
55 executionModel_ = executionModel;
56}
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 80 of file signal_detector.cpp.

81{
82 this->updatableClients_.clear();
83 for (auto pair : this->smaccStateMachine_->getOrthogonals())
84 {
85 auto & orthogonal = pair.second;
86 auto & clients = orthogonal->getClients();
87
88 for (auto & client : clients)
89 {
90 // updatable client components
91 auto updatableClient = dynamic_cast<ISmaccUpdatable *>(client.get());
92
93 if (updatableClient != nullptr)
94 {
95 RCLCPP_DEBUG_STREAM(
96 getLogger(), "Adding updatable client: " << demangleType(typeid(updatableClient)));
97 this->updatableClients_.push_back(updatableClient);
98 }
99
100 // updatable client components
101 std::vector<std::shared_ptr<ISmaccComponent>> components;
102 client->getComponents(components);
103 for (auto & componententry : components)
104 {
105 auto updatableComponent = dynamic_cast<ISmaccUpdatable *>(componententry.get());
106 if (updatableComponent != nullptr)
107 {
108 RCLCPP_DEBUG_STREAM(
109 getLogger(),
110 "Adding updatable component: " << demangleType(typeid(*updatableComponent)));
111 this->updatableClients_.push_back(updatableComponent);
112 }
113 }
114 }
115 }
116}
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 123 of file signal_detector.cpp.

124{
125 updatableStateElements_.push_back(std::vector<ISmaccUpdatable *>());
126
127 auto & updatableElements = updatableStateElements_.back();
128
129 for (auto pair : this->smaccStateMachine_->getOrthogonals())
130 {
131 auto & orthogonal = pair.second;
132 auto & behaviors = orthogonal->getClientBehaviors().back();
133
134 for (auto & currentBehavior : behaviors)
135 {
136 ISmaccUpdatable * updatableClientBehavior =
137 dynamic_cast<ISmaccUpdatable *>(currentBehavior.get());
138
139 if (updatableClientBehavior != nullptr)
140 {
141 RCLCPP_DEBUG_STREAM(
142 getLogger(),
143 "Adding updatable behavior: " << demangleType(typeid(updatableClientBehavior)));
144 updatableElements.push_back(updatableClientBehavior);
145 }
146 }
147 }
148
149 auto updatableState = dynamic_cast<ISmaccUpdatable *>(currentState);
150 if (updatableState != nullptr)
151 {
152 updatableElements.push_back(updatableState);
153 }
154
155 auto statereactors = currentState->getStateReactors();
156 for (auto & sr : statereactors)
157 {
158 ISmaccUpdatable * updatableStateReactor = dynamic_cast<ISmaccUpdatable *>(sr.get());
159 if (updatableStateReactor != nullptr)
160 {
161 RCLCPP_DEBUG_STREAM(
162 getLogger(),
163 "Adding updatable stateReactorr: " << demangleType(typeid(updatableStateReactor)));
164 updatableElements.push_back(updatableStateReactor);
165 }
166 }
167
168 auto eventgenerators = currentState->getEventGenerators();
169 for (auto & eg : eventgenerators)
170 {
171 ISmaccUpdatable * updatableEventGenerator = dynamic_cast<ISmaccUpdatable *>(eg.get());
172 if (updatableEventGenerator != nullptr)
173 {
174 RCLCPP_DEBUG_STREAM(
175 getLogger(),
176 "Adding updatable eventGenerator: " << demangleType(typeid(updatableEventGenerator)));
177 updatableElements.push_back(updatableEventGenerator);
178 }
179 }
180}
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 58 of file signal_detector.cpp.

58{ 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 65 of file signal_detector.cpp.

66{
67 smaccStateMachine_ = stateMachine;
68 lastState_ = std::numeric_limits<int64_t>::quiet_NaN();
70 this->getNode()->declare_parameter("signal_detector_loop_freq", this->loop_rate_hz);
71
72 initialized_ = true;
73}
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 217 of file signal_detector.cpp.

217{ signalDetectorThread_.join(); }

References signalDetectorThread_.

◆ notifyStateConfigured()

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

Definition at line 182 of file signal_detector.cpp.

183{
184 this->findUpdatableStateElements(currentState);
185}
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 187 of file signal_detector.cpp.

188{
189 this->updatableStateElements_.pop_back();
190}

References updatableStateElements_.

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

Here is the caller graph for this function:

◆ pollingLoop()

void smacc2::SignalDetector::pollingLoop ( )

pollingLoop()

Definition at line 332 of file signal_detector.cpp.

333{
334 // rclcpp::Node::SharedPtr nh("~"); // use node name as root of the parameter server
335 rclcpp::Node::SharedPtr _;
336 rclcpp::Rate r0(20);
337
338 while (!initialized_)
339 {
340 r0.sleep();
341 }
342
343 auto nh = getNode();
344
345 if (!nh->get_parameter("signal_detector_loop_freq", this->loop_rate_hz))
346 {
347 RCLCPP_WARN(
348 getLogger(),
349 "Signal Detector frequency (ros param signal_detector_loop_freq) was not set, using default "
350 "frequency: "
351 "%lf",
352 this->loop_rate_hz);
353 }
354 else
355 {
356 RCLCPP_WARN(
357 getLogger(), "Signal Detector frequency (ros param signal_detector_loop_freq): %lf",
358 this->loop_rate_hz);
359 }
360
361 nh->set_parameter(rclcpp::Parameter("signal_detector_loop_freq", this->loop_rate_hz));
362
363 RCLCPP_INFO_STREAM(getLogger(), "[SignalDetector] Loop rate hz:" << loop_rate_hz);
364
366 {
367 RCLCPP_INFO_STREAM(getLogger(), "[SignalDetector] Running in single-threaded mode.");
368
369 rclcpp::Rate r(loop_rate_hz);
370 while (rclcpp::ok() && !end_)
371 {
372 RCLCPP_INFO_STREAM_THROTTLE(
373 getLogger(), *getNode()->get_clock(), 10000, "[SignalDetector] Heartbeat");
374 pollOnce();
375 rclcpp::spin_some(nh);
376 r.sleep();
377 }
378 }
379 else
380 {
381 RCLCPP_INFO_STREAM(getLogger(), "[SignalDetector] Running in multi-threaded mode.");
382
383 rclcpp::executors::MultiThreadedExecutor executor;
384 executor.add_node(nh);
385 executor.spin();
386 }
387}

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

246{
247 // precondition: smaccStateMachine_ != nullptr
248
249 //TRACEPOINT( spinOnce);
250 TRACEPOINT(spinOnce);
251
252 std::lock_guard<std::recursive_mutex> lock(smaccStateMachine_->m_mutex_);
253 try
254 {
255 //smaccStateMachine_->lockStateMachine("update behaviors");
256
258 RCLCPP_DEBUG_STREAM(getLogger(), "Updatable clients: " << this->updatableClients_.size());
259
260 if (this->updatableClients_.size())
261 {
262 auto node = getNode();
263 for (auto * updatableClient : this->updatableClients_)
264 {
265 auto updatableElementName = demangleType(typeid(*updatableClient)).c_str();
266 try
267 {
268 RCLCPP_DEBUG_STREAM(
269 node->get_logger(),
270 "[PollOnce] update client call: " << demangleType(typeid(*updatableClient)));
271
272 TRACEPOINT(smacc2_state_update_start, updatableElementName);
273 updatableClient->executeUpdate(smaccStateMachine_->getNode());
274 TRACEPOINT(smacc2_state_update_start, updatableElementName);
275 }
276 catch (const std::exception & e)
277 {
278 RCLCPP_ERROR_STREAM(
279 node->get_logger(),
280 "Error in updatable elemnent " << updatableElementName << ": " << e.what() << '\n');
281 }
282 }
283 }
284
285 // STATE UPDATABLE ELEMENTS
286 if (
289 this->smaccStateMachine_->stateMachineCurrentAction !=
291 this->smaccStateMachine_->stateMachineCurrentAction !=
293 this->smaccStateMachine_->stateMachineCurrentAction !=
295 {
296 RCLCPP_DEBUG_STREAM(
297 getLogger(), "Updatable states: " << this->updatableStateElements_.size());
298
299 for (auto stateElement : this->updatableStateElements_)
300 {
301 for (auto * udpatableStateElement : stateElement)
302 {
303 std::string updatableElementName = demangleType(typeid(*udpatableStateElement));
304 auto updatableElementNameCstr = updatableElementName.c_str();
305
306 RCLCPP_DEBUG_STREAM(
307 getLogger(), "pollOnce update client behavior call: "
308 << demangleType(typeid(*udpatableStateElement)));
309 TRACEPOINT(smacc2_state_update_start, updatableElementNameCstr);
310
311 udpatableStateElement->executeUpdate(smaccStateMachine_->getNode());
312 TRACEPOINT(smacc2_state_update_start, updatableElementNameCstr);
313 }
314 }
315 }
316 }
317 catch (std::exception & ex)
318 {
319 RCLCPP_ERROR(getLogger(), "Exception during Signal Detector update loop. %s.", ex.what());
320 }
321
322 auto nh = this->getNode();
323 rclcpp::spin_some(nh);
324 //smaccStateMachine_->unlockStateMachine("update behaviors");
325}
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 207 of file signal_detector.cpp.

208{
209 signalDetectorThread_ = boost::thread(boost::bind(&SignalDetector::pollingLoop, this));
210}

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

198{
199 processorHandle_ = processorHandle;
200}

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

224{ 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 231 of file signal_detector.cpp.

232{
233 if (scheduler_)
234 {
235 RCLCPP_INFO(getLogger(), "[SignalDetector] Terminating scheduler...");
236 scheduler_->terminate();
237 }
238}

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: