From 7cb9fa88986b383ae907664b2ebf125f8157893e Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Thu, 12 Mar 2015 09:14:29 -0700 Subject: [PATCH] AP_Compass: Correct parameter checks in compass cal --- libraries/AP_Compass/CompassCalibrator.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Compass/CompassCalibrator.cpp b/libraries/AP_Compass/CompassCalibrator.cpp index 1059f7c5cf..532fed8209 100644 --- a/libraries/AP_Compass/CompassCalibrator.cpp +++ b/libraries/AP_Compass/CompassCalibrator.cpp @@ -254,8 +254,8 @@ bool CompassCalibrator::fit_acceptable() { _params.diag.y > 0.2f && _params.diag.y < 5.0f && _params.diag.z > 0.2f && _params.diag.z < 5.0f && fabsf(_params.offdiag.x) < 1.0f && //absolute of sine/cosine output cannot be greater than 1 - fabsf(_params.offdiag.x) < 1.0f && - fabsf(_params.offdiag.x) < 1.0f ){ + fabsf(_params.offdiag.y) < 1.0f && + fabsf(_params.offdiag.z) < 1.0f ){ return _fitness <= sq(_tolerance); }