in rosbag_cloud_recorders/src/utils/recorder.cpp [557:595]
void Recorder::DoRecordSnapshotter() {
ros::NodeHandle nh;
while (nh.ok() || !queue_queue_.empty()) {
boost::unique_lock<boost::mutex> lock(queue_mutex_);
while (queue_queue_.empty()) {
if (!nh.ok())
{
return;
}
queue_condition_.wait(lock);
}
OutgoingQueue out_queue = queue_queue_.front();
queue_queue_.pop();
lock.release()->unlock();
string target_filename = out_queue.filename;
string write_filename = target_filename + string(".active");
try {
bag_.open(write_filename, rosbag::bagmode::Write);
}
catch (const rosbag::BagException& ex) {
ROS_ERROR("Error writing: %s", ex.what());
return;
}
while (!out_queue.queue->empty()) {
OutgoingMessage out = out_queue.queue->front();
out_queue.queue->pop();
bag_.write(out.topic, out.time, *out.msg);
}
StopWriting();
}
}