From e6b3638d848016dca8f85cd580f451da9aa5b2fd Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 12 May 2016 15:45:18 +0900 Subject: [PATCH] Copter: minor change to land mode's logic to use rangefinder No functional change --- ArduCopter/control_land.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/control_land.cpp b/ArduCopter/control_land.cpp index 1425f693fd..eecd1545c9 100644 --- a/ArduCopter/control_land.cpp +++ b/ArduCopter/control_land.cpp @@ -234,7 +234,7 @@ void Copter::land_nogps_run() float Copter::get_land_descent_speed() { #if RANGEFINDER_ENABLED == ENABLED - bool rangefinder_ok = rangefinder_state.enabled && (rangefinder.status() == RangeFinder::RangeFinder_Good); + bool rangefinder_ok = rangefinder_state.enabled && rangefinder_state.alt_healthy; #else bool rangefinder_ok = false; #endif @@ -252,7 +252,7 @@ float Copter::get_land_descent_speed() } // if we are above 10m and the rangefinder does not sense anything perform regular alt hold descent - if ((target_alt_cm >= LAND_START_ALT) && !(rangefinder_ok && rangefinder_state.alt_healthy)) { + if ((target_alt_cm >= LAND_START_ALT) && !rangefinder_ok) { if (g.land_speed_high > 0) { // user has asked for a different landing speed than normal descent rate return -abs(g.land_speed_high);