diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index 6f6051f896..91c2db7fd6 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -755,8 +755,8 @@ bool AP_Arming_Copter::arm(const AP_Arming::Method method, const bool do_arming_ copter.sprayer.test_pump(false); #endif - // enable output to motors - copter.enable_motor_output(); + // output lowest possible value to motors + copter.motors->output_min(); // finally actually arm the motors copter.motors->armed(true); diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 8322ad66e6..be136776ed 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -891,7 +891,6 @@ private: void default_dead_zones(); void init_rc_in(); void init_rc_out(); - void enable_motor_output(); void read_radio(); void set_throttle_and_failsafe(uint16_t throttle_pwm); void set_throttle_zero_flag(int16_t throttle_control); diff --git a/ArduCopter/compassmot.cpp b/ArduCopter/compassmot.cpp index 5e24bd2b40..532cbb243a 100644 --- a/ArduCopter/compassmot.cpp +++ b/ArduCopter/compassmot.cpp @@ -123,7 +123,7 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan) EXPECT_DELAY_MS(5000); // enable motors and pass through throttle - enable_motor_output(); + motors->output_min(); // output lowest possible value to motors motors->armed(true); hal.util->set_soft_armed(true); diff --git a/ArduCopter/motor_test.cpp b/ArduCopter/motor_test.cpp index 13114e1744..6efd17d41f 100644 --- a/ArduCopter/motor_test.cpp +++ b/ArduCopter/motor_test.cpp @@ -153,7 +153,7 @@ 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()) { - enable_motor_output(); + motors->output_min(); // output lowest possible value to motors motors->armed(true); hal.util->set_soft_armed(true); } diff --git a/ArduCopter/radio.cpp b/ArduCopter/radio.cpp index 0de13687d1..57043fba91 100644 --- a/ArduCopter/radio.cpp +++ b/ArduCopter/radio.cpp @@ -77,13 +77,6 @@ void Copter::init_rc_out() } -// enable_motor_output() - enable and output lowest possible value to motors -void Copter::enable_motor_output() -{ - // enable motors - motors->output_min(); -} - void Copter::read_radio() { const uint32_t tnow_ms = millis(); diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index dae7a40c28..b2b8c95e07 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -208,7 +208,7 @@ void Copter::init_ardupilot() // enable output to motors if (arming.rc_calibration_checks(true)) { - enable_motor_output(); + motors->output_min(); // output lowest possible value to motors } // attempt to set the intial_mode, else set to STABILIZE