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 rosInitialized_ = false;
71 executionModel_ = executionModel;
72}
73
74rclcpp::Node::SharedPtr SignalDetector::getNode() { return this->smaccStateMachine_->getNode(); }
75
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 initialized_ = true;
89}
90
97{
98 this->updatableClients_.clear();
99 for (auto pair : this->smaccStateMachine_->getOrthogonals())
100 {
101 auto & orthogonal = pair.second;
102 auto & clients = orthogonal->getClients();
103
104 for (auto & client : clients)
105 {
106 // updatable client components
107 auto updatableClient = dynamic_cast<ISmaccUpdatable *>(client.get());
108
109 if (updatableClient != nullptr)
110 {
111 RCLCPP_DEBUG_STREAM(
112 getLogger(), "Adding updatable client: " << demangleType(typeid(updatableClient)));
113 this->updatableClients_.push_back(updatableClient);
114 }
115
116 // updatable client components
117 std::vector<std::shared_ptr<ISmaccComponent>> components;
118 client->getComponents(components);
119 for (auto & componententry : components)
120 {
121 auto updatableComponent = dynamic_cast<ISmaccUpdatable *>(componententry.get());
122 if (updatableComponent != nullptr)
123 {
124 RCLCPP_DEBUG_STREAM(
125 getLogger(),
126 "Adding updatable component: " << demangleType(typeid(*updatableComponent)));
127 this->updatableClients_.push_back(updatableComponent);
128 }
129 }
130 }
131 }
132}
133
140{
141 updatableStateElements_.push_back(std::vector<ISmaccUpdatable *>());
142
143 auto & updatableElements = updatableStateElements_.back();
144
145 for (auto pair : this->smaccStateMachine_->getOrthogonals())
146 {
147 auto & orthogonal = pair.second;
148 auto & behaviors = orthogonal->getClientBehaviors().back();
149
150 for (auto & currentBehavior : behaviors)
151 {
152 ISmaccUpdatable * updatableClientBehavior =
153 dynamic_cast<ISmaccUpdatable *>(currentBehavior.get());
154
155 if (updatableClientBehavior != nullptr)
156 {
157 RCLCPP_DEBUG_STREAM(
158 getLogger(),
159 "Adding updatable behavior: " << demangleType(typeid(updatableClientBehavior)));
160 updatableElements.push_back(updatableClientBehavior);
161 }
162 }
163 }
164
165 auto updatableState = dynamic_cast<ISmaccUpdatable *>(currentState);
166 if (updatableState != nullptr)
167 {
168 updatableElements.push_back(updatableState);
169 }
170
171 auto statereactors = currentState->getStateReactors();
172 for (auto & sr : statereactors)
173 {
174 ISmaccUpdatable * updatableStateReactor = dynamic_cast<ISmaccUpdatable *>(sr.get());
175 if (updatableStateReactor != nullptr)
176 {
177 RCLCPP_DEBUG_STREAM(
178 getLogger(),
179 "Adding updatable stateReactorr: " << demangleType(typeid(updatableStateReactor)));
180 updatableElements.push_back(updatableStateReactor);
181 }
182 }
183
184 auto eventgenerators = currentState->getEventGenerators();
185 for (auto & eg : eventgenerators)
186 {
187 ISmaccUpdatable * updatableEventGenerator = dynamic_cast<ISmaccUpdatable *>(eg.get());
188 if (updatableEventGenerator != nullptr)
189 {
190 RCLCPP_DEBUG_STREAM(
191 getLogger(),
192 "Adding updatable eventGenerator: " << demangleType(typeid(updatableEventGenerator)));
193 updatableElements.push_back(updatableEventGenerator);
194 }
195 }
196}
197
199{
200 this->findUpdatableStateElements(currentState);
201}
202
204{
205 this->updatableStateElements_.pop_back();
206}
207
209{
210 RCLCPP_INFO(getLogger(), "[SignalDetector] ROS initialization complete, enabling polling loop");
211 rosInitialized_ = true;
212}
213
219void SignalDetector::setProcessorHandle(SmaccFifoScheduler::processor_handle processorHandle)
220{
221 processorHandle_ = processorHandle;
222}
223
230{
231 signalDetectorThread_ = boost::thread(boost::bind(&SignalDetector::pollingLoop, this));
232}
233
240
246void SignalDetector::stop() { end_ = true; }
247
254{
255 if (scheduler_)
256 {
257 RCLCPP_INFO(getLogger(), "[SignalDetector] Terminating scheduler...");
258 scheduler_->terminate();
259 }
260}
261
268{
269 // precondition: smaccStateMachine_ != nullptr
270
271 //TRACETOOLS_TRACEPOINT( spinOnce);
272 TRACETOOLS_TRACEPOINT(spinOnce);
273
274 std::lock_guard<std::recursive_mutex> lock(smaccStateMachine_->m_mutex_);
275 try
276 {
277 //smaccStateMachine_->lockStateMachine("update behaviors");
278
280 RCLCPP_DEBUG_STREAM(getLogger(), "Updatable clients: " << this->updatableClients_.size());
281
282 if (this->updatableClients_.size())
283 {
284 auto node = getNode();
285 for (auto * updatableClient : this->updatableClients_)
286 {
287 auto updatableElementName = demangleType(typeid(*updatableClient)).c_str();
288 try
289 {
290 RCLCPP_DEBUG_STREAM(
291 node->get_logger(),
292 "[PollOnce] update client call: " << demangleType(typeid(*updatableClient)));
293
294 TRACETOOLS_TRACEPOINT(smacc2_state_update_start, updatableElementName);
295 updatableClient->executeUpdate(smaccStateMachine_->getNode());
296 TRACETOOLS_TRACEPOINT(smacc2_state_update_start, updatableElementName);
297 }
298 catch (const std::exception & e)
299 {
300 RCLCPP_ERROR_STREAM(
301 node->get_logger(),
302 "Error in updatable elemnent " << updatableElementName << ": " << e.what() << '\n');
303 }
304 }
305 }
306
307 // STATE UPDATABLE ELEMENTS
308 if (
311 this->smaccStateMachine_->stateMachineCurrentAction !=
313 this->smaccStateMachine_->stateMachineCurrentAction !=
315 this->smaccStateMachine_->stateMachineCurrentAction !=
317 {
318 RCLCPP_DEBUG_STREAM(
319 getLogger(), "Updatable states: " << this->updatableStateElements_.size());
320
321 for (auto stateElement : this->updatableStateElements_)
322 {
323 for (auto * udpatableStateElement : stateElement)
324 {
325 std::string updatableElementName = demangleType(typeid(*udpatableStateElement));
326 auto updatableElementNameCstr = updatableElementName.c_str();
327
328 RCLCPP_DEBUG_STREAM(
329 getLogger(), "pollOnce update client behavior call: "
330 << demangleType(typeid(*udpatableStateElement)));
331 TRACETOOLS_TRACEPOINT(smacc2_state_update_start, updatableElementNameCstr);
332
333 udpatableStateElement->executeUpdate(smaccStateMachine_->getNode());
334 TRACETOOLS_TRACEPOINT(smacc2_state_update_start, updatableElementNameCstr);
335 }
336 }
337 }
338 }
339 catch (std::exception & ex)
340 {
341 RCLCPP_ERROR(getLogger(), "Exception during Signal Detector update loop. %s.", ex.what());
342 }
343
344 auto nh = this->getNode();
345 rclcpp::spin_some(nh);
346 //smaccStateMachine_->unlockStateMachine("update behaviors");
347}
348
355{
356 // rclcpp::Node::SharedPtr nh("~"); // use node name as root of the parameter server
357 rclcpp::Node::SharedPtr _;
358 rclcpp::Rate r0(20);
359
360 // Wait for both SignalDetector::initialize() (called from ISmaccStateMachine constructor)
361 // and ROS initialization to complete (initializeROS called from initiate_impl).
362 // This ensures orthogonals, clients, and ROS objects are fully initialized
363 // before we start polling and accessing them.
364 while ((!initialized_ || !rosInitialized_) && rclcpp::ok() && !end_)
365 {
366 r0.sleep();
367 }
368
369 if (!rclcpp::ok() || end_)
370 {
371 RCLCPP_INFO(getLogger(), "[SignalDetector] Shutdown requested before initialization completed");
372 return;
373 }
374
375 auto nh = getNode();
376
377 if (!nh->get_parameter("signal_detector_loop_freq", this->loop_rate_hz))
378 {
379 RCLCPP_WARN(
380 getLogger(),
381 "Signal Detector frequency (ros param signal_detector_loop_freq) was not set, using default "
382 "frequency: "
383 "%lf",
384 this->loop_rate_hz);
385 }
386 else
387 {
388 RCLCPP_WARN(
389 getLogger(), "Signal Detector frequency (ros param signal_detector_loop_freq): %lf",
390 this->loop_rate_hz);
391 }
392
393 nh->set_parameter(rclcpp::Parameter("signal_detector_loop_freq", this->loop_rate_hz));
394
395 RCLCPP_INFO_STREAM(getLogger(), "[SignalDetector] Loop rate hz:" << loop_rate_hz);
396
398 {
399 RCLCPP_INFO_STREAM(getLogger(), "[SignalDetector] Running in single-threaded mode.");
400
401 rclcpp::Rate r(loop_rate_hz);
402 while (rclcpp::ok() && !end_)
403 {
404 RCLCPP_INFO_STREAM_THROTTLE(
405 getLogger(), *getNode()->get_clock(), 10000, "[SignalDetector] Heartbeat");
406 pollOnce();
407 rclcpp::spin_some(nh);
408 r.sleep();
409 }
410 }
411 else
412 {
413 RCLCPP_INFO_STREAM(getLogger(), "[SignalDetector] Running in multi-threaded mode.");
414
415 rclcpp::executors::MultiThreadedExecutor executor;
416 executor.add_node(nh);
417 executor.spin();
418 }
419}
420
421void onSignalShutdown(int /*sig*/)
422{
423 // IMPORTANT: Signal handlers can only call async-signal-safe functions
424 // We must NOT call complex C++ methods here (like terminateScheduler)
425 // as they may use mutexes/condition variables which are not signal-safe
426
427 // Stop the signal detector loop (atomic operation - signal-safe)
428 SmExecution & smExecution = SmExecution::getInstance();
429 if (smExecution.signalDetector)
430 {
431 smExecution.signalDetector->stop();
432 }
433
434 // Trigger ROS2 shutdown (this handles its own signal safety)
435 rclcpp::shutdown();
436
437 // Note: Scheduler termination will happen from main thread after polling loop exits
438}
439
440void onSigQuit(int)
441{
442 RCLCPP_INFO(rclcpp::get_logger("SMACC"), "SignalDetector: SIGQUIT received.");
443 exit(0);
444}
445
446} // 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_
std::atomic< bool > rosInitialized_
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
smacc2_state_update_start