Tracker: update for new AC_PID settings

This commit is contained in:
Andy Piper 2023-10-01 18:21:01 +01:00 committed by Andrew Tridgell
parent 5b0f30ad44
commit 4c1c01f571
1 changed files with 14 additions and 58 deletions

View File

@ -387,45 +387,23 @@ const AP_Param::Info Tracker::var_info[] = {
// @Units: d% // @Units: d%
// @User: Advanced // @User: Advanced
// @Param: PITCH2SRV_ADV
// @DisplayName: Advanced Pitch parameters enable
// @Description: Advanced Pitch parameters enable
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
// @Param: PITCH2SRV_D_FF // @Param: PITCH2SRV_D_FF
// @DisplayName: Pitch Derivative FeedForward Gain // @DisplayName: Pitch Derivative FeedForward Gain
// @Description: FF D Gain which produces an output that is proportional to the rate of change of the target // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target
// @Range: 0.001 0.1 // @Range: 0 0.1
// @Increment: 0.001 // @Increment: 0.001
// @User: Advanced // @User: Advanced
// @Param: PITCH2SRV_NTF // @Param: PITCH2SRV_NTF
// @DisplayName: Pitch Target notch Filter center frequency // @DisplayName: Pitch Target notch filter index
// @Description: Pitch Target notch Filter center frequency in Hz. // @Description: Pitch Target notch filter index
// @Range: 10 495 // @Range: 1 8
// @Units: Hz
// @User: Advanced // @User: Advanced
// @Param: PITCH2SRV_NEF // @Param: PITCH2SRV_NEF
// @DisplayName: Pitch Error notch Filter center frequency // @DisplayName: Pitch Error notch filter index
// @Description: Pitch Error notch Filter center frequency in Hz. // @Description: Pitch Error notch filter index
// @Range: 10 495 // @Range: 1 8
// @Units: Hz
// @User: Advanced
// @Param: PITCH2SRV_NBW
// @DisplayName: Pitch notch Filter bandwidth
// @Description: Pitch notch Filter bandwidth in Hz.
// @Range: 5 250
// @Units: Hz
// @User: Advanced
// @Param: PITCH2SRV_NATT
// @DisplayName: Pitch notch Filter attenuation
// @Description: Pitch notch Filter attenuation in dB.
// @Range: 5 50
// @Units: dB
// @User: Advanced // @User: Advanced
GGROUP(pidPitch2Srv, "PITCH2SRV_", AC_PID), GGROUP(pidPitch2Srv, "PITCH2SRV_", AC_PID),
@ -505,45 +483,23 @@ const AP_Param::Info Tracker::var_info[] = {
// @Units: d% // @Units: d%
// @User: Advanced // @User: Advanced
// @Param: YAW2SRV_ADV
// @DisplayName: Advanced Yaw parameters enable
// @Description: Advanced Yaw parameters enable
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
// @Param: YAW2SRV_D_FF // @Param: YAW2SRV_D_FF
// @DisplayName: Yaw Derivative FeedForward Gain // @DisplayName: Yaw Derivative FeedForward Gain
// @Description: FF D Gain which produces an output that is proportional to the rate of change of the target // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target
// @Range: 0.001 0.1 // @Range: 0 0.1
// @Increment: 0.001 // @Increment: 0.001
// @User: Advanced // @User: Advanced
// @Param: YAW2SRV_NTF // @Param: YAW2SRV_NTF
// @DisplayName: Yaw Target notch Filter center frequency // @DisplayName: Yaw Target notch filter index
// @Description: Yaw Target notch Filter center frequency in Hz. // @Description: Yaw Target notch filter index
// @Range: 10 495 // @Range: 1 8
// @Units: Hz
// @User: Advanced // @User: Advanced
// @Param: YAW2SRV_NEF // @Param: YAW2SRV_NEF
// @DisplayName: Yaw Error notch Filter center frequency // @DisplayName: Yaw Error notch filter index
// @Description: Yaw Error notch Filter center frequency in Hz. // @Description: Yaw Error notch filter index
// @Range: 10 495 // @Range: 1 8
// @Units: Hz
// @User: Advanced
// @Param: YAW2SRV_NBW
// @DisplayName: Yaw notch Filter bandwidth
// @Description: Yaw notch Filter bandwidth in Hz.
// @Range: 5 250
// @Units: Hz
// @User: Advanced
// @Param: YAW2SRV_NATT
// @DisplayName: Yaw notch Filter attenuation
// @Description: Yaw notch Filter attenuation in dB.
// @Range: 5 50
// @Units: dB
// @User: Advanced // @User: Advanced
GGROUP(pidYaw2Srv, "YAW2SRV_", AC_PID), GGROUP(pidYaw2Srv, "YAW2SRV_", AC_PID),