ros::Time GetRosBagStartTime()

in rosbag_cloud_recorders/src/utils/file_utils.cpp [119:179]


ros::Time GetRosBagStartTime(const std::string& file_path)
{
  // Get the file name
  std::string file_name = file_path;
  size_t index = file_path.find_last_of('/');
  if (index != std::string::npos) {
    file_name = file_path.substr(index+1);
  }

  // Strip bag number if it exists
  std::string bag_name = file_name;
  index = file_path.find_last_of('_');
  if (index != std::string::npos) {
    bag_name = file_name.substr(0, index);
  }

  // If bag extension wasn't stripped before, remove it now
  std::string ts_unparsed = bag_name;
  index = file_path.find_last_of('.');
  if (index != std::string::npos) {
    ts_unparsed = bag_name.substr(0, index);
  }
  
  // Pull the timestamp out of the remaining string
  std::regex time_stamp_regex(R"([0-9]{4}-[0-9]{2}-[0-9]{2}-[0-9]{2}-[0-9]{2}-[0-9]{2})");
  std::smatch match;
  auto ts_begin = std::sregex_iterator(ts_unparsed.begin(), ts_unparsed.end(), time_stamp_regex);
  auto ts_end = std::sregex_iterator();
  while (ts_begin != ts_end) {
    match = *ts_begin;
    ts_begin++;
  }
  if (match.empty()) {
    AWS_LOGSTREAM_WARN(__func__, "Could not find timestamp in rosbag filename via regex");
    return {};
  }
  std::string time_stamp = match.str(0);

  // Convert time stamp to ros time
  auto input_facet = new boost::posix_time::time_input_facet(kRosBagFileFormat);
  std::stringstream ss;
  ss.imbue(std::locale(ss.getloc(), input_facet));
  ss.str(time_stamp);
  boost::posix_time::ptime pt;
  ss >> pt;

  if (pt == boost::posix_time::ptime()) {
    AWS_LOGSTREAM_WARN(__func__, "Parsing rosbag file timestamp failed");
    return {};
  }

  boost::posix_time::ptime utc_pt = pt - GetUTCOffset();

  try {
    // This can throw an exception if the time is too far in the future.
    return ros::Time::fromBoost(utc_pt);
  } catch (std::exception& e) {
    AWS_LOGSTREAM_WARN(__func__, "Parsing rosbag file timestamp threw exception: " << e.what());
    return {};
  }
}