From f2b0fc35662d73cb1c9ecd7fcc3b91f672e33584 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 27 Dec 2014 13:33:06 +0900 Subject: [PATCH] Copter: disarm on landing regardless of pilot input --- ArduCopter/APM_Config.h | 2 +- ArduCopter/config.h | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduCopter/APM_Config.h b/ArduCopter/APM_Config.h index 97e59f6999..9045bb97a4 100644 --- a/ArduCopter/APM_Config.h +++ b/ArduCopter/APM_Config.h @@ -40,7 +40,7 @@ // other settings //#define THROTTLE_IN_DEADBAND 100 // redefine size of throttle deadband in pwm (0 ~ 1000) -//#define LAND_REQUIRE_MIN_THROTTLE_TO_DISARM DISABLED // when set to DISABLED vehicle will disarm after landing (in LAND mode or RTL) even if pilot has not put throttle to zero +//#define LAND_REQUIRE_MIN_THROTTLE_TO_DISARM ENABLED // when set to ENABLED vehicle will only disarm after landing (in AUTO, LAND or RTL) if pilot has put throttle to zero //#define HIL_MODE HIL_MODE_SENSORS // build for hardware-in-the-loop simulation diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 987b323511..695188663e 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -505,8 +505,8 @@ #ifndef LAND_DETECTOR_ROTATION_MAX # define LAND_DETECTOR_ROTATION_MAX 0.50f // vehicle rotation must be below 0.5 rad/sec (=30deg/sec for) vehicle to consider itself landed #endif -#ifndef LAND_REQUIRE_MIN_THROTTLE_TO_DISARM // require pilot to reduce throttle to minimum before vehicle will disarm - # define LAND_REQUIRE_MIN_THROTTLE_TO_DISARM ENABLED +#ifndef LAND_REQUIRE_MIN_THROTTLE_TO_DISARM + # define LAND_REQUIRE_MIN_THROTTLE_TO_DISARM DISABLED // we do not require pilot to reduce throttle to minimum before vehicle will disarm in AUTO, LAND or RTL #endif #ifndef LAND_REPOSITION_DEFAULT # define LAND_REPOSITION_DEFAULT 1 // by default the pilot can override roll/pitch during landing