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

This commit is contained in:
Andrew Tridgell 2019-07-05 12:40:48 +10:00 committed by Randy Mackay
parent 0e4aad27c5
commit c75862d0e6

View File

@ -455,7 +455,7 @@ void NavEKF3_core::detectOptFlowTakeoff(void)
Vector3f angRateVec; Vector3f angRateVec;
Vector3f gyroBias; Vector3f gyroBias;
getGyroBias(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) { if (dual_ins) {
angRateVec = (ins.get_gyro(0) + ins.get_gyro(1)) * 0.5f - gyroBias; angRateVec = (ins.get_gyro(0) + ins.get_gyro(1)) * 0.5f - gyroBias;
} else { } else {