27#include <lttng/tracepoint.h>
38using namespace std::chrono_literals;
63 lastState_ = std::numeric_limits<uint64_t>::quiet_NaN();
80 auto & orthogonal = pair.second;
81 auto & clients = orthogonal->getClients();
83 for (
auto & client : clients)
88 if (updatableClient !=
nullptr)
96 std::vector<std::shared_ptr<ISmaccComponent>> components;
97 client->getComponents(components);
98 for (
auto & componententry : components)
100 auto updatableComponent =
dynamic_cast<ISmaccUpdatable *
>(componententry.get());
101 if (updatableComponent !=
nullptr)
105 "Adding updatable component: " <<
demangleType(
typeid(*updatableComponent)));
126 auto & orthogonal = pair.second;
127 auto & behaviors = orthogonal->getClientBehaviors().back();
129 for (
auto & currentBehavior : behaviors)
134 if (updatableClientBehavior !=
nullptr)
138 "Adding updatable behavior: " <<
demangleType(
typeid(updatableClientBehavior)));
139 updatableElements.push_back(updatableClientBehavior);
145 if (updatableState !=
nullptr)
147 updatableElements.push_back(updatableState);
151 for (
auto & sr : statereactors)
154 if (updatableStateReactor !=
nullptr)
158 "Adding updatable stateReactorr: " <<
demangleType(
typeid(updatableStateReactor)));
159 updatableElements.push_back(updatableStateReactor);
164 for (
auto & eg : eventgenerators)
167 if (updatableEventGenerator !=
nullptr)
171 "Adding updatable eventGenerator: " <<
demangleType(
typeid(updatableEventGenerator)));
172 updatableElements.push_back(updatableEventGenerator);
246 auto updatableElementName =
demangleType(
typeid(*updatableClient)).c_str();
251 "[PollOnce] update client call: " <<
demangleType(
typeid(*updatableClient)));
257 catch (
const std::exception & e)
261 "Error in updatable elemnent " << updatableElementName <<
": " << e.what() <<
'\n');
270 this->smaccStateMachine_->stateMachineCurrentAction !=
272 this->smaccStateMachine_->stateMachineCurrentAction !=
274 this->smaccStateMachine_->stateMachineCurrentAction !=
282 for (
auto * udpatableStateElement : stateElement)
284 std::string updatableElementName =
demangleType(
typeid(*udpatableStateElement));
285 auto updatableElementNameCstr = updatableElementName.c_str();
288 getLogger(),
"pollOnce update client behavior call: "
298 catch (std::exception & ex)
300 RCLCPP_ERROR(
getLogger(),
"Exception during Signal Detector update loop. %s", ex.what());
304 rclcpp::spin_some(nh);
316 rclcpp::Node::SharedPtr _;
326 if (!nh->get_parameter(
"signal_detector_loop_freq", this->loop_rate_hz))
330 "Signal detector frequency (ros param signal_detector_loop_freq) was not set, using default "
338 getLogger(),
"Signal detector frequency (ros param signal_detector_loop_freq): %lf",
342 nh->set_parameter(rclcpp::Parameter(
"signal_detector_loop_freq", this->
loop_rate_hz));
348 RCLCPP_INFO_STREAM(
getLogger(),
"[SignalDetector] running in single threaded mode");
351 while (rclcpp::ok() && !
end_)
353 RCLCPP_INFO_STREAM_THROTTLE(
356 rclcpp::spin_some(nh);
362 RCLCPP_INFO_STREAM(
getLogger(),
"[SignalDetector] running in multi threaded mode");
364 rclcpp::executors::MultiThreadedExecutor executor;
365 executor.add_node(nh);
372 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_
boost::thread signalDetectorThread_
void notifyStateExited(ISmaccState *currentState)
ExecutionModel executionModel_
void initialize(ISmaccStateMachine *stateMachine)
std::vector< std::vector< ISmaccUpdatable * > > updatableStateElements_
rclcpp::Logger getLogger()
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)
void findUpdatableClientsAndComponents()
ISmaccStateMachine * smaccStateMachine_
void notifyStateConfigured(ISmaccState *currentState)
std::atomic< bool > initialized_
std::string demangleType(const std::type_info *tinfo)
boost::statechart::fifo_scheduler< SmaccFifoWorker, SmaccAllocator > SmaccFifoScheduler
void TRACEPOINT(spinOnce)
smacc2_state_update_start