SMACC2
Loading...
Searching...
No Matches
smacc_signal_detector.hpp
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#pragma once
21
22#include <atomic>
23#include <boost/thread.hpp>
24#include <smacc2/common.hpp>
25#include <smacc2_msgs/msg/smacc_status.hpp>
26
27namespace smacc2
28{
34
35// Mostly define the state machine ros thread and receive events state machine components (clients, state elements)
36// This class also contains the event queue of the state machine
38{
39public:
41 SmaccFifoScheduler * scheduler,
43
44 void initialize(ISmaccStateMachine * stateMachine);
45
46 void setProcessorHandle(SmaccFifoScheduler::processor_handle processorHandle);
47
48 // Runs the polling loop into a thread...
49 void runThread();
50
51 // Waits for the polling thread to end...
52 void join();
53
54 void stop();
55
56 void terminateScheduler();
57
58 void pollingLoop();
59
60 template <typename EventType>
61 void postEvent(EventType * ev)
62 {
63 boost::intrusive_ptr<EventType> weakPtrEvent = ev;
64 this->scheduler_->queue_event(processorHandle_, weakPtrEvent);
65 }
66
67 rclcpp::Node::SharedPtr getNode();
68 inline rclcpp::Logger getLogger() { return getNode()->get_logger(); }
69
70 void notifyStateConfigured(ISmaccState * currentState);
71
72 void notifyStateExited(ISmaccState * currentState);
73
74private:
75 void pollOnce();
76
78
79 std::vector<ISmaccUpdatable *> updatableClients_;
80
81 std::vector<std::vector<ISmaccUpdatable *>> updatableStateElements_;
82 std::atomic<int64_t> lastState_;
83
85
86 void findUpdatableStateElements(ISmaccState * currentState);
87
88 // Loop frequency of the signal detector (to check answers from actionservers)
90
91 std::atomic<bool> end_;
92
93 std::atomic<bool> initialized_;
94
95 rclcpp::Publisher<smacc2_msgs::msg::SmaccStatus>::SharedPtr statusPub_;
96
97 // ---- boost statechart related ----
98
100
101 SmaccFifoScheduler::processor_handle processorHandle_;
102
104
106};
107
108void onSigQuit(int sig);
109
110// Global variables for graceful shutdown handling
111// Declared here, defined in signal_detector.cpp
112extern std::atomic<bool> g_shutdown_requested;
114
115// Signal handler for graceful shutdown (SIGINT/SIGTERM)
116void onSignalShutdown(int sig);
117
118// Main entry point for any SMACC state machine
119// It instantiates and starts the specified state machine type
120// it uses two threads: a new thread and the current one.
121// The created thread is for the state machine process
122// it locks the current thread to handle events of the state machine
123template <typename StateMachineType>
125{
126 // Register signal handlers for graceful shutdown
127 ::signal(SIGINT, onSignalShutdown);
128 ::signal(SIGTERM, onSignalShutdown);
129 ::signal(SIGQUIT, onSigQuit);
130
131 // create the asynchronous state machine scheduler
132 SmaccFifoScheduler scheduler1(true);
133
134 // create the signalDetector component
135 SignalDetector signalDetector(&scheduler1, executionModel);
136
137 // Store global reference for signal handler access
138 g_signal_detector = &signalDetector;
139
140 // create the asynchronous state machine processor
141 SmaccFifoScheduler::processor_handle sm =
142 scheduler1.create_processor<StateMachineType>(&signalDetector);
143
144 // initialize the asynchronous state machine processor
145 signalDetector.setProcessorHandle(sm);
146
147 scheduler1.initiate_processor(sm);
148
149 //create a thread for the asynchronous state machine processor execution
150 boost::thread schedulerThread(boost::bind(&sc::fifo_scheduler<>::operator(), &scheduler1, 0));
151
152 // use the main thread for the signal detector component (waiting actionclient requests)
153 signalDetector.pollingLoop();
154
155 // After polling loop exits (due to shutdown), terminate the scheduler from main thread
156 // This is safe to call here (not from signal handler) as we're in the main thread context
157 RCLCPP_INFO(rclcpp::get_logger("SMACC"), "Polling loop exited. Terminating scheduler...");
158 signalDetector.terminateScheduler();
159
160 // Wait for scheduler thread to finish
161 RCLCPP_INFO(rclcpp::get_logger("SMACC"), "Waiting for scheduler thread to join...");
162 schedulerThread.join();
163 RCLCPP_INFO(rclcpp::get_logger("SMACC"), "Scheduler thread terminated. Shutdown complete.");
164
165 // Clear global reference
166 g_signal_detector = nullptr;
167}
168
170{
171 boost::thread * schedulerThread;
172 boost::thread * signalDetectorLoop;
175 SmaccFifoScheduler::processor_handle sm;
176};
177
178template <typename StateMachineType>
180{
181 // Register signal handlers for graceful shutdown
182 ::signal(SIGINT, onSignalShutdown);
183 ::signal(SIGTERM, onSignalShutdown);
184 ::signal(SIGQUIT, onSigQuit);
185
186 SmExecution * ret = new SmExecution();
187
188 // create the asynchronous state machine scheduler
189 ret->scheduler1 = new SmaccFifoScheduler(true);
190
191 // create the signalDetector component
193
194 // Store global reference for signal handler access
196
197 // create the asynchronous state machine processor
198 ret->sm = ret->scheduler1->create_processor<StateMachineType>(ret->signalDetector);
199
200 // initialize the asynchronous state machine processor
202
203 ret->scheduler1->initiate_processor(ret->sm);
204
205 //create a thread for the asynchronous state machine processor execution
206 ret->schedulerThread =
207 new boost::thread(boost::bind(&sc::fifo_scheduler<>::operator(), ret->scheduler1, NULL));
208 ret->signalDetectorLoop =
209 new boost::thread(boost::bind(&SignalDetector::pollingLoop, ret->signalDetector));
210
211 return ret;
212}
213
214} // namespace smacc2
SmaccFifoScheduler * scheduler_
void notifyStateExited(ISmaccState *currentState)
void initialize(ISmaccStateMachine *stateMachine)
std::vector< std::vector< ISmaccUpdatable * > > updatableStateElements_
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)
ISmaccStateMachine * smaccStateMachine_
void notifyStateConfigured(ISmaccState *currentState)
std::atomic< bool > initialized_
void onSigQuit(int sig)
SignalDetector * g_signal_detector
SmExecution * run_async()
void onSignalShutdown(int sig)
std::atomic< bool > g_shutdown_requested
void run(ExecutionModel executionModel=ExecutionModel::SINGLE_THREAD_SPINNER)
boost::statechart::fifo_scheduler< SmaccFifoWorker, SmaccAllocator > SmaccFifoScheduler
SmaccFifoScheduler::processor_handle sm
SmaccFifoScheduler * scheduler1