@@ -82,7 +82,7 @@ class RecorderImpl
82
82
std::shared_ptr<rosbag2_cpp::Writer> writer_;
83
83
rosbag2_storage::StorageOptions storage_options_;
84
84
rosbag2_transport::RecordOptions record_options_;
85
- std::atomic<bool > stop_discovery_;
85
+ std::atomic<bool > stop_discovery_ = false ;
86
86
std::unordered_map<std::string, std::shared_ptr<rclcpp::SubscriptionBase>> subscriptions_;
87
87
88
88
private:
@@ -132,14 +132,15 @@ class RecorderImpl
132
132
rclcpp::Service<rosbag2_interfaces::srv::SplitBagfile>::SharedPtr srv_split_bagfile_;
133
133
134
134
std::atomic<bool > paused_ = false ;
135
+ std::atomic<bool > in_recording_ = false ;
135
136
std::shared_ptr<KeyboardHandler> keyboard_handler_;
136
137
KeyboardHandler::callback_handle_t toggle_paused_key_callback_handle_ =
137
138
KeyboardHandler::invalid_handle;
138
139
139
140
// Variables for event publishing
140
141
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 ;
143
144
rosbag2_cpp::bag_events::BagSplitInfo bag_split_info_;
144
145
std::mutex event_publisher_thread_mutex_;
145
146
std::condition_variable event_publisher_thread_wake_cv_;
@@ -185,12 +186,17 @@ RecorderImpl::~RecorderImpl()
185
186
stop ();
186
187
}
187
188
188
-
189
189
void RecorderImpl::stop ()
190
190
{
191
191
stop_discovery_ = true ;
192
192
if (discovery_future_.valid ()) {
193
- discovery_future_.wait ();
193
+ auto status = discovery_future_.wait_for (2 * record_options_.topic_polling_interval );
194
+ if (status != std::future_status::ready) {
195
+ RCLCPP_ERROR_STREAM (
196
+ node->get_logger (),
197
+ " discovery_future_.wait_for(" << record_options_.topic_polling_interval .count () <<
198
+ " ) return status: " << (status == std::future_status::timeout ? " timeout" : " deferred" ));
199
+ }
194
200
}
195
201
paused_ = true ;
196
202
subscriptions_.clear ();
@@ -204,10 +210,18 @@ void RecorderImpl::stop()
204
210
if (event_publisher_thread_.joinable ()) {
205
211
event_publisher_thread_.join ();
206
212
}
213
+ in_recording_ = false ;
214
+ RCLCPP_INFO (node->get_logger (), " Recording stopped" );
207
215
}
208
216
209
217
void RecorderImpl::record ()
210
218
{
219
+ if (in_recording_.exchange (true )) {
220
+ RCLCPP_WARN_STREAM (
221
+ node->get_logger (),
222
+ " Called Recorder::record() while already in recording, dismissing request." );
223
+ return ;
224
+ }
211
225
paused_ = record_options_.start_paused ;
212
226
topic_qos_profile_overrides_ = record_options_.topic_qos_profile_overrides ;
213
227
if (record_options_.rmw_serialization_format .empty ()) {
@@ -274,9 +288,8 @@ void RecorderImpl::record()
274
288
// Start the thread that will publish events
275
289
event_publisher_thread_ = std::thread (&RecorderImpl::event_publisher_thread_main, this );
276
290
277
- split_event_pub_ = node->create_publisher <rosbag2_interfaces::msg::WriteSplitEvent>(
278
- " events/write_split" ,
279
- 1 );
291
+ split_event_pub_ =
292
+ node->create_publisher <rosbag2_interfaces::msg::WriteSplitEvent>(" events/write_split" , 1 );
280
293
rosbag2_cpp::bag_events::WriterEventCallbacks callbacks;
281
294
callbacks.write_split_callback =
282
295
[this ](rosbag2_cpp::bag_events::BagSplitInfo & info) {
@@ -297,15 +310,13 @@ void RecorderImpl::record()
297
310
discovery_future_ =
298
311
std::async (std::launch::async, std::bind (&RecorderImpl::topics_discovery, this ));
299
312
}
313
+ RCLCPP_INFO (node->get_logger (), " Recording..." );
300
314
}
301
315
302
316
void RecorderImpl::event_publisher_thread_main ()
303
317
{
304
318
RCLCPP_INFO (node->get_logger (), " Event publisher thread: Starting" );
305
-
306
- bool should_exit = false ;
307
-
308
- while (!should_exit) {
319
+ while (!event_publisher_thread_should_exit_.load ()) {
309
320
std::unique_lock<std::mutex> lock (event_publisher_thread_mutex_);
310
321
event_publisher_thread_wake_cv_.wait (
311
322
lock,
@@ -319,10 +330,7 @@ void RecorderImpl::event_publisher_thread_main()
319
330
message.opened_file = bag_split_info_.opened_file ;
320
331
split_event_pub_->publish (message);
321
332
}
322
-
323
- should_exit = event_publisher_thread_should_exit_;
324
333
}
325
-
326
334
RCLCPP_INFO (node->get_logger (), " Event publisher thread: Exiting" );
327
335
}
328
336
0 commit comments