mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
AP_InertialSensor: added gyro_harmonic_notch_enabled()
This commit is contained in:
parent
77d21f9f5d
commit
9dc618ddd4
@ -243,6 +243,9 @@ public:
|
||||
// check for vibration movement. True when all axis show nearly zero movement
|
||||
bool is_still();
|
||||
|
||||
// return true if harmonic notch enabled
|
||||
bool gyro_harmonic_notch_enabled(void) const { return _harmonic_notch_filter.enabled(); }
|
||||
|
||||
/*
|
||||
HIL set functions. The minimum for HIL is set_accel() and
|
||||
set_gyro(). The others are option for higher fidelity log
|
||||
|
@ -244,7 +244,7 @@ protected:
|
||||
// return the notch filter attenuation in dB for the sample rate
|
||||
float _gyro_notch_attenuation_dB(void) const { return _imu._notch_filter.attenuation_dB(); }
|
||||
|
||||
uint8_t _gyro_notch_enabled(void) const { return _imu._notch_filter.enabled(); }
|
||||
bool _gyro_notch_enabled(void) const { return _imu._notch_filter.enabled(); }
|
||||
|
||||
// return the harmonic notch filter center in Hz for the sample rate
|
||||
float gyro_harmonic_notch_center_freq_hz() const { return _imu._calculated_harmonic_notch_freq_hz; }
|
||||
@ -255,7 +255,7 @@ protected:
|
||||
// return the harmonic notch filter attenuation in dB for the sample rate
|
||||
float gyro_harmonic_notch_attenuation_dB(void) const { return _imu._harmonic_notch_filter.attenuation_dB(); }
|
||||
|
||||
uint8_t gyro_harmonic_notch_enabled(void) const { return _imu._harmonic_notch_filter.enabled(); }
|
||||
bool gyro_harmonic_notch_enabled(void) const { return _imu._harmonic_notch_filter.enabled(); }
|
||||
|
||||
// common gyro update function for all backends
|
||||
void update_gyro(uint8_t instance);
|
||||
|
Loading…
Reference in New Issue
Block a user