@@ -190,16 +190,28 @@ class Player
190190class Recorder
191191{
192192private:
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+ }
194205 std::shared_ptr<rosbag2_transport::Recorder> recorder_;
195206
196207public:
197208 Recorder ()
198209 {
199210 auto init_options = rclcpp::InitOptions ();
200211 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+ }
203215 std::signal (
204216 SIGTERM, [](int /* signal */ ) {
205217 rosbag2_py::Recorder::cancel ();
@@ -210,10 +222,7 @@ class Recorder
210222 });
211223 }
212224
213- virtual ~Recorder ()
214- {
215- rclcpp::shutdown ();
216- }
225+ virtual ~Recorder () = default ;
217226
218227 void record (
219228 const rosbag2_storage::StorageOptions & storage_options,
@@ -229,33 +238,35 @@ class Recorder
229238 std::move (writer), storage_options, record_options, node_name);
230239 recorder_->record ();
231240
232- exec_ ->add_node (recorder_);
241+ get_executor_instance () ->add_node (recorder_);
233242 // Release the GIL for long-running record, so that calling Python code can use other threads
234- {
243+ try {
235244 py::gil_scoped_release release;
236245 while (!exit_) {
237- exec_ ->spin_all (std::chrono::milliseconds (30 ));
246+ get_executor_instance () ->spin_all (std::chrono::milliseconds (30 ));
238247 }
239248 if (recorder_) {
240249 recorder_->stop ();
241250 // 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 ));
243252 }
253+ } catch (...) {
254+ get_executor_instance ()->remove_node (recorder_);
244255 }
256+ get_executor_instance ()->remove_node (recorder_);
245257 }
246258
247259 static void cancel ()
248260 {
249261 exit_ = true ;
250- if (exec_ ) {
251- exec_ ->cancel ();
262+ if (get_executor_instance () ) {
263+ get_executor_instance () ->cancel ();
252264 }
253265 }
254266
255267 static std::atomic_bool exit_;
256268};
257269
258- std::unique_ptr<rclcpp::executors::SingleThreadedExecutor> Recorder::exec_;
259270std::atomic_bool Recorder::exit_{false };
260271
261272// Return a RecordOptions struct with defaults set for rewriting bags.
0 commit comments