20 #ifndef STATE_ESTIMATION_NODES__STEADY_TIME_GRID_HPP_
21 #define STATE_ESTIMATION_NODES__STEADY_TIME_GRID_HPP_
31 namespace state_estimation
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} {}
70 const std::chrono::system_clock::time_point & current_timestamp)
const noexcept
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;
84 return m_first_measurement_timestamp > std::chrono::system_clock::time_point{};
89 std::chrono::system_clock::time_point m_first_measurement_timestamp{};
91 std::chrono::system_clock::duration m_interval_between_timestamps{};
99 #endif // STATE_ESTIMATION_NODES__STEADY_TIME_GRID_HPP_