AP_AHRS_DCM: NFC comment on check_matrix() normalization reset

This commit is contained in:
Joshua Henderson 2022-04-15 19:59:48 -04:00 committed by Andrew Tridgell
parent 9d73cfb28f
commit 7cc2382a78
1 changed files with 4 additions and 1 deletions

View File

@ -265,7 +265,10 @@ AP_AHRS_DCM::check_matrix(void)
normalize();
if (_dcm_matrix.is_nan() ||
fabsf(_dcm_matrix.c.x) > 10) {
fabsf(_dcm_matrix.c.x) > 10.0) {
// See Issue #20284: regarding the selection of 10.0 for DCM reset
// This won't be lowered without evidence of an issue or mathematical proof & testing of a lower bound
// normalisation didn't fix the problem! We're
// in real trouble. All we can do is reset
//Serial.printf("ERROR: DCM matrix error. _dcm_matrix.c.x=%f\n",