Factory class to create some kind of low pass filter.
More...
#include <filter_factory.hpp>
|
template<typename T , typename ClockT = DummyClock> |
static std::unique_ptr< FilterBase< T, ClockT > > | create (const std::string &type, T cutoff_frequency) |
|
template<typename T , typename ClockT = DummyClock> |
static std::unique_ptr< FilterBase< T, ClockT > > | create (FilterType type, T cutoff_frequency) |
|
Factory class to create some kind of low pass filter.
◆ create() [1/2]
template<typename T , typename ClockT = DummyClock>
static std::unique_ptr<FilterBase<T, ClockT> > autoware::common::signal_filters::FilterFactory::create |
( |
const std::string & |
type, |
|
|
T |
cutoff_frequency |
|
) |
| |
|
inlinestatic |
Create a low pass filter
- Parameters
-
[in] | type | The name of the filter type, expects one of "none, "low_pass_filter" |
[in] | cutoff_frequency | The filter starts to have < 1.0 frequency response starting around here |
- Template Parameters
-
T | The floating point type of the filter |
ClockT | The clock type of the filter. Use default parameter if you want to provide durations between points yourself |
◆ create() [2/2]
template<typename T , typename ClockT = DummyClock>
static std::unique_ptr<FilterBase<T, ClockT> > autoware::common::signal_filters::FilterFactory::create |
( |
FilterType |
type, |
|
|
T |
cutoff_frequency |
|
) |
| |
|
inlinestatic |
Create a low pass filter
- Parameters
-
[in] | type | The type of the filter type |
[in] | cutoff_frequency | The filter starts to have < 1.0 frequency response starting around here |
- Template Parameters
-
T | The floating point type of the filter |
ClockT | The clock type of the filter. Use default parameter if you want to provide durations between points yourself |
The documentation for this class was generated from the following file: