SMACC2
Loading...
Searching...
No Matches
signal_detector.cpp
Go to the documentation of this file.
1// Copyright 2021 RobosoftAI Inc.
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15/*****************************************************************************************************************
16 *
17 * Authors: Pablo Inigo Blasco, Brett Aldrich
18 *
19 ******************************************************************************************************************/
20
21#include <signal.h>
22#include <limits>
23#include <memory>
24#include <thread>
25#include <vector>
26
27#include <lttng/tracepoint.h>
31// #include <smacc2/smacc_tracing/trace_provider.hpp>
33
34//#include "tracetools/tracetools.h"
35
36namespace smacc2
37{
38using namespace std::chrono_literals;
39
46: schedulerThread(nullptr),
47 signalDetectorLoop(nullptr),
48 signalDetector(nullptr),
49 scheduler1(nullptr)
50{
51}
52
54{
55 static SmExecution instance;
56 return instance;
57}
58
65{
66 scheduler_ = scheduler;
67 loop_rate_hz = 20.0;
68 end_ = false;
69 initialized_ = false;
70 executionModel_ = executionModel;
71}
72
73rclcpp::Node::SharedPtr SignalDetector::getNode() { return this->smaccStateMachine_->getNode(); }
74
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}
89
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}
132
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}
196
198{
199 this->findUpdatableStateElements(currentState);
200}
201
203{
204 this->updatableStateElements_.pop_back();
205}
206
212void SignalDetector::setProcessorHandle(SmaccFifoScheduler::processor_handle processorHandle)
213{
214 processorHandle_ = processorHandle;
215}
216
223{
224 signalDetectorThread_ = boost::thread(boost::bind(&SignalDetector::pollingLoop, this));
225}
226
233
239void SignalDetector::stop() { end_ = true; }
240
247{
248 if (scheduler_)
249 {
250 RCLCPP_INFO(getLogger(), "[SignalDetector] Terminating scheduler...");
251 scheduler_->terminate();
252 }
253}
254
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}
341
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}
403
404void onSignalShutdown(int sig)
405{
406 // IMPORTANT: Signal handlers can only call async-signal-safe functions
407 // We must NOT call complex C++ methods here (like terminateScheduler)
408 // as they may use mutexes/condition variables which are not signal-safe
409
410 // Stop the signal detector loop (atomic operation - signal-safe)
411 SmExecution & smExecution = SmExecution::getInstance();
412 if (smExecution.signalDetector)
413 {
414 smExecution.signalDetector->stop();
415 }
416
417 // Trigger ROS2 shutdown (this handles its own signal safety)
418 rclcpp::shutdown();
419
420 // Note: Scheduler termination will happen from main thread after polling loop exits
421}
422
423void onSigQuit(int)
424{
425 RCLCPP_INFO(rclcpp::get_logger("SMACC"), "SignalDetector: SIGQUIT received.");
426 exit(0);
427}
428
429} // namespace smacc2
StateMachineInternalAction stateMachineCurrentAction
rclcpp::Node::SharedPtr getNode()
const std::map< std::string, std::shared_ptr< smacc2::ISmaccOrthogonal > > & getOrthogonals() const
std::vector< std::shared_ptr< StateReactor > > & getStateReactors()
std::vector< std::shared_ptr< SmaccEventGenerator > > & getEventGenerators()
SmaccFifoScheduler * scheduler_
void notifyStateExited(ISmaccState *currentState)
void initialize(ISmaccStateMachine *stateMachine)
std::vector< std::vector< ISmaccUpdatable * > > updatableStateElements_
rclcpp::Node::SharedPtr getNode()
SmaccFifoScheduler::processor_handle processorHandle_
SignalDetector(SmaccFifoScheduler *scheduler, ExecutionModel executionModel=ExecutionModel::SINGLE_THREAD_SPINNER)
std::atomic< int64_t > lastState_
std::vector< ISmaccUpdatable * > updatableClients_
void setProcessorHandle(SmaccFifoScheduler::processor_handle processorHandle)
void findUpdatableStateElements(ISmaccState *currentState)
ISmaccStateMachine * smaccStateMachine_
void notifyStateConfigured(ISmaccState *currentState)
std::atomic< bool > initialized_
static SmExecution & getInstance()
std::string demangleType(const std::type_info *tinfo)
void onSigQuit(int sig)
void onSignalShutdown(int sig)
boost::statechart::fifo_scheduler< SmaccFifoWorker, SmaccAllocator > SmaccFifoScheduler
void TRACEPOINT(spinOnce)
smacc2_state_update_start