AP_NavEKF2: fixed gcc 9.3 build error

gcc 9.3 doesn't like the use of get_accel(i) when array length is 1
This commit is contained in:
Andrew Tridgell 2020-11-13 11:32:18 +11:00 committed by Peter Barker
parent 19c42ca0ed
commit 7099bb6096

View File

@ -971,6 +971,11 @@ float NavEKF2_core::MagDeclination(void) const
*/
void NavEKF2_core::learnInactiveBiases(void)
{
#if INS_MAX_INSTANCES == 1
inactiveBias[0].gyro_bias = stateStruct.gyro_bias;
inactiveBias[0].gyro_scale = stateStruct.gyro_scale;
inactiveBias[0].accel_zbias = stateStruct.accel_zbias;
#else
const auto &ins = dal.ins();
// learn gyro biases
@ -1029,6 +1034,7 @@ void NavEKF2_core::learnInactiveBiases(void)
inactiveBias[i].accel_zbias -= error * (1.0e-4f * dtEkfAvg);
}
}
#endif
}
// Writes the default equivalent airspeed in m/s to be used in forward flight if a measured airspeed is required and not available.