mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
APM: fixed overflow in geofence code for altitudes above 327 meters
This commit is contained in:
parent
4829e937ea
commit
24ba59f528
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user