mirror of https://github.com/ArduPilot/ardupilot
Plane: Quadplane: check with motors if motor test is allowed
This commit is contained in:
parent
717f82f104
commit
6b106c401c
|
@ -87,6 +87,14 @@ MAV_RESULT QuadPlane::mavlink_motor_test_start(mavlink_channel_t chan, uint8_t m
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "Must be disarmed for motor test");
|
gcs().send_text(MAV_SEVERITY_INFO, "Must be disarmed for motor test");
|
||||||
return MAV_RESULT_FAILED;
|
return MAV_RESULT_FAILED;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Check Motor test is allowed
|
||||||
|
char failure_msg[50] {};
|
||||||
|
if (!motors->motor_test_checks(ARRAY_SIZE(failure_msg), failure_msg)) {
|
||||||
|
gcs().send_text(MAV_SEVERITY_CRITICAL,"Motor Test: %s", failure_msg);
|
||||||
|
return MAV_RESULT_FAILED;
|
||||||
|
}
|
||||||
|
|
||||||
// if test has not started try to start it
|
// if test has not started try to start it
|
||||||
if (!motor_test.running) {
|
if (!motor_test.running) {
|
||||||
// start test
|
// start test
|
||||||
|
|
Loading…
Reference in New Issue