Autoware.Auto
autoware::motion::control::trajectory_follower::Butterworth2dFilter Class Reference

2nd-order Butterworth Filter reference : S. Butterworth, "On the Theory of Filter Amplifier", Experimental wireless, 1930. More...

#include <lowpass_filter.hpp>

Public Member Functions

 Butterworth2dFilter (float64_t dt=0.01, float64_t f_cutoff_hz=5.0)
 constructor with initialization More...
 
 ~Butterworth2dFilter ()
 destructor More...
 
void initialize (const float64_t &dt, const float64_t &f_cutoff_hz)
 constructor More...
 
float64_t filter (const float64_t &u)
 filtering (call this function at each sampling time with input) More...
 
void filt_vector (const std::vector< float64_t > &t, std::vector< float64_t > &u) const
 filtering for time-series data More...
 
void filtfilt_vector (const std::vector< float64_t > &t, std::vector< float64_t > &u) const
 filtering for time-series data from both forward-backward direction for zero phase delay More...
 
void getCoefficients (std::vector< float64_t > &coeffs) const
 get filter coefficients More...
 

Detailed Description

2nd-order Butterworth Filter reference : S. Butterworth, "On the Theory of Filter Amplifier", Experimental wireless, 1930.

Constructor & Destructor Documentation

◆ Butterworth2dFilter()

autoware::motion::control::trajectory_follower::Butterworth2dFilter::Butterworth2dFilter ( float64_t  dt = 0.01,
float64_t  f_cutoff_hz = 5.0 
)
explicit

constructor with initialization

Parameters
[in]dtsampling time
[in]f_cutoff_hzcutoff frequency [Hz]

◆ ~Butterworth2dFilter()

autoware::motion::control::trajectory_follower::Butterworth2dFilter::~Butterworth2dFilter ( )

destructor

Member Function Documentation

◆ filt_vector()

void autoware::motion::control::trajectory_follower::Butterworth2dFilter::filt_vector ( const std::vector< float64_t > &  t,
std::vector< float64_t > &  u 
) const

filtering for time-series data

Parameters
[in]ttime-series data for input vector
[out]uobject vector

◆ filter()

float64_t autoware::motion::control::trajectory_follower::Butterworth2dFilter::filter ( const float64_t &  u)

filtering (call this function at each sampling time with input)

Parameters
[in]uscalar input for filter
Returns
filtered scalar value

◆ filtfilt_vector()

void autoware::motion::control::trajectory_follower::Butterworth2dFilter::filtfilt_vector ( const std::vector< float64_t > &  t,
std::vector< float64_t > &  u 
) const

filtering for time-series data from both forward-backward direction for zero phase delay

Parameters
[in]ttime-series data for input vector
[out]uobject vector

◆ getCoefficients()

void autoware::motion::control::trajectory_follower::Butterworth2dFilter::getCoefficients ( std::vector< float64_t > &  coeffs) const

get filter coefficients

Parameters
[out]coeffscoefficients of filter [a0, a1, a2, b0, b1, b2].

◆ initialize()

void autoware::motion::control::trajectory_follower::Butterworth2dFilter::initialize ( const float64_t &  dt,
const float64_t &  f_cutoff_hz 
)

constructor

Parameters
[in]dtsampling time
[in]f_cutoff_hzcutoff frequency [Hz]

The documentation for this class was generated from the following files: