Autoware.Auto
steady_time_grid.hpp
Go to the documentation of this file.
1 // Copyright 2021 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__STEADY_TIME_GRID_HPP_
19 #define STATE_ESTIMATION_NODES__STEADY_TIME_GRID_HPP_
20 
22 
23 #include <algorithm>
24 #include <chrono>
25 #include <utility>
26 
27 namespace autoware
28 {
29 namespace prediction
30 {
31 
40 {
41 public:
45  SteadyTimeGrid() = default;
46 
55  const std::chrono::system_clock::time_point & measurement_timestamp,
56  const std::chrono::system_clock::duration & interval_between_timestamps)
57  : m_first_measurement_timestamp{measurement_timestamp},
58  m_interval_between_timestamps{interval_between_timestamps} {}
59 
67  inline std::chrono::system_clock::time_point get_next_timestamp_after(
68  const std::chrono::system_clock::time_point & current_timestamp) const noexcept
69  {
70  const auto prev_time_index =
71  (current_timestamp - m_first_measurement_timestamp) / m_interval_between_timestamps;
72  return m_first_measurement_timestamp + (prev_time_index + 1L) * m_interval_between_timestamps;
73  }
74 
80  inline bool is_initialized() const noexcept
81  {
82  return m_first_measurement_timestamp > std::chrono::system_clock::time_point{};
83  }
84 
85 private:
87  std::chrono::system_clock::time_point m_first_measurement_timestamp{};
89  std::chrono::system_clock::duration m_interval_between_timestamps{};
90 };
91 
92 
93 } // namespace prediction
94 } // namespace autoware
95 
96 #endif // STATE_ESTIMATION_NODES__STEADY_TIME_GRID_HPP_
std::chrono::system_clock::time_point get_next_timestamp_after(const std::chrono::system_clock::time_point &current_timestamp) const noexcept
Get the next timestamp on the grid given a query one.
Definition: steady_time_grid.hpp:67
bool is_initialized() const noexcept
Determine if initialized with a non-zero timestamp.
Definition: steady_time_grid.hpp:80
SteadyTimeGrid(const std::chrono::system_clock::time_point &measurement_timestamp, const std::chrono::system_clock::duration &interval_between_timestamps)
Constructs a new instance from the time the event has occurred (measurement was received) and its tim...
Definition: steady_time_grid.hpp:54
SteadyTimeGrid()=default
Allow empty initialization.
This is a utility class that allows querying timestamps on a 1D grid.
Definition: steady_time_grid.hpp:39
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24