ArduCopter: only call init_rc_out() once to avoid losing MOT information

This commit is contained in:
Andy Piper 2021-05-02 14:03:00 +01:00 committed by Andrew Tridgell
parent d70b8425f7
commit ef18b9f943
2 changed files with 0 additions and 2 deletions

View File

@ -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);

View File

@ -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);