mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-20 14:55:21 +03:00
Warning removal where present if pidBetaflight is skipped.
This commit is contained in:
parent
9e0a786dde
commit
df11d398aa
1 changed files with 4 additions and 1 deletions
|
@ -66,9 +66,10 @@ uint8_t PIDweight[3];
|
|||
static int32_t errorGyroI[3];
|
||||
static float errorGyroIf[3];
|
||||
|
||||
#ifdef SKIP_PID_FLOAT
|
||||
|
||||
static void pidLegacy(const pidProfile_t *pidProfile, uint16_t max_angle_inclination,
|
||||
const rollAndPitchTrims_t *angleTrim, const rxConfig_t *rxConfig);
|
||||
#ifdef SKIP_PID_FLOAT
|
||||
pidControllerFuncPtr pid_controller = pidLegacy; // which pid controller are we using
|
||||
#else
|
||||
static void pidBetaflight(const pidProfile_t *pidProfile, uint16_t max_angle_inclination,
|
||||
|
@ -107,6 +108,7 @@ const angle_index_t rcAliasToAngleIndexMap[] = { AI_ROLL, AI_PITCH };
|
|||
static pt1Filter_t deltaFilter[3];
|
||||
static pt1Filter_t yawFilter;
|
||||
|
||||
#ifndef SKIP_PID_FLOAT
|
||||
// Betaflight pid controller, which will be maintained in the future with additional features specialised for current (mini) multirotor usage. Based on 2DOF reference design (matlab)
|
||||
static void pidBetaflight(const pidProfile_t *pidProfile, uint16_t max_angle_inclination,
|
||||
const rollAndPitchTrims_t *angleTrim, const rxConfig_t *rxConfig)
|
||||
|
@ -302,6 +304,7 @@ static void pidBetaflight(const pidProfile_t *pidProfile, uint16_t max_angle_inc
|
|||
#endif
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
// Legacy pid controller betaflight evolved pid rewrite based on 2.9 releae. Good for fastest cycletimes for those who believe in that. Don't expect much development in the future
|
||||
static void pidLegacy(const pidProfile_t *pidProfile, uint16_t max_angle_inclination,
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue