|
Autoware.Auto
|
|
This is a time storage class that keeps the time with respect to the clock that timestamped the last measurement. More...
#include <measurement_time_keeper.hpp>
Public Member Functions | |
| MeasurementBasedTimeKeeper ()=default | |
| Allow empty initialization. More... | |
| MeasurementBasedTimeKeeper (const GlobalTime &time_of_event, const MeasurementBasedTime ×tamp) | |
| Constructs a new instance from the time the event has occured (measurement was received) and its timestamp. More... | |
| common::types::bool8_t | is_initialized () const noexcept |
| Determines if initialized with proper timestamps. More... | |
| template<typename MeasurementT > | |
| void | update_with_measurement (const GlobalTime &time_of_event, const MeasurementT &measurement) |
| Update when a new measurement is received. This changes the base of calculation of the local time. More... | |
| MeasurementBasedTime::duration | time_since_last_temporal_update (const GlobalTime &time_point) const noexcept |
| Get the time since the last temporal update in measurement clock frame. More... | |
| MeasurementBasedTime::duration | time_since_last_temporal_update (const MeasurementBasedTime &time_point) const noexcept |
| Get the time since the last temporal update. More... | |
| void | increment_last_temporal_update_time (const MeasurementBasedTime::duration &time_since_last_update) noexcept |
| Increment the time of last temporal update by a given amount. More... | |
| MeasurementBasedTime | latest_timestamp () const noexcept |
| Get the latest stored timestamp. More... | |
This is a time storage class that keeps the time with respect to the clock that timestamped the last measurement.
All the local times are with respect to the clock that timestamped the last measurement, the global time is reported by the global system clock of the system that received the message.
|
default |
Allow empty initialization.
|
inline |
Constructs a new instance from the time the event has occured (measurement was received) and its timestamp.
| [in] | time_of_event | The time of event occurance (measurement received). |
| [in] | timestamp | The timestamp of the message. |
|
inlinenoexcept |
Increment the time of last temporal update by a given amount.
| [in] | time_since_last_update | The time passed since last update. |
|
inlinenoexcept |
Determines if initialized with proper timestamps.
|
inlinenoexcept |
Get the latest stored timestamp.
|
inlinenoexcept |
Get the time since the last temporal update in measurement clock frame.
| [in] | time_point | The global time of the update reported by the clock. |
|
inlinenoexcept |
Get the time since the last temporal update.
| [in] | time_point | The time of the update reported in the measurement clock frame. |
|
inline |
Update when a new measurement is received. This changes the base of calculation of the local time.
| [in] | time_of_event | The time of event occurance (time of message received). |
| [in] | measurement | The measurement |
| MeasurementT | Type of measurement. |