AP_NavEKF: Remove redundant if statement

Thank you to OXINARF for picking up this one
This commit is contained in:
Paul Riseborough 2015-11-06 17:34:53 +11:00
parent 2243f95074
commit 0f8cfa02ab
1 changed files with 5 additions and 8 deletions

View File

@ -3973,15 +3973,12 @@ void NavEKF_core::readGpsData()
// Set the EKF origin and magnetic field declination if not previously set and GPS checks have passed // Set the EKF origin and magnetic field declination if not previously set and GPS checks have passed
if (!validOrigin && gpsGoodToAlign) { if (!validOrigin && gpsGoodToAlign) {
// Set the NE origin to the current GPS position if not previously set
if (!validOrigin) {
setOrigin(); setOrigin();
// Now we know the location we have an estimate for the magnetic field declination and adjust the earth field accordingly // Now we know the location we have an estimate for the magnetic field declination and adjust the earth field accordingly
alignMagStateDeclination(); alignMagStateDeclination();
// Set the height of the NED origin to height of baro height datum relative to GPS height datum' // Set the height of the NED origin to height of baro height datum relative to GPS height datum'
EKF_origin.alt = gpsloc.alt - hgtMea; EKF_origin.alt = gpsloc.alt - hgtMea;
} }
}
// Commence GPS aiding when able to // Commence GPS aiding when able to
if ((frontend._fusionModeGPS != 3) && (PV_AidingMode != AID_ABSOLUTE) && vehicleArmed && gpsGoodToAlign) { if ((frontend._fusionModeGPS != 3) && (PV_AidingMode != AID_ABSOLUTE) && vehicleArmed && gpsGoodToAlign) {