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 //
15 // Co-developed by Tier IV, Inc. and Apex.AI, Inc.
16 
19 
20 #ifndef STATE_ESTIMATION_NODES__STEADY_TIME_GRID_HPP_
21 #define STATE_ESTIMATION_NODES__STEADY_TIME_GRID_HPP_
22 
23 #include <algorithm>
24 #include <chrono>
25 #include <utility>
26 
27 namespace autoware
28 {
29 namespace common
30 {
31 namespace state_estimation
32 {
33 
42 {
43 public:
47  SteadyTimeGrid() = default;
48 
57  const std::chrono::system_clock::time_point & measurement_timestamp,
58  const std::chrono::system_clock::duration & interval_between_timestamps)
59  : m_first_measurement_timestamp{measurement_timestamp},
60  m_interval_between_timestamps{interval_between_timestamps} {}
61 
69  inline std::chrono::system_clock::time_point get_next_timestamp_after(
70  const std::chrono::system_clock::time_point & current_timestamp) const noexcept
71  {
72  const auto prev_time_index =
73  (current_timestamp - m_first_measurement_timestamp) / m_interval_between_timestamps;
74  return m_first_measurement_timestamp + (prev_time_index + 1L) * m_interval_between_timestamps;
75  }
76 
82  inline bool is_initialized() const noexcept
83  {
84  return m_first_measurement_timestamp > std::chrono::system_clock::time_point{};
85  }
86 
87 private:
89  std::chrono::system_clock::time_point m_first_measurement_timestamp{};
91  std::chrono::system_clock::duration m_interval_between_timestamps{};
92 };
93 
94 
95 } // namespace state_estimation
96 } // namespace common
97 } // namespace autoware
98 
99 #endif // STATE_ESTIMATION_NODES__STEADY_TIME_GRID_HPP_
autoware::common::state_estimation::SteadyTimeGrid::get_next_timestamp_after
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:69
autoware::common::state_estimation::SteadyTimeGrid::SteadyTimeGrid
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:56
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::common::state_estimation::SteadyTimeGrid
This is a utility class that allows querying timestamps on a 1D grid.
Definition: steady_time_grid.hpp:41
autoware::common::state_estimation::SteadyTimeGrid::is_initialized
bool is_initialized() const noexcept
Determine if initialized with a non-zero timestamp.
Definition: steady_time_grid.hpp:82
autoware::common::state_estimation::SteadyTimeGrid::SteadyTimeGrid
SteadyTimeGrid()=default
Allow empty initialization.