mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF2: adjust for location flags being moved out of union
This commit is contained in:
parent
828317860a
commit
9be604e3ce
|
@ -322,8 +322,8 @@ bool NavEKF2_core::getLLH(struct Location &loc) const
|
|||
if(getPosD(posD) && getOriginLLH(origin)) {
|
||||
// Altitude returned is an absolute altitude relative to the WGS-84 spherioid
|
||||
loc.alt = origin.alt - posD*100;
|
||||
loc.flags.relative_alt = 0;
|
||||
loc.flags.terrain_alt = 0;
|
||||
loc.relative_alt = 0;
|
||||
loc.terrain_alt = 0;
|
||||
|
||||
// there are three modes of operation, absolute position (GPS fusion), relative position (optical flow fusion) and constant position (no aiding)
|
||||
if (filterStatus.flags.horiz_pos_abs || filterStatus.flags.horiz_pos_rel) {
|
||||
|
@ -354,8 +354,8 @@ bool NavEKF2_core::getLLH(struct Location &loc) const
|
|||
if ((gps.status() >= AP_GPS::GPS_OK_FIX_3D)) {
|
||||
const struct Location &gpsloc = gps.location();
|
||||
loc = gpsloc;
|
||||
loc.flags.relative_alt = 0;
|
||||
loc.flags.terrain_alt = 0;
|
||||
loc.relative_alt = 0;
|
||||
loc.terrain_alt = 0;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue