mirror of https://github.com/ArduPilot/ardupilot
AP_RPM: stop defaulting RPM_PIN to 54
This commit is contained in:
parent
bbcce717dc
commit
7eaab583d4
|
@ -64,7 +64,7 @@ const AP_Param::GroupInfo AP_RPM::var_info[] = {
|
|||
// @Description: Which pin to use
|
||||
// @Values: -1:Disabled,50:PixhawkAUX1,51:PixhawkAUX2,52:PixhawkAUX3,53:PixhawkAUX4,54:PixhawkAUX5,55:PixhawkAUX6
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("_PIN", 5, AP_RPM, _pin[0], 54),
|
||||
AP_GROUPINFO("_PIN", 5, AP_RPM, _pin[0], -1),
|
||||
|
||||
// @Param: _ESC_MASK
|
||||
// @DisplayName: Bitmask of ESC telemetry channels to average
|
||||
|
|
Loading…
Reference in New Issue