From 7cb9ad6e2b3b6a93879db0da76f54faa65c6e288 Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Mon, 1 Aug 2016 21:05:21 -0700 Subject: [PATCH] Copter: descend normally from 35cm --- ArduCopter/control_land.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/control_land.cpp b/ArduCopter/control_land.cpp index f981bc27b6..d45d619718 100644 --- a/ArduCopter/control_land.cpp +++ b/ArduCopter/control_land.cpp @@ -196,7 +196,7 @@ void Copter::land_run_vertical_control(bool pause_descent) // Constrain the demanded vertical velocity so that it is between the configured maximum descent speed and the configured minimum descent speed. cmb_rate = constrain_float(cmb_rate, max_land_descent_velocity, -abs(g.land_speed)); - if (doing_precision_landing && alt_above_ground < 200.0f) { + if (doing_precision_landing && rangefinder_alt_ok() && rangefinder_state.alt_cm > 35.0f && rangefinder_state.alt_cm < 200.0f) { float max_descent_speed = abs(g.land_speed)/2.0f; float land_slowdown = MAX(0.0f, pos_control.get_horizontal_error()*(max_descent_speed/precland_acceptable_error)); cmb_rate = MIN(-precland_min_descent_speed, -max_descent_speed+land_slowdown);