mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_NavEKF2: replace location_offset() and get_distance() function calls with Location object member function calls
This allows removing duplicated code
This commit is contained in:
parent
fa9a460c30
commit
79ee52917f
@ -328,7 +328,7 @@ bool NavEKF2_core::getLLH(struct Location &loc) const
|
||||
loc.lat = EKF_origin.lat;
|
||||
loc.lng = EKF_origin.lng;
|
||||
// correct for IMU offset (EKF calculations are at the IMU position)
|
||||
location_offset(loc, (outputDataNew.position.x + posOffsetNED.x), (outputDataNew.position.y + posOffsetNED.y));
|
||||
loc.offset((outputDataNew.position.x + posOffsetNED.x), (outputDataNew.position.y + posOffsetNED.y));
|
||||
return true;
|
||||
} else {
|
||||
// we could be in constant position mode because the vehicle has taken off without GPS, or has lost GPS
|
||||
@ -342,7 +342,7 @@ bool NavEKF2_core::getLLH(struct Location &loc) const
|
||||
} else {
|
||||
// if no GPS fix, provide last known position before entering the mode
|
||||
// correct for IMU offset (EKF calculations are at the IMU position)
|
||||
location_offset(loc, (lastKnownPositionNE.x + posOffsetNED.x), (lastKnownPositionNE.y + posOffsetNED.y));
|
||||
loc.offset((lastKnownPositionNE.x + posOffsetNED.x), (lastKnownPositionNE.y + posOffsetNED.y));
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user