Skip to content

Commit 1f2c53a

Browse files
committed
Gracefully handle SIGINT and SIGTERM signal for rosbag2 recorder
- Call recorder->stop() and exec_->cancel() instead of rclcpp::shutdown Signed-off-by: Michael Orlov <[email protected]>
1 parent af4ca0c commit 1f2c53a

File tree

1 file changed

+32
-10
lines changed

1 file changed

+32
-10
lines changed

Diff for: rosbag2_py/src/rosbag2_py/_transport.cpp

+32-10
Original file line numberDiff line numberDiff line change
@@ -190,16 +190,23 @@ class Player
190190
class Recorder
191191
{
192192
private:
193-
std::unique_ptr<rclcpp::executors::SingleThreadedExecutor> exec_;
193+
static std::unique_ptr<rclcpp::executors::SingleThreadedExecutor> exec_;
194+
std::shared_ptr<rosbag2_transport::Recorder> recorder_;
194195

195196
public:
196197
Recorder()
197198
{
198-
rclcpp::init(0, nullptr);
199+
auto init_options = rclcpp::InitOptions();
200+
init_options.shutdown_on_signal = false;
201+
rclcpp::init(0, nullptr, init_options, rclcpp::SignalHandlerOptions::None);
199202
exec_ = std::make_unique<rclcpp::executors::SingleThreadedExecutor>();
200203
std::signal(
201204
SIGTERM, [](int /* signal */) {
202-
rclcpp::shutdown();
205+
rosbag2_py::Recorder::cancel();
206+
});
207+
std::signal(
208+
SIGINT, [](int /* signal */) {
209+
rosbag2_py::Recorder::cancel();
203210
});
204211
}
205212

@@ -218,24 +225,39 @@ class Recorder
218225
}
219226

220227
auto writer = rosbag2_transport::ReaderWriterFactory::make_writer(record_options);
221-
auto recorder = std::make_shared<rosbag2_transport::Recorder>(
228+
recorder_ = std::make_shared<rosbag2_transport::Recorder>(
222229
std::move(writer), storage_options, record_options, node_name);
223-
recorder->record();
230+
recorder_->record();
224231

225-
exec_->add_node(recorder);
232+
exec_->add_node(recorder_);
226233
// Release the GIL for long-running record, so that calling Python code can use other threads
227234
{
228235
py::gil_scoped_release release;
229-
exec_->spin();
236+
while (!exit_) {
237+
exec_->spin_all(std::chrono::milliseconds(30));
238+
}
239+
if (recorder_) {
240+
recorder_->stop();
241+
// Need to spin once to be able to send notifications about bag split and close
242+
exec_->spin_some(std::chrono::milliseconds(30));
243+
}
230244
}
231245
}
232246

233-
void cancel()
247+
static void cancel()
234248
{
235-
exec_->cancel();
249+
exit_ = true;
250+
if (exec_) {
251+
exec_->cancel();
252+
}
236253
}
254+
255+
static std::atomic_bool exit_;
237256
};
238257

258+
std::unique_ptr<rclcpp::executors::SingleThreadedExecutor> Recorder::exec_;
259+
std::atomic_bool Recorder::exit_{false};
260+
239261
// Return a RecordOptions struct with defaults set for rewriting bags.
240262
rosbag2_transport::RecordOptions bag_rewrite_default_record_options()
241263
{
@@ -360,7 +382,7 @@ PYBIND11_MODULE(_transport, m) {
360382
.def(
361383
"record", &rosbag2_py::Recorder::record, py::arg("storage_options"), py::arg("record_options"),
362384
py::arg("node_name") = "rosbag2_recorder")
363-
.def("cancel", &rosbag2_py::Recorder::cancel)
385+
.def_static("cancel", &rosbag2_py::Recorder::cancel)
364386
;
365387

366388
m.def(

0 commit comments

Comments
 (0)