diff --git a/ArduCopter/radio.pde b/ArduCopter/radio.pde index e057ff99bafd6e0f7efc64d8abf440ec1293198a..3d8423a639ada92c80972051d57ddb4d2905befa 100644 --- a/ArduCopter/radio.pde +++ b/ArduCopter/radio.pde @@ -86,7 +86,7 @@ static void init_rc_out() if(g.esc_calibrate == 0) { // we will enter esc_calibrate mode on next reboot g.esc_calibrate.set_and_save(1); - // send miinimum throttle out to ESC + // send minimum throttle out to ESC motors.output_min(); // display message on console cliSerial->printf_P(PSTR("Entering ESC Calibration: please restart APM.\n")); @@ -99,7 +99,7 @@ static void init_rc_out() cliSerial->printf_P(PSTR("ESC Calibration active: passing throttle through to ESCs.\n")); // clear esc flag g.esc_calibrate.set_and_save(0); - // block until we restart + // pass through user throttle to escs init_esc(); } }else{ diff --git a/ArduCopter/setup.pde b/ArduCopter/setup.pde index e11253f4cdf5fbf7f8fb33545f23471bee37bb71..e1c414fe176987228582ba28ea0ef1691ff568f5 100644 --- a/ArduCopter/setup.pde +++ b/ArduCopter/setup.pde @@ -1095,6 +1095,8 @@ static void print_enabled(bool b) static void init_esc() { + // reduce update rate to motors to 50Hz + motors.set_update_rate(50); motors.enable(); motors.armed(true); while(1) {