Autoware.Auto
time.hpp
Go to the documentation of this file.
1 // Copyright 2020 Apex.AI, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 //    http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
17 
18 #ifndef STATE_ESTIMATION_NODES__TIME_HPP_
19 #define STATE_ESTIMATION_NODES__TIME_HPP_
20 
21 
22 #include <common/types.hpp>
23 
24 #include <chrono>
25 #include <utility>
26 
27 namespace autoware
28 {
29 namespace prediction
30 {
31 
37 {
38  kGlobal,
40 };
41 
47 template<TimeReferenceFrame kTimeReferenceFrame>
48 class Time : public std::chrono::system_clock::time_point
49 {
50  using Base = std::chrono::system_clock::time_point;
51 
52 public:
54  Time() = default;
60  explicit Time(const Base & time_point)
61  : Base{time_point} {}
68  {
69  return time_since_epoch() > Time::duration{0LL};
70  }
71 
77  friend Time operator+(Time time_1, const Time & time_2)
78  {
79  return Time{time_1 + time_2.time_since_epoch()};
80  }
81 
103  template<typename IntT, typename DurationT>
104  friend Time operator+(const Time & time, const std::chrono::duration<IntT, DurationT> & duration)
105  {
106  return Time{static_cast<const Base &>(time) + duration};
107  }
108 
130  template<typename IntT, typename DurationT>
131  friend Time operator-(const Time & time, const std::chrono::duration<IntT, DurationT> & duration)
132  {
133  return Time{static_cast<const Base &>(time) - duration};
134  }
135 };
136 
141 
142 
143 } // namespace prediction
144 } // namespace autoware
145 
146 #endif // STATE_ESTIMATION_NODES__TIME_HPP_
autoware::prediction::TimeReferenceFrame::kMeasurement
@ kMeasurement
types.hpp
This file includes common type definition.
autoware::prediction::Time::Time
Time()=default
Default contructor.
autoware::prediction::Time
This class describes a time point with respect to some time reference frame.
Definition: time.hpp:48
autoware::common::types::bool8_t
bool bool8_t
Definition: types.hpp:33
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::prediction::TimeReferenceFrame
TimeReferenceFrame
This class describes a time reference frame. This is used to define in which clock a particular time ...
Definition: time.hpp:36
autoware::prediction::TimeReferenceFrame::kGlobal
@ kGlobal
autoware::prediction::Time::Time
Time(const Base &time_point)
Constructs a new instance from a time_point.
Definition: time.hpp:60
autoware::prediction::Time::is_valid
common::types::bool8_t is_valid() const noexcept
Determines if the stored time_point is valid.
Definition: time.hpp:67
autoware::prediction::Time::operator+
friend Time operator+(const Time &time, const std::chrono::duration< IntT, DurationT > &duration)
Overload operator +.
Definition: time.hpp:104
autoware::prediction::Time::operator-
friend Time operator-(const Time &time, const std::chrono::duration< IntT, DurationT > &duration)
Overload operator -.
Definition: time.hpp:131
autoware::prediction::Time::operator+
friend Time operator+(Time time_1, const Time &time_2)
Add an operator + for two time points.
Definition: time.hpp:77