SITL: Avoid run-time FPEs due to bad gyro settings if SIM_DRIFT_TIME is set to 0

_gyro_drift essentially suffers a divide-by-zero if SIM_DRIFT_TIME is 0.  The gyro initialisation routines in AP_InertialSensor do not return once the generated NaN propogates back to them.
This commit is contained in:
Peter Barker 2015-04-18 22:26:36 +10:00 committed by Andrew Tridgell
parent 12957867fd
commit c95348c1d9
1 changed files with 2 additions and 1 deletions

View File

@ -80,7 +80,8 @@ uint16_t SITL_State::_airspeed_sensor(float airspeed)
float SITL_State::_gyro_drift(void)
{
if (_sitl->drift_speed == 0.0) {
if (_sitl->drift_speed == 0.0f ||
_sitl->drift_time == 0.0f) {
return 0;
}
double period = _sitl->drift_time * 2;