SMACC2
Loading...
Searching...
No Matches
signal_detector.cpp
Go to the documentation of this file.
1// Copyright 2025 Robosoft 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 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}
98
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}
141
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}
205
207{
208 this->findUpdatableStateElements(currentState);
209}
210
212{
213 this->updatableStateElements_.pop_back();
214}
215
217{
218 RCLCPP_INFO(getLogger(), "[SignalDetector] ROS initialization complete, enabling polling loop");
219 rosInitialized_ = true;
220}
221
227void SignalDetector::setProcessorHandle(SmaccFifoScheduler::processor_handle processorHandle)
228{
229 processorHandle_ = processorHandle;
230}
231
238{
239 signalDetectorThread_ = boost::thread(boost::bind(&SignalDetector::pollingLoop, this));
240}
241
248
254void SignalDetector::stop() { end_ = true; }
255
262{
263 if (scheduler_)
264 {
265 RCLCPP_INFO(getLogger(), "[SignalDetector] Terminating scheduler...");
266 scheduler_->terminate();
267 }
268}
269
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}
353
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}
425
426void onSignalShutdown(int /*sig*/)
427{
428 // IMPORTANT: Signal handlers can only call async-signal-safe functions
429 // We must NOT call complex C++ methods here (like terminateScheduler)
430 // as they may use mutexes/condition variables which are not signal-safe
431
432 // Stop the signal detector loop (atomic operation - signal-safe)
433 SmExecution & smExecution = SmExecution::getInstance();
434 if (smExecution.signalDetector)
435 {
436 smExecution.signalDetector->stop();
437 }
438
439 // Trigger ROS2 shutdown (this handles its own signal safety)
440 rclcpp::shutdown();
441
442 // Note: Scheduler termination will happen from main thread after polling loop exits
443}
444
445void onSigQuit(int)
446{
447 RCLCPP_INFO(rclcpp::get_logger("SMACC"), "SignalDetector: SIGQUIT received.");
448 exit(0);
449}
450
451} // 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