mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-19 22:35:23 +03:00
AIR MODE Safety Enhancements
This commit is contained in:
parent
72e9a4dc17
commit
b84e9f4676
5 changed files with 46 additions and 18 deletions
|
@ -61,8 +61,6 @@ uint8_t dynP8[3], dynI8[3], dynD8[3], PIDweight[3];
|
|||
|
||||
static int32_t errorGyroI[3] = { 0, 0, 0 };
|
||||
static float errorGyroIf[3] = { 0.0f, 0.0f, 0.0f };
|
||||
static int32_t errorAngleI[2] = { 0, 0 };
|
||||
static float errorAngleIf[2] = { 0.0f, 0.0f };
|
||||
|
||||
static void pidRewrite(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig,
|
||||
uint16_t max_angle_inclination, rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig);
|
||||
|
@ -72,15 +70,6 @@ typedef void (*pidControllerFuncPtr)(pidProfile_t *pidProfile, controlRateConfig
|
|||
|
||||
pidControllerFuncPtr pid_controller = pidRewrite; // which pid controller are we using, defaultMultiWii
|
||||
|
||||
void pidResetErrorAngle(void)
|
||||
{
|
||||
errorAngleI[ROLL] = 0;
|
||||
errorAngleI[PITCH] = 0;
|
||||
|
||||
errorAngleIf[ROLL] = 0.0f;
|
||||
errorAngleIf[PITCH] = 0.0f;
|
||||
}
|
||||
|
||||
void pidResetErrorGyro(void)
|
||||
{
|
||||
errorGyroI[ROLL] = 0;
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue