mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
Copter: default RC_FEEL to Medium
This commit is contained in:
parent
b1002eae3b
commit
738e4d89db
@ -450,7 +450,7 @@ const AP_Param::Info Copter::var_info[] PROGMEM = {
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
// @Values: 0:Very Soft, 25:Soft, 50:Medium, 75:Crisp, 100:Very Crisp
|
||||
GSCALAR(rc_feel_rp, "RC_FEEL_RP", RC_FEEL_RP_VERY_CRISP),
|
||||
GSCALAR(rc_feel_rp, "RC_FEEL_RP", RC_FEEL_RP_MEDIUM),
|
||||
|
||||
#if POSHOLD_ENABLED == ENABLED
|
||||
// @Param: PHLD_BRAKE_RATE
|
||||
|
Loading…
Reference in New Issue
Block a user