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
This commit is contained in:
Brent McLaughlin 2020-11-18 22:33:26 -05:00 committed by Randy Mackay
parent 5edae526fd
commit 04f817020f

View File

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