mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter: enable motors at end of initialisation
This commit is contained in:
parent
6a1c58b5a5
commit
1bfbf0d43f
@ -69,12 +69,6 @@ void Copter::init_rc_out()
|
||||
// check if we should enter esc calibration mode
|
||||
esc_calibration_startup_check();
|
||||
|
||||
// enable output to motors
|
||||
arming.pre_arm_rc_checks(true);
|
||||
if (ap.pre_arm_rc_check) {
|
||||
enable_motor_output();
|
||||
}
|
||||
|
||||
// refresh auxiliary channel to function map
|
||||
SRV_Channels::update_aux_servo_function();
|
||||
|
||||
|
@ -307,6 +307,12 @@ void Copter::init_ardupilot()
|
||||
ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW));
|
||||
ins.set_dataflash(&DataFlash);
|
||||
|
||||
// enable output to motors
|
||||
arming.pre_arm_rc_checks(true);
|
||||
if (ap.pre_arm_rc_check) {
|
||||
enable_motor_output();
|
||||
}
|
||||
|
||||
cliSerial->printf("\nReady to FLY ");
|
||||
|
||||
// flag that initialisation has completed
|
||||
|
Loading…
Reference in New Issue
Block a user