Autoware.Auto
autoware::prediction::History< FilterT, kNumOfStates, EventT > Class Template Reference

This class encapsulates a history of events used with EKF. More...

#include <history.hpp>

Classes

class  EkfStateUpdater
 
class  HistoryEntry
 

Public Member Functions

 History (FilterT &filter, const std::size_t max_history_size, const common::types::float32_t mahalanobis_threshold)
 Construct history from a filter pointer with a specific size. More...
 
void emplace_event (const Timestamp &timestamp, const HistoryEntry &entry)
 Add an event to history. If it is added to the middle the following ones are automatically replayed on top of it. More...
 
bool empty () const noexcept
 Check if the history is empty. More...
 
std::size_t size () const noexcept
 Get size of history. More...
 
const Timestamp & get_last_timestamp () const noexcept
 Get last timestamp in history. More...
 
const HistoryEntryget_last_event () const noexcept
 Get last event in history. More...
 
const FilterT & get_filter () const noexcept
 Get the filter as a const ref. More...
 
FilterT & get_filter () noexcept
 Get the filter. More...
 

Detailed Description

template<typename FilterT, std::int32_t kNumOfStates, typename ... EventT>
class autoware::prediction::History< FilterT, kNumOfStates, EventT >

This class encapsulates a history of events used with EKF.

        The class handles adding events to a history of a specified size. It models the
        behavior of a circular buffer, meaning that as new events come in, the oldest ones
        are removed. The events can be either measurement types or specific events like
        reset or prediction. Whenever an event is added to the middle of the history all the
        following events get rolled on top of this event to produce a new state.
Template Parameters
FilterTType of EKF filter used.
kNumOfStatesDimensionality of the state in the filter.
EventTA variadic template of all possible events.

Constructor & Destructor Documentation

◆ History()

template<typename FilterT , std::int32_t kNumOfStates, typename ... EventT>
autoware::prediction::History< FilterT, kNumOfStates, EventT >::History ( FilterT &  filter,
const std::size_t  max_history_size,
const common::types::float32_t  mahalanobis_threshold 
)
inlineexplicit

Construct history from a filter pointer with a specific size.

Parameters
filterThe filter pointer to be used internally.
[in]max_history_sizeThe maximum history size.
[in]mahalanobis_thresholdThe mahalanobis threshold

Member Function Documentation

◆ emplace_event()

template<typename FilterT , std::int32_t kNumOfStates, typename ... EventT>
void autoware::prediction::History< FilterT, kNumOfStates, EventT >::emplace_event ( const Timestamp &  timestamp,
const HistoryEntry entry 
)

Add an event to history. If it is added to the middle the following ones are automatically replayed on top of it.

Parameters
[in]timestampThe timestamp of the event.
[in]entryThe entry to be added to history.

◆ empty()

template<typename FilterT , std::int32_t kNumOfStates, typename ... EventT>
bool autoware::prediction::History< FilterT, kNumOfStates, EventT >::empty ( ) const
inlinenoexcept

Check if the history is empty.

◆ get_filter() [1/2]

template<typename FilterT , std::int32_t kNumOfStates, typename ... EventT>
const FilterT& autoware::prediction::History< FilterT, kNumOfStates, EventT >::get_filter ( ) const
inlinenoexcept

Get the filter as a const ref.

◆ get_filter() [2/2]

template<typename FilterT , std::int32_t kNumOfStates, typename ... EventT>
FilterT& autoware::prediction::History< FilterT, kNumOfStates, EventT >::get_filter ( )
inlinenoexcept

Get the filter.

◆ get_last_event()

template<typename FilterT , std::int32_t kNumOfStates, typename ... EventT>
const HistoryEntry& autoware::prediction::History< FilterT, kNumOfStates, EventT >::get_last_event ( ) const
inlinenoexcept

Get last event in history.

◆ get_last_timestamp()

template<typename FilterT , std::int32_t kNumOfStates, typename ... EventT>
const Timestamp& autoware::prediction::History< FilterT, kNumOfStates, EventT >::get_last_timestamp ( ) const
inlinenoexcept

Get last timestamp in history.

◆ size()

template<typename FilterT , std::int32_t kNumOfStates, typename ... EventT>
std::size_t autoware::prediction::History< FilterT, kNumOfStates, EventT >::size ( ) const
inlinenoexcept

Get size of history.


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