mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-19 14:25:20 +03:00
Add ITerm anti-windup based on motor output saturation
Added noise threshold for PID ITerm accumulation Removed ITerm setpoint scaler. Added CLI and MSP settings Made default ITerm noise threshold zero. Added CLI setting. Removed itermWindupPointPercent from MSP
This commit is contained in:
parent
990c13b7ea
commit
9dfb3e45ee
8 changed files with 39 additions and 22 deletions
|
@ -56,6 +56,7 @@
|
|||
#define EXTERNAL_CONVERSION_MAX_VALUE 2000
|
||||
|
||||
static uint8_t motorCount;
|
||||
static float motorMixRange;
|
||||
|
||||
int16_t motor[MAX_SUPPORTED_MOTORS];
|
||||
int16_t motor_disarmed[MAX_SUPPORTED_MOTORS];
|
||||
|
@ -245,6 +246,11 @@ uint8_t getMotorCount()
|
|||
return motorCount;
|
||||
}
|
||||
|
||||
float getMotorMixRange()
|
||||
{
|
||||
return motorMixRange;
|
||||
}
|
||||
|
||||
bool isMotorProtocolDshot(void) {
|
||||
#ifdef USE_DSHOT
|
||||
switch(motorConfig->motorPwmProtocol) {
|
||||
|
@ -500,7 +506,7 @@ void mixTable(pidProfile_t *pidProfile)
|
|||
}
|
||||
}
|
||||
|
||||
const float motorMixRange = motorMixMax - motorMixMin;
|
||||
motorMixRange = motorMixMax - motorMixMin;
|
||||
|
||||
if (motorMixRange > 1.0f) {
|
||||
for (int i = 0; i < motorCount; i++) {
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue