Autoware.Auto
|
|
#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>> | |
T | filter (T value, typename clock_type::time_point time_stamp) |
template<typename DummyT = T, typename = std::enable_if_t<!use_time_point_api, DummyT>> | |
T | filter (T value, std::chrono::nanoseconds duration) |
Protected Member Functions | |
T | 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... | |
Interface class for filters in the signal processing sense; attenuate response from various frequency domains
T | A floating point type for the signal |
ClockT | The (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) |
using autoware::common::signal_filters::FilterBase< T, ClockT >::clock_type = ClockT |
using autoware::common::signal_filters::FilterBase< T, ClockT >::signal_type = T |
|
virtualdefault |
Destructor.
|
inline |
Primary API: receives a value and outputs the result of the filter
[in] | value | An observation on the signal |
[in] | duration | Time since last observation, must be positive |
std::domain_error | If duration is negative |
std::domain_error | If value is not normal |
DummyT | Dummy type to get SFINAE to work |
|
inline |
Primary API: receives a value and outputs the result of the filter
[in] | value | An observation on the signal |
[in] | time_stamp | The time of the current observation |
std::domain_error | If time_stamp goes back in time |
std::domain_error | If value is not normal |
DummyT | Dummy type to get SFINAE to work |
|
protectedpure virtual |
Actual implementation, error checking already done, can assume duration is positive.
Implemented in autoware::common::signal_filters::LowPassFilter< T, ClockT >.
|
inlineprotected |
Underlying implementation, with error checking.