diff --git a/ArduCopter/commands.pde b/ArduCopter/commands.pde index 82626ef8cd..7730ad053c 100644 --- a/ArduCopter/commands.pde +++ b/ArduCopter/commands.pde @@ -1,16 +1,5 @@ // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- -static int32_t get_RTL_alt() -{ - if(g.rtl_altitude <= 0) { - return min(current_loc.alt, RTL_ALT_MAX); - }else if (g.rtl_altitude < current_loc.alt) { - return min(current_loc.alt, RTL_ALT_MAX); - }else{ - return g.rtl_altitude; - } -} - // run this at setup on the ground // ------------------------------- static void init_home() diff --git a/ArduCopter/config.h b/ArduCopter/config.h index f4b3da842e..67b394219a 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -541,10 +541,6 @@ # define RTL_ALT 1500 // default alt to return to home in cm, 0 = Maintain current altitude #endif -#ifndef RTL_ALT_MAX - # define RTL_ALT_MAX 8000 // Max height to return to home in cm (i.e 80m) -#endif - #ifndef RTL_LOITER_TIME # define RTL_LOITER_TIME 5000 // Time (in milliseconds) to loiter above home before begining final descent #endif diff --git a/ArduCopter/control_rtl.pde b/ArduCopter/control_rtl.pde index 5bbd80c298..aec6b97cb6 100644 --- a/ArduCopter/control_rtl.pde +++ b/ArduCopter/control_rtl.pde @@ -268,3 +268,11 @@ static void rtl_land_run() rtl_state_complete = ap.land_complete; } +// get_RTL_alt - return altitude which vehicle should return home at +// 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); +} +