AP_AHRS: prevent a infinity value

This commit is contained in:
Andrew Tridgell 2014-04-21 15:23:01 +10:00
parent 7ca08294e7
commit 4d24a86088

View File

@ -629,6 +629,10 @@ AP_AHRS_DCM::drift_correction(float deltat)
} else { } else {
GA_b[i] = _ra_sum[i]; GA_b[i] = _ra_sum[i];
} }
if (GA_b[i].is_zero()) {
// wait for some non-zero acceleration information
continue;
}
GA_b[i].normalize(); GA_b[i].normalize();
if (GA_b[i].is_inf()) { if (GA_b[i].is_inf()) {
// wait for some non-zero acceleration information // wait for some non-zero acceleration information