From 7ced9b1bd30d551565e63518f3b9da2ad85d3c73 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 23 Sep 2014 12:49:45 +0900 Subject: [PATCH] TradHeli: remove overall throttle level from landing check --- ArduCopter/control_land.pde | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/ArduCopter/control_land.pde b/ArduCopter/control_land.pde index 1092df79f9..cca30718e4 100644 --- a/ArduCopter/control_land.pde +++ b/ArduCopter/control_land.pde @@ -204,7 +204,10 @@ static void update_land_detector() { // detect whether we have landed by watching for low climb rate, motors hitting their lower limit, overall low throttle and low rotation rate if ((abs(climb_rate) < LAND_DETECTOR_CLIMBRATE_MAX) && motors.limit.throttle_lower && - (motors.get_throttle_out() < get_non_takeoff_throttle()) && (ahrs.get_gyro().length() < LAND_DETECTOR_ROTATION_MAX)) { +#if FRAME_CONFIG != HELI_FRAME + (motors.get_throttle_out() < get_non_takeoff_throttle()) && +#endif + (ahrs.get_gyro().length() < LAND_DETECTOR_ROTATION_MAX)) { if (!ap.land_complete) { // increase counter until we hit the trigger then set land complete flag if( land_detector < LAND_DETECTOR_TRIGGER) {