18 #ifndef STATE_ESTIMATION_NODES__STEADY_TIME_GRID_HPP_
19 #define STATE_ESTIMATION_NODES__STEADY_TIME_GRID_HPP_
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} {}
68 const std::chrono::system_clock::time_point & current_timestamp)
const noexcept
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;
82 return m_first_measurement_timestamp > std::chrono::system_clock::time_point{};
87 std::chrono::system_clock::time_point m_first_measurement_timestamp{};
89 std::chrono::system_clock::duration m_interval_between_timestamps{};
96 #endif // STATE_ESTIMATION_NODES__STEADY_TIME_GRID_HPP_