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// Signal handler for graceful shutdown (SIGINT/SIGTERM)
111void onSignalShutdown(int sig);
112
113// Singleton class managing SMACC execution lifecycle
114// Replaces global g_signal_detector for signal handler access
116{
117public:
118 // Get singleton instance
119 static SmExecution & getInstance();
120
121 // Delete copy and move constructors/operators
122 SmExecution(const SmExecution &) = delete;
123 SmExecution & operator=(const SmExecution &) = delete;
126
127 boost::thread * schedulerThread;
128 boost::thread * signalDetectorLoop;
131 SmaccFifoScheduler::processor_handle sm;
132
133private:
134 // Private constructor for singleton
135 SmExecution();
136};
137
138// Main entry point for any SMACC state machine
139// It instantiates and starts the specified state machine type
140// it uses two threads: a new thread and the current one.
141// The created thread is for the state machine process
142// it locks the current thread to handle events of the state machine
143template <typename StateMachineType>
145{
146 // Register signal handlers for graceful shutdown
147 ::signal(SIGINT, onSignalShutdown);
148 ::signal(SIGTERM, onSignalShutdown);
149 ::signal(SIGQUIT, onSigQuit);
150
151 // Get singleton instance
152 SmExecution & smExecution = SmExecution::getInstance();
153
154 // create the asynchronous state machine scheduler
155 SmaccFifoScheduler scheduler1(true);
156
157 // create the signalDetector component
158 SignalDetector signalDetector(&scheduler1, executionModel);
159
160 // Store in singleton for signal handler access
161 smExecution.signalDetector = &signalDetector;
162 smExecution.scheduler1 = &scheduler1;
163
164 // create the asynchronous state machine processor
165 SmaccFifoScheduler::processor_handle sm =
166 scheduler1.create_processor<StateMachineType>(&signalDetector);
167
168 // initialize the asynchronous state machine processor
169 signalDetector.setProcessorHandle(sm);
170 smExecution.sm = sm;
171
172 scheduler1.initiate_processor(sm);
173
174 //create a thread for the asynchronous state machine processor execution
175 boost::thread schedulerThread(boost::bind(&sc::fifo_scheduler<>::operator(), &scheduler1, 0));
176 smExecution.schedulerThread = &schedulerThread;
177
178 // use the main thread for the signal detector component (waiting actionclient requests)
179 signalDetector.pollingLoop();
180
181 // After polling loop exits (due to shutdown), terminate the scheduler from main thread
182 // This is safe to call here (not from signal handler) as we're in the main thread context
183 RCLCPP_INFO(rclcpp::get_logger("SMACC"), "Polling loop exited. Terminating scheduler...");
184 signalDetector.terminateScheduler();
185
186 // Wait for scheduler thread to finish
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.");
190
191 // Clear singleton references
192 smExecution.signalDetector = nullptr;
193 smExecution.scheduler1 = nullptr;
194 smExecution.schedulerThread = nullptr;
195}
196
197template <typename StateMachineType>
199{
200 // Register signal handlers for graceful shutdown
201 ::signal(SIGINT, onSignalShutdown);
202 ::signal(SIGTERM, onSignalShutdown);
203 ::signal(SIGQUIT, onSigQuit);
204
205 // Get singleton instance
206 SmExecution & smExecution = SmExecution::getInstance();
207
208 // create the asynchronous state machine scheduler
209 smExecution.scheduler1 = new SmaccFifoScheduler(true);
210
211 // create the signalDetector component
212 smExecution.signalDetector = new SignalDetector(smExecution.scheduler1);
213
214 // create the asynchronous state machine processor
215 smExecution.sm =
216 smExecution.scheduler1->create_processor<StateMachineType>(smExecution.signalDetector);
217
218 // initialize the asynchronous state machine processor
219 smExecution.signalDetector->setProcessorHandle(smExecution.sm);
220
221 smExecution.scheduler1->initiate_processor(smExecution.sm);
222
223 //create a thread for the asynchronous state machine processor execution
224 smExecution.schedulerThread =
225 new boost::thread(boost::bind(&sc::fifo_scheduler<>::operator(), smExecution.scheduler1, NULL));
226 smExecution.signalDetectorLoop =
227 new boost::thread(boost::bind(&SignalDetector::pollingLoop, smExecution.signalDetector));
228
229 return smExecution;
230}
231
232} // 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_
SmaccFifoScheduler::processor_handle sm
static SmExecution & getInstance()
SmaccFifoScheduler * scheduler1
SmExecution & operator=(const SmExecution &)=delete
SmExecution & operator=(SmExecution &&)=delete
SmExecution(const SmExecution &)=delete
SmExecution(SmExecution &&)=delete
void onSigQuit(int sig)
void onSignalShutdown(int sig)
SmExecution & run_async()
void run(ExecutionModel executionModel=ExecutionModel::SINGLE_THREAD_SPINNER)
boost::statechart::fifo_scheduler< SmaccFifoWorker, SmaccAllocator > SmaccFifoScheduler