@@ -184,15 +184,32 @@ class Player
184
184
const rosbag2_storage::StorageOptions & storage_options,
185
185
PlayOptions & play_options)
186
186
{
187
- play_impl (storage_options, play_options, false );
187
+ play_impl (storage_options, play_options, false , 0 , true );
188
+ }
189
+
190
+ void play_with_signal_option (
191
+ const rosbag2_storage::StorageOptions & storage_options,
192
+ PlayOptions & play_options,
193
+ bool enable_signal_handling)
194
+ {
195
+ play_impl (storage_options, play_options, false , 0 , enable_signal_handling);
188
196
}
189
197
190
198
void burst (
191
199
const rosbag2_storage::StorageOptions & storage_options,
192
200
PlayOptions & play_options,
193
201
size_t num_messages)
194
202
{
195
- play_impl (storage_options, play_options, true , num_messages);
203
+ play_impl (storage_options, play_options, true , num_messages, true );
204
+ }
205
+
206
+ void burst_with_signal_option (
207
+ const rosbag2_storage::StorageOptions & storage_options,
208
+ PlayOptions & play_options,
209
+ size_t num_messages,
210
+ bool enable_signal_handling)
211
+ {
212
+ play_impl (storage_options, play_options, true , num_messages, enable_signal_handling);
196
213
}
197
214
198
215
protected:
@@ -215,13 +232,10 @@ class Player
215
232
{
216
233
if (old_sigterm_handler_ != SIG_ERR) {
217
234
std::signal (SIGTERM, old_sigterm_handler_);
218
- old_sigterm_handler_ = SIG_ERR;
219
235
}
220
236
if (old_sigint_handler_ != SIG_ERR) {
221
237
std::signal (SIGINT, old_sigint_handler_);
222
- old_sigint_handler_ = SIG_ERR;
223
238
}
224
- deferred_sig_number_ = -1 ;
225
239
}
226
240
227
241
static void process_deferred_signal ()
@@ -243,9 +257,12 @@ class Player
243
257
const rosbag2_storage::StorageOptions & storage_options,
244
258
PlayOptions & play_options,
245
259
bool burst = false ,
246
- size_t burst_num_messages = 0 )
260
+ size_t burst_num_messages = 0 ,
261
+ bool enable_signal_handling = true )
247
262
{
248
- install_signal_handlers ();
263
+ if (enable_signal_handling) {
264
+ install_signal_handlers ();
265
+ }
249
266
try {
250
267
auto reader = rosbag2_transport::ReaderWriterFactory::make_reader (storage_options);
251
268
std::shared_ptr<KeyboardHandler> keyboard_handler;
@@ -297,25 +314,30 @@ class Player
297
314
}
298
315
exec.remove_node (player);
299
316
} catch (...) {
300
- process_deferred_signal ();
301
- uninstall_signal_handlers ();
317
+ if (enable_signal_handling) {
318
+ uninstall_signal_handlers ();
319
+ process_deferred_signal ();
320
+ }
302
321
throw ;
303
322
}
304
- process_deferred_signal ();
305
- uninstall_signal_handlers ();
323
+ if (enable_signal_handling) {
324
+ uninstall_signal_handlers ();
325
+ process_deferred_signal ();
326
+ }
306
327
}
307
328
308
329
static std::atomic_bool exit_;
330
+ static_assert (std::atomic_bool::is_always_lock_free);
309
331
static std::condition_variable wait_for_exit_cv_;
310
332
static SignalHandlerType old_sigint_handler_;
311
333
static SignalHandlerType old_sigterm_handler_;
312
- static int deferred_sig_number_;
334
+ static volatile std:: sig_atomic_t deferred_sig_number_;
313
335
std::mutex wait_for_exit_mutex_;
314
336
};
315
337
316
338
Player::SignalHandlerType Player::old_sigint_handler_ {SIG_ERR};
317
339
Player::SignalHandlerType Player::old_sigterm_handler_ {SIG_ERR};
318
- int Player::deferred_sig_number_{-1 };
340
+ volatile std:: sig_atomic_t Player::deferred_sig_number_{-1 };
319
341
std::atomic_bool Player::exit_{false };
320
342
std::condition_variable Player::wait_for_exit_cv_{};
321
343
@@ -339,7 +361,18 @@ class Recorder
339
361
RecordOptions & record_options,
340
362
std::string & node_name)
341
363
{
342
- install_signal_handlers ();
364
+ record_with_signal_option (storage_options, record_options, node_name, true );
365
+ }
366
+
367
+ void record_with_signal_option (
368
+ const rosbag2_storage::StorageOptions & storage_options,
369
+ RecordOptions & record_options,
370
+ std::string & node_name,
371
+ bool enable_signal_handling)
372
+ {
373
+ if (enable_signal_handling) {
374
+ install_signal_handlers ();
375
+ }
343
376
try {
344
377
exit_ = false ;
345
378
auto exec = std::make_unique<rclcpp::executors::SingleThreadedExecutor>();
@@ -385,12 +418,16 @@ class Recorder
385
418
}
386
419
exec->remove_node (recorder);
387
420
} catch (...) {
388
- process_deferred_signal ();
389
- uninstall_signal_handlers ();
421
+ if (enable_signal_handling) {
422
+ uninstall_signal_handlers ();
423
+ process_deferred_signal ();
424
+ }
390
425
throw ;
391
426
}
392
- process_deferred_signal ();
393
- uninstall_signal_handlers ();
427
+ if (enable_signal_handling) {
428
+ uninstall_signal_handlers ();
429
+ process_deferred_signal ();
430
+ }
394
431
}
395
432
396
433
static void cancel ()
@@ -419,13 +456,10 @@ class Recorder
419
456
{
420
457
if (old_sigterm_handler_ != SIG_ERR) {
421
458
std::signal (SIGTERM, old_sigterm_handler_);
422
- old_sigterm_handler_ = SIG_ERR;
423
459
}
424
460
if (old_sigint_handler_ != SIG_ERR) {
425
461
std::signal (SIGINT, old_sigint_handler_);
426
- old_sigint_handler_ = SIG_ERR;
427
462
}
428
- deferred_sig_number_ = -1 ;
429
463
}
430
464
431
465
static void process_deferred_signal ()
@@ -444,16 +478,17 @@ class Recorder
444
478
}
445
479
446
480
static std::atomic_bool exit_;
481
+ static_assert (std::atomic_bool::is_always_lock_free);
447
482
static std::condition_variable wait_for_exit_cv_;
448
483
static SignalHandlerType old_sigint_handler_;
449
484
static SignalHandlerType old_sigterm_handler_;
450
- static int deferred_sig_number_;
485
+ static volatile std:: sig_atomic_t deferred_sig_number_;
451
486
std::mutex wait_for_exit_mutex_;
452
487
};
453
488
454
489
Recorder::SignalHandlerType Recorder::old_sigint_handler_ {SIG_ERR};
455
490
Recorder::SignalHandlerType Recorder::old_sigterm_handler_ {SIG_ERR};
456
- int Recorder::deferred_sig_number_{-1 };
491
+ volatile std:: sig_atomic_t Recorder::deferred_sig_number_{-1 };
457
492
std::atomic_bool Recorder::exit_{false };
458
493
std::condition_variable Recorder::wait_for_exit_cv_{};
459
494
@@ -591,18 +626,22 @@ PYBIND11_MODULE(_transport, m) {
591
626
.def (py::init<>())
592
627
.def (py::init<const std::string &>())
593
628
.def (" play" , &rosbag2_py::Player::play, py::arg (" storage_options" ), py::arg (" play_options" ))
594
- .def (
595
- " burst" , &rosbag2_py::Player::burst, py::arg (" storage_options" ), py::arg (" play_options" ),
629
+ .def (" play" , &rosbag2_py::Player::play_with_signal_option, py::arg (" storage_options" ),
630
+ py::arg (" play_options" ), py::arg (" enable_signal_handling" ))
631
+ .def (" burst" , &rosbag2_py::Player::burst, py::arg (" storage_options" ), py::arg (" play_options" ),
596
632
py::arg (" num_messages" ))
633
+ .def (" burst" , &rosbag2_py::Player::burst_with_signal_option, py::arg (" storage_options" ),
634
+ py::arg (" play_options" ), py::arg (" num_messages" ), py::arg (" enable_signal_handling" ))
597
635
.def_static (" cancel" , &rosbag2_py::Player::cancel)
598
636
;
599
637
600
638
py::class_<rosbag2_py::Recorder>(m, " Recorder" )
601
639
.def (py::init<>())
602
640
.def (py::init<const std::string &>())
603
- .def (
604
- " record" , &rosbag2_py::Recorder::record, py::arg (" storage_options" ), py::arg (" record_options" ),
605
- py::arg (" node_name" ) = " rosbag2_recorder" )
641
+ .def (" record" , &rosbag2_py::Recorder::record, py::arg (" storage_options" ),
642
+ py::arg (" record_options" ), py::arg (" node_name" ) = " rosbag2_recorder" )
643
+ .def (" record" , &rosbag2_py::Recorder::record_with_signal_option, py::arg (" storage_options" ),
644
+ py::arg (" record_options" ), py::arg (" node_name" ), py::arg (" enable_signal_handling" ))
606
645
.def_static (" cancel" , &rosbag2_py::Recorder::cancel)
607
646
;
608
647
0 commit comments