time.h
Go to the documentation of this file.
1 /*
2  * Copyright 2016 The Cartographer Authors
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 #ifndef CARTOGRAPHER_COMMON_TIME_H_
18 #define CARTOGRAPHER_COMMON_TIME_H_
19 
20 #include <chrono>
21 #include <ostream>
22 #include <ratio>
23 
25 
26 namespace cartographer {
27 namespace common {
28 
30  (719162ll * 24ll * 60ll * 60ll);
31 
33  using rep = int64;
34  using period = std::ratio<1, 10000000>;
35  using duration = std::chrono::duration<rep, period>;
36  using time_point = std::chrono::time_point<UniversalTimeScaleClock>;
37  static constexpr bool is_steady = true;
38 };
39 
40 // Represents Universal Time Scale durations and timestamps which are 64-bit
41 // integers representing the 100 nanosecond ticks since the Epoch which is
42 // January 1, 1 at the start of day in UTC.
45 
46 // Convenience functions to create common::Durations.
47 Duration FromSeconds(double seconds);
48 Duration FromMilliseconds(int64 milliseconds);
49 
50 // Returns the given duration in seconds.
52 
53 // Creates a time from a Universal Time Scale.
54 Time FromUniversal(int64 ticks);
55 
56 // Outputs the Universal Time Scale timestamp for a given Time.
58 
59 // For logging and unit tests, outputs the timestamp integer.
60 std::ostream& operator<<(std::ostream& os, Time time);
61 
62 } // namespace common
63 } // namespace cartographer
64 
65 #endif // CARTOGRAPHER_COMMON_TIME_H_
common::Duration FromMilliseconds(const int64 milliseconds)
Definition: time.cc:43
std::ostream & operator<<(std::ostream &os, const Time time)
Definition: time.cc:38
constexpr int64 kUtsEpochOffsetFromUnixEpochInSeconds
Definition: time.h:29
std::ratio< 1, 10000000 > period
Definition: time.h:34
UniversalTimeScaleClock::time_point Time
Definition: time.h:44
Time FromUniversal(const int64 ticks)
Definition: time.cc:34
Duration FromSeconds(const double seconds)
Definition: time.cc:24
UniversalTimeScaleClock::duration Duration
Definition: time.h:43
std::chrono::time_point< UniversalTimeScaleClock > time_point
Definition: time.h:36
std::chrono::duration< rep, period > duration
Definition: time.h:35
int64 ToUniversal(const Time time)
Definition: time.cc:36
double ToSeconds(const Duration duration)
Definition: time.cc:29
int64_t int64
Definition: port.h:31


cartographer
Author(s):
autogenerated on Wed Jun 5 2019 21:57:59