From 41752eef8b0f5ea48cb0e8a323dc6a9c44a2c9a7 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 3 Jul 2017 09:33:36 +0900 Subject: [PATCH] Copter:default RC_FEEL to 50 --- ArduCopter/Parameters.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 6f783dbdcd..c48f62f092 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -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_SOFT), + GSCALAR(rc_feel_rp, "RC_FEEL_RP", RC_FEEL_RP_MEDIUM), #if POSHOLD_ENABLED == ENABLED // @Param: PHLD_BRAKE_RATE