27#include <lttng/tracepoint.h>
38using namespace std::chrono_literals;
46: schedulerThread(nullptr),
47 signalDetectorLoop(nullptr),
48 signalDetector(nullptr),
84 lastState_ = std::numeric_limits<int64_t>::quiet_NaN();
88 auto context =
getNode()->get_node_base_interface()->get_context();
109 auto & orthogonal = pair.second;
110 auto & clients = orthogonal->getClients();
112 for (
auto & client : clients)
117 if (updatableClient !=
nullptr)
125 std::vector<std::shared_ptr<ISmaccComponent>> components;
126 client->getComponents(components);
127 for (
auto & componententry : components)
129 auto updatableComponent =
dynamic_cast<ISmaccUpdatable *
>(componententry.get());
130 if (updatableComponent !=
nullptr)
134 "Adding updatable component: " <<
demangleType(
typeid(*updatableComponent)));
155 auto & orthogonal = pair.second;
156 auto & behaviors = orthogonal->getClientBehaviors().back();
158 for (
auto & currentBehavior : behaviors)
163 if (updatableClientBehavior !=
nullptr)
167 "Adding updatable behavior: " <<
demangleType(
typeid(updatableClientBehavior)));
168 updatableElements.push_back(updatableClientBehavior);
174 if (updatableState !=
nullptr)
176 updatableElements.push_back(updatableState);
180 for (
auto & sr : statereactors)
183 if (updatableStateReactor !=
nullptr)
187 "Adding updatable stateReactorr: " <<
demangleType(
typeid(updatableStateReactor)));
188 updatableElements.push_back(updatableStateReactor);
193 for (
auto & eg : eventgenerators)
196 if (updatableEventGenerator !=
nullptr)
200 "Adding updatable eventGenerator: " <<
demangleType(
typeid(updatableEventGenerator)));
201 updatableElements.push_back(updatableEventGenerator);
218 RCLCPP_INFO(
getLogger(),
"[SignalDetector] ROS initialization complete, enabling polling loop");
265 RCLCPP_INFO(
getLogger(),
"[SignalDetector] Terminating scheduler...");
280 TRACETOOLS_TRACEPOINT(spinOnce);
295 auto updatableElementName =
demangleType(
typeid(*updatableClient)).c_str();
300 "[PollOnce] update client call: " <<
demangleType(
typeid(*updatableClient)));
306 catch (
const std::exception & e)
310 "Error in updatable elemnent " << updatableElementName <<
": " << e.what() <<
'\n');
319 this->smaccStateMachine_->stateMachineCurrentAction !=
321 this->smaccStateMachine_->stateMachineCurrentAction !=
323 this->smaccStateMachine_->stateMachineCurrentAction !=
331 for (
auto * udpatableStateElement : stateElement)
333 std::string updatableElementName =
demangleType(
typeid(*udpatableStateElement));
334 auto updatableElementNameCstr = updatableElementName.c_str();
337 getLogger(),
"pollOnce update client behavior call: "
347 catch (std::exception & ex)
349 RCLCPP_ERROR(
getLogger(),
"Exception during Signal Detector update loop. %s.", ex.what());
362 rclcpp::Node::SharedPtr _;
374 if (!rclcpp::ok() ||
end_)
376 RCLCPP_INFO(
getLogger(),
"[SignalDetector] Shutdown requested before initialization completed");
382 if (!nh->get_parameter(
"signal_detector_loop_freq", this->loop_rate_hz))
386 "Signal Detector frequency (ros param signal_detector_loop_freq) was not set, using default "
394 getLogger(),
"Signal Detector frequency (ros param signal_detector_loop_freq): %lf",
398 nh->set_parameter(rclcpp::Parameter(
"signal_detector_loop_freq", this->
loop_rate_hz));
404 RCLCPP_INFO_STREAM(
getLogger(),
"[SignalDetector] Running in single-threaded mode.");
407 while (rclcpp::ok() && !
end_)
409 RCLCPP_INFO_STREAM_THROTTLE(
412 rclcpp::spin_some(nh);
418 RCLCPP_INFO_STREAM(
getLogger(),
"[SignalDetector] Running in multi-threaded mode.");
420 rclcpp::executors::MultiThreadedExecutor executor;
421 executor.add_node(nh);
447 RCLCPP_INFO(rclcpp::get_logger(
"SMACC"),
"SignalDetector: SIGQUIT received.");
StateMachineInternalAction stateMachineCurrentAction
rclcpp::Node::SharedPtr getNode()
const std::map< std::string, std::shared_ptr< smacc2::ISmaccOrthogonal > > & getOrthogonals() const
std::recursive_mutex m_mutex_
std::vector< std::shared_ptr< StateReactor > > & getStateReactors()
std::vector< std::shared_ptr< SmaccEventGenerator > > & getEventGenerators()
SmaccFifoScheduler * scheduler_
void terminateScheduler()
boost::thread signalDetectorThread_
void notifyStateExited(ISmaccState *currentState)
ExecutionModel executionModel_
void initialize(ISmaccStateMachine *stateMachine)
std::vector< std::vector< ISmaccUpdatable * > > updatableStateElements_
std::atomic< bool > rosInitialized_
rclcpp::Logger getLogger()
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 notifyRosInitialized()
void setProcessorHandle(SmaccFifoScheduler::processor_handle processorHandle)
void findUpdatableStateElements(ISmaccState *currentState)
void findUpdatableClientsAndComponents()
ISmaccStateMachine * smaccStateMachine_
void notifyStateConfigured(ISmaccState *currentState)
std::atomic< bool > initialized_
static SmExecution & getInstance()
SignalDetector * signalDetector
std::string demangleType(const std::type_info *tinfo)
void onSignalShutdown(int sig)
boost::statechart::fifo_scheduler< SmaccFifoWorker, SmaccAllocator > SmaccFifoScheduler
smacc2_state_update_start