Autoware.Auto
autoware::prediction::MeasurementBasedTimeKeeper Class Reference

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 &timestamp)
 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...
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ MeasurementBasedTimeKeeper() [1/2]

autoware::prediction::MeasurementBasedTimeKeeper::MeasurementBasedTimeKeeper ( )
default

Allow empty initialization.

◆ MeasurementBasedTimeKeeper() [2/2]

autoware::prediction::MeasurementBasedTimeKeeper::MeasurementBasedTimeKeeper ( const GlobalTime time_of_event,
const MeasurementBasedTime timestamp 
)
inline

Constructs a new instance from the time the event has occured (measurement was received) and its timestamp.

Parameters
[in]time_of_eventThe time of event occurance (measurement received).
[in]timestampThe timestamp of the message.

Member Function Documentation

◆ increment_last_temporal_update_time()

void autoware::prediction::MeasurementBasedTimeKeeper::increment_last_temporal_update_time ( const MeasurementBasedTime::duration &  time_since_last_update)
inlinenoexcept

Increment the time of last temporal update by a given amount.

Parameters
[in]time_since_last_updateThe time passed since last update.

◆ is_initialized()

common::types::bool8_t autoware::prediction::MeasurementBasedTimeKeeper::is_initialized ( ) const
inlinenoexcept

Determines if initialized with proper timestamps.

Returns
True if initialized, False otherwise.

◆ latest_timestamp()

MeasurementBasedTime autoware::prediction::MeasurementBasedTimeKeeper::latest_timestamp ( ) const
inlinenoexcept

Get the latest stored timestamp.

Returns
The latest time with respect to the clock that timestamped the measurement.

◆ time_since_last_temporal_update() [1/2]

MeasurementBasedTime::duration autoware::prediction::MeasurementBasedTimeKeeper::time_since_last_temporal_update ( const GlobalTime time_point) const
inlinenoexcept

Get the time since the last temporal update in measurement clock frame.

Parameters
[in]time_pointThe global time of the update reported by the clock.
Returns
Returns the duration that passed since the last temporal update.

◆ time_since_last_temporal_update() [2/2]

MeasurementBasedTime::duration autoware::prediction::MeasurementBasedTimeKeeper::time_since_last_temporal_update ( const MeasurementBasedTime time_point) const
inlinenoexcept

Get the time since the last temporal update.

Parameters
[in]time_pointThe time of the update reported in the measurement clock frame.
Returns
Returns the duration that passed since the last temporal update.

◆ update_with_measurement()

template<typename MeasurementT >
void autoware::prediction::MeasurementBasedTimeKeeper::update_with_measurement ( const GlobalTime time_of_event,
const MeasurementT &  measurement 
)
inline

Update when a new measurement is received. This changes the base of calculation of the local time.

Parameters
[in]time_of_eventThe time of event occurance (time of message received).
[in]measurementThe measurement
Template Parameters
MeasurementTType of measurement.

The documentation for this class was generated from the following file: