1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-26 01:35:41 +03:00

Soft Filtering (Gyro, Dterm, Pterm)

pterm_cut_hz added

Let's play with this as well to get more noise filtered

Code Cleanup

Make filter more flexible for reuse

rewrite correction pterm

Define static delta in filter

Fix array count

ident

return function for filter

Filter Function enhanced

Full software filtering (DTerm, PTerm, Gyro, Acc)

Normalize Variables

Revert Back gyro settings

Bugfix gyro/acc filter // (MPU60xx equalize lpf settings)

Moved filtering to mw.c

This has been done to prevent reusing old cycletime for filter function.

acc_cut_hz removed (not needed)

Harakiri zero fix
This commit is contained in:
borisbstyle 2015-06-10 10:00:36 +02:00
parent 6323fd15d6
commit 10f2d35759
11 changed files with 156 additions and 33 deletions

View file

@ -19,7 +19,6 @@
#define GYRO_I_MAX 256 // Gyro I limiter
#define RCconstPI 0.159154943092f // 0.5f / M_PI;
#define MAIN_CUT_HZ 12.0f // (default 12Hz, Range 1-50Hz)
#define OLD_YAW 0 // [0/1] 0 = MultiWii 2.3 yaw, 1 = older yaw.
#define YAW_P_LIMIT_MIN 100 // Maximum value for yaw P limiter
#define YAW_P_LIMIT_MAX 500 // Maximum value for yaw P limiter
@ -63,6 +62,9 @@ typedef struct pidProfile_s {
float H_level;
uint8_t H_sensitivity;
uint16_t yaw_p_limit; // set P term limit (fixed value was 300)
uint8_t dterm_cut_hz; // (default 17Hz, Range 1-50Hz) Used for PT1 element in PID1, PID2 and PID5
uint8_t pterm_cut_hz; // Used for fitlering Pterm noise on noisy frames
uint8_t gyro_cut_hz; // Used for soft gyro filtering
} pidProfile_t;
#define DEGREES_TO_DECIDEGREES(angle) (angle * 10)
@ -75,4 +77,3 @@ void pidSetController(pidControllerType_e type);
void pidResetErrorAngle(void);
void pidResetErrorGyro(void);