mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_InertialSensor: eliminate SITL float-equals issues
This commit is contained in:
parent
d968e27b45
commit
04c36efdbf
@ -164,8 +164,8 @@ void AP_InertialSensor_SITL::timer_update(void)
|
||||
|
||||
float AP_InertialSensor_SITL::gyro_drift(void)
|
||||
{
|
||||
if (sitl->drift_speed == 0.0f ||
|
||||
sitl->drift_time == 0.0f) {
|
||||
if (is_zero(sitl->drift_speed) ||
|
||||
is_zero(sitl->drift_time)) {
|
||||
return 0;
|
||||
}
|
||||
double period = sitl->drift_time * 2;
|
||||
|
Loading…
Reference in New Issue
Block a user