mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 17:03:57 -04:00
AP_NavEKF: Remove redundant if statement
Thank you to OXINARF for picking up this one
This commit is contained in:
parent
2243f95074
commit
0f8cfa02ab
@ -3973,14 +3973,11 @@ 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
|
setOrigin();
|
||||||
if (!validOrigin) {
|
// Now we know the location we have an estimate for the magnetic field declination and adjust the earth field accordingly
|
||||||
setOrigin();
|
alignMagStateDeclination();
|
||||||
// Now we know the location we have an estimate for the magnetic field declination and adjust the earth field accordingly
|
// Set the height of the NED origin to ‘height of baro height datum relative to GPS height datum'
|
||||||
alignMagStateDeclination();
|
EKF_origin.alt = gpsloc.alt - hgtMea;
|
||||||
// Set the height of the NED origin to ‘height of baro height datum relative to GPS height datum'
|
|
||||||
EKF_origin.alt = gpsloc.alt - hgtMea;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Commence GPS aiding when able to
|
// Commence GPS aiding when able to
|
||||||
|
Loading…
Reference in New Issue
Block a user