mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_NavEKF3: use first usable compass index to set magSelectIndex
This commit is contained in:
parent
124eaf1a38
commit
cd5b764fd8
@ -94,7 +94,7 @@ void NavEKF3_core::controlMagYawReset()
|
||||
if (magYawResetRequest && use_compass()) {
|
||||
// send initial alignment status to console
|
||||
if (!yawAlignComplete) {
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "EKF3 IMU%u initial yaw alignment complete",(unsigned)imu_index);
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "EKF3 IMU%u MAG%u initial yaw alignment complete",(unsigned)imu_index, (unsigned)magSelectIndex);
|
||||
}
|
||||
|
||||
// set yaw from a single mag sample
|
||||
@ -102,10 +102,10 @@ void NavEKF3_core::controlMagYawReset()
|
||||
|
||||
// send in-flight yaw alignment status to console
|
||||
if (finalResetRequest) {
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "EKF3 IMU%u in-flight yaw alignment complete",(unsigned)imu_index);
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "EKF3 IMU%u MAG%u in-flight yaw alignment complete",(unsigned)imu_index, (unsigned)magSelectIndex);
|
||||
} else if (interimResetRequest) {
|
||||
magYawAnomallyCount++;
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "EKF3 IMU%u ground mag anomaly, yaw re-aligned",(unsigned)imu_index);
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "EKF3 IMU%u MAG%u ground mag anomaly, yaw re-aligned",(unsigned)imu_index, (unsigned)magSelectIndex);
|
||||
}
|
||||
|
||||
// clear the complete flags if an interim reset has been performed to allow subsequent
|
||||
|
@ -454,7 +454,7 @@ void NavEKF3_core::InitialiseVariablesMag()
|
||||
mag_state.q0 = 1;
|
||||
mag_state.DCM.identity();
|
||||
inhibitMagStates = true;
|
||||
magSelectIndex = 0;
|
||||
magSelectIndex = dal.compass().get_first_usable();
|
||||
lastMagOffsetsValid = false;
|
||||
magStateResetRequest = false;
|
||||
magStateInitComplete = false;
|
||||
|
Loading…
Reference in New Issue
Block a user