From 07420521aba19ee856235beed50269072b4d2234 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sun, 31 Aug 2014 10:44:09 +0900 Subject: [PATCH] Copter: default LAND_REPOSITION to 1 --- ArduCopter/config.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/config.h b/ArduCopter/config.h index d92bee3abc..4129372df7 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -446,7 +446,7 @@ # define LAND_REQUIRE_MIN_THROTTLE_TO_DISARM ENABLED #endif #ifndef LAND_REPOSITION_DEFAULT - # define LAND_REPOSITION_DEFAULT 0 // by default the pilot cannot override roll/pitch during landing + # define LAND_REPOSITION_DEFAULT 1 // by default the pilot can override roll/pitch during landing #endif #ifndef LAND_WITH_DELAY_MS # define LAND_WITH_DELAY_MS 4000 // default delay (in milliseconds) when a land-with-delay is triggered during a failsafe event