Go to the documentation of this file.
18 #ifndef SIGNAL_FILTERS__LOW_PASS_FILTER_HPP_
19 #define SIGNAL_FILTERS__LOW_PASS_FILTER_HPP_
30 namespace signal_filters
35 template<
typename T,
typename ClockT = std::chrono::steady_clock>
42 if (T{} >= cutoff_frequency_hz) {
43 throw std::domain_error{
"Cutoff frequency is non-positve"};
45 constexpr T
TAU{
static_cast<T
>(2.0 * 3.14159)};
46 m_rc_inv =
TAU * cutoff_frequency_hz;
52 T
filter_impl(T value, std::chrono::nanoseconds duration)
override
54 const auto dt = std::chrono::duration_cast<std::chrono::duration<T>>(duration).count();
56 const auto alpha = T{1.0} - std::exp(-dt * m_rc_inv);
57 m_signal += alpha * (value - m_signal);
69 #endif // SIGNAL_FILTERS__LOW_PASS_FILTER_HPP_
constexpr float32_t TAU
tau = 2 pi
Definition: types.hpp:54
T filter_impl(T value, std::chrono::nanoseconds duration) override
Actual implementation, error checking already done, can assume duration is positive.
Definition: low_pass_filter.hpp:52
LowPassFilter(T cutoff_frequency_hz)
Definition: low_pass_filter.hpp:39
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
Interface definition for signal processing filters.
Definition: low_pass_filter.hpp:36
#define SIGNAL_FILTERS_PUBLIC
Definition: common/signal_filters/include/signal_filters/visibility_control.hpp:44
Definition: signal_filter.hpp:52