Browse Source

Plane: don't allow motortest if motors not allocated

gps-1.3.1
Peter Barker 4 years ago committed by Peter Barker
parent
commit
7e8f812909
  1. 4
      ArduPlane/motor_test.cpp

4
ArduPlane/motor_test.cpp

@ -77,6 +77,10 @@ void QuadPlane::motor_test_output() @@ -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…
Cancel
Save