AP_NavEKF2: ext nav will not reset yaw if compass is used

This commit is contained in:
chobits 2019-08-14 14:35:29 +08:00 committed by Randy Mackay
parent 45e6896d95
commit a7aa43f5d5

View File

@ -329,9 +329,11 @@ void NavEKF2_core::setAidingMode()
if (canUseExtNav) {
gcs().send_text(MAV_SEVERITY_INFO, "EKF2 IMU%u is using external nav data",(unsigned)imu_index);
gcs().send_text(MAV_SEVERITY_INFO, "EKF2 IMU%u initial pos NED = %3.1f,%3.1f,%3.1f (m)",(unsigned)imu_index,(double)extNavDataDelayed.pos.x,(double)extNavDataDelayed.pos.y,(double)extNavDataDelayed.pos.z);
// handle yaw reset as special case
extNavYawResetRequest = true;
controlMagYawReset();
//handle yaw reset as special case only if compass is disabled
if (!use_compass()) {
extNavYawResetRequest = true;
controlMagYawReset();
}
// handle height reset as special case
hgtMea = -extNavDataDelayed.pos.z;
posDownObsNoise = sq(constrain_float(extNavDataDelayed.posErr, 0.1f, 10.0f));