mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 16:48:29 -04:00
AC_AttitudeControl: remove old RAT_FILT param desc
This commit is contained in:
parent
6597d5c825
commit
b9ff846162
@ -211,30 +211,6 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = {
|
|||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("THR_MIX_MAN", 6, AC_AttitudeControl_Multi, _thr_mix_man, AC_ATTITUDE_CONTROL_MAN_DEFAULT),
|
AP_GROUPINFO("THR_MIX_MAN", 6, AC_AttitudeControl_Multi, _thr_mix_man, AC_ATTITUDE_CONTROL_MAN_DEFAULT),
|
||||||
|
|
||||||
// @Param: RAT_RLL_FILT
|
|
||||||
// @DisplayName: Roll axis rate controller input frequency in Hz
|
|
||||||
// @Description: Roll axis rate controller input frequency in Hz
|
|
||||||
// @Range: 1 100
|
|
||||||
// @Increment: 1
|
|
||||||
// @Units: Hz
|
|
||||||
// @User: Standard
|
|
||||||
|
|
||||||
// @Param: RAT_PIT_FILT
|
|
||||||
// @DisplayName: Pitch axis rate controller input frequency in Hz
|
|
||||||
// @Description: Pitch axis rate controller input frequency in Hz
|
|
||||||
// @Range: 1 100
|
|
||||||
// @Increment: 1
|
|
||||||
// @Units: Hz
|
|
||||||
// @User: Standard
|
|
||||||
|
|
||||||
// @Param: RAT_YAW_FILT
|
|
||||||
// @DisplayName: Yaw axis rate controller input frequency in Hz
|
|
||||||
// @Description: Yaw axis rate controller input frequency in Hz
|
|
||||||
// @Range: 1 10
|
|
||||||
// @Increment: 1
|
|
||||||
// @Units: Hz
|
|
||||||
// @User: Standard
|
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user