From ef18b9f9438775cfda3d313e9771f66850aa6350 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sun, 2 May 2021 14:03:00 +0100 Subject: [PATCH] ArduCopter: only call init_rc_out() once to avoid losing MOT information --- ArduCopter/compassmot.cpp | 1 - ArduCopter/motor_test.cpp | 1 - 2 files changed, 2 deletions(-) diff --git a/ArduCopter/compassmot.cpp b/ArduCopter/compassmot.cpp index ae3030a6ce..63ae89e807 100644 --- a/ArduCopter/compassmot.cpp +++ b/ArduCopter/compassmot.cpp @@ -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); diff --git a/ArduCopter/motor_test.cpp b/ArduCopter/motor_test.cpp index 1cea7014cb..2ac911f8f3 100644 --- a/ArduCopter/motor_test.cpp +++ b/ArduCopter/motor_test.cpp @@ -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);