From 7099bb60969585608d1f199b65f51e86307045de Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 13 Nov 2020 11:32:18 +1100 Subject: [PATCH] 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 --- libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp index 2056c345c5..2f309519e7 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp @@ -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.