mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Copter: RTL alt should not be above fence alt
Resolves issue #435 If the altitude fence is enabled, when the vehicle RTLs it will return at the lower of the RTL_ALT and the FENCE_ALT_MAX
This commit is contained in:
parent
4686eef266
commit
0665cf6b28
@ -359,7 +359,16 @@ static void rtl_land_run()
|
||||
// altitude is in cm above home
|
||||
static float get_RTL_alt()
|
||||
{
|
||||
// return maximum of current altitude and rtl altitude
|
||||
return max(current_loc.alt, g.rtl_altitude);
|
||||
// maximum of current altitude and rtl altitude
|
||||
float rtl_alt = max(current_loc.alt, g.rtl_altitude);
|
||||
|
||||
#if AC_FENCE == ENABLED
|
||||
// ensure not above fence altitude if alt fence is enabled
|
||||
if ((fence.get_enabled_fences() & AC_FENCE_TYPE_ALT_MAX) != 0) {
|
||||
rtl_alt = min(rtl_alt, fence.get_safe_alt()*100.0f);
|
||||
}
|
||||
#endif
|
||||
|
||||
return rtl_alt;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user