mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: only call init_rc_out() once to avoid losing MOT information
This commit is contained in:
parent
d70b8425f7
commit
ef18b9f943
|
@ -122,7 +122,6 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan)
|
|||
EXPECT_DELAY_MS(5000);
|
||||
|
||||
// enable motors and pass through throttle
|
||||
init_rc_out();
|
||||
enable_motor_output();
|
||||
motors->armed(true);
|
||||
hal.util->set_soft_armed(true);
|
||||
|
|
|
@ -150,7 +150,6 @@ MAV_RESULT Copter::mavlink_motor_test_start(const GCS_MAVLINK &gcs_chan, uint8_t
|
|||
EXPECT_DELAY_MS(3000);
|
||||
// enable and arm motors
|
||||
if (!motors->armed()) {
|
||||
init_rc_out();
|
||||
enable_motor_output();
|
||||
motors->armed(true);
|
||||
hal.util->set_soft_armed(true);
|
||||
|
|
Loading…
Reference in New Issue