AP_Tuning: debounce RC input

This commit is contained in:
Peter Barker 2019-06-17 20:46:00 +10:00 committed by Tom Pittenger
parent b6dbb8f464
commit 288b13868b

View File

@ -89,7 +89,9 @@ void AP_Tuning::check_selector_switch(void)
// low selector
if (selector_start_ms != 0) {
uint32_t hold_time = AP_HAL::millis() - selector_start_ms;
if (hold_time < 2000) {
if (hold_time < 200) {
// debounce!
} else if (hold_time < 2000) {
// re-center the value
re_center();
gcs().send_text(MAV_SEVERITY_INFO, "Tuning: recentered %s", get_tuning_name(current_parm));
@ -97,10 +99,10 @@ void AP_Tuning::check_selector_switch(void)
// change parameter
next_parameter();
}
}
selector_start_ms = 0;
}
}
}
/*
re-center the tuning value