@@ -190,16 +190,28 @@ class Player
190
190
class Recorder
191
191
{
192
192
private:
193
- static std::unique_ptr<rclcpp::executors::SingleThreadedExecutor> exec_;
193
+ using ExecutorT = rclcpp::executors::SingleThreadedExecutor;
194
+ static std::unique_ptr<ExecutorT, void (*)(ExecutorT *)> & get_executor_instance ()
195
+ {
196
+ static std::unique_ptr<ExecutorT, void (*)(ExecutorT *)> executor (
197
+ new ExecutorT (),
198
+ [](ExecutorT * exec_ptr) {
199
+ delete exec_ptr;
200
+ rclcpp::shutdown ();
201
+ }
202
+ );
203
+ return executor;
204
+ }
194
205
std::shared_ptr<rosbag2_transport::Recorder> recorder_;
195
206
196
207
public:
197
208
Recorder ()
198
209
{
199
210
auto init_options = rclcpp::InitOptions ();
200
211
init_options.shutdown_on_signal = false ;
201
- rclcpp::init (0 , nullptr , init_options, rclcpp::SignalHandlerOptions::None);
202
- exec_ = std::make_unique<rclcpp::executors::SingleThreadedExecutor>();
212
+ if (!rclcpp::ok ()) {
213
+ rclcpp::init (0 , nullptr , init_options, rclcpp::SignalHandlerOptions::None);
214
+ }
203
215
std::signal (
204
216
SIGTERM, [](int /* signal */ ) {
205
217
rosbag2_py::Recorder::cancel ();
@@ -210,10 +222,7 @@ class Recorder
210
222
});
211
223
}
212
224
213
- virtual ~Recorder ()
214
- {
215
- rclcpp::shutdown ();
216
- }
225
+ virtual ~Recorder () = default ;
217
226
218
227
void record (
219
228
const rosbag2_storage::StorageOptions & storage_options,
@@ -229,33 +238,35 @@ class Recorder
229
238
std::move (writer), storage_options, record_options, node_name);
230
239
recorder_->record ();
231
240
232
- exec_ ->add_node (recorder_);
241
+ get_executor_instance () ->add_node (recorder_);
233
242
// Release the GIL for long-running record, so that calling Python code can use other threads
234
- {
243
+ try {
235
244
py::gil_scoped_release release;
236
245
while (!exit_) {
237
- exec_ ->spin_all (std::chrono::milliseconds (30 ));
246
+ get_executor_instance () ->spin_all (std::chrono::milliseconds (30 ));
238
247
}
239
248
if (recorder_) {
240
249
recorder_->stop ();
241
250
// Need to spin once to be able to send notifications about bag split and close
242
- exec_ ->spin_some (std::chrono::milliseconds (30 ));
251
+ get_executor_instance () ->spin_some (std::chrono::milliseconds (30 ));
243
252
}
253
+ } catch (...) {
254
+ get_executor_instance ()->remove_node (recorder_);
244
255
}
256
+ get_executor_instance ()->remove_node (recorder_);
245
257
}
246
258
247
259
static void cancel ()
248
260
{
249
261
exit_ = true ;
250
- if (exec_ ) {
251
- exec_ ->cancel ();
262
+ if (get_executor_instance () ) {
263
+ get_executor_instance () ->cancel ();
252
264
}
253
265
}
254
266
255
267
static std::atomic_bool exit_;
256
268
};
257
269
258
- std::unique_ptr<rclcpp::executors::SingleThreadedExecutor> Recorder::exec_;
259
270
std::atomic_bool Recorder::exit_{false };
260
271
261
272
// Return a RecordOptions struct with defaults set for rewriting bags.
0 commit comments