mirror of https://github.com/ArduPilot/ardupilot
Copter: rename ESC param to ESC_CALIBRATION
This commit is contained in:
parent
1a911553eb
commit
c33453fcf9
|
@ -353,12 +353,12 @@ const AP_Param::Info Copter::var_info[] PROGMEM = {
|
|||
// @User: Standard
|
||||
GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),
|
||||
|
||||
// @Param: ESC
|
||||
// @Param: ESC_CALIBRATION
|
||||
// @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 if throttle high, 2:Start-up in ESC Calibration mode regardless of throttle, 9:Disabled
|
||||
GSCALAR(esc_calibrate, "ESC", 0),
|
||||
GSCALAR(esc_calibrate, "ESC_CALIBRATION", 0),
|
||||
|
||||
// @Param: TUNE
|
||||
// @DisplayName: Channel 6 Tuning
|
||||
|
|
Loading…
Reference in New Issue