Browse Source

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
c415-sdk
Brent McLaughlin 4 years ago committed by Randy Mackay
parent
commit
04f817020f
  1. 2
      ArduCopter/precision_landing.cpp

2
ArduCopter/precision_landing.cpp

@ -17,7 +17,7 @@ void Copter::update_precland()
// use range finder altitude if it is valid, otherwise use home alt // use range finder altitude if it is valid, otherwise use home alt
if (rangefinder_alt_ok()) { 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()); precland.update(height_above_ground_cm, rangefinder_alt_ok());

Loading…
Cancel
Save