diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp index 12266aa947..473d216adb 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp @@ -8,12 +8,21 @@ extern const AP_HAL::HAL& hal; // table of user settable parameters const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] PROGMEM = { - // @Param: DUMMY - // @DisplayName: Dummy parameter - // @Description: This is the dummy parameters - // @Increment: 0.1 - // @User: User - AP_GROUPINFO("DUMMY", 0, AC_AttitudeControl_Heli, _dummy_param, 0), + // @Param: RATE_RP_MAX + // @DisplayName: Angle Rate Roll-Pitch max + // @Description: maximum rotation rate in roll/pitch axis requested by angle controller used in stabilize, loiter, rtl, auto flight modes + // @Range: 90000 250000 + // @Increment: 500 + // @User: Advanced + AP_GROUPINFO("RATE_RP_MAX", 0, AC_AttitudeControl_Heli, _angle_rate_rp_max, AC_ATTITUDE_CONTROL_ANGLE_RATE_RP_MAX_DEFAULT), + + // @Param: RATE_Y_MAX + // @DisplayName: Angle Rate Yaw max + // @Description: maximum rotation rate in roll/pitch axis requested by angle controller used in stabilize, loiter, rtl, auto flight modes + // @Range: 90000 250000 + // @Increment: 500 + // @User: Advanced + AP_GROUPINFO("RATE_Y_MAX", 1, AC_AttitudeControl_Heli, _angle_rate_y_max, AC_ATTITUDE_CONTROL_ANGLE_RATE_Y_MAX_DEFAULT), // @Param: RATE_RLL_FF // @DisplayName: Rate Roll Feed Forward @@ -21,7 +30,7 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] PROGMEM = { // @Range: 0 10 // @Increment: 0.01 // @User: Standard - AP_GROUPINFO("RATE_RLL_FF", 1, AC_AttitudeControl_Heli, _heli_roll_ff, AC_ATTITUDE_HELI_ROLL_FF), + AP_GROUPINFO("RATE_RLL_FF", 2, AC_AttitudeControl_Heli, _heli_roll_ff, AC_ATTITUDE_HELI_ROLL_FF), // @Param: RATE_PIT_FF // @DisplayName: Rate Pitch Feed Forward @@ -29,7 +38,7 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] PROGMEM = { // @Range: 0 10 // @Increment: 0.01 // @User: Standard - AP_GROUPINFO("RATE_PIT_FF", 2, AC_AttitudeControl_Heli, _heli_pitch_ff, AC_ATTITUDE_HELI_ROLL_FF), + AP_GROUPINFO("RATE_PIT_FF", 3, AC_AttitudeControl_Heli, _heli_pitch_ff, AC_ATTITUDE_HELI_ROLL_FF), // @Param: RATE_YAW_FF // @DisplayName: Rate Yaw Feed Forward