Sub: bugfix fail condition in motor test initialization

This commit is contained in:
Jacob Walser 2019-03-19 22:29:21 -04:00
parent e6e0a2f0a5
commit 69caf2d918

View File

@ -158,6 +158,7 @@ bool Sub::init_motor_test()
// after failure. // after failure.
if (tnow < last_do_motor_test_fail_ms + 10000 && last_do_motor_test_fail_ms > 0) { 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"); gcs_send_text(MAV_SEVERITY_CRITICAL, "10 second cool down required");
return false;
} }
// check if safety switch has been pushed // check if safety switch has been pushed