|
|
|
@ -41,6 +41,7 @@ void Copter::motor_test_output()
@@ -41,6 +41,7 @@ void Copter::motor_test_output()
|
|
|
|
|
motor_test_start_ms = now; |
|
|
|
|
if (!motors->armed()) { |
|
|
|
|
motors->armed(true); |
|
|
|
|
hal.util->set_soft_armed(true); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
return; |
|
|
|
@ -152,6 +153,7 @@ MAV_RESULT Copter::mavlink_motor_test_start(const GCS_MAVLINK &gcs_chan, uint8_t
@@ -152,6 +153,7 @@ MAV_RESULT Copter::mavlink_motor_test_start(const GCS_MAVLINK &gcs_chan, uint8_t
|
|
|
|
|
init_rc_out(); |
|
|
|
|
enable_motor_output(); |
|
|
|
|
motors->armed(true); |
|
|
|
|
hal.util->set_soft_armed(true); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// disable throttle and gps failsafe
|
|
|
|
@ -197,6 +199,7 @@ void Copter::motor_test_stop()
@@ -197,6 +199,7 @@ void Copter::motor_test_stop()
|
|
|
|
|
|
|
|
|
|
// disarm motors
|
|
|
|
|
motors->armed(false); |
|
|
|
|
hal.util->set_soft_armed(false); |
|
|
|
|
|
|
|
|
|
// reset timeout
|
|
|
|
|
motor_test_start_ms = 0; |
|
|
|
|