Copter: reduce RC_FEEL default to 25

This commit is contained in:
Leonard Hall 2017-06-01 10:06:12 +09:00 committed by Randy Mackay
parent ffe701bda3
commit c61d0a7373
1 changed files with 1 additions and 1 deletions

View File

@ -464,7 +464,7 @@ const AP_Param::Info Copter::var_info[] = {
// @Increment: 10
// @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_MEDIUM),
GSCALAR(rc_feel_rp, "RC_FEEL_RP", RC_FEEL_RP_SOFT),
#if POSHOLD_ENABLED == ENABLED
// @Param: PHLD_BRAKE_RATE