mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 10:38:28 -04:00
AP_BLHeli: correct SERVO_BLH_POLES parameter value range metadata
This commit is contained in:
parent
1c162c8b64
commit
6b2ad734b6
@ -104,7 +104,7 @@ const AP_Param::GroupInfo AP_BLHeli::var_info[] = {
|
||||
// @Param: POLES
|
||||
// @DisplayName: Motor Poles
|
||||
// @Description: This allows calculation of true RPM from ESC's eRPM. The default is 14.
|
||||
// @Values: 1-127
|
||||
// @Range: 1 127
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("POLES", 9, AP_BLHeli, motor_poles, 14),
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user