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

This commit is contained in:
Leonard Hall 2021-08-03 13:35:50 +09:30 committed by Randy Mackay
parent 870888efeb
commit dd9bc4da67
1 changed files with 10 additions and 10 deletions

View File

@ -465,14 +465,14 @@ const AP_Param::Info Blimp::var_info[] = {
// @Units: cm/s/s // @Units: cm/s/s
// @User: Advanced // @User: Advanced
// @Param: VELXY_FILT // @Param: VELXY_FLTE
// @DisplayName: Velocity (horizontal) input filter // @DisplayName: Velocity (horizontal) input filter
// @Description: Velocity (horizontal) input filter. This filter (in Hz) is applied to the input for P and I terms // @Description: Velocity (horizontal) input filter. This filter (in Hz) is applied to the input for P and I terms
// @Range: 0 100 // @Range: 0 100
// @Units: Hz // @Units: Hz
// @User: Advanced // @User: Advanced
// @Param: VELXY_D_FILT // @Param: VELXY_FLTD
// @DisplayName: Velocity (horizontal) input filter // @DisplayName: Velocity (horizontal) input filter
// @Description: Velocity (horizontal) input filter. This filter (in Hz) is applied to the input for D term // @Description: Velocity (horizontal) input filter. This filter (in Hz) is applied to the input for D term
// @Range: 0 100 // @Range: 0 100
@ -516,14 +516,14 @@ const AP_Param::Info Blimp::var_info[] = {
// @Units: cm/s/s // @Units: cm/s/s
// @User: Advanced // @User: Advanced
// @Param: VELZ_FILT // @Param: VELZ_FLTE
// @DisplayName: Velocity (vertical) input filter // @DisplayName: Velocity (vertical) input filter
// @Description: Velocity (vertical) input filter. This filter (in Hz) is applied to the input for P and I terms // @Description: Velocity (vertical) input filter. This filter (in Hz) is applied to the input for P and I terms
// @Range: 0 100 // @Range: 0 100
// @Units: Hz // @Units: Hz
// @User: Advanced // @User: Advanced
// @Param: VELZ_D_FILT // @Param: VELZ_FLTD
// @DisplayName: Velocity (vertical) input filter // @DisplayName: Velocity (vertical) input filter
// @Description: Velocity (vertical) input filter. This filter (in Hz) is applied to the input for D term // @Description: Velocity (vertical) input filter. This filter (in Hz) is applied to the input for D term
// @Range: 0 100 // @Range: 0 100
@ -567,14 +567,14 @@ const AP_Param::Info Blimp::var_info[] = {
// @Units: cm/s/s // @Units: cm/s/s
// @User: Advanced // @User: Advanced
// @Param: VELYAW_FILT // @Param: VELYAW_FLTE
// @DisplayName: Velocity (yaw) input filter // @DisplayName: Velocity (yaw) input filter
// @Description: Velocity (yaw) input filter. This filter (in Hz) is applied to the input for P and I terms // @Description: Velocity (yaw) input filter. This filter (in Hz) is applied to the input for P and I terms
// @Range: 0 100 // @Range: 0 100
// @Units: Hz // @Units: Hz
// @User: Advanced // @User: Advanced
// @Param: VELYAW_D_FILT // @Param: VELYAW_FLTE
// @DisplayName: Velocity (yaw) input filter // @DisplayName: Velocity (yaw) input filter
// @Description: Velocity (yaw) input filter. This filter (in Hz) is applied to the input for D term // @Description: Velocity (yaw) input filter. This filter (in Hz) is applied to the input for D term
// @Range: 0 100 // @Range: 0 100
@ -618,14 +618,14 @@ const AP_Param::Info Blimp::var_info[] = {
// @Units: cm/s/s // @Units: cm/s/s
// @User: Advanced // @User: Advanced
// @Param: POSXY_FILT // @Param: POSXY_FLTE
// @DisplayName: Position (horizontal) input filter // @DisplayName: Position (horizontal) input filter
// @Description: Position (horizontal) input filter. This filter (in Hz) is applied to the input for P and I terms // @Description: Position (horizontal) input filter. This filter (in Hz) is applied to the input for P and I terms
// @Range: 0 100 // @Range: 0 100
// @Units: Hz // @Units: Hz
// @User: Advanced // @User: Advanced
// @Param: POSXY_D_FILT // @Param: POSXY_FLTD
// @DisplayName: Position (horizontal) input filter // @DisplayName: Position (horizontal) input filter
// @Description: Position (horizontal) input filter. This filter (in Hz) is applied to the input for D term // @Description: Position (horizontal) input filter. This filter (in Hz) is applied to the input for D term
// @Range: 0 100 // @Range: 0 100
@ -669,14 +669,14 @@ const AP_Param::Info Blimp::var_info[] = {
// @Units: cm/s/s // @Units: cm/s/s
// @User: Advanced // @User: Advanced
// @Param: POSZ_FILT // @Param: POSZ_FLTE
// @DisplayName: Position (vertical) input filter // @DisplayName: Position (vertical) input filter
// @Description: Position (vertical) input filter. This filter (in Hz) is applied to the input for P and I terms // @Description: Position (vertical) input filter. This filter (in Hz) is applied to the input for P and I terms
// @Range: 0 100 // @Range: 0 100
// @Units: Hz // @Units: Hz
// @User: Advanced // @User: Advanced
// @Param: POSZ_D_FILT // @Param: POSZ_FLTD
// @DisplayName: Position (vertical) input filter // @DisplayName: Position (vertical) input filter
// @Description: Position (vertical) input filter. This filter (in Hz) is applied to the input for D term // @Description: Position (vertical) input filter. This filter (in Hz) is applied to the input for D term
// @Range: 0 100 // @Range: 0 100