APM: fixed overflow in geofence code for altitudes above 327 meters

This commit is contained in:
Andrew Tridgell 2012-07-31 15:46:47 +10:00
parent 8c47b0c087
commit 0b49ac0ed0
1 changed files with 3 additions and 3 deletions

View File

@ -151,7 +151,7 @@ static bool geofence_check_minalt(void)
if (g.fence_minalt == 0) {
return false;
}
return (current_loc.alt < (g.fence_minalt*100) + home.alt);
return (current_loc.alt < (g.fence_minalt*100.0) + home.alt);
}
/*
@ -165,7 +165,7 @@ static bool geofence_check_maxalt(void)
if (g.fence_maxalt == 0) {
return false;
}
return (current_loc.alt > (g.fence_maxalt*100) + home.alt);
return (current_loc.alt > (g.fence_maxalt*100.0) + home.alt);
}
@ -263,7 +263,7 @@ static void geofence_check(bool altitude_check_only)
// invalid min/max, use RTL_altitude
guided_WP.alt = home.alt + g.RTL_altitude;
} else {
guided_WP.alt = home.alt + 100*(g.fence_minalt + g.fence_maxalt)/2;
guided_WP.alt = home.alt + 100.0*(g.fence_minalt + g.fence_maxalt)/2;
}
guided_WP.id = 0;
guided_WP.p1 = 0;