AP_NavEKF2: use first usable compass index to set magSelectIndex

This commit is contained in:
Siddharth Purohit 2021-05-20 21:38:38 +05:30 committed by Andrew Tridgell
parent a52f04ddde
commit 124eaf1a38
2 changed files with 4 additions and 4 deletions

View File

@ -148,14 +148,14 @@ void NavEKF2_core::controlMagYawReset()
// send initial alignment status to console
if (!yawAlignComplete) {
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "EKF2 IMU%u initial yaw alignment complete",(unsigned)imu_index);
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "EKF2 IMU%u MAG%u initial yaw alignment complete",(unsigned)imu_index, (unsigned)magSelectIndex);
}
// send in-flight yaw alignment status to console
if (finalResetRequest) {
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "EKF2 IMU%u in-flight yaw alignment complete",(unsigned)imu_index);
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "EKF2 IMU%u MAG%u in-flight yaw alignment complete",(unsigned)imu_index, (unsigned)magSelectIndex);
} else if (interimResetRequest) {
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "EKF2 IMU%u ground mag anomaly, yaw re-aligned",(unsigned)imu_index);
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "EKF2 IMU%u MAG%u ground mag anomaly, yaw re-aligned",(unsigned)imu_index, (unsigned)magSelectIndex);
}
// update the yaw reset completed status

View File

@ -348,7 +348,7 @@ void NavEKF2_core::InitialiseVariablesMag()
inhibitMagStates = true;
magSelectIndex = 0;
magSelectIndex = dal.compass().get_first_usable();
lastMagOffsetsValid = false;
magStateResetRequest = false;
magStateInitComplete = false;