Browse Source

Copter: setting ESC param to 2 skips high throttle check

This allows the all-at-once ESC calibration to be performed on a setup
in which the RC input takes some time to come online.
mission-4.1.18
Randy Mackay 11 years ago
parent
commit
e1a6b07e60
  1. 2
      ArduCopter/Parameters.pde
  2. 2
      ArduCopter/radio.pde

2
ArduCopter/Parameters.pde

@ -343,7 +343,7 @@ const AP_Param::Info var_info[] PROGMEM = { @@ -343,7 +343,7 @@ const AP_Param::Info var_info[] PROGMEM = {
// @DisplayName: ESC Calibration
// @Description: Controls whether ArduCopter will enter ESC calibration on the next restart. Do not adjust this parameter manually.
// @User: Advanced
// @Values: 0:Normal Start-up,1:Start-up in ESC Calibration mode
// @Values: 0:Normal Start-up, 1:Start-up in ESC Calibration mode if throttle high, 2:Start-up in ESC Calibration mode regardless of throttle
GSCALAR(esc_calibrate, "ESC", 0),
// @Param: TUNE

2
ArduCopter/radio.pde

@ -57,7 +57,7 @@ static void init_rc_out() @@ -57,7 +57,7 @@ static void init_rc_out()
g.rc_3.set_range_out(0,1000);
// full throttle means to enter ESC calibration
if(g.rc_3.control_in >= (g.throttle_max - 50)) {
if(g.rc_3.control_in >= (g.throttle_max - 50) || (g.esc_calibrate == 2)) {
if(g.esc_calibrate == 0) {
// we will enter esc_calibrate mode on next reboot
g.esc_calibrate.set_and_save(1);

Loading…
Cancel
Save