Copter: stop setting motor output levels at boot

We should not have different state in our motors library based on your RC stick positions at boot.

this call is made anywhere we actually arm the motors anyway.
This commit is contained in:
Peter Barker 2023-03-24 11:22:49 +11:00 committed by Peter Barker
parent 9ec6b69433
commit 3f21946d50
1 changed files with 1 additions and 4 deletions

View File

@ -206,10 +206,7 @@ void Copter::init_ardupilot()
ins.set_log_raw_bit(MASK_LOG_IMU_RAW);
// enable output to motors
if (arming.rc_calibration_checks(true)) {
motors->output_min(); // output lowest possible value to motors
}
motors->output_min(); // output lowest possible value to motors
// attempt to set the intial_mode, else set to STABILIZE
if (!set_mode((enum Mode::Number)g.initial_mode.get(), ModeReason::INITIALISED)) {