Autoware.Auto
autoware::common::signal_filters::FilterBase< T, ClockT > Class Template Referenceabstract

#include <signal_filter.hpp>

Public Types

using clock_type = ClockT
 
using signal_type = T
 

Public Member Functions

virtual ~FilterBase ()=default
 Destructor. More...
 
template<typename DummyT = T, typename = std::enable_if_t<use_time_point_api, DummyT>>
filter (T value, typename clock_type::time_point time_stamp)
 
template<typename DummyT = T, typename = std::enable_if_t<!use_time_point_api, DummyT>>
filter (T value, std::chrono::nanoseconds duration)
 

Protected Member Functions

filter_impl_checked (T value, std::chrono::nanoseconds duration)
 Underlying implementation, with error checking. More...
 
virtual T filter_impl (T value, std::chrono::nanoseconds duration)=0
 Actual implementation, error checking already done, can assume duration is positive. More...
 

Detailed Description

template<typename T, typename ClockT = DummyClock>
class autoware::common::signal_filters::FilterBase< T, ClockT >

Interface class for filters in the signal processing sense; attenuate response from various frequency domains

Template Parameters
TA floating point type for the signal
ClockTThe (std::)clock type intended to be used. Setting this implies that the time_point-based API is going to be used (and that the duration API can't be used)

Member Typedef Documentation

◆ clock_type

template<typename T , typename ClockT = DummyClock>
using autoware::common::signal_filters::FilterBase< T, ClockT >::clock_type = ClockT

◆ signal_type

template<typename T , typename ClockT = DummyClock>
using autoware::common::signal_filters::FilterBase< T, ClockT >::signal_type = T

Constructor & Destructor Documentation

◆ ~FilterBase()

template<typename T , typename ClockT = DummyClock>
virtual autoware::common::signal_filters::FilterBase< T, ClockT >::~FilterBase ( )
virtualdefault

Destructor.

Member Function Documentation

◆ filter() [1/2]

template<typename T , typename ClockT = DummyClock>
template<typename DummyT = T, typename = std::enable_if_t<!use_time_point_api, DummyT>>
T autoware::common::signal_filters::FilterBase< T, ClockT >::filter ( value,
std::chrono::nanoseconds  duration 
)
inline

Primary API: receives a value and outputs the result of the filter

Parameters
[in]valueAn observation on the signal
[in]durationTime since last observation, must be positive
Returns
The result of the filter
Exceptions
std::domain_errorIf duration is negative
std::domain_errorIf value is not normal
Template Parameters
DummyTDummy type to get SFINAE to work

◆ filter() [2/2]

template<typename T , typename ClockT = DummyClock>
template<typename DummyT = T, typename = std::enable_if_t<use_time_point_api, DummyT>>
T autoware::common::signal_filters::FilterBase< T, ClockT >::filter ( value,
typename clock_type::time_point  time_stamp 
)
inline

Primary API: receives a value and outputs the result of the filter

Parameters
[in]valueAn observation on the signal
[in]time_stampThe time of the current observation
Returns
The result of the filter
Exceptions
std::domain_errorIf time_stamp goes back in time
std::domain_errorIf value is not normal
Template Parameters
DummyTDummy type to get SFINAE to work

◆ filter_impl()

template<typename T , typename ClockT = DummyClock>
virtual T autoware::common::signal_filters::FilterBase< T, ClockT >::filter_impl ( value,
std::chrono::nanoseconds  duration 
)
protectedpure virtual

Actual implementation, error checking already done, can assume duration is positive.

Implemented in autoware::common::signal_filters::LowPassFilter< T, ClockT >.

◆ filter_impl_checked()

template<typename T , typename ClockT = DummyClock>
T autoware::common::signal_filters::FilterBase< T, ClockT >::filter_impl_checked ( value,
std::chrono::nanoseconds  duration 
)
inlineprotected

Underlying implementation, with error checking.


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