Browse Source

Copter: enable motors at end of initialisation

mission-4.1.18
Randy Mackay 8 years ago
parent
commit
1bfbf0d43f
  1. 6
      ArduCopter/radio.cpp
  2. 6
      ArduCopter/system.cpp

6
ArduCopter/radio.cpp

@ -69,12 +69,6 @@ void Copter::init_rc_out() @@ -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();

6
ArduCopter/system.cpp

@ -307,6 +307,12 @@ void Copter::init_ardupilot() @@ -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…
Cancel
Save