Skip to content

Commit 6ceed91

Browse files
[humble] Fix for possible freeze in Recorder::stop() (backport #1381) (#1388)
* Fix for possible freeze in Recorder::stop() (#1381) * Fix for possible freeze in Recorder::stop() - It was possible a freeze in recorder due to the race condition when calling Recorder::stop() while event publisher thread hasn't been fully started yet. Signed-off-by: Michael Orlov <[email protected]> * Move event_publisher_thread_wake_cv_.notify_all() out of the mutex lock Signed-off-by: Michael Orlov <[email protected]> --------- Signed-off-by: Michael Orlov <[email protected]> (cherry picked from commit c6cc69a) # Conflicts: # rosbag2_transport/src/rosbag2_transport/recorder.cpp * Resolve merge conflicts Signed-off-by: Michael Orlov <[email protected]> * Remove `in_recording_` variable for ABI compatibility Signed-off-by: Michael Orlov <[email protected]> --------- Signed-off-by: Michael Orlov <[email protected]> Co-authored-by: Michael Orlov <[email protected]>
1 parent 07fd903 commit 6ceed91

File tree

2 files changed

+13
-10
lines changed

2 files changed

+13
-10
lines changed

Diff for: rosbag2_transport/include/rosbag2_transport/recorder.hpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -164,6 +164,7 @@ class Recorder : public rclcpp::Node
164164
std::unordered_set<std::string> topic_unknown_types_;
165165
rclcpp::Service<rosbag2_interfaces::srv::Snapshot>::SharedPtr srv_snapshot_;
166166
std::atomic<bool> paused_ = false;
167+
167168
// Keyboard handler
168169
std::shared_ptr<KeyboardHandler> keyboard_handler_;
169170
// Toogle paused key callback handle
@@ -172,8 +173,8 @@ class Recorder : public rclcpp::Node
172173

173174
// Variables for event publishing
174175
rclcpp::Publisher<rosbag2_interfaces::msg::WriteSplitEvent>::SharedPtr split_event_pub_;
175-
bool event_publisher_thread_should_exit_ = false;
176-
bool write_split_has_occurred_ = false;
176+
std::atomic<bool> event_publisher_thread_should_exit_ = false;
177+
std::atomic<bool> write_split_has_occurred_ = false;
177178
rosbag2_cpp::bag_events::BagSplitInfo bag_split_info_;
178179
std::mutex event_publisher_thread_mutex_;
179180
std::condition_variable event_publisher_thread_wake_cv_;

Diff for: rosbag2_transport/src/rosbag2_transport/recorder.cpp

+10-8
Original file line numberDiff line numberDiff line change
@@ -121,7 +121,13 @@ void Recorder::stop()
121121
{
122122
stop_discovery_ = true;
123123
if (discovery_future_.valid()) {
124-
discovery_future_.wait();
124+
auto status = discovery_future_.wait_for(2 * record_options_.topic_polling_interval);
125+
if (status != std::future_status::ready) {
126+
RCLCPP_ERROR_STREAM(
127+
get_logger(),
128+
"discovery_future_.wait_for(" << record_options_.topic_polling_interval.count() <<
129+
") return status: " << (status == std::future_status::timeout ? "timeout" : "deferred"));
130+
}
125131
}
126132
paused_ = true;
127133
subscriptions_.clear();
@@ -135,6 +141,7 @@ void Recorder::stop()
135141
if (event_publisher_thread_.joinable()) {
136142
event_publisher_thread_.join();
137143
}
144+
RCLCPP_INFO(get_logger(), "Recording stopped");
138145
}
139146

140147
void Recorder::record()
@@ -190,15 +197,13 @@ void Recorder::record()
190197
discovery_future_ =
191198
std::async(std::launch::async, std::bind(&Recorder::topics_discovery, this));
192199
}
200+
RCLCPP_INFO(get_logger(), "Recording...");
193201
}
194202

195203
void Recorder::event_publisher_thread_main()
196204
{
197205
RCLCPP_INFO(get_logger(), "Event publisher thread: Starting");
198-
199-
bool should_exit = false;
200-
201-
while (!should_exit) {
206+
while (!event_publisher_thread_should_exit_.load()) {
202207
std::unique_lock<std::mutex> lock(event_publisher_thread_mutex_);
203208
event_publisher_thread_wake_cv_.wait(
204209
lock,
@@ -222,10 +227,7 @@ void Recorder::event_publisher_thread_main()
222227
"Failed to publish message on '/events/write_split' topic.");
223228
}
224229
}
225-
226-
should_exit = event_publisher_thread_should_exit_;
227230
}
228-
229231
RCLCPP_INFO(get_logger(), "Event publisher thread: Exiting");
230232
}
231233

0 commit comments

Comments
 (0)