std::vector RollingRecorder::GetRosBagsToDelete()

in rosbag_cloud_recorders/src/rolling_recorder/rolling_recorder.cpp [99:130]


std::vector<std::string> RollingRecorder::GetRosBagsToDelete() const
{
  AWS_LOG_DEBUG(__func__, "Getting ros bags to delete");
  boost::filesystem::path dir_path(upload_request_data_->rolling_recorder_options_.write_directory);
  std::vector<std::string> delete_files;
  boost::system::error_code ec;
  for (boost::filesystem::directory_iterator itr(dir_path, ec);
       itr != boost::filesystem::directory_iterator(); ++itr) {
    if (ec.value() != 0) {
      AWS_LOGSTREAM_WARN(__func__, "boost::filesystem::directory_iterator errored with message: " << ec.message());
      break;
    }
    if (itr->path().extension().string() != ".bag") {
      continue;
    }
    const auto & file_path = itr->path().string();
    const auto & file_paths = upload_request_data_->recorder_status_.GetUploadGoal().files;
    if (file_paths.end() != std::find(file_paths.begin(), file_paths.end(), file_path)) {
      AWS_LOGSTREAM_DEBUG(__func__, "Skipping deletion of upload candidate: " << file_path);
      continue;
    }
    AWS_LOGSTREAM_DEBUG(__func__, "Checking path: " << file_path);
    auto bag_start_time = Utils::GetRosBagStartTime(file_path);
    AWS_LOGSTREAM_DEBUG(__func__, "Bag start time is: "<< bag_start_time);
    if (bag_start_time != ros::Time(0) && ros::Time::now() - bag_start_time > 
      upload_request_data_->rolling_recorder_options_.max_record_time) {
      AWS_LOGSTREAM_DEBUG(__func__, "Marking file for deletion: " << file_path);
      delete_files.emplace_back(file_path);
    }
  }
  return delete_files;
}