mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
AP_NavEKF3: 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:
parent
7099bb6096
commit
c14d19be68
@ -1188,6 +1188,10 @@ void NavEKF3_core::getTimingStatistics(struct ekf_timing &_timing)
|
||||
*/
|
||||
void NavEKF3_core::learnInactiveBiases(void)
|
||||
{
|
||||
#if INS_MAX_INSTANCES == 1
|
||||
inactiveBias[0].gyro_bias = stateStruct.gyro_bias;
|
||||
inactiveBias[0].accel_bias = stateStruct.accel_bias;
|
||||
#else
|
||||
const auto &ins = dal.ins();
|
||||
|
||||
// learn gyro biases
|
||||
@ -1248,6 +1252,7 @@ void NavEKF3_core::learnInactiveBiases(void)
|
||||
inactiveBias[i].accel_bias -= error * (1.0e-4f * dtEkfAvg);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
/*
|
||||
|
Loading…
Reference in New Issue
Block a user