From 04f817020fd7361b00c774ccd8a02004062b62c6 Mon Sep 17 00:00:00 2001 From: Brent McLaughlin Date: Wed, 18 Nov 2020 22:33:26 -0500 Subject: [PATCH] Copter: use glitch-protected range from rangefinder for precision landing use glitch protected result from rangefinder so precision landing avoids aggressive maneuvers due to large range spikes --- ArduCopter/precision_landing.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/precision_landing.cpp b/ArduCopter/precision_landing.cpp index 4ae12b3e5d..ea184522c0 100644 --- a/ArduCopter/precision_landing.cpp +++ b/ArduCopter/precision_landing.cpp @@ -17,7 +17,7 @@ void Copter::update_precland() // use range finder altitude if it is valid, otherwise use home alt if (rangefinder_alt_ok()) { - height_above_ground_cm = rangefinder_state.alt_cm; + height_above_ground_cm = rangefinder_state.alt_cm_glitch_protected; } precland.update(height_above_ground_cm, rangefinder_alt_ok());