diff --git a/Blimp/Log.cpp b/Blimp/Log.cpp index 01a3e0f3e7..17c3161fab 100644 --- a/Blimp/Log.cpp +++ b/Blimp/Log.cpp @@ -280,6 +280,7 @@ const struct LogStructure Blimp::log_structure[] = { // @Field: I: integral part of PID // @Field: D: derivative part of PID // @Field: FF: controller feed-forward portion of response + // @Field: DFF: controller derivative feed-forward portion of response // @Field: Dmod: scaler applied to D gain to reduce limit cycling // @Field: SRate: slew rate // @Field: Flags: bitmask of PID state flags diff --git a/Blimp/Parameters.cpp b/Blimp/Parameters.cpp index aab8caeadc..26971ef2e6 100644 --- a/Blimp/Parameters.cpp +++ b/Blimp/Parameters.cpp @@ -730,45 +730,23 @@ const AP_Param::Info Blimp::var_info[] = { // @Units: d% // @User: Advanced - // @Param: POSYAW_ADV - // @DisplayName: Advanced Yaw parameters enable - // @Description: Advanced Yaw parameters enable - // @Values: 0:Disabled,1:Enabled - // @User: Advanced - // @Param: POSYAW_D_FF // @DisplayName: Position (yaw) Derivative FeedForward Gain // @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 // @User: Advanced // @Param: POSYAW_NTF - // @DisplayName: Position (yaw) Target notch Filter center frequency - // @Description: Position (yaw) Target notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz + // @DisplayName: Position (yaw) Target notch filter index + // @Description: Position (yaw) Target notch filter index + // @Range: 1 8 // @User: Advanced // @Param: POSYAW_NEF - // @DisplayName: Position (yaw) Error notch Filter center frequency - // @Description: Position (yaw) Error notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz - // @User: Advanced - - // @Param: POSYAW_NBW - // @DisplayName: Position (yaw) notch Filter bandwidth - // @Description: Position (yaw) notch Filter bandwidth in Hz. - // @Range: 5 250 - // @Units: Hz - // @User: Advanced - - // @Param: POSYAW_NATT - // @DisplayName: Position (yaw) notch Filter attenuation - // @Description: Position (yaw) notch Filter attenuation in dB. - // @Range: 5 50 - // @Units: dB + // @DisplayName: Position (yaw) Error notch filter index + // @Description: Position (yaw) Error notch filter index + // @Range: 1 8 // @User: Advanced GOBJECT(pid_pos_yaw, "POSYAW_", AC_PID),