mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
AP_InertialSensor: cope with zero delta angle time from Replay
This commit is contained in:
parent
f367180f47
commit
4401cbec72
@ -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();
|
||||
|
Loading…
Reference in New Issue
Block a user