From 9dc618ddd418c7b0d9f92a7915a67ed658f7a524 Mon Sep 17 00:00:00 2001
From: Andrew Tridgell <andrew@tridgell.net>
Date: Sun, 17 Nov 2019 16:26:22 +1100
Subject: [PATCH] AP_InertialSensor: added gyro_harmonic_notch_enabled()

---
 libraries/AP_InertialSensor/AP_InertialSensor.h         | 3 +++
 libraries/AP_InertialSensor/AP_InertialSensor_Backend.h | 4 ++--
 2 files changed, 5 insertions(+), 2 deletions(-)

diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.h b/libraries/AP_InertialSensor/AP_InertialSensor.h
index 8df2b9caf9..0ff1aaa84f 100644
--- a/libraries/AP_InertialSensor/AP_InertialSensor.h
+++ b/libraries/AP_InertialSensor/AP_InertialSensor.h
@@ -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
diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Backend.h b/libraries/AP_InertialSensor/AP_InertialSensor_Backend.h
index 8befc03edf..dc1b770fd1 100644
--- a/libraries/AP_InertialSensor/AP_InertialSensor_Backend.h
+++ b/libraries/AP_InertialSensor/AP_InertialSensor_Backend.h
@@ -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);