diff --git a/ArduCopter/APM_Config.h b/ArduCopter/APM_Config.h index 2b9b1c9718..94f49f88d2 100644 --- a/ArduCopter/APM_Config.h +++ b/ArduCopter/APM_Config.h @@ -45,7 +45,6 @@ // other settings //#define THROTTLE_IN_DEADBAND 100 // redefine size of throttle deadband in pwm (0 ~ 1000) -//#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/commands_logic.cpp b/ArduCopter/commands_logic.cpp index 6d13d3cc41..23f296a542 100644 --- a/ArduCopter/commands_logic.cpp +++ b/ArduCopter/commands_logic.cpp @@ -253,15 +253,8 @@ void Copter::exit_mission() set_mode(LAND, MODE_REASON_MISSION_END); } }else{ -#if LAND_REQUIRE_MIN_THROTTLE_TO_DISARM == ENABLED - // disarm when the landing detector says we've landed and throttle is at minimum - if (ap.throttle_zero || failsafe.radio) { - init_disarm_motors(); - } -#else // if we've landed it's safe to disarm init_disarm_motors(); -#endif } } diff --git a/ArduCopter/config.h b/ArduCopter/config.h index d24cf7abd7..d2ae4e5213 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -365,9 +365,6 @@ #ifndef LAND_START_ALT # define LAND_START_ALT 1000 // altitude in cm where land controller switches to slow rate of descent #endif -#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 #endif diff --git a/ArduCopter/control_land.cpp b/ArduCopter/control_land.cpp index 2f4e85c21e..a8390a64dc 100644 --- a/ArduCopter/control_land.cpp +++ b/ArduCopter/control_land.cpp @@ -66,17 +66,10 @@ void Copter::land_gps_run() #endif wp_nav.init_loiter_target(); -#if LAND_REQUIRE_MIN_THROTTLE_TO_DISARM == ENABLED - // disarm when the landing detector says we've landed and throttle is at minimum - if (ap.land_complete && (ap.throttle_zero || failsafe.radio)) { - init_disarm_motors(); - } -#else // disarm when the landing detector says we've landed if (ap.land_complete) { init_disarm_motors(); } -#endif return; } @@ -132,17 +125,10 @@ void Copter::land_nogps_run() attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); #endif -#if LAND_REQUIRE_MIN_THROTTLE_TO_DISARM == ENABLED - // disarm when the landing detector says we've landed and throttle is at minimum - if (ap.land_complete && (ap.throttle_zero || failsafe.radio)) { - init_disarm_motors(); - } -#else // disarm when the landing detector says we've landed if (ap.land_complete) { init_disarm_motors(); } -#endif return; } diff --git a/ArduCopter/control_rtl.cpp b/ArduCopter/control_rtl.cpp index 92629702bd..de29d8fc38 100644 --- a/ArduCopter/control_rtl.cpp +++ b/ArduCopter/control_rtl.cpp @@ -375,17 +375,10 @@ void Copter::rtl_land_run() // set target to current position wp_nav.init_loiter_target(); -#if LAND_REQUIRE_MIN_THROTTLE_TO_DISARM == ENABLED - // disarm when the landing detector says we've landed and throttle is at minimum - if (ap.land_complete && (ap.throttle_zero || failsafe.radio)) { - init_disarm_motors(); - } -#else // disarm when the landing detector says we've landed if (ap.land_complete) { init_disarm_motors(); } -#endif // check if we've completed this stage of RTL rtl_state_complete = ap.land_complete;