Sub: bugfix fail condition in motor test initialization

This commit is contained in:
Jacob Walser 2019-03-19 22:29:21 -04:00 committed by Randy Mackay
parent 7b5fb719dc
commit ad67511f46

View File

@ -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