Copter: remove enable_motor_output method

this doesn't actually do what it says it does.  I think the functionality to set the motors armed was split out long ago but this little method and its misleading comments remained
This commit is contained in:
Peter Barker 2023-03-24 11:26:44 +11:00 committed by Randy Mackay
parent 467cb75e95
commit 9c2d68bcd1
6 changed files with 5 additions and 13 deletions

View File

@ -755,8 +755,8 @@ bool AP_Arming_Copter::arm(const AP_Arming::Method method, const bool do_arming_
copter.sprayer.test_pump(false); copter.sprayer.test_pump(false);
#endif #endif
// enable output to motors // output lowest possible value to motors
copter.enable_motor_output(); copter.motors->output_min();
// finally actually arm the motors // finally actually arm the motors
copter.motors->armed(true); copter.motors->armed(true);

View File

@ -891,7 +891,6 @@ private:
void default_dead_zones(); void default_dead_zones();
void init_rc_in(); void init_rc_in();
void init_rc_out(); void init_rc_out();
void enable_motor_output();
void read_radio(); void read_radio();
void set_throttle_and_failsafe(uint16_t throttle_pwm); void set_throttle_and_failsafe(uint16_t throttle_pwm);
void set_throttle_zero_flag(int16_t throttle_control); void set_throttle_zero_flag(int16_t throttle_control);

View File

@ -123,7 +123,7 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan)
EXPECT_DELAY_MS(5000); EXPECT_DELAY_MS(5000);
// enable motors and pass through throttle // enable motors and pass through throttle
enable_motor_output(); motors->output_min(); // output lowest possible value to motors
motors->armed(true); motors->armed(true);
hal.util->set_soft_armed(true); hal.util->set_soft_armed(true);

View File

@ -153,7 +153,7 @@ MAV_RESULT Copter::mavlink_motor_test_start(const GCS_MAVLINK &gcs_chan, uint8_t
EXPECT_DELAY_MS(3000); EXPECT_DELAY_MS(3000);
// enable and arm motors // enable and arm motors
if (!motors->armed()) { if (!motors->armed()) {
enable_motor_output(); motors->output_min(); // output lowest possible value to motors
motors->armed(true); motors->armed(true);
hal.util->set_soft_armed(true); hal.util->set_soft_armed(true);
} }

View File

@ -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() void Copter::read_radio()
{ {
const uint32_t tnow_ms = millis(); const uint32_t tnow_ms = millis();

View File

@ -208,7 +208,7 @@ void Copter::init_ardupilot()
// enable output to motors // enable output to motors
if (arming.rc_calibration_checks(true)) { 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 // attempt to set the intial_mode, else set to STABILIZE