Browse Source

Copter: fixed can't enter esc calibration by RC.

mission-4.1.18
misswhile 6 years ago committed by Randy Mackay
parent
commit
15a326bade
  1. 6
      ArduCopter/system.cpp

6
ArduCopter/system.cpp

@ -111,6 +111,9 @@ void Copter::init_ardupilot()
// allocate the motors class // allocate the motors class
allocate_motors(); allocate_motors();
// initialise rc channels including setting mode
rc().init();
// sets up motors and output to escs // sets up motors and output to escs
init_rc_out(); init_rc_out();
@ -215,9 +218,6 @@ void Copter::init_ardupilot()
// initialise AP_Logger library // initialise AP_Logger library
logger.setVehicle_Startup_Writer(FUNCTOR_BIND(&copter, &Copter::Log_Write_Vehicle_Startup_Messages, void)); logger.setVehicle_Startup_Writer(FUNCTOR_BIND(&copter, &Copter::Log_Write_Vehicle_Startup_Messages, void));
// initialise rc channels including setting mode
rc().init();
startup_INS_ground(); startup_INS_ground();
#ifdef ENABLE_SCRIPTING #ifdef ENABLE_SCRIPTING

Loading…
Cancel
Save