SITL: SIM_XPlane: fix fabsf/abs warning; location alts are in integer cm

This commit is contained in:
Peter Barker 2016-10-20 13:35:57 +11:00 committed by Lucas De Marchi
parent cc86011d20
commit 8b38ce666d
1 changed files with 1 additions and 1 deletions

View File

@ -302,7 +302,7 @@ bool XPlane::receive_data(void)
accel_earth.z += GRAVITY_MSS;
// the position may slowly deviate due to float accuracy and longitude scaling
if (get_distance(loc, location) > 4 || fabsf(loc.alt - location.alt)*0.01 > 2) {
if (get_distance(loc, location) > 4 || abs(loc.alt - location.alt)*0.01f > 2.0f) {
printf("X-Plane home reset dist=%f alt=%.1f/%.1f\n",
get_distance(loc, location), loc.alt*0.01f, location.alt*0.01f);
// reset home location