mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF2: don't use disabled gyros in opticalflow takeoff detection
This commit is contained in:
parent
91889d22cd
commit
14265d9580
|
@ -456,7 +456,7 @@ void NavEKF2_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 {
|
||||||
|
|
Loading…
Reference in New Issue