mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Copter: avoid terrain failsafe from a single out-of-range rangefinder reading
This commit is contained in:
parent
67ff96d8de
commit
8e095d4a81
@ -40,8 +40,10 @@ void Copter::read_rangefinder(void)
|
|||||||
// filter rangefinder for use by AC_WPNav
|
// filter rangefinder for use by AC_WPNav
|
||||||
uint32_t now = AP_HAL::millis();
|
uint32_t now = AP_HAL::millis();
|
||||||
|
|
||||||
|
const bool timed_out = now - rangefinder_state.last_healthy_ms > RANGEFINDER_TIMEOUT_MS;
|
||||||
|
|
||||||
if (rangefinder_state.alt_healthy) {
|
if (rangefinder_state.alt_healthy) {
|
||||||
if (now - rangefinder_state.last_healthy_ms > RANGEFINDER_TIMEOUT_MS) {
|
if (timed_out) {
|
||||||
// reset filter if we haven't used it within the last second
|
// reset filter if we haven't used it within the last second
|
||||||
rangefinder_state.alt_cm_filt.reset(rangefinder_state.alt_cm);
|
rangefinder_state.alt_cm_filt.reset(rangefinder_state.alt_cm);
|
||||||
} else {
|
} else {
|
||||||
@ -51,7 +53,9 @@ void Copter::read_rangefinder(void)
|
|||||||
}
|
}
|
||||||
|
|
||||||
// send rangefinder altitude and health to waypoint navigation library
|
// send rangefinder altitude and health to waypoint navigation library
|
||||||
wp_nav->set_rangefinder_alt(rangefinder_state.enabled, rangefinder_state.alt_healthy, rangefinder_state.alt_cm_filt.get());
|
if (rangefinder_state.alt_healthy || timed_out) {
|
||||||
|
wp_nav->set_rangefinder_alt(rangefinder_state.enabled, rangefinder_state.alt_healthy, rangefinder_state.alt_cm_filt.get());
|
||||||
|
}
|
||||||
|
|
||||||
#else
|
#else
|
||||||
rangefinder_state.enabled = false;
|
rangefinder_state.enabled = false;
|
||||||
|
Loading…
Reference in New Issue
Block a user