Browse Source

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

master
David Dewey 12 years ago committed by Randy Mackay
parent
commit
0545185218
  1. 4
      ArduCopter/config.h
  2. 1
      ArduCopter/control_rtl.pde

4
ArduCopter/config.h

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

1
ArduCopter/control_rtl.pde

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

Loading…
Cancel
Save