mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: correct blending check
This commit is contained in:
parent
7e9c56c50e
commit
2be3797f9e
|
@ -1174,7 +1174,7 @@ bool AP_GPS::calc_blend_weights(void)
|
|||
memset(&_blend_weights, 0, sizeof(_blend_weights));
|
||||
|
||||
// exit immediately if not enough receivers to do blending
|
||||
if (num_instances < 2 || drivers[1] == nullptr || _type[1] == GPS_TYPE_NONE) {
|
||||
if (state[0].status <= NO_FIX || state[1].status <= NO_FIX) {
|
||||
return false;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue