From 3dfaa5f02195e2a265f43239dba19d9dfc264a4a Mon Sep 17 00:00:00 2001 From: Justin Date: Mon, 8 Jul 2019 10:47:57 -0700 Subject: [PATCH] Sub: Changed the MAV_SEVERITY of the motor test timed out message to INFO so that it wont be read out loud everytime the user ends the motor test --- ArduSub/motors.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduSub/motors.cpp b/ArduSub/motors.cpp index b67f523ecc..e16c37a32c 100644 --- a/ArduSub/motors.cpp +++ b/ArduSub/motors.cpp @@ -60,7 +60,7 @@ bool Sub::verify_motor_test() // Require at least 2 Hz incoming do_set_motor requests if (AP_HAL::millis() > last_do_motor_test_ms + 500) { - gcs().send_text(MAV_SEVERITY_WARNING, "Motor test timed out!"); + gcs().send_text(MAV_SEVERITY_INFO, "Motor test timed out!"); pass = false; }