mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
Sub: bugfix fail condition in motor test initialization
This commit is contained in:
parent
7b5fb719dc
commit
ad67511f46
@ -150,6 +150,7 @@ bool Sub::init_motor_test()
|
||||
// after failure.
|
||||
if (tnow < last_do_motor_test_fail_ms + 10000 && last_do_motor_test_fail_ms > 0) {
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "10 second cool down required");
|
||||
return false;
|
||||
}
|
||||
|
||||
// check if safety switch has been pushed
|
||||
|
Loading…
Reference in New Issue
Block a user