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.
This commit is contained in:
Randy Mackay 2015-01-06 15:55:32 +09:00
parent 152a3a2828
commit 1266a31631
1 changed files with 1 additions and 1 deletions

View File

@ -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)