Skip to content

Commit bb8d2a5

Browse files
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]>
1 parent 46a23e9 commit bb8d2a5

File tree

1 file changed

+33
-15
lines changed

1 file changed

+33
-15
lines changed

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

+33-15
Original file line numberDiff line numberDiff line change
@@ -292,11 +292,12 @@ void RecorderImpl::record()
292292
response->paused = is_paused();
293293
});
294294

295+
split_event_pub_ =
296+
node->create_publisher<rosbag2_interfaces::msg::WriteSplitEvent>("events/write_split", 1);
297+
295298
// Start the thread that will publish events
296299
event_publisher_thread_ = std::thread(&RecorderImpl::event_publisher_thread_main, this);
297300

298-
split_event_pub_ =
299-
node->create_publisher<rosbag2_interfaces::msg::WriteSplitEvent>("events/write_split", 1);
300301
rosbag2_cpp::bag_events::WriterEventCallbacks callbacks;
301302
callbacks.write_split_callback =
302303
[this](rosbag2_cpp::bag_events::BagSplitInfo & info) {
@@ -336,7 +337,17 @@ void RecorderImpl::event_publisher_thread_main()
336337
auto message = rosbag2_interfaces::msg::WriteSplitEvent();
337338
message.closed_file = bag_split_info_.closed_file;
338339
message.opened_file = bag_split_info_.opened_file;
339-
split_event_pub_->publish(message);
340+
try {
341+
split_event_pub_->publish(message);
342+
} catch (const std::exception & e) {
343+
RCLCPP_ERROR_STREAM(
344+
node->get_logger(),
345+
"Failed to publish message on '/events/write_split' topic. \nError: " << e.what());
346+
} catch (...) {
347+
RCLCPP_ERROR_STREAM(
348+
node->get_logger(),
349+
"Failed to publish message on '/events/write_split' topic.");
350+
}
340351
}
341352
}
342353
RCLCPP_INFO(node->get_logger(), "Event publisher thread: Exiting");
@@ -395,19 +406,26 @@ void RecorderImpl::topics_discovery()
395406
}
396407
}
397408
while (rclcpp::ok() && stop_discovery_ == false) {
398-
auto topics_to_subscribe =
399-
get_requested_or_available_topics();
400-
for (const auto & topic_and_type : topics_to_subscribe) {
401-
warn_if_new_qos_for_subscribed_topic(topic_and_type.first);
402-
}
403-
auto missing_topics = get_missing_topics(topics_to_subscribe);
404-
subscribe_topics(missing_topics);
409+
try {
410+
auto topics_to_subscribe = get_requested_or_available_topics();
411+
for (const auto & topic_and_type : topics_to_subscribe) {
412+
warn_if_new_qos_for_subscribed_topic(topic_and_type.first);
413+
}
414+
auto missing_topics = get_missing_topics(topics_to_subscribe);
415+
subscribe_topics(missing_topics);
405416

406-
if (!record_options_.topics.empty() && subscriptions_.size() == record_options_.topics.size()) {
407-
RCLCPP_INFO(
408-
node->get_logger(),
409-
"All requested topics are subscribed. Stopping discovery...");
410-
return;
417+
if (!record_options_.topics.empty() &&
418+
subscriptions_.size() == record_options_.topics.size())
419+
{
420+
RCLCPP_INFO(
421+
node->get_logger(),
422+
"All requested topics are subscribed. Stopping discovery...");
423+
return;
424+
}
425+
} catch (const std::exception & e) {
426+
RCLCPP_ERROR_STREAM(node->get_logger(), "Failure in topics discovery.\nError: " << e.what());
427+
} catch (...) {
428+
RCLCPP_ERROR_STREAM(node->get_logger(), "Failure in topics discovery.");
411429
}
412430
std::this_thread::sleep_for(record_options_.topic_polling_interval);
413431
}

0 commit comments

Comments
 (0)