Browse Source

AC_InputManager: tradheli-Fix parameter metadata errors

celiu-4.0.17-rc8
Bill Geyer 5 years ago committed by Randy Mackay
parent
commit
a05f00d180
  1. 16
      libraries/AC_InputManager/AC_InputManager_Heli.cpp

16
libraries/AC_InputManager/AC_InputManager_Heli.cpp

@ -19,37 +19,37 @@ const AP_Param::GroupInfo AC_InputManager_Heli::var_info[] = {
// @User: Advanced // @User: Advanced
AP_GROUPINFO("ACRO_COL_EXP", 5, AC_InputManager_Heli, _acro_col_expo, 0), AP_GROUPINFO("ACRO_COL_EXP", 5, AC_InputManager_Heli, _acro_col_expo, 0),
// @Param: STAB_COL_MIN // @Param: STB_COL_1
// @DisplayName: Stabilize Collective Low // @DisplayName: Stabilize Collective Low
// @Description: Helicopter's minimum collective pitch setting at zero collective stick input in Stabilize mode. Set this as a percent of collective range given by H_COL_MAX minus H_COL_MIN. // @Description: Helicopter's minimum collective pitch setting at zero collective stick input in Stabilize mode. Set this as a percent of collective range given by H_COL_MAX minus H_COL_MIN.
// @Range: 0 50 // @Range: 0 100
// @Units: % // @Units: %
// @Increment: 1 // @Increment: 1
// @User: Standard // @User: Standard
AP_GROUPINFO("STB_COL_1", 6, AC_InputManager_Heli, _heli_stab_col_min, AC_ATTITUDE_HELI_STAB_COLLECTIVE_MIN_DEFAULT), AP_GROUPINFO("STB_COL_1", 6, AC_InputManager_Heli, _heli_stab_col_min, AC_ATTITUDE_HELI_STAB_COLLECTIVE_MIN_DEFAULT),
// @Param: STAB_COL_LOW // @Param: STB_COL_2
// @DisplayName: Stabilize Collective Mid-Low // @DisplayName: Stabilize Collective Mid-Low
// @Description: Helicopter's collective pitch setting at mid-low (40%) collective stick input in Stabilize mode. Set this as a percent of collective range given by H_COL_MAX minus H_COL_MIN. // @Description: Helicopter's collective pitch setting at mid-low (40%) collective stick input in Stabilize mode. Set this as a percent of collective range given by H_COL_MAX minus H_COL_MIN.
// @Range: 0 50 // @Range: 0 100
// @Units: % // @Units: %
// @Increment: 1 // @Increment: 1
// @User: Standard // @User: Standard
AP_GROUPINFO("STB_COL_2", 7, AC_InputManager_Heli, _heli_stab_col_low, AC_ATTITUDE_HELI_STAB_COLLECTIVE_LOW_DEFAULT), AP_GROUPINFO("STB_COL_2", 7, AC_InputManager_Heli, _heli_stab_col_low, AC_ATTITUDE_HELI_STAB_COLLECTIVE_LOW_DEFAULT),
// @Param: STAB_COL_HGH // @Param: STB_COL_3
// @DisplayName: Stabilize Collective Mid-High // @DisplayName: Stabilize Collective Mid-High
// @Description: Helicopter's collective pitch setting at mid-high (60%) collective stick input in Stabilize mode. Set this as a percent of collective range given by H_COL_MAX minus H_COL_MIN. // @Description: Helicopter's collective pitch setting at mid-high (60%) collective stick input in Stabilize mode. Set this as a percent of collective range given by H_COL_MAX minus H_COL_MIN.
// @Range: 50 100 // @Range: 0 100
// @Units: % // @Units: %
// @Increment: 1 // @Increment: 1
// @User: Standard // @User: Standard
AP_GROUPINFO("STB_COL_3", 8, AC_InputManager_Heli, _heli_stab_col_high, AC_ATTITUDE_HELI_STAB_COLLECTIVE_HIGH_DEFAULT), AP_GROUPINFO("STB_COL_3", 8, AC_InputManager_Heli, _heli_stab_col_high, AC_ATTITUDE_HELI_STAB_COLLECTIVE_HIGH_DEFAULT),
// @Param: STAB_COL_MAX // @Param: STB_COL_4
// @DisplayName: Stabilize Collective High // @DisplayName: Stabilize Collective High
// @Description: Helicopter's maximum collective pitch setting at full collective stick input in Stabilize mode. Set this as a percent of collective range given by H_COL_MAX minus H_COL_MIN. // @Description: Helicopter's maximum collective pitch setting at full collective stick input in Stabilize mode. Set this as a percent of collective range given by H_COL_MAX minus H_COL_MIN.
// @Range: 50 100 // @Range: 0 100
// @Units: % // @Units: %
// @Increment: 1 // @Increment: 1
// @User: Standard // @User: Standard

Loading…
Cancel
Save