mirror of https://github.com/ArduPilot/ardupilot
RC_Channel: set AP_PARAM_NO_SHIFT
This commit is contained in:
parent
018c7425a4
commit
4deb01b8d5
|
@ -42,7 +42,7 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = {
|
|||
// @Range: 800 2200
|
||||
// @Increment: 1
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("MIN", 0, RC_Channel, radio_min, 1100),
|
||||
AP_GROUPINFO_FLAGS("MIN", 0, RC_Channel, radio_min, 1100, AP_PARAM_NO_SHIFT),
|
||||
|
||||
// @Param: TRIM
|
||||
// @DisplayName: RC trim PWM
|
||||
|
|
Loading…
Reference in New Issue