Browse Source

Rover: ensure arming when running motor test

c415-sdk
Peter Barker 4 years ago committed by Randy Mackay
parent
commit
001c39f17b
  1. 4
      Rover/motor_test.cpp

4
Rover/motor_test.cpp

@ -124,7 +124,9 @@ MAV_RESULT Rover::mavlink_motor_test_start(const GCS_MAVLINK &gcs_chan, AP_Motor @@ -124,7 +124,9 @@ MAV_RESULT Rover::mavlink_motor_test_start(const GCS_MAVLINK &gcs_chan, AP_Motor
// arm motors
if (!arming.is_armed()) {
arming.arm(AP_Arming::Method::MOTORTEST);
if (!arming.arm(AP_Arming::Method::MOTORTEST)) {
return MAV_RESULT_FAILED;
}
}
// disable failsafes

Loading…
Cancel
Save