AP_NavEKF2: don't use disabled gyros in opticalflow takeoff detection

This commit is contained in:
Andrew Tridgell 2019-07-05 12:40:48 +10:00
parent 91889d22cd
commit 14265d9580
1 changed files with 1 additions and 1 deletions

View File

@ -456,7 +456,7 @@ void NavEKF2_core::detectOptFlowTakeoff(void)
Vector3f angRateVec;
Vector3f gyroBias;
getGyroBias(gyroBias);
bool dual_ins = ins.get_gyro_health(0) && ins.get_gyro_health(1);
bool dual_ins = ins.use_gyro(0) && ins.use_gyro(1);
if (dual_ins) {
angRateVec = (ins.get_gyro(0) + ins.get_gyro(1)) * 0.5f - gyroBias;
} else {