mirror of https://github.com/ArduPilot/ardupilot
Plane: don't allow motortest if motors not allocated
This commit is contained in:
parent
03e382b1e3
commit
ebec8076c4
|
@ -77,6 +77,10 @@ void QuadPlane::motor_test_output()
|
|||
MAV_RESULT QuadPlane::mavlink_motor_test_start(mavlink_channel_t chan, uint8_t motor_seq, uint8_t throttle_type,
|
||||
uint16_t throttle_value, float timeout_sec, uint8_t motor_count)
|
||||
{
|
||||
if (!available() || motors == nullptr) {
|
||||
return MAV_RESULT_FAILED;
|
||||
}
|
||||
|
||||
if (motors->armed()) {
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Must be disarmed for motor test");
|
||||
return MAV_RESULT_FAILED;
|
||||
|
|
Loading…
Reference in New Issue