1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-25 01:05:27 +03:00

Pid Controller Cleanup

Correction to dump
This commit is contained in:
borisbstyle 2015-10-23 00:39:15 +02:00
parent d076a60eb5
commit d685b4d6d8
5 changed files with 62 additions and 507 deletions

View file

@ -18,10 +18,6 @@
#pragma once
#define GYRO_I_MAX 256 // Gyro I limiter
#define RCconstPI 0.159154943092f // 0.5f / M_PI;
#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
typedef enum {
PIDROLL,
@ -38,18 +34,15 @@ typedef enum {
} pidIndex_e;
typedef enum {
PID_CONTROLLER_MULTI_WII,
PID_CONTROLLER_REWRITE,
PID_CONTROLLER_REWRITE = 1,
PID_CONTROLLER_LUX_FLOAT,
PID_CONTROLLER_MULTI_WII_23,
PID_CONTROLLER_MULTI_WII_HYBRID,
PID_CONTROLLER_HARAKIRI,
PID_COUNT
} pidControllerType_e;
#define IS_PID_CONTROLLER_FP_BASED(pidController) (pidController == 2)
typedef struct pidProfile_s {
uint8_t pidController; // 0 = multiwii original, 1 = rewrite from http://www.multiwii.com/forum/viewtopic.php?f=8&t=3671, 1, 2 = Luggi09s new baseflight pid
uint8_t pidController; // 1 = rewrite, 2 = luxfloat
uint8_t P8[PID_ITEM_COUNT];
uint8_t I8[PID_ITEM_COUNT];
@ -62,12 +55,7 @@ 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
uint8_t pid5_oldyw; // [0/1] 0 = multiwii 2.3 yaw, 1 = older yaw
#ifdef GTUNE
uint8_t gtune_lolimP[3]; // [0..200] Lower limit of P during G tune