Skip to content

Commit

Permalink
Copter: Autotune: Increase waiting for level timeout.
Browse files Browse the repository at this point in the history
  • Loading branch information
lthall committed Apr 15, 2024
1 parent 8c8a22b commit 57dcb55
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion libraries/AC_AutoTune/AC_AutoTune.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -272,7 +272,7 @@ bool AC_AutoTune::currently_level()
{
// abort AutoTune if we pass 2 * AUTOTUNE_LEVEL_TIMEOUT_MS
const uint32_t now_ms = AP_HAL::millis();
if (now_ms - level_start_time_ms > 2 * AUTOTUNE_LEVEL_TIMEOUT_MS) {
if (now_ms - level_start_time_ms > 3 * AUTOTUNE_LEVEL_TIMEOUT_MS) {
gcs().send_text(MAV_SEVERITY_CRITICAL, "AutoTune: Failed to level, please tune manually");
mode = FAILED;
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_FAILED);
Expand Down

0 comments on commit 57dcb55

Please sign in to comment.