Skip to content

Commit

Permalink
Plane: change tuning selector timing
Browse files Browse the repository at this point in the history
  • Loading branch information
shellixyz committed Dec 26, 2023
1 parent 43effec commit 64159fd
Showing 1 changed file with 4 additions and 4 deletions.
8 changes: 4 additions & 4 deletions libraries/AP_Tuning/AP_Tuning.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,7 +83,7 @@ void AP_Tuning::check_selector_switch(void)
selector_start_ms = AP_HAL::millis();
}
uint32_t hold_time = AP_HAL::millis() - selector_start_ms;
if (hold_time > 5000 && changed) {
if (hold_time > 3000 && changed) {
// save tune
save_parameters();
re_center();
Expand All @@ -96,13 +96,13 @@ 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 < 200) {
if (hold_time < 50) {
// debounce!
} else if (hold_time < 2000) {
} else if (hold_time < 500) {
// re-center the value
re_center();
gcs().send_text(MAV_SEVERITY_INFO, "Tuning: recentered %s", get_tuning_name(current_parm));
} else if (hold_time < 5000) {
} else if (hold_time < 1000) {
// change parameter
next_parameter();
}
Expand Down

0 comments on commit 64159fd

Please sign in to comment.