Plane: fix PID filter names FILT -> FLTE, D_FILT -> FLTD

This commit is contained in:
Leonard Hall 2021-08-03 13:36:07 +09:30 committed by Randy Mackay
parent 2e6e3d7b89
commit 23732690a7

View File

@ -611,7 +611,7 @@ const AP_Param::ConversionInfo q_conversion_table[] = {
{ Parameters::k_param_quadplane, 4046, AP_PARAM_FLOAT, "Q_P_VELXY_P"}, // Q_VXY_P
{ Parameters::k_param_quadplane, 78, AP_PARAM_FLOAT, "Q_P_VELXY_I"}, // Q_VXY_I
{ Parameters::k_param_quadplane, 142, AP_PARAM_FLOAT, "Q_P_VELXY_IMAX"}, // Q_VXY_IMAX
{ Parameters::k_param_quadplane, 206, AP_PARAM_FLOAT, "Q_P_VELXY_FILT"}, // Q_VXY_FILT_HZ
{ Parameters::k_param_quadplane, 206, AP_PARAM_FLOAT, "Q_P_VELXY_FLTE"}, // Q_VXY_FILT_HZ
{ Parameters::k_param_quadplane, 4047, AP_PARAM_FLOAT, "Q_P_VELZ_P"}, // Q_VZ_P
{ Parameters::k_param_quadplane, 4048, AP_PARAM_FLOAT, "Q_P_ACCZ_P"}, // Q_AZ_P
{ Parameters::k_param_quadplane, 80, AP_PARAM_FLOAT, "Q_P_ACCZ_I"}, // Q_AZ_I