Skip to content

Commit

Permalink
[humble] Gracefully handle SIGINT and SIGTERM in rosbag2 recorder (ba…
Browse files Browse the repository at this point in the history
…ckport #1301) (#1395)

* Gracefully handle SIGINT and SIGTERM in rosbag2 recorder (#1301)

* 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]>

* Use singleton for static executor in the rosbag2_py::Recorder

Signed-off-by: Michael Orlov <[email protected]>

* Rollback to the non-static executor and don't call executor->cancel()

- In case when signal will arrive we will trigger our internal exit_
variable and wait while current exec_->spin_all(10msec) will exit.

Signed-off-by: Michael Orlov <[email protected]>

* Spin recorder node in a separate thread for better handling exit

- Run exec->spin() in a separate thread, because we need to call
exec->cancel() after recorder->stop() to be able to send notifications
about bag split and close.
- Wait on conditional variable for exit_ flag

Signed-off-by: Michael Orlov <[email protected]>

* Address race condition in rosbag2_py.test_record_cancel

- Add `record_thread.join()` before trying to parse metadata.

Signed-off-by: Michael Orlov <[email protected]>

---------

Signed-off-by: Michael Orlov <[email protected]>
(cherry picked from commit 46a23e9)

# Conflicts:
#	rosbag2_py/src/rosbag2_py/_transport.cpp
#	rosbag2_py/test/test_transport.py

* Address merge conflicts

Signed-off-by: Michael Orlov <[email protected]>

* Workaround for segmentation fault in rclcpp::SignalHandler::uninstall()

Signed-off-by: Michael Orlov <[email protected]>

---------

Signed-off-by: Michael Orlov <[email protected]>
Co-authored-by: Michael Orlov <[email protected]>
  • Loading branch information
mergify[bot] and MichaelOrlov authored Jul 4, 2023
1 parent 6ceed91 commit e97cf9e
Show file tree
Hide file tree
Showing 2 changed files with 44 additions and 13 deletions.
56 changes: 43 additions & 13 deletions rosbag2_py/src/rosbag2_py/_transport.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -141,29 +141,36 @@ class Player

class Recorder
{
private:
std::unique_ptr<rclcpp::executors::SingleThreadedExecutor> exec_;

public:
Recorder()
{
rclcpp::init(0, nullptr);
exec_ = std::make_unique<rclcpp::executors::SingleThreadedExecutor>();
auto init_options = rclcpp::InitOptions();
init_options.shutdown_on_signal = false;
rclcpp::init(0, nullptr, init_options, rclcpp::SignalHandlerOptions::SigInt);
rclcpp::uninstall_signal_handlers();

std::signal(
SIGTERM, [](int /* signal */) {
rclcpp::shutdown();
rosbag2_py::Recorder::cancel();
});
std::signal(
SIGINT, [](int /* signal */) {
rosbag2_py::Recorder::cancel();
});
}

virtual ~Recorder()
{
// rclcpp::install_signal_handlers(rclcpp::SignalHandlerOptions::SigTerm);
rclcpp::shutdown();
}

void record(
const rosbag2_storage::StorageOptions & storage_options,
RecordOptions & record_options)
{
exit_ = false;
auto exec = std::make_unique<rclcpp::executors::SingleThreadedExecutor>();
if (record_options.rmw_serialization_format.empty()) {
record_options.rmw_serialization_format = std::string(rmw_get_serialization_format());
}
Expand All @@ -173,20 +180,42 @@ class Recorder
std::move(writer), storage_options, record_options);
recorder->record();

exec_->add_node(recorder);
// Release the GIL for long-running record, so that calling Python code can use other threads
exec->add_node(recorder);
// Run exec->spin() in a separate thread, because we need to call exec->cancel() after
// recorder->stop() to be able to send notifications about bag split and close.
auto spin_thread = std::thread(
[&exec]() {
exec->spin();
});
{
// Release the GIL for long-running record, so that calling Python code can use other threads
py::gil_scoped_release release;
exec_->spin();
std::unique_lock<std::mutex> lock(wait_for_exit_mutex_);
wait_for_exit_cv_.wait(lock, [] {return rosbag2_py::Recorder::exit_.load();});
recorder->stop();
}
exec->cancel();
if (spin_thread.joinable()) {
spin_thread.join();
}
exec->remove_node(recorder);
}

void cancel()
static void cancel()
{
exec_->cancel();
exit_ = true;
wait_for_exit_cv_.notify_all();
}

protected:
static std::atomic_bool exit_;
static std::condition_variable wait_for_exit_cv_;
std::mutex wait_for_exit_mutex_;
};

std::atomic_bool Recorder::exit_{false};
std::condition_variable Recorder::wait_for_exit_cv_{};

// Simple wrapper to read the output config YAML into structs
void bag_rewrite(
const std::vector<rosbag2_storage::StorageOptions> & input_options,
Expand Down Expand Up @@ -283,8 +312,9 @@ PYBIND11_MODULE(_transport, m) {

py::class_<rosbag2_py::Recorder>(m, "Recorder")
.def(py::init())
.def("record", &rosbag2_py::Recorder::record)
.def("cancel", &rosbag2_py::Recorder::cancel)
.def(
"record", &rosbag2_py::Recorder::record, py::arg("storage_options"), py::arg("record_options"))
.def_static("cancel", &rosbag2_py::Recorder::cancel)
;

m.def(
Expand Down
1 change: 1 addition & 0 deletions rosbag2_py/test/test_transport.py
Original file line number Diff line number Diff line change
Expand Up @@ -85,3 +85,4 @@ def test_record_cancel(tmp_path):
db3_path = Path(bag_path) / 'test_record_cancel_0.db3'
assert wait_for(lambda: metadata_path.is_file() and db3_path.is_file(),
timeout=rclpy.duration.Duration(seconds=3))
record_thread.join()

0 comments on commit e97cf9e

Please sign in to comment.