mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
AP_Compass: eliminated possible division by zero in AK8963
This commit is contained in:
parent
b804430276
commit
f0753e965e
@ -483,6 +483,11 @@ bool AP_Compass_AK8963::read()
|
||||
return false;
|
||||
}
|
||||
|
||||
if (_accum_count == 0) {
|
||||
/* We're not ready to publish*/
|
||||
return true;
|
||||
}
|
||||
|
||||
/* Update */
|
||||
_field[0].x = _mag_x_accum * magnetometer_ASA[0] / _accum_count;
|
||||
_field[0].y = _mag_y_accum * magnetometer_ASA[1] / _accum_count;
|
||||
|
Loading…
Reference in New Issue
Block a user