Browse Source

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

zr-v5.1
Andy Piper 4 years ago committed by Andrew Tridgell
parent
commit
ef18b9f943
  1. 1
      ArduCopter/compassmot.cpp
  2. 1
      ArduCopter/motor_test.cpp

1
ArduCopter/compassmot.cpp

@ -122,7 +122,6 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan) @@ -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);

1
ArduCopter/motor_test.cpp

@ -150,7 +150,6 @@ MAV_RESULT Copter::mavlink_motor_test_start(const GCS_MAVLINK &gcs_chan, uint8_t @@ -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…
Cancel
Save