AC_CustomControl: update for new AC_PID settings

enable filters with AP_FILTER_ENABLED
This commit is contained in:
Andy Piper 2023-10-01 18:21:00 +01:00 committed by Andrew Tridgell
parent b7a969d462
commit 560030c9ba
2 changed files with 20 additions and 86 deletions

View File

@ -186,7 +186,7 @@ void AC_CustomControl::log_switch(void) {
void AC_CustomControl::set_notch_sample_rate(float sample_rate) void AC_CustomControl::set_notch_sample_rate(float sample_rate)
{ {
#if AC_PID_ADVANCED_ENABLED #if AP_FILTER_ENABLED
if (_backend != nullptr) { if (_backend != nullptr) {
_backend->set_notch_sample_rate(sample_rate); _backend->set_notch_sample_rate(sample_rate);
} }

View File

@ -102,12 +102,6 @@ const AP_Param::GroupInfo AC_CustomControl_PID::var_info[] = {
// @Increment: 0.01 // @Increment: 0.01
// @User: Advanced // @User: Advanced
// @Param: RAT_RLL_ADV
// @DisplayName: Roll Advanced parameters enable
// @Description: Roll Advanced parameters enable
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
// @Param: RAT_RLL_D_FF // @Param: RAT_RLL_D_FF
// @DisplayName: Roll Derivative FeedForward Gain // @DisplayName: Roll 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
@ -116,31 +110,15 @@ const AP_Param::GroupInfo AC_CustomControl_PID::var_info[] = {
// @User: Advanced // @User: Advanced
// @Param: RAT_RLL_NTF // @Param: RAT_RLL_NTF
// @DisplayName: Roll Target notch Filter center frequency // @DisplayName: Roll Target notch filter index
// @Description: Roll Target notch Filter center frequency in Hz. // @Description: Roll Target notch filter index
// @Range: 10 495 // @Range: 1 8
// @Units: Hz
// @User: Advanced // @User: Advanced
// @Param: RAT_RLL_NEF // @Param: RAT_RLL_NEF
// @DisplayName: Roll Error notch Filter center frequency // @DisplayName: Roll Error notch filter index
// @Description: Roll Error notch Filter center frequency in Hz. // @Description: Roll Error notch filter index
// @Range: 10 495 // @Range: 1 8
// @Units: Hz
// @User: Advanced
// @Param: RAT_RLL_NBW
// @DisplayName: Roll notch Filter bandwidth
// @Description: Roll notch Filter bandwidth in Hz.
// @Range: 5 250
// @Units: Hz
// @User: Advanced
// @Param: RAT_RLL_NATT
// @DisplayName: Roll notch Filter attenuation
// @Description: Roll notch Filter attenuation in dB.
// @Range: 5 50
// @Units: dB
// @User: Advanced // @User: Advanced
AP_SUBGROUPINFO(_pid_atti_rate_roll, "RAT_RLL_", 4, AC_CustomControl_PID, AC_PID), AP_SUBGROUPINFO(_pid_atti_rate_roll, "RAT_RLL_", 4, AC_CustomControl_PID, AC_PID),
@ -218,12 +196,6 @@ const AP_Param::GroupInfo AC_CustomControl_PID::var_info[] = {
// @Increment: 0.01 // @Increment: 0.01
// @User: Advanced // @User: Advanced
// @Param: RAT_PIT_ADV
// @DisplayName: Pitch Advanced parameters enable
// @Description: Pitch Advanced parameters enable
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
// @Param: RAT_PIT_D_FF // @Param: RAT_PIT_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
@ -232,31 +204,15 @@ const AP_Param::GroupInfo AC_CustomControl_PID::var_info[] = {
// @User: Advanced // @User: Advanced
// @Param: RAT_PIT_NTF // @Param: RAT_PIT_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: RAT_PIT_NEF // @Param: RAT_PIT_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: RAT_PIT_NBW
// @DisplayName: Pitch notch Filter bandwidth
// @Description: Pitch notch Filter bandwidth in Hz.
// @Range: 5 250
// @Units: Hz
// @User: Advanced
// @Param: RAT_PIT_NATT
// @DisplayName: Pitch notch Filter attenuation
// @Description: Pitch notch Filter attenuation in dB.
// @Range: 5 50
// @Units: dB
// @User: Advanced // @User: Advanced
AP_SUBGROUPINFO(_pid_atti_rate_pitch, "RAT_PIT_", 5, AC_CustomControl_PID, AC_PID), AP_SUBGROUPINFO(_pid_atti_rate_pitch, "RAT_PIT_", 5, AC_CustomControl_PID, AC_PID),
@ -335,12 +291,6 @@ const AP_Param::GroupInfo AC_CustomControl_PID::var_info[] = {
// @Increment: 0.01 // @Increment: 0.01
// @User: Advanced // @User: Advanced
// @Param: RAT_YAW_ADV
// @DisplayName: Yaw Advanced parameters enable
// @Description: Yaw Advanced parameters enable
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
// @Param: RAT_YAW_D_FF // @Param: RAT_YAW_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
@ -349,31 +299,15 @@ const AP_Param::GroupInfo AC_CustomControl_PID::var_info[] = {
// @User: Advanced // @User: Advanced
// @Param: RAT_YAW_NTF // @Param: RAT_YAW_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: RAT_YAW_NEF // @Param: RAT_YAW_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: RAT_YAW_NBW
// @DisplayName: Yaw notch Filter bandwidth
// @Description: Yaw notch Filter bandwidth in Hz.
// @Range: 5 250
// @Units: Hz
// @User: Advanced
// @Param: RAT_YAW_NATT
// @DisplayName: Yaw notch Filter attenuation
// @Description: Yaw notch Filter attenuation in dB.
// @Range: 5 50
// @Units: dB
// @User: Advanced // @User: Advanced
AP_SUBGROUPINFO(_pid_atti_rate_yaw, "RAT_YAW_", 6, AC_CustomControl_PID, AC_PID), AP_SUBGROUPINFO(_pid_atti_rate_yaw, "RAT_YAW_", 6, AC_CustomControl_PID, AC_PID),
@ -461,7 +395,7 @@ void AC_CustomControl_PID::reset(void)
void AC_CustomControl_PID::set_notch_sample_rate(float sample_rate) void AC_CustomControl_PID::set_notch_sample_rate(float sample_rate)
{ {
#if AC_PID_ADVANCED_ENABLED #if AP_FILTER_ENABLED
_pid_atti_rate_roll.set_notch_sample_rate(sample_rate); _pid_atti_rate_roll.set_notch_sample_rate(sample_rate);
_pid_atti_rate_pitch.set_notch_sample_rate(sample_rate); _pid_atti_rate_pitch.set_notch_sample_rate(sample_rate);
_pid_atti_rate_yaw.set_notch_sample_rate(sample_rate); _pid_atti_rate_yaw.set_notch_sample_rate(sample_rate);