Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 #ifndef CARTOGRAPHER_COMMON_TIME_H_
00018 #define CARTOGRAPHER_COMMON_TIME_H_
00019
00020 #include <chrono>
00021 #include <ostream>
00022 #include <ratio>
00023
00024 #include "cartographer/common/port.h"
00025
00026 namespace cartographer {
00027 namespace common {
00028
00029 constexpr int64 kUtsEpochOffsetFromUnixEpochInSeconds =
00030 (719162ll * 24ll * 60ll * 60ll);
00031
00032 struct UniversalTimeScaleClock {
00033 using rep = int64;
00034 using period = std::ratio<1, 10000000>;
00035 using duration = std::chrono::duration<rep, period>;
00036 using time_point = std::chrono::time_point<UniversalTimeScaleClock>;
00037 static constexpr bool is_steady = true;
00038 };
00039
00040
00041
00042
00043 using Duration = UniversalTimeScaleClock::duration;
00044 using Time = UniversalTimeScaleClock::time_point;
00045
00046
00047 Duration FromSeconds(double seconds);
00048 Duration FromMilliseconds(int64 milliseconds);
00049
00050
00051 double ToSeconds(Duration duration);
00052 double ToSeconds(std::chrono::steady_clock::duration duration);
00053
00054
00055 Time FromUniversal(int64 ticks);
00056
00057
00058 int64 ToUniversal(Time time);
00059
00060
00061 std::ostream& operator<<(std::ostream& os, Time time);
00062
00063
00064 double GetThreadCpuTimeSeconds();
00065
00066 }
00067 }
00068
00069 #endif // CARTOGRAPHER_COMMON_TIME_H_