From 99d6a45948d323b3dd69237601d0244498d6b395 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sun, 1 Jul 2012 13:34:02 -0700 Subject: [PATCH] Config.h Removed Approach delay redundancy - using land timer instead Removed Retro loiter mode param --- ArduCopter/config.h | 10 ---------- 1 file changed, 10 deletions(-) diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 8342b83cee..63162b38f6 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -565,12 +565,6 @@ # define RTL_AUTO_LAND ENABLED #endif -// RTL Approach Delay in seconds -#ifndef RTL_APPROACH_DELAY -# define RTL_APPROACH_DELAY 20 -#endif - - // LOITER Mode #ifndef OF_LOITER_YAW # define OF_LOITER_YAW YAW_HOLD @@ -990,10 +984,6 @@ #endif -#ifndef RETRO_LOITER_MODE -# define RETRO_LOITER_MODE DISABLED -#endif - #ifndef ALTERNATIVE_YAW_MODE # define ALTERNATIVE_YAW_MODE DISABLED #endif