Browse Source

AP_NavEKF2: use get_distance_NE instead of location_diff

mission-4.1.18
Pierre Kancir 6 years ago committed by Tom Pittenger
parent
commit
50e99b6e1a
  1. 2
      libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp
  2. 2
      libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp

2
libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp

@ -531,7 +531,7 @@ void NavEKF2_core::readGpsData() @@ -531,7 +531,7 @@ void NavEKF2_core::readGpsData()
// convert GPS measurements to local NED and save to buffer to be fused later if we have a valid origin
if (validOrigin) {
gpsDataNew.pos = location_diff(EKF_origin, gpsloc);
gpsDataNew.pos = EKF_origin.get_distance_NE(gpsloc);
gpsDataNew.hgt = (float)((double)0.01 * (double)gpsloc.alt - ekfGpsRefHgt);
storedGPS.push(gpsDataNew);
// declare GPS available for use

2
libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp

@ -252,7 +252,7 @@ bool NavEKF2_core::getPosNE(Vector2f &posNE) const @@ -252,7 +252,7 @@ bool NavEKF2_core::getPosNE(Vector2f &posNE) const
if ((AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D)) {
// If the origin has been set and we have GPS, then return the GPS position relative to the origin
const struct Location &gpsloc = AP::gps().location();
Vector2f tempPosNE = location_diff(EKF_origin, gpsloc);
const Vector2f tempPosNE = EKF_origin.get_distance_NE(gpsloc);
posNE.x = tempPosNE.x;
posNE.y = tempPosNE.y;
return false;

Loading…
Cancel
Save