mirror of https://github.com/ArduPilot/ardupilot
AP_AHRS: fixed get_position for EKF to use correct relative altitude
we need to use the EKF relative height plus the current AHRS home
This commit is contained in:
parent
869fb23062
commit
6781a8d329
|
@ -168,7 +168,11 @@ void AP_AHRS_NavEKF::reset_attitude(const float &_roll, const float &_pitch, con
|
|||
// dead-reckoning support
|
||||
bool AP_AHRS_NavEKF::get_position(struct Location &loc) const
|
||||
{
|
||||
if (using_EKF() && EKF.getLLH(loc)) {
|
||||
Vector3f ned_pos;
|
||||
if (using_EKF() && EKF.getLLH(loc) && EKF.getPosNED(ned_pos)) {
|
||||
// fixup altitude using relative position from AHRS home, not
|
||||
// EKF origin
|
||||
loc.alt = get_home().alt - ned_pos.z*100;
|
||||
return true;
|
||||
}
|
||||
return AP_AHRS_DCM::get_position(loc);
|
||||
|
|
Loading…
Reference in New Issue