源码可在https://github.com/learnmoreonce/SLAM 下载
common/time.h
/*
预备知识:
c++11 提供了语言级别的时间函数.包括duration和time_point
duration是时间段,指的是某单位时间上的一个明确的tick(片刻数):
3分钟->"3个1分钟",
1.5个"1/3秒" :1.5是tick,1/3秒是时间单位
time_point是一个duration和一个epoch(起点)的组合:
2017年5月4日是"自1970,01,01"以来的126200000秒数
common/time.h主要功能是提供时间转换函数:
*/
#ifndef CARTOGRAPHER_COMMON_TIME_H_
#define CARTOGRAPHER_COMMON_TIME_H_
#include <chrono>
#include <ostream>
#include <ratio>
#include "cartographer/common/port.h"
namespace cartographer {
namespace common {
//719162 是0001年1月1日到1970年1月1日所经历的天数
constexpr int64 kUtsEpochOffsetFromUnixEpochInSeconds =
(719162ll * 24ll * 60ll * 60ll);
struct UniversalTimeScaleClock {
using rep = int64;
using period = std::ratio<1, 10000000>; //百万分之一秒,1us 》错了&#