diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp index 7569dc2072..cc2d6b90bd 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp @@ -49,9 +49,16 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = { // @Increment: 0.001 // @User: Standard + // @Param: RAT_RLL_FF + // @DisplayName: Roll axis rate controller feed forward + // @Description: Roll axis rate controller feed forward + // @Range: 0 0.5 + // @Increment: 0.001 + // @User: Standard + // @Param: RAT_RLL_FILT - // @DisplayName: Roll axis rate conroller input frequency in Hz - // @Description: Roll axis rate conroller input frequency in Hz + // @DisplayName: Roll axis rate controller input frequency in Hz + // @Description: Roll axis rate controller input frequency in Hz // @Units: Hz // @Range: 1 20 // @Increment: 1 @@ -85,9 +92,16 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = { // @Increment: 0.001 // @User: Standard + // @Param: RAT_PIT_FF + // @DisplayName: Pitch axis rate controller feed forward + // @Description: Pitch axis rate controller feed forward + // @Range: 0 0.5 + // @Increment: 0.001 + // @User: Standard + // @Param: RAT_PIT_FILT - // @DisplayName: Pitch axis rate conroller input frequency in Hz - // @Description: Pitch axis rate conroller input frequency in Hz + // @DisplayName: Pitch axis rate controller input frequency in Hz + // @Description: Pitch axis rate controller input frequency in Hz // @Units: Hz // @Range: 1 20 // @Increment: 1 @@ -121,9 +135,16 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = { // @Increment: 0.001 // @User: Standard + // @Param: RAT_YAW_FF + // @DisplayName: Yaw axis rate controller feed forward + // @Description: Yaw axis rate controller feed forward + // @Range: 0 0.5 + // @Increment: 0.001 + // @User: Standard + // @Param: RAT_YAW_FILT - // @DisplayName: Yaw axis rate conroller input frequency in Hz - // @Description: Yaw axis rate conroller input frequency in Hz + // @DisplayName: Yaw axis rate controller input frequency in Hz + // @Description: Yaw axis rate controller input frequency in Hz // @Units: Hz // @Range: 1 20 // @Increment: 1 diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp index 0241ebc4e9..8abcf594d8 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp @@ -36,6 +36,13 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = { // @Increment: 0.001 // @User: Standard + // @Param: RAT_RLL_FF + // @DisplayName: Roll axis rate controller feed forward + // @Description: Roll axis rate controller feed forward + // @Range: 0 0.5 + // @Increment: 0.001 + // @User: Standard + // @Param: RAT_RLL_FILT // @DisplayName: Roll axis rate controller input frequency in Hz // @Description: Roll axis rate controller input frequency in Hz @@ -74,6 +81,13 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = { // @Increment: 0.001 // @User: Standard + // @Param: RAT_PIT_FF + // @DisplayName: Pitch axis rate controller feed forward + // @Description: Pitch axis rate controller feed forward + // @Range: 0 0.5 + // @Increment: 0.001 + // @User: Standard + // @Param: RAT_PIT_FILT // @DisplayName: Pitch axis rate controller input frequency in Hz // @Description: Pitch axis rate controller input frequency in Hz @@ -112,6 +126,13 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = { // @Increment: 0.001 // @User: Standard + // @Param: RAT_YAW_FF + // @DisplayName: Yaw axis rate controller feed forward + // @Description: Yaw axis rate controller feed forward + // @Range: 0 0.5 + // @Increment: 0.001 + // @User: Standard + // @Param: RAT_YAW_FILT // @DisplayName: Yaw axis rate controller input frequency in Hz // @Description: Yaw axis rate controller input frequency in Hz diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp index 68c106c1b5..8fe79c81bb 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp @@ -36,6 +36,13 @@ const AP_Param::GroupInfo AC_AttitudeControl_Sub::var_info[] = { // @Increment: 0.001 // @User: Standard + // @Param: RAT_RLL_FF + // @DisplayName: Roll axis rate controller feed forward + // @Description: Roll axis rate controller feed forward + // @Range: 0 0.5 + // @Increment: 0.001 + // @User: Standard + // @Param: RAT_RLL_FILT // @DisplayName: Roll axis rate controller input frequency in Hz // @Description: Roll axis rate controller input frequency in Hz @@ -74,6 +81,13 @@ const AP_Param::GroupInfo AC_AttitudeControl_Sub::var_info[] = { // @Increment: 0.001 // @User: Standard + // @Param: RAT_PIT_FF + // @DisplayName: Pitch axis rate controller feed forward + // @Description: Pitch axis rate controller feed forward + // @Range: 0 0.5 + // @Increment: 0.001 + // @User: Standard + // @Param: RAT_PIT_FILT // @DisplayName: Pitch axis rate controller input frequency in Hz // @Description: Pitch axis rate controller input frequency in Hz @@ -112,6 +126,13 @@ const AP_Param::GroupInfo AC_AttitudeControl_Sub::var_info[] = { // @Increment: 0.001 // @User: Standard + // @Param: RAT_YAW_FF + // @DisplayName: Yaw axis rate controller feed forward + // @Description: Yaw axis rate controller feed forward + // @Range: 0 0.5 + // @Increment: 0.001 + // @User: Standard + // @Param: RAT_YAW_FILT // @DisplayName: Yaw axis rate controller input frequency in Hz // @Description: Yaw axis rate controller input frequency in Hz