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;
45{
46 scheduler_ = scheduler;
47 loop_rate_hz = 20.0;
48 end_ = false;
49 initialized_ = false;
50 executionModel_ = executionModel;
51}
52
53rclcpp::Node::SharedPtr SignalDetector::getNode() { return this->smaccStateMachine_->getNode(); }
54
61{
62 smaccStateMachine_ = stateMachine;
63 lastState_ = std::numeric_limits<uint64_t>::quiet_NaN();
65 this->getNode()->declare_parameter("signal_detector_loop_freq", this->loop_rate_hz);
66
67 initialized_ = true;
68}
69
76{
77 this->updatableClients_.clear();
78 for (auto pair : this->smaccStateMachine_->getOrthogonals())
79 {
80 auto & orthogonal = pair.second;
81 auto & clients = orthogonal->getClients();
82
83 for (auto & client : clients)
84 {
85 // updatable client components
86 auto updatableClient = dynamic_cast<ISmaccUpdatable *>(client.get());
87
88 if (updatableClient != nullptr)
89 {
90 RCLCPP_DEBUG_STREAM(
91 getLogger(), "Adding updatable client: " << demangleType(typeid(updatableClient)));
92 this->updatableClients_.push_back(updatableClient);
93 }
94
95 // updatable client components
96 std::vector<std::shared_ptr<ISmaccComponent>> components;
97 client->getComponents(components);
98 for (auto & componententry : components)
99 {
100 auto updatableComponent = dynamic_cast<ISmaccUpdatable *>(componententry.get());
101 if (updatableComponent != nullptr)
102 {
103 RCLCPP_DEBUG_STREAM(
104 getLogger(),
105 "Adding updatable component: " << demangleType(typeid(*updatableComponent)));
106 this->updatableClients_.push_back(updatableComponent);
107 }
108 }
109 }
110 }
111}
112
119{
120 updatableStateElements_.push_back(std::vector<ISmaccUpdatable *>());
121
122 auto & updatableElements = updatableStateElements_.back();
123
124 for (auto pair : this->smaccStateMachine_->getOrthogonals())
125 {
126 auto & orthogonal = pair.second;
127 auto & behaviors = orthogonal->getClientBehaviors().back();
128
129 for (auto & currentBehavior : behaviors)
130 {
131 ISmaccUpdatable * updatableClientBehavior =
132 dynamic_cast<ISmaccUpdatable *>(currentBehavior.get());
133
134 if (updatableClientBehavior != nullptr)
135 {
136 RCLCPP_DEBUG_STREAM(
137 getLogger(),
138 "Adding updatable behavior: " << demangleType(typeid(updatableClientBehavior)));
139 updatableElements.push_back(updatableClientBehavior);
140 }
141 }
142 }
143
144 auto updatableState = dynamic_cast<ISmaccUpdatable *>(currentState);
145 if (updatableState != nullptr)
146 {
147 updatableElements.push_back(updatableState);
148 }
149
150 auto statereactors = currentState->getStateReactors();
151 for (auto & sr : statereactors)
152 {
153 ISmaccUpdatable * updatableStateReactor = dynamic_cast<ISmaccUpdatable *>(sr.get());
154 if (updatableStateReactor != nullptr)
155 {
156 RCLCPP_DEBUG_STREAM(
157 getLogger(),
158 "Adding updatable stateReactorr: " << demangleType(typeid(updatableStateReactor)));
159 updatableElements.push_back(updatableStateReactor);
160 }
161 }
162
163 auto eventgenerators = currentState->getEventGenerators();
164 for (auto & eg : eventgenerators)
165 {
166 ISmaccUpdatable * updatableEventGenerator = dynamic_cast<ISmaccUpdatable *>(eg.get());
167 if (updatableEventGenerator != nullptr)
168 {
169 RCLCPP_DEBUG_STREAM(
170 getLogger(),
171 "Adding updatable eventGenerator: " << demangleType(typeid(updatableEventGenerator)));
172 updatableElements.push_back(updatableEventGenerator);
173 }
174 }
175}
176
178{
179 this->findUpdatableStateElements(currentState);
180}
181
183{
184 this->updatableStateElements_.pop_back();
185}
186
192void SignalDetector::setProcessorHandle(SmaccFifoScheduler::processor_handle processorHandle)
193{
194 processorHandle_ = processorHandle;
195}
196
203{
204 signalDetectorThread_ = boost::thread(boost::bind(&SignalDetector::pollingLoop, this));
205}
206
213
219void SignalDetector::stop() { end_ = true; }
220
227{
228 // precondition: smaccStateMachine_ != nullptr
229
230 //TRACEPOINT( spinOnce);
231 TRACEPOINT(spinOnce);
232
233 std::lock_guard<std::recursive_mutex> lock(smaccStateMachine_->m_mutex_);
234 try
235 {
236 //smaccStateMachine_->lockStateMachine("update behaviors");
237
239 RCLCPP_DEBUG_STREAM(getLogger(), "updatable clients: " << this->updatableClients_.size());
240
241 if (this->updatableClients_.size())
242 {
243 auto node = getNode();
244 for (auto * updatableClient : this->updatableClients_)
245 {
246 auto updatableElementName = demangleType(typeid(*updatableClient)).c_str();
247 try
248 {
249 RCLCPP_DEBUG_STREAM(
250 node->get_logger(),
251 "[PollOnce] update client call: " << demangleType(typeid(*updatableClient)));
252
253 TRACEPOINT(smacc2_state_update_start, updatableElementName);
254 updatableClient->executeUpdate(smaccStateMachine_->getNode());
255 TRACEPOINT(smacc2_state_update_start, updatableElementName);
256 }
257 catch (const std::exception & e)
258 {
259 RCLCPP_ERROR_STREAM(
260 node->get_logger(),
261 "Error in updatable elemnent " << updatableElementName << ": " << e.what() << '\n');
262 }
263 }
264 }
265
266 // STATE UPDATABLE ELEMENTS
267 if (
270 this->smaccStateMachine_->stateMachineCurrentAction !=
272 this->smaccStateMachine_->stateMachineCurrentAction !=
274 this->smaccStateMachine_->stateMachineCurrentAction !=
276 {
277 RCLCPP_DEBUG_STREAM(
278 getLogger(), "updatable states: " << this->updatableStateElements_.size());
279
280 for (auto stateElement : this->updatableStateElements_)
281 {
282 for (auto * udpatableStateElement : stateElement)
283 {
284 std::string updatableElementName = demangleType(typeid(*udpatableStateElement));
285 auto updatableElementNameCstr = updatableElementName.c_str();
286
287 RCLCPP_DEBUG_STREAM(
288 getLogger(), "pollOnce update client behavior call: "
289 << demangleType(typeid(*udpatableStateElement)));
290 TRACEPOINT(smacc2_state_update_start, updatableElementNameCstr);
291
292 udpatableStateElement->executeUpdate(smaccStateMachine_->getNode());
293 TRACEPOINT(smacc2_state_update_start, updatableElementNameCstr);
294 }
295 }
296 }
297 }
298 catch (std::exception & ex)
299 {
300 RCLCPP_ERROR(getLogger(), "Exception during Signal Detector update loop. %s", ex.what());
301 }
302
303 auto nh = this->getNode();
304 rclcpp::spin_some(nh);
305 //smaccStateMachine_->unlockStateMachine("update behaviors");
306}
307
314{
315 // rclcpp::Node::SharedPtr nh("~"); // use node name as root of the parameter server
316 rclcpp::Node::SharedPtr _;
317 rclcpp::Rate r0(20);
318
319 while (!initialized_)
320 {
321 r0.sleep();
322 }
323
324 auto nh = getNode();
325
326 if (!nh->get_parameter("signal_detector_loop_freq", this->loop_rate_hz))
327 {
328 RCLCPP_WARN(
329 getLogger(),
330 "Signal detector frequency (ros param signal_detector_loop_freq) was not set, using default "
331 "frequency: "
332 "%lf",
333 this->loop_rate_hz);
334 }
335 else
336 {
337 RCLCPP_WARN(
338 getLogger(), "Signal detector frequency (ros param signal_detector_loop_freq): %lf",
339 this->loop_rate_hz);
340 }
341
342 nh->set_parameter(rclcpp::Parameter("signal_detector_loop_freq", this->loop_rate_hz));
343
344 RCLCPP_INFO_STREAM(getLogger(), "[SignalDetector] loop rate hz:" << loop_rate_hz);
345
347 {
348 RCLCPP_INFO_STREAM(getLogger(), "[SignalDetector] running in single threaded mode");
349
350 rclcpp::Rate r(loop_rate_hz);
351 while (rclcpp::ok() && !end_)
352 {
353 RCLCPP_INFO_STREAM_THROTTLE(
354 getLogger(), *getNode()->get_clock(), 10000, "[SignalDetector] heartbeat");
355 pollOnce();
356 rclcpp::spin_some(nh);
357 r.sleep();
358 }
359 }
360 else
361 {
362 RCLCPP_INFO_STREAM(getLogger(), "[SignalDetector] running in multi threaded mode");
363
364 rclcpp::executors::MultiThreadedExecutor executor;
365 executor.add_node(nh);
366 executor.spin();
367 }
368}
369
370void onSigQuit(int)
371{
372 RCLCPP_INFO(rclcpp::get_logger("SMACC"), "SignalDetector: SIGQUIT received");
373 exit(0);
374}
375
376} // 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()
Definition: smacc_state.hpp:80
std::vector< std::shared_ptr< SmaccEventGenerator > > & getEventGenerators()
Definition: smacc_state.hpp:82
SmaccFifoScheduler * scheduler_
void notifyStateExited(ISmaccState *currentState)
void initialize(ISmaccStateMachine *stateMachine)
std::vector< std::vector< ISmaccUpdatable * > > updatableStateElements_
std::atomic< uint64_t > lastState_
rclcpp::Node::SharedPtr getNode()
SmaccFifoScheduler::processor_handle processorHandle_
SignalDetector(SmaccFifoScheduler *scheduler, ExecutionModel executionModel=ExecutionModel::SINGLE_THREAD_SPINNER)
std::vector< ISmaccUpdatable * > updatableClients_
void setProcessorHandle(SmaccFifoScheduler::processor_handle processorHandle)
void findUpdatableStateElements(ISmaccState *currentState)
ISmaccStateMachine * smaccStateMachine_
void notifyStateConfigured(ISmaccState *currentState)
std::atomic< bool > initialized_
std::string demangleType(const std::type_info *tinfo)
void onSigQuit(int sig)
boost::statechart::fifo_scheduler< SmaccFifoWorker, SmaccAllocator > SmaccFifoScheduler
void TRACEPOINT(spinOnce)
smacc2_state_update_start