From 8b36c59d8b11f63bade7933e71640b6f6bcbd33f Mon Sep 17 00:00:00 2001 From: Robert Lefebvre Date: Thu, 9 Jan 2014 17:02:08 -0500 Subject: [PATCH] TradHeli: rename Stab_Col parameters With H_ prefix they appear with the rest of the tradheli specific params in the parameter list. --- ArduCopter/Parameters.pde | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/ArduCopter/Parameters.pde b/ArduCopter/Parameters.pde index 306dad34fc..a35eb2403c 100644 --- a/ArduCopter/Parameters.pde +++ b/ArduCopter/Parameters.pde @@ -472,23 +472,23 @@ const AP_Param::Info var_info[] PROGMEM = { // @User: Standard GSCALAR(heli_yaw_ff, "RATE_YAW_FF", HELI_YAW_FF), - // @Param: STAB_COL_MIN + // @Param: H_STAB_COL_MIN // @DisplayName: Heli Stabilize Throttle Collective Minimum // @Description: Helicopter's minimum collective position while pilot directly controls collective in stabilize mode // @Range: 0 500 // @Units: Percent*10 // @Increment: 1 // @User: Standard - GSCALAR(heli_stab_col_min, "STAB_COL_MIN", HELI_STAB_COLLECTIVE_MIN_DEFAULT), + GSCALAR(heli_stab_col_min, "H_STAB_COL_MIN", HELI_STAB_COLLECTIVE_MIN_DEFAULT), - // @Param: STAB_COL_MAX + // @Param: H_STAB_COL_MAX // @DisplayName: Stabilize Throttle Maximum // @Description: Helicopter's maximum collective position while pilot directly controls collective in stabilize mode // @Range: 500 1000 // @Units: Percent*10 // @Increment: 1 // @User: Standard - GSCALAR(heli_stab_col_max, "STAB_COL_MAX", HELI_STAB_COLLECTIVE_MAX_DEFAULT), + GSCALAR(heli_stab_col_max, "H_STAB_COL_MAX", HELI_STAB_COLLECTIVE_MAX_DEFAULT), #endif #if FRAME_CONFIG == SINGLE_FRAME