Copter: RTL at no less than 2m above home alt

This commit is contained in:
David Dewey 2013-08-13 16:53:45 +08:00 committed by Randy Mackay
parent 67b0c6f5c4
commit 0545185218
2 changed files with 5 additions and 0 deletions

View File

@ -467,6 +467,10 @@
# define RTL_ALT 1500 // default alt to return to home in cm, 0 = Maintain current altitude
#endif
#ifndef RTL_ALT_MIN
# define RTL_ALT_MIN 200 // min height above ground for RTL (i.e 2m)
#endif
#ifndef RTL_LOITER_TIME
# define RTL_LOITER_TIME 5000 // Time (in milliseconds) to loiter above home before begining final descent
#endif

View File

@ -389,6 +389,7 @@ static float get_RTL_alt()
{
// maximum of current altitude and rtl altitude
float rtl_alt = max(current_loc.alt, g.rtl_altitude);
rtl_alt = max(rtl_alt, RTL_ALT_MIN);
#if AC_FENCE == ENABLED
// ensure not above fence altitude if alt fence is enabled