From e16cccf21846d65595ef345c91bb31404e442070 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 7 Jan 2016 17:29:54 +0900 Subject: [PATCH] Copter: RTL config formatting fix No functional change --- ArduCopter/config.h | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/ArduCopter/config.h b/ArduCopter/config.h index d340e314e0..a1a65fef86 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -484,24 +484,24 @@ # define RTL_ALT 1500 // default alt to return to home in cm, 0 = Maintain current altitude #endif -#ifndef RTL_CONE_SLOPE - # define RTL_CONE_SLOPE 3.0f // slope of RTL cone. 0 = No cone -#endif - #ifndef RTL_ALT_MIN # define RTL_ALT_MIN 200 // min height above ground for RTL (i.e 2m) #endif +#ifndef RTL_CLIMB_MIN_DEFAULT + # define RTL_CLIMB_MIN_DEFAULT 0 // vehicle will always climb this many cm as first stage of RTL +#endif + #ifndef RTL_ABS_MIN_CLIMB - # define RTL_ABS_MIN_CLIMB 250 // absolute minimum initial climb + # define RTL_ABS_MIN_CLIMB 250 // absolute minimum initial climb #endif -#ifndef RTL_MIN_CONE_SLOPE - # define RTL_MIN_CONE_SLOPE 0.5f // absolute minimum initial climb +#ifndef RTL_CONE_SLOPE + # define RTL_CONE_SLOPE 3.0f // slope of RTL cone (height / distance). 0 = No cone #endif -#ifndef RTL_CLIMB_MIN_DEFAULT - # define RTL_CLIMB_MIN_DEFAULT 0 // vehicle will always climb this many cm as first stage of RTL +#ifndef RTL_MIN_CONE_SLOPE + # define RTL_MIN_CONE_SLOPE 0.5f // minimum slope of cone #endif #ifndef RTL_LOITER_TIME