mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
AR_AttitudeControl: allow filter to be zero
Also increase default filter to 50hz
This commit is contained in:
parent
16d3e5c00d
commit
4ac5ef3a13
@ -59,7 +59,7 @@ const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = {
|
||||
// @Param: _STR_RAT_FILT
|
||||
// @DisplayName: Steering control filter frequency
|
||||
// @Description: Steering control input filter. Lower values reduce noise but add delay.
|
||||
// @Range: 1.000 100.000
|
||||
// @Range: 0.000 100.000
|
||||
// @Increment: 0.1
|
||||
// @Units: Hz
|
||||
// @User: Standard
|
||||
@ -102,7 +102,7 @@ const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = {
|
||||
// @Param: _SPEED_FILT
|
||||
// @DisplayName: Speed control filter frequency
|
||||
// @Description: Speed control input filter. Lower values reduce noise but add delay.
|
||||
// @Range: 1.000 100.000
|
||||
// @Range: 0.000 100.000
|
||||
// @Increment: 0.1
|
||||
// @Units: Hz
|
||||
// @User: Standard
|
||||
|
@ -12,12 +12,12 @@
|
||||
#define AR_ATTCONTROL_STEER_RATE_I 0.50f
|
||||
#define AR_ATTCONTROL_STEER_RATE_IMAX 1.00f
|
||||
#define AR_ATTCONTROL_STEER_RATE_D 0.00f
|
||||
#define AR_ATTCONTROL_STEER_RATE_FILT 5.00f
|
||||
#define AR_ATTCONTROL_STEER_RATE_FILT 50.00f
|
||||
#define AR_ATTCONTROL_THR_SPEED_P 0.20f
|
||||
#define AR_ATTCONTROL_THR_SPEED_I 0.20f
|
||||
#define AR_ATTCONTROL_THR_SPEED_IMAX 1.00f
|
||||
#define AR_ATTCONTROL_THR_SPEED_D 0.00f
|
||||
#define AR_ATTCONTROL_THR_SPEED_FILT 5.00f
|
||||
#define AR_ATTCONTROL_THR_SPEED_FILT 50.00f
|
||||
#define AR_ATTCONTROL_DT 0.02f
|
||||
#define AR_ATTCONTROL_TIMEOUT_MS 200
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user