From 4ac5ef3a13f512f18fbc137dbe8f283dfce669f7 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 2 Jan 2018 15:10:02 +0900 Subject: [PATCH] AR_AttitudeControl: allow filter to be zero Also increase default filter to 50hz --- libraries/APM_Control/AR_AttitudeControl.cpp | 4 ++-- libraries/APM_Control/AR_AttitudeControl.h | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/APM_Control/AR_AttitudeControl.cpp b/libraries/APM_Control/AR_AttitudeControl.cpp index bf281b7736..dc8209917f 100644 --- a/libraries/APM_Control/AR_AttitudeControl.cpp +++ b/libraries/APM_Control/AR_AttitudeControl.cpp @@ -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 diff --git a/libraries/APM_Control/AR_AttitudeControl.h b/libraries/APM_Control/AR_AttitudeControl.h index 5582c02f42..f3f9ac411c 100644 --- a/libraries/APM_Control/AR_AttitudeControl.h +++ b/libraries/APM_Control/AR_AttitudeControl.h @@ -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