@@ -82,7 +82,7 @@ class RecorderImpl
8282 std::shared_ptr<rosbag2_cpp::Writer> writer_;
8383 rosbag2_storage::StorageOptions storage_options_;
8484 rosbag2_transport::RecordOptions record_options_;
85- std::atomic<bool > stop_discovery_;
85+ std::atomic<bool > stop_discovery_ = false ;
8686 std::unordered_map<std::string, std::shared_ptr<rclcpp::SubscriptionBase>> subscriptions_;
8787
8888private:
@@ -132,14 +132,15 @@ class RecorderImpl
132132 rclcpp::Service<rosbag2_interfaces::srv::SplitBagfile>::SharedPtr srv_split_bagfile_;
133133
134134 std::atomic<bool > paused_ = false ;
135+ std::atomic<bool > in_recording_ = false ;
135136 std::shared_ptr<KeyboardHandler> keyboard_handler_;
136137 KeyboardHandler::callback_handle_t toggle_paused_key_callback_handle_ =
137138 KeyboardHandler::invalid_handle;
138139
139140 // Variables for event publishing
140141 rclcpp::Publisher<rosbag2_interfaces::msg::WriteSplitEvent>::SharedPtr split_event_pub_;
141- bool event_publisher_thread_should_exit_ = false ;
142- bool write_split_has_occurred_ = false ;
142+ std::atomic< bool > event_publisher_thread_should_exit_ = false ;
143+ std::atomic< bool > write_split_has_occurred_ = false ;
143144 rosbag2_cpp::bag_events::BagSplitInfo bag_split_info_;
144145 std::mutex event_publisher_thread_mutex_;
145146 std::condition_variable event_publisher_thread_wake_cv_;
@@ -191,12 +192,17 @@ RecorderImpl::~RecorderImpl()
191192 stop ();
192193}
193194
194-
195195void RecorderImpl::stop ()
196196{
197197 stop_discovery_ = true ;
198198 if (discovery_future_.valid ()) {
199- discovery_future_.wait ();
199+ auto status = discovery_future_.wait_for (2 * record_options_.topic_polling_interval );
200+ if (status != std::future_status::ready) {
201+ RCLCPP_ERROR_STREAM (
202+ node->get_logger (),
203+ " discovery_future_.wait_for(" << record_options_.topic_polling_interval .count () <<
204+ " ) return status: " << (status == std::future_status::timeout ? " timeout" : " deferred" ));
205+ }
200206 }
201207 paused_ = true ;
202208 subscriptions_.clear ();
@@ -210,10 +216,18 @@ void RecorderImpl::stop()
210216 if (event_publisher_thread_.joinable ()) {
211217 event_publisher_thread_.join ();
212218 }
219+ in_recording_ = false ;
220+ RCLCPP_INFO (node->get_logger (), " Recording stopped" );
213221}
214222
215223void RecorderImpl::record ()
216224{
225+ if (in_recording_.exchange (true )) {
226+ RCLCPP_WARN_STREAM (
227+ node->get_logger (),
228+ " Called Recorder::record() while already in recording, dismissing request." );
229+ return ;
230+ }
217231 paused_ = record_options_.start_paused ;
218232 stop_discovery_ = record_options_.is_discovery_disabled ;
219233 topic_qos_profile_overrides_ = record_options_.topic_qos_profile_overrides ;
@@ -281,9 +295,8 @@ void RecorderImpl::record()
281295 // Start the thread that will publish events
282296 event_publisher_thread_ = std::thread (&RecorderImpl::event_publisher_thread_main, this );
283297
284- split_event_pub_ = node->create_publisher <rosbag2_interfaces::msg::WriteSplitEvent>(
285- " events/write_split" ,
286- 1 );
298+ split_event_pub_ =
299+ node->create_publisher <rosbag2_interfaces::msg::WriteSplitEvent>(" events/write_split" , 1 );
287300 rosbag2_cpp::bag_events::WriterEventCallbacks callbacks;
288301 callbacks.write_split_callback =
289302 [this ](rosbag2_cpp::bag_events::BagSplitInfo & info) {
@@ -305,15 +318,13 @@ void RecorderImpl::record()
305318 discovery_future_ =
306319 std::async (std::launch::async, std::bind (&RecorderImpl::topics_discovery, this ));
307320 }
321+ RCLCPP_INFO (node->get_logger (), " Recording..." );
308322}
309323
310324void RecorderImpl::event_publisher_thread_main ()
311325{
312326 RCLCPP_INFO (node->get_logger (), " Event publisher thread: Starting" );
313-
314- bool should_exit = false ;
315-
316- while (!should_exit) {
327+ while (!event_publisher_thread_should_exit_.load ()) {
317328 std::unique_lock<std::mutex> lock (event_publisher_thread_mutex_);
318329 event_publisher_thread_wake_cv_.wait (
319330 lock,
@@ -327,10 +338,7 @@ void RecorderImpl::event_publisher_thread_main()
327338 message.opened_file = bag_split_info_.opened_file ;
328339 split_event_pub_->publish (message);
329340 }
330-
331- should_exit = event_publisher_thread_should_exit_;
332341 }
333-
334342 RCLCPP_INFO (node->get_logger (), " Event publisher thread: Exiting" );
335343}
336344
0 commit comments