mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
AP_GPS: correct blending check
This commit is contained in:
parent
d88d8fc178
commit
75527ef567
@ -1184,7 +1184,7 @@ bool AP_GPS::calc_blend_weights(void)
|
|||||||
memset(&_blend_weights, 0, sizeof(_blend_weights));
|
memset(&_blend_weights, 0, sizeof(_blend_weights));
|
||||||
|
|
||||||
// exit immediately if not enough receivers to do blending
|
// 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;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user