diff --git a/AntennaTracker/Parameters.cpp b/AntennaTracker/Parameters.cpp index e1757fba32..b9c48d4e9a 100644 --- a/AntennaTracker/Parameters.cpp +++ b/AntennaTracker/Parameters.cpp @@ -387,6 +387,47 @@ const AP_Param::Info Tracker::var_info[] = { // @Units: d% // @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 + // @DisplayName: Pitch 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 + // @Increment: 0.001 + // @User: Advanced + + // @Param: PITCH2SRV_NTF + // @DisplayName: Pitch Target notch Filter center frequency + // @Description: Pitch Target notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: PITCH2SRV_NEF + // @DisplayName: Pitch Error notch Filter center frequency + // @Description: Pitch Error notch Filter center frequency in Hz. + // @Range: 10 495 + // @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 + GGROUP(pidPitch2Srv, "PITCH2SRV_", AC_PID), // @Param: YAW2SRV_P @@ -464,6 +505,47 @@ const AP_Param::Info Tracker::var_info[] = { // @Units: d% // @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 + // @DisplayName: 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 + // @Increment: 0.001 + // @User: Advanced + + // @Param: YAW2SRV_NTF + // @DisplayName: Yaw Target notch Filter center frequency + // @Description: Yaw Target notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: YAW2SRV_NEF + // @DisplayName: Yaw Error notch Filter center frequency + // @Description: Yaw Error notch Filter center frequency in Hz. + // @Range: 10 495 + // @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 + GGROUP(pidYaw2Srv, "YAW2SRV_", AC_PID), #if AP_SCRIPTING_ENABLED diff --git a/AntennaTracker/Tracker.cpp b/AntennaTracker/Tracker.cpp index f3284e985e..fbf3427c50 100644 --- a/AntennaTracker/Tracker.cpp +++ b/AntennaTracker/Tracker.cpp @@ -103,6 +103,8 @@ void Tracker::one_second_loop() set_likely_flying(hal.util->get_soft_armed()); AP_Notify::flags.flying = hal.util->get_soft_armed(); + + g.pidYaw2Srv.set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz()); } void Tracker::ten_hz_logging_loop()