mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-13 10:03:57 -03:00
AP_NavEKF3: check GPS used before resetting pos due to GPS receiver change
This commit is contained in:
parent
f79d5d2d2c
commit
183ce50138
@ -431,7 +431,7 @@ void NavEKF3_core::SelectVelPosFusion()
|
||||
selectHeightForFusion();
|
||||
|
||||
// if we are using GPS, check for a change in receiver and reset position and height
|
||||
if (gpsDataToFuse && PV_AidingMode == AID_ABSOLUTE && gpsDataDelayed.sensor_idx != last_gps_idx) {
|
||||
if (gpsDataToFuse && (PV_AidingMode == AID_ABSOLUTE) && (frontend->_fusionModeGPS != 3) && (gpsDataDelayed.sensor_idx != last_gps_idx)) {
|
||||
// record the ID of the GPS that we are using for the reset
|
||||
last_gps_idx = gpsDataDelayed.sensor_idx;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user