Skip to content

Commit 9819e5f

Browse files
committed
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]>
1 parent 8a08167 commit 9819e5f

File tree

1 file changed

+23
-21
lines changed

1 file changed

+23
-21
lines changed

rosbag2_py/src/rosbag2_py/_transport.cpp

Lines changed: 23 additions & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -189,19 +189,13 @@ class Player
189189

190190
class Recorder
191191
{
192-
private:
193-
using ExecutorT = rclcpp::executors::SingleThreadedExecutor;
194-
std::unique_ptr<ExecutorT> exec_;
195-
std::shared_ptr<rosbag2_transport::Recorder> recorder_;
196-
197192
public:
198193
Recorder()
199194
{
200195
auto init_options = rclcpp::InitOptions();
201196
init_options.shutdown_on_signal = false;
202197
rclcpp::init(0, nullptr, init_options, rclcpp::SignalHandlerOptions::None);
203198

204-
exec_ = std::make_unique<ExecutorT>();
205199
std::signal(
206200
SIGTERM, [](int /* signal */) {
207201
rosbag2_py::Recorder::cancel();
@@ -222,42 +216,50 @@ class Recorder
222216
RecordOptions & record_options,
223217
std::string & node_name)
224218
{
219+
exit_ = false;
220+
auto exec = std::make_unique<rclcpp::executors::SingleThreadedExecutor>();
225221
if (record_options.rmw_serialization_format.empty()) {
226222
record_options.rmw_serialization_format = std::string(rmw_get_serialization_format());
227223
}
228224

229225
auto writer = rosbag2_transport::ReaderWriterFactory::make_writer(record_options);
230-
recorder_ = std::make_shared<rosbag2_transport::Recorder>(
226+
auto recorder = std::make_shared<rosbag2_transport::Recorder>(
231227
std::move(writer), storage_options, record_options, node_name);
232-
recorder_->record();
228+
recorder->record();
233229

234-
exec_->add_node(recorder_);
235-
try {
230+
exec->add_node(recorder);
231+
// Run exec->spin() in a separate thread, because we need to call exec->cancel() after
232+
// recorder->stop() to be able to send notifications about bag split and close.
233+
auto spin_thread = std::thread(
234+
[&exec]() {
235+
exec->spin();
236+
});
237+
{
236238
// Release the GIL for long-running record, so that calling Python code can use other threads
237239
py::gil_scoped_release release;
238-
while (!exit_) {
239-
exec_->spin_all(std::chrono::milliseconds(10));
240-
}
241-
if (recorder_) {
242-
recorder_->stop();
243-
// Need to spin node to be able to send notifications about bag split and close
244-
exec_->spin_all(std::chrono::milliseconds(10));
245-
}
246-
} catch (...) {
247-
exec_->remove_node(recorder_);
240+
std::unique_lock<std::mutex> lock(wait_for_exit_mutex_);
241+
wait_for_exit_cv_.wait(lock, [] {return rosbag2_py::Recorder::exit_.load();});
242+
recorder->stop();
248243
}
249-
exec_->remove_node(recorder_);
244+
exec->cancel();
245+
if (spin_thread.joinable()) {spin_thread.join();}
246+
exec->remove_node(recorder);
250247
}
251248

252249
static void cancel()
253250
{
254251
exit_ = true;
252+
wait_for_exit_cv_.notify_all();
255253
}
256254

255+
protected:
257256
static std::atomic_bool exit_;
257+
static std::condition_variable wait_for_exit_cv_;
258+
std::mutex wait_for_exit_mutex_;
258259
};
259260

260261
std::atomic_bool Recorder::exit_{false};
262+
std::condition_variable Recorder::wait_for_exit_cv_{};
261263

262264
// Return a RecordOptions struct with defaults set for rewriting bags.
263265
rosbag2_transport::RecordOptions bag_rewrite_default_record_options()

0 commit comments

Comments
 (0)