APM:Libraries
Public Member Functions | Protected Attributes | Private Attributes | List of all members
LowPassFilter2p< T > Class Template Reference

#include <LowPassFilter2p.h>

Public Member Functions

 LowPassFilter2p ()
 
 LowPassFilter2p (float sample_freq, float cutoff_freq)
 
void set_cutoff_frequency (float sample_freq, float cutoff_freq)
 
float get_cutoff_freq (void) const
 
float get_sample_freq (void) const
 
apply (const T &sample)
 
void reset (void)
 

Protected Attributes

struct DigitalBiquadFilter< T >::biquad_params _params
 

Private Attributes

DigitalBiquadFilter< T > _filter
 

Detailed Description

template<class T>
class LowPassFilter2p< T >

Definition at line 50 of file LowPassFilter2p.h.

Constructor & Destructor Documentation

◆ LowPassFilter2p() [1/2]

template<class T >
LowPassFilter2p< T >::LowPassFilter2p ( )

Definition at line 56 of file LowPassFilter2p.cpp.

◆ LowPassFilter2p() [2/2]

template<class T >
LowPassFilter2p< T >::LowPassFilter2p ( float  sample_freq,
float  cutoff_freq 
)

Definition at line 62 of file LowPassFilter2p.cpp.

Member Function Documentation

◆ apply()

template<class T>
T LowPassFilter2p< T >::apply ( const T &  sample)

Definition at line 85 of file LowPassFilter2p.cpp.

Referenced by AP_InertialSensor_Invensense::_accumulate(), AP_InertialSensor_Invensense::_accumulate_sensor_rate_sampling(), AP_InertialSensor_Backend::_notify_new_accel_raw_sample(), AP_InertialSensor_Backend::_notify_new_gyro_raw_sample(), and loop().

Here is the caller graph for this function:

◆ get_cutoff_freq()

template<class T >
float LowPassFilter2p< T >::get_cutoff_freq ( void  ) const

Definition at line 75 of file LowPassFilter2p.cpp.

◆ get_sample_freq()

template<class T >
float LowPassFilter2p< T >::get_sample_freq ( void  ) const

Definition at line 80 of file LowPassFilter2p.cpp.

◆ reset()

template<class T >
void LowPassFilter2p< T >::reset ( void  )

Definition at line 90 of file LowPassFilter2p.cpp.

Referenced by AP_InertialSensor_Backend::_notify_new_accel_raw_sample(), and AP_InertialSensor_Backend::_notify_new_gyro_raw_sample().

Here is the caller graph for this function:

◆ set_cutoff_frequency()

template<class T >
void LowPassFilter2p< T >::set_cutoff_frequency ( float  sample_freq,
float  cutoff_freq 
)

Definition at line 69 of file LowPassFilter2p.cpp.

Referenced by AP_InertialSensor_Backend::update_accel(), and AP_InertialSensor_Backend::update_gyro().

Here is the caller graph for this function:

Member Data Documentation

◆ _filter

template<class T>
DigitalBiquadFilter<T> LowPassFilter2p< T >::_filter
private

Definition at line 67 of file LowPassFilter2p.h.

◆ _params

template<class T>
struct DigitalBiquadFilter< T >::biquad_params LowPassFilter2p< T >::_params
protected

Definition at line 64 of file LowPassFilter2p.h.


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