APM:Libraries
|
#include <LowPassFilter.h>
Public Member Functions | |
LowPassFilter () | |
LowPassFilter (float cutoff_freq) | |
LowPassFilter (float sample_freq, float cutoff_freq) | |
void | set_cutoff_frequency (float cutoff_freq) |
void | set_cutoff_frequency (float sample_freq, float cutoff_freq) |
float | get_cutoff_freq (void) const |
T | apply (T sample, float dt) |
T | apply (T sample) |
const T & | get () const |
void | reset (T value) |
void | reset (void) |
Protected Attributes | |
float | _cutoff_freq |
Private Attributes | |
DigitalLPF< T > | _filter |
Definition at line 72 of file LowPassFilter.h.
LowPassFilter< T >::LowPassFilter | ( | ) |
Definition at line 67 of file LowPassFilter.cpp.
LowPassFilter< T >::LowPassFilter | ( | float | cutoff_freq | ) |
Definition at line 71 of file LowPassFilter.cpp.
LowPassFilter< T >::LowPassFilter | ( | float | sample_freq, |
float | cutoff_freq | ||
) |
Definition at line 75 of file LowPassFilter.cpp.
T LowPassFilter< T >::apply | ( | T | sample, |
float | dt | ||
) |
Definition at line 99 of file LowPassFilter.cpp.
Referenced by AP_InertialSensor::calc_vibration_and_clipping(), SITL::Aircraft::filtered_idx(), loop(), AC_AttitudeControl_Heli::rate_bf_to_motor_roll_pitch(), AC_AttitudeControl_Heli::rate_target_to_motor_yaw(), AC_PosControl::run_xy_controller(), AC_PosControl::run_z_controller(), AP_MotorsMulticopter::update_lift_max_from_batt_voltage(), AP_MotorsMulticopter::update_throttle_filter(), and AP_MotorsHeli::update_throttle_filter().
T LowPassFilter< T >::apply | ( | T | sample | ) |
Definition at line 104 of file LowPassFilter.cpp.
const T & LowPassFilter< T >::get | ( | void | ) | const |
Definition at line 109 of file LowPassFilter.cpp.
Referenced by AP_MotorsMulticopter::apply_thrust_curve_and_volt_scaling(), AP_MotorsMulticopter::get_batt_voltage_filt(), AP_Motors::get_throttle(), AP_Motors::get_throttle_bidirectional(), AP_InertialSensor::get_vibration_levels(), AC_PosControl::run_xy_controller(), AP_MotorsMulticopter::update_throttle_filter(), and AP_MotorsHeli::update_throttle_filter().
float LowPassFilter< T >::get_cutoff_freq | ( | void | ) | const |
Definition at line 94 of file LowPassFilter.cpp.
void LowPassFilter< T >::reset | ( | T | value | ) |
Definition at line 114 of file LowPassFilter.cpp.
Referenced by AP_Motors::AP_Motors(), AP_MotorsMulticopter::AP_MotorsMulticopter(), loop(), AP_MotorsHeli::output_disarmed(), AC_PosControl::run_xy_controller(), AC_PosControl::run_z_controller(), AP_MotorsHeli_Dual::servo_test(), AP_MotorsHeli_Single::servo_test(), AP_MotorsMulticopter::update_lift_max_from_batt_voltage(), AP_MotorsMulticopter::update_throttle_filter(), and AP_MotorsHeli::update_throttle_filter().
|
inline |
Definition at line 88 of file LowPassFilter.h.
Referenced by LowPassFilter< Vector2f >::reset().
void LowPassFilter< T >::set_cutoff_frequency | ( | float | cutoff_freq | ) |
Definition at line 82 of file LowPassFilter.cpp.
Referenced by AP_InertialSensor::AP_InertialSensor(), AP_Motors::AP_Motors(), AP_MotorsMulticopter::AP_MotorsMulticopter(), SITL::Aircraft::filtered_idx(), LowPassFilter< Vector2f >::LowPassFilter(), AC_PosControl::run_xy_controller(), AC_PosControl::set_dt(), AP_Motors::set_throttle_filter_cutoff(), and setup().
void LowPassFilter< T >::set_cutoff_frequency | ( | float | sample_freq, |
float | cutoff_freq | ||
) |
Definition at line 87 of file LowPassFilter.cpp.
|
protected |
Definition at line 91 of file LowPassFilter.h.
Referenced by LowPassFilter< Vector2f >::apply(), LowPassFilter< Vector2f >::get_cutoff_freq(), and LowPassFilter< Vector2f >::set_cutoff_frequency().
|
private |
Definition at line 94 of file LowPassFilter.h.
Referenced by LowPassFilter< Vector2f >::apply(), LowPassFilter< Vector2f >::get(), LowPassFilter< Vector2f >::reset(), and LowPassFilter< Vector2f >::set_cutoff_frequency().