From 863b4bf9283bf3c4d532b651ffb2db0406e8c257 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 16 Jan 2023 17:04:15 +1100 Subject: [PATCH] AP_Compass: fixed zero compass diagonals this fixes a regression from 4.2 to 4.3. previously we automatically set the diagnoals to 1,1,1 if they were 0,0,0. We don't do that any more. I was helping a user who had copied an old config with 0,0,0 for diagonals and did not understand two things: - the compass did not work in 4.3 - large vehicle mag cal didn't work --- libraries/AP_Compass/AP_Compass_Backend.cpp | 14 ++++++----- .../AP_Compass/AP_Compass_Calibration.cpp | 24 ++++++++++--------- 2 files changed, 21 insertions(+), 17 deletions(-) diff --git a/libraries/AP_Compass/AP_Compass_Backend.cpp b/libraries/AP_Compass/AP_Compass_Backend.cpp index 920eee63cd..bbca45ddb3 100644 --- a/libraries/AP_Compass/AP_Compass_Backend.cpp +++ b/libraries/AP_Compass/AP_Compass_Backend.cpp @@ -90,13 +90,15 @@ void AP_Compass_Backend::correct_field(Vector3f &mag, uint8_t i) #if AP_COMPASS_DIAGONALS_ENABLED // apply eliptical correction - Matrix3f mat( - diagonals.x, offdiagonals.x, offdiagonals.y, - offdiagonals.x, diagonals.y, offdiagonals.z, - offdiagonals.y, offdiagonals.z, diagonals.z - ); + if (!diagonals.is_zero()) { + Matrix3f mat( + diagonals.x, offdiagonals.x, offdiagonals.y, + offdiagonals.x, diagonals.y, offdiagonals.z, + offdiagonals.y, offdiagonals.z, diagonals.z + ); - mag = mat * mag; + mag = mat * mag; + } #endif #if COMPASS_MOT_ENABLED diff --git a/libraries/AP_Compass/AP_Compass_Calibration.cpp b/libraries/AP_Compass/AP_Compass_Calibration.cpp index 56c1236a03..9943fc8740 100644 --- a/libraries/AP_Compass/AP_Compass_Calibration.cpp +++ b/libraries/AP_Compass/AP_Compass_Calibration.cpp @@ -463,18 +463,20 @@ bool Compass::get_uncorrected_field(uint8_t instance, Vector3f &field) const // needed to remove the effects of the eliptical correction // when calculating new offsets const Vector3f &diagonals = get_diagonals(instance); - const Vector3f &offdiagonals = get_offdiagonals(instance); - Matrix3f mat { - diagonals.x, offdiagonals.x, offdiagonals.y, - offdiagonals.x, diagonals.y, offdiagonals.z, - offdiagonals.y, offdiagonals.z, diagonals.z - }; - if (!mat.invert()) { - return false; - } + if (!diagonals.is_zero()) { + const Vector3f &offdiagonals = get_offdiagonals(instance); + Matrix3f mat { + diagonals.x, offdiagonals.x, offdiagonals.y, + offdiagonals.x, diagonals.y, offdiagonals.z, + offdiagonals.y, offdiagonals.z, diagonals.z + }; + if (!mat.invert()) { + return false; + } - // remove impact of diagonals and off-diagonals - field = mat * field; + // remove impact of diagonals and off-diagonals + field = mat * field; + } #endif // remove impact of offsets