@@ -285,11 +285,12 @@ void RecorderImpl::record()
285285 response->paused = is_paused ();
286286 });
287287
288+ split_event_pub_ =
289+ node->create_publisher <rosbag2_interfaces::msg::WriteSplitEvent>(" events/write_split" , 1 );
290+
288291 // Start the thread that will publish events
289292 event_publisher_thread_ = std::thread (&RecorderImpl::event_publisher_thread_main, this );
290293
291- split_event_pub_ =
292- node->create_publisher <rosbag2_interfaces::msg::WriteSplitEvent>(" events/write_split" , 1 );
293294 rosbag2_cpp::bag_events::WriterEventCallbacks callbacks;
294295 callbacks.write_split_callback =
295296 [this ](rosbag2_cpp::bag_events::BagSplitInfo & info) {
@@ -328,7 +329,17 @@ void RecorderImpl::event_publisher_thread_main()
328329 auto message = rosbag2_interfaces::msg::WriteSplitEvent ();
329330 message.closed_file = bag_split_info_.closed_file ;
330331 message.opened_file = bag_split_info_.opened_file ;
331- split_event_pub_->publish (message);
332+ try {
333+ split_event_pub_->publish (message);
334+ } catch (const std::exception & e) {
335+ RCLCPP_ERROR_STREAM (
336+ node->get_logger (),
337+ " Failed to publish message on '/events/write_split' topic. \n Error: " << e.what ());
338+ } catch (...) {
339+ RCLCPP_ERROR_STREAM (
340+ node->get_logger (),
341+ " Failed to publish message on '/events/write_split' topic." );
342+ }
332343 }
333344 }
334345 RCLCPP_INFO (node->get_logger (), " Event publisher thread: Exiting" );
@@ -373,19 +384,26 @@ bool RecorderImpl::is_paused()
373384void RecorderImpl::topics_discovery ()
374385{
375386 while (rclcpp::ok () && stop_discovery_ == false ) {
376- auto topics_to_subscribe =
377- get_requested_or_available_topics ();
378- for (const auto & topic_and_type : topics_to_subscribe) {
379- warn_if_new_qos_for_subscribed_topic (topic_and_type.first );
380- }
381- auto missing_topics = get_missing_topics (topics_to_subscribe);
382- subscribe_topics (missing_topics);
387+ try {
388+ auto topics_to_subscribe = get_requested_or_available_topics ();
389+ for (const auto & topic_and_type : topics_to_subscribe) {
390+ warn_if_new_qos_for_subscribed_topic (topic_and_type.first );
391+ }
392+ auto missing_topics = get_missing_topics (topics_to_subscribe);
393+ subscribe_topics (missing_topics);
383394
384- if (!record_options_.topics .empty () && subscriptions_.size () == record_options_.topics .size ()) {
385- RCLCPP_INFO (
386- node->get_logger (),
387- " All requested topics are subscribed. Stopping discovery..." );
388- return ;
395+ if (!record_options_.topics .empty () &&
396+ subscriptions_.size () == record_options_.topics .size ())
397+ {
398+ RCLCPP_INFO (
399+ node->get_logger (),
400+ " All requested topics are subscribed. Stopping discovery..." );
401+ return ;
402+ }
403+ } catch (const std::exception & e) {
404+ RCLCPP_ERROR_STREAM (node->get_logger (), " Failure in topics discovery.\n Error: " << e.what ());
405+ } catch (...) {
406+ RCLCPP_ERROR_STREAM (node->get_logger (), " Failure in topics discovery." );
389407 }
390408 std::this_thread::sleep_for (record_options_.topic_polling_interval );
391409 }
0 commit comments