mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 09:38:29 -04:00
Copter: allow disabling ESC calibration
This commit is contained in:
parent
764fa36716
commit
1a911553eb
@ -357,7 +357,7 @@ const AP_Param::Info Copter::var_info[] PROGMEM = {
|
|||||||
// @DisplayName: ESC Calibration
|
// @DisplayName: ESC Calibration
|
||||||
// @Description: Controls whether ArduCopter will enter ESC calibration on the next restart. Do not adjust this parameter manually.
|
// @Description: Controls whether ArduCopter will enter ESC calibration on the next restart. Do not adjust this parameter manually.
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
// @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
|
// @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, 9:Disabled
|
||||||
GSCALAR(esc_calibrate, "ESC", 0),
|
GSCALAR(esc_calibrate, "ESC", 0),
|
||||||
|
|
||||||
// @Param: TUNE
|
// @Param: TUNE
|
||||||
|
@ -13,7 +13,8 @@ enum ESCCalibrationModes {
|
|||||||
ESCCAL_NONE = 0,
|
ESCCAL_NONE = 0,
|
||||||
ESCCAL_PASSTHROUGH_IF_THROTTLE_HIGH = 1,
|
ESCCAL_PASSTHROUGH_IF_THROTTLE_HIGH = 1,
|
||||||
ESCCAL_PASSTHROUGH_ALWAYS = 2,
|
ESCCAL_PASSTHROUGH_ALWAYS = 2,
|
||||||
ESCCAL_AUTO = 3
|
ESCCAL_AUTO = 3,
|
||||||
|
ESCCAL_DISABLED = 9,
|
||||||
};
|
};
|
||||||
|
|
||||||
// check if we should enter esc calibration mode
|
// check if we should enter esc calibration mode
|
||||||
@ -23,7 +24,7 @@ void Copter::esc_calibration_startup_check()
|
|||||||
pre_arm_rc_checks();
|
pre_arm_rc_checks();
|
||||||
if (!ap.pre_arm_rc_check) {
|
if (!ap.pre_arm_rc_check) {
|
||||||
// clear esc flag for next time
|
// clear esc flag for next time
|
||||||
if (g.esc_calibrate != ESCCAL_NONE) {
|
if ((g.esc_calibrate != ESCCAL_NONE) && (g.esc_calibrate != ESCCAL_DISABLED)) {
|
||||||
g.esc_calibrate.set_and_save(ESCCAL_NONE);
|
g.esc_calibrate.set_and_save(ESCCAL_NONE);
|
||||||
}
|
}
|
||||||
return;
|
return;
|
||||||
@ -59,12 +60,16 @@ void Copter::esc_calibration_startup_check()
|
|||||||
// perform automatic ESC calibration
|
// perform automatic ESC calibration
|
||||||
esc_calibration_auto();
|
esc_calibration_auto();
|
||||||
break;
|
break;
|
||||||
|
case ESCCAL_DISABLED:
|
||||||
default:
|
default:
|
||||||
// do nothing
|
// do nothing
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
// clear esc flag for next time
|
// clear esc flag for next time
|
||||||
g.esc_calibrate.set_and_save(ESCCAL_NONE);
|
if (g.esc_calibrate != ESCCAL_DISABLED) {
|
||||||
|
g.esc_calibrate.set_and_save(ESCCAL_NONE);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// esc_calibration_passthrough - pass through pilot throttle to escs
|
// esc_calibration_passthrough - pass through pilot throttle to escs
|
||||||
|
Loading…
Reference in New Issue
Block a user