From f41d7ddaee5c0ece8df31b01459254d66940030b Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 6 Jan 2015 15:55:32 +0900 Subject: [PATCH] Rally: reduce distance limit to 300m for copter This reduces the chance that a forgotten rally point will cause the vehicle to RTL to a distant location because instead it will RTL to home. --- libraries/AP_Rally/AP_Rally.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Rally/AP_Rally.cpp b/libraries/AP_Rally/AP_Rally.cpp index fee98c28b9..bdf1e7d6e8 100644 --- a/libraries/AP_Rally/AP_Rally.cpp +++ b/libraries/AP_Rally/AP_Rally.cpp @@ -13,7 +13,7 @@ StorageAccess AP_Rally::_storage(StorageManager::StorageRally); // ArduCopter/defines.h sets this, and this definition will be moved into ArduPlane/defines.h when that is patched to use the lib #ifdef APM_BUILD_DIRECTORY #if APM_BUILD_TYPE(APM_BUILD_ArduCopter) - #define RALLY_LIMIT_KM_DEFAULT 2.0 + #define RALLY_LIMIT_KM_DEFAULT 0.3 #elif APM_BUILD_TYPE(APM_BUILD_ArduPlane) #define RALLY_LIMIT_KM_DEFAULT 5.0 #elif APM_BUILD_TYPE(APM_BUILD_APMrover2)