mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Sub: bugfix fail condition in motor test initialization
This commit is contained in:
parent
e6e0a2f0a5
commit
69caf2d918
@ -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
|
||||||
|
Loading…
Reference in New Issue
Block a user