mirror of https://github.com/ArduPilot/ardupilot
Copter: update for changed INS_NOTCH parameter name
This commit is contained in:
parent
800c21fc41
commit
9741a0b8cd
|
@ -1387,7 +1387,8 @@ void Copter::convert_pid_parameters(void)
|
|||
AP_Param::convert_old_parameters(&ff_and_filt_conversion_info[i], 1.0f);
|
||||
}
|
||||
|
||||
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" },
|
||||
|
@ -1399,11 +1400,12 @@ void Copter::convert_pid_parameters(void)
|
|||
for (uint8_t i=0; i<notchfilt_table_size; i++) {
|
||||
AP_Param::convert_old_parameters(¬chfilt_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
|
||||
|
||||
// ACRO_RP_P and ACRO_Y_P replaced with ACRO_RP_RATE and ACRO_Y_RATE for Copter-4.2
|
||||
const AP_Param::ConversionInfo acro_rpy_conversion_info[] = {
|
||||
|
|
Loading…
Reference in New Issue