Autoware.Auto
|
|
#include <low_pass_filter.hpp>
Public Member Functions | |
LowPassFilter (T cutoff_frequency_hz) | |
virtual | ~LowPassFilter ()=default |
Destructor. More... | |
![]() | |
virtual | ~FilterBase ()=default |
Destructor. More... | |
T | filter (T value, typename clock_type::time_point time_stamp) |
T | filter (T value, std::chrono::nanoseconds duration) |
Protected Member Functions | |
T | filter_impl (T value, std::chrono::nanoseconds duration) override |
Actual implementation, error checking already done, can assume duration is positive. More... | |
![]() | |
T | filter_impl_checked (T value, std::chrono::nanoseconds duration) |
Underlying implementation, with error checking. More... | |
Additional Inherited Members | |
![]() | |
using | clock_type = std::chrono::steady_clock |
using | signal_type = T |
Basic low pass filter implemented as an exponential moving average
T | A floating point type for the signal |
|
inlineexplicit |
|
virtualdefault |
Destructor.
|
inlineoverrideprotectedvirtual |
Actual implementation, error checking already done, can assume duration is positive.
Implements autoware::common::signal_filters::FilterBase< T, std::chrono::steady_clock >.