Copter: remove LAND_REQUIRE_MIN_THROTTLE_TO_DISARM feature

This definition has been false for over a year and we have not heard of any users wanting to delay the disarming until the pilot's throttle goes to zero.  Removing this feature removes a small bit of complexity from the code.
This commit is contained in:
Randy Mackay 2016-08-01 11:40:20 +09:00
parent d1e257d5b6
commit ac4f36a992
5 changed files with 0 additions and 32 deletions

View File

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

View File

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

View File

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

View File

@ -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;
}

View File

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