Skip to content

Commit

Permalink
AP_Compass: Correct parameter checks in compass cal
Browse files Browse the repository at this point in the history
  • Loading branch information
jschall committed Mar 12, 2015
1 parent 81c5a85 commit b422512
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions libraries/AP_Compass/CompassCalibrator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}
Expand Down

0 comments on commit b422512

Please sign in to comment.