AP_AHRS: Update for compatibility with EKF interface change

This commit is contained in:
priseborough 2017-05-30 11:38:49 +10:00 committed by Francisco Ferreira
parent 3ae7998f51
commit a3483d0d34
1 changed files with 4 additions and 4 deletions

View File

@ -386,7 +386,7 @@ bool AP_AHRS_NavEKF::get_position(struct Location &loc) const
return AP_AHRS_DCM::get_position(loc);
case EKF_TYPE2:
if (EKF2.getLLH(loc) && EKF2.getPosD(-1,ned_pos.z) && EKF2.getOriginLLH(origin)) {
if (EKF2.getLLH(loc) && EKF2.getPosD(-1,ned_pos.z) && EKF2.getOriginLLH(-1,origin)) {
// fixup altitude using relative position from EKF origin
loc.alt = origin.alt - ned_pos.z*100;
return true;
@ -394,7 +394,7 @@ bool AP_AHRS_NavEKF::get_position(struct Location &loc) const
break;
case EKF_TYPE3:
if (EKF3.getLLH(loc) && EKF3.getPosD(-1,ned_pos.z) && EKF3.getOriginLLH(origin)) {
if (EKF3.getLLH(loc) && EKF3.getPosD(-1,ned_pos.z) && EKF3.getOriginLLH(-1,origin)) {
// fixup altitude using relative position from EKF origin
loc.alt = origin.alt - ned_pos.z*100;
return true;
@ -1412,13 +1412,13 @@ bool AP_AHRS_NavEKF::get_origin(Location &ret) const
case EKF_TYPE2:
default:
if (!EKF2.getOriginLLH(ret)) {
if (!EKF2.getOriginLLH(-1,ret)) {
return false;
}
return true;
case EKF_TYPE3:
if (!EKF3.getOriginLLH(ret)) {
if (!EKF3.getOriginLLH(-1,ret)) {
return false;
}
return true;