From 69caf2d918e6bcd02dd4900bfb76432938a88ffa Mon Sep 17 00:00:00 2001 From: Jacob Walser Date: Tue, 19 Mar 2019 22:29:21 -0400 Subject: [PATCH] Sub: bugfix fail condition in motor test initialization --- ArduSub/motors.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/ArduSub/motors.cpp b/ArduSub/motors.cpp index 8fff7dc13a..d32f6937d1 100644 --- a/ArduSub/motors.cpp +++ b/ArduSub/motors.cpp @@ -158,6 +158,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