From 627f62d23bee0fd333fb99be64a530cbcaa3fa91 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 13 Apr 2022 20:10:37 +1000 Subject: [PATCH] Plane: param conversion for INS_NOTCH to INS_HNTC2 --- ArduPlane/Parameters.cpp | 18 ++++++++++++++++++ 1 file changed, 18 insertions(+) diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index f287fddfd8..76fbda72e7 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -1502,5 +1502,23 @@ void Plane::load_parameters(void) } #endif + if (!ins.gyro_notch_enabled()) { + // notch filter parameter conversions (moved to INS_HNTC2) for 4.2.x, converted from fixed notch + const AP_Param::ConversionInfo notchfilt_conversion_info[] { + { Parameters::k_param_ins, 101, AP_PARAM_INT8, "INS_HNTC2_ENABLE" }, + { Parameters::k_param_ins, 293, AP_PARAM_FLOAT, "INS_HNTC2_ATT" }, + { Parameters::k_param_ins, 357, AP_PARAM_FLOAT, "INS_HNTC2_FREQ" }, + { Parameters::k_param_ins, 421, AP_PARAM_FLOAT, "INS_HNTC2_BW" }, + }; + uint8_t notchfilt_table_size = ARRAY_SIZE(notchfilt_conversion_info); + for (uint8_t i=0; iprintf("load_all took %uus\n", (unsigned)(micros() - before)); }