mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
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
This commit is contained in:
parent
51e4f00cd2
commit
d20db9fad2
@ -179,7 +179,7 @@ bool Sub::verify_motor_test()
|
|||||||
|
|
||||||
// Require at least 2 Hz incoming do_set_motor requests
|
// Require at least 2 Hz incoming do_set_motor requests
|
||||||
if (AP_HAL::millis() > last_do_motor_test_ms + 500) {
|
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;
|
pass = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user