Plane: param conversion for INS_NOTCH to INS_HNTC2

This commit is contained in:
Andrew Tridgell 2022-04-13 20:10:37 +10:00
parent 1cd1519a4f
commit 7aafd5cf98
1 changed files with 5 additions and 3 deletions

View File

@ -1502,7 +1502,8 @@ void Plane::load_parameters(void)
}
#endif
if (!ins.gyro_notch_enabled()) {
#if HAL_INS_NUM_HARMONIC_NOTCH_FILTERS > 1
if (!ins.gyro_harmonic_notch_enabled(1)) {
// 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" },
@ -1514,11 +1515,12 @@ void Plane::load_parameters(void)
for (uint8_t i=0; i<notchfilt_table_size; i++) {
AP_Param::convert_old_parameters(&notchfilt_conversion_info[i], 1.0f);
}
if (ins.gyro_notch_enabled()) {
if (ins.gyro_harmonic_notch_enabled(1)) {
AP_Param::set_default_by_name("INS_HNTC2_MODE", 0);
AP_Param::set_default_by_name("INS_HNTC2_HMNCS", 1);
}
}
#endif // HAL_INS_NUM_HARMONIC_NOTCH_FILTERS
hal.console->printf("load_all took %uus\n", (unsigned)(micros() - before));
}