From 4401cbec72afb3a2c1c0fc8135d891bfaaa275e7 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 26 Apr 2016 15:37:11 +1000 Subject: [PATCH] AP_InertialSensor: cope with zero delta angle time from Replay --- libraries/AP_InertialSensor/AP_InertialSensor.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index 2ce4fda8be..d939b55c9c 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -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();