23#include <boost/thread.hpp>
25#include <smacc2_msgs/msg/smacc_status.hpp>
60 template <
typename EventType>
63 boost::intrusive_ptr<EventType> weakPtrEvent = ev;
67 rclcpp::Node::SharedPtr
getNode();
95 rclcpp::Publisher<smacc2_msgs::msg::SmaccStatus>::SharedPtr
statusPub_;
131 SmaccFifoScheduler::processor_handle
sm;
143template <
typename StateMachineType>
165 SmaccFifoScheduler::processor_handle sm =
166 scheduler1.create_processor<StateMachineType>(&signalDetector);
172 scheduler1.initiate_processor(sm);
175 boost::thread schedulerThread(boost::bind(&sc::fifo_scheduler<>::operator(), &scheduler1, 0));
183 RCLCPP_INFO(rclcpp::get_logger(
"SMACC"),
"Polling loop exited. Terminating scheduler...");
187 RCLCPP_INFO(rclcpp::get_logger(
"SMACC"),
"Waiting for scheduler thread to join...");
188 schedulerThread.join();
189 RCLCPP_INFO(rclcpp::get_logger(
"SMACC"),
"Scheduler thread terminated. Shutdown complete.");
197template <
typename StateMachineType>
221 smExecution.
scheduler1->initiate_processor(smExecution.
sm);
225 new boost::thread(boost::bind(&sc::fifo_scheduler<>::operator(), smExecution.
scheduler1, NULL));
SmaccFifoScheduler * scheduler_
void terminateScheduler()
boost::thread signalDetectorThread_
void postEvent(EventType *ev)
void notifyStateExited(ISmaccState *currentState)
ExecutionModel executionModel_
void initialize(ISmaccStateMachine *stateMachine)
std::vector< std::vector< ISmaccUpdatable * > > updatableStateElements_
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 setProcessorHandle(SmaccFifoScheduler::processor_handle processorHandle)
rclcpp::Publisher< smacc2_msgs::msg::SmaccStatus >::SharedPtr statusPub_
void findUpdatableStateElements(ISmaccState *currentState)
void findUpdatableClientsAndComponents()
ISmaccStateMachine * smaccStateMachine_
void notifyStateConfigured(ISmaccState *currentState)
std::atomic< bool > initialized_
SmaccFifoScheduler::processor_handle sm
boost::thread * schedulerThread
boost::thread * signalDetectorLoop
static SmExecution & getInstance()
SmaccFifoScheduler * scheduler1
SmExecution & operator=(const SmExecution &)=delete
SmExecution & operator=(SmExecution &&)=delete
SmExecution(const SmExecution &)=delete
SignalDetector * signalDetector
SmExecution(SmExecution &&)=delete
void onSignalShutdown(int sig)
SmExecution & run_async()
void run(ExecutionModel executionModel=ExecutionModel::SINGLE_THREAD_SPINNER)
boost::statechart::fifo_scheduler< SmaccFifoWorker, SmaccAllocator > SmaccFifoScheduler