Autoware.Auto
autoware::common::signal_filters::FilterFactory Class Reference

Factory class to create some kind of low pass filter. More...

#include <filter_factory.hpp>

Static Public Member Functions

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)
 

Detailed Description

Factory class to create some kind of low pass filter.

Member Function Documentation

◆ 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,
cutoff_frequency 
)
inlinestatic

Create a low pass filter

Parameters
[in]typeThe name of the filter type, expects one of "none, "low_pass_filter"
[in]cutoff_frequencyThe filter starts to have < 1.0 frequency response starting around here
Template Parameters
TThe floating point type of the filter
ClockTThe 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,
cutoff_frequency 
)
inlinestatic

Create a low pass filter

Parameters
[in]typeThe type of the filter type
[in]cutoff_frequencyThe filter starts to have < 1.0 frequency response starting around here
Template Parameters
TThe floating point type of the filter
ClockTThe 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: