AP_InertialSensor: cope with zero delta angle time from Replay

This commit is contained in:
Andrew Tridgell 2016-04-26 15:37:11 +10:00
parent f367180f47
commit 4401cbec72

View File

@ -1172,7 +1172,7 @@ float AP_InertialSensor::get_delta_velocity_dt(uint8_t i) const
*/
float AP_InertialSensor::get_delta_angle_dt(uint8_t i) const
{
if (_delta_angle_valid[i]) {
if (_delta_angle_valid[i] && _delta_angle_dt[i] > 0) {
return _delta_angle_dt[i];
}
return get_delta_time();