Skip to content

Commit 07fd903

Browse files
[humble] Fix for rosbag2_transport::Recorder failures due to the unhandled exceptions (backport #1382) (#1403)
* Fix for rosbag2_transport::Recorder failures due to the unhandled exceptions (#1382) * Fix for rosbag2_transport::Recorder failures due to unhandled exceptions Signed-off-by: Michael Orlov <[email protected]> * Revert "Fix for rosbag2_transport::Recorder failures due to unhandled exceptions" This reverts commit 767d440. Signed-off-by: Michael Orlov <[email protected]> * Handle exceptions in event publisher and discovery threads - Exceptions potentially may come from the underlying node operations when we are invalidating context via rclcpp::shutdown(). We need to have possibility to correct finish recording in this case. Signed-off-by: Michael Orlov <[email protected]> --------- Signed-off-by: Michael Orlov <[email protected]> (cherry picked from commit bb8d2a5) # Conflicts: # rosbag2_transport/src/rosbag2_transport/recorder.cpp * Fix for merge conflicts Signed-off-by: Michael Orlov <[email protected]> --------- Signed-off-by: Michael Orlov <[email protected]> Co-authored-by: Michael Orlov <[email protected]>
1 parent c3456fe commit 07fd903

File tree

1 file changed

+33
-16
lines changed

1 file changed

+33
-16
lines changed

rosbag2_transport/src/rosbag2_transport/recorder.cpp

Lines changed: 33 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -163,12 +163,12 @@ void Recorder::record()
163163
});
164164
}
165165

166+
split_event_pub_ =
167+
create_publisher<rosbag2_interfaces::msg::WriteSplitEvent>("events/write_split", 1);
168+
166169
// Start the thread that will publish events
167170
event_publisher_thread_ = std::thread(&Recorder::event_publisher_thread_main, this);
168171

169-
split_event_pub_ = create_publisher<rosbag2_interfaces::msg::WriteSplitEvent>(
170-
"events/write_split",
171-
1);
172172
rosbag2_cpp::bag_events::WriterEventCallbacks callbacks;
173173
callbacks.write_split_callback =
174174
[this](rosbag2_cpp::bag_events::BagSplitInfo & info) {
@@ -210,7 +210,17 @@ void Recorder::event_publisher_thread_main()
210210
auto message = rosbag2_interfaces::msg::WriteSplitEvent();
211211
message.closed_file = bag_split_info_.closed_file;
212212
message.opened_file = bag_split_info_.opened_file;
213-
split_event_pub_->publish(message);
213+
try {
214+
split_event_pub_->publish(message);
215+
} catch (const std::exception & e) {
216+
RCLCPP_ERROR_STREAM(
217+
get_logger(),
218+
"Failed to publish message on '/events/write_split' topic. \nError: " << e.what());
219+
} catch (...) {
220+
RCLCPP_ERROR_STREAM(
221+
get_logger(),
222+
"Failed to publish message on '/events/write_split' topic.");
223+
}
214224
}
215225

216226
should_exit = event_publisher_thread_should_exit_;
@@ -272,19 +282,26 @@ void Recorder::topics_discovery()
272282
}
273283
}
274284
while (rclcpp::ok() && stop_discovery_ == false) {
275-
auto topics_to_subscribe =
276-
get_requested_or_available_topics();
277-
for (const auto & topic_and_type : topics_to_subscribe) {
278-
warn_if_new_qos_for_subscribed_topic(topic_and_type.first);
279-
}
280-
auto missing_topics = get_missing_topics(topics_to_subscribe);
281-
subscribe_topics(missing_topics);
285+
try {
286+
auto topics_to_subscribe = get_requested_or_available_topics();
287+
for (const auto & topic_and_type : topics_to_subscribe) {
288+
warn_if_new_qos_for_subscribed_topic(topic_and_type.first);
289+
}
290+
auto missing_topics = get_missing_topics(topics_to_subscribe);
291+
subscribe_topics(missing_topics);
282292

283-
if (!record_options_.topics.empty() && subscriptions_.size() == record_options_.topics.size()) {
284-
RCLCPP_INFO(
285-
this->get_logger(),
286-
"All requested topics are subscribed. Stopping discovery...");
287-
return;
293+
if (!record_options_.topics.empty() &&
294+
subscriptions_.size() == record_options_.topics.size())
295+
{
296+
RCLCPP_INFO(
297+
get_logger(),
298+
"All requested topics are subscribed. Stopping discovery...");
299+
return;
300+
}
301+
} catch (const std::exception & e) {
302+
RCLCPP_ERROR_STREAM(get_logger(), "Failure in topics discovery.\nError: " << e.what());
303+
} catch (...) {
304+
RCLCPP_ERROR_STREAM(get_logger(), "Failure in topics discovery.");
288305
}
289306
std::this_thread::sleep_for(record_options_.topic_polling_interval);
290307
}

0 commit comments

Comments
 (0)