1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-13 03:20:00 +03:00

NOINLINE some pid.c functions

This commit is contained in:
ctzsnooze 2024-11-27 08:14:40 +11:00
parent 070e80f8f6
commit 56a3f7cec2

View file

@ -317,7 +317,7 @@ void pidResetIterm(void)
} }
#ifdef USE_WING #ifdef USE_WING
static float calcWingThrottle(void) static float FAST_CODE_NOINLINE calcWingThrottle(void)
{ {
float batteryThrottleFactor = 1.0f; float batteryThrottleFactor = 1.0f;
if (pidRuntime.tpaSpeed.maxVoltage > 0.0f) { if (pidRuntime.tpaSpeed.maxVoltage > 0.0f) {
@ -328,7 +328,7 @@ static float calcWingThrottle(void)
return getMotorOutputRms() * batteryThrottleFactor; return getMotorOutputRms() * batteryThrottleFactor;
} }
static float calcWingAcceleration(float throttle, float pitchAngleRadians) static float FAST_CODE_NOINLINE calcWingAcceleration(float throttle, float pitchAngleRadians)
{ {
const tpaSpeedParams_t *tpa = &pidRuntime.tpaSpeed; const tpaSpeedParams_t *tpa = &pidRuntime.tpaSpeed;
@ -339,7 +339,7 @@ static float calcWingAcceleration(float throttle, float pitchAngleRadians)
return thrust - drag + gravity; return thrust - drag + gravity;
} }
static float calcWingTpaArgument(void) static float FAST_CODE_NOINLINE calcWingTpaArgument(void)
{ {
const float t = calcWingThrottle(); const float t = calcWingThrottle();
const float pitchRadians = DECIDEGREES_TO_RADIANS(attitude.values.pitch); const float pitchRadians = DECIDEGREES_TO_RADIANS(attitude.values.pitch);
@ -366,7 +366,7 @@ static float calcWingTpaArgument(void)
return tpaArgument; return tpaArgument;
} }
static void updateStermTpaFactor(int axis, float tpaFactor) static void FAST_CODE_NOINLINE updateStermTpaFactor(int axis, float tpaFactor)
{ {
float tpaFactorSterm = tpaFactor; float tpaFactorSterm = tpaFactor;
if (pidRuntime.tpaCurveType == TPA_CURVE_HYPERBOLIC) { if (pidRuntime.tpaCurveType == TPA_CURVE_HYPERBOLIC) {
@ -378,7 +378,7 @@ static void updateStermTpaFactor(int axis, float tpaFactor)
pidRuntime.tpaFactorSterm[axis] = tpaFactorSterm; pidRuntime.tpaFactorSterm[axis] = tpaFactorSterm;
} }
static void updateStermTpaFactors(void) { static void FAST_CODE_NOINLINE updateStermTpaFactors(void) {
for (int i = 0; i < XYZ_AXIS_COUNT; i++) { for (int i = 0; i < XYZ_AXIS_COUNT; i++) {
float tpaFactor = pidRuntime.tpaFactor; float tpaFactor = pidRuntime.tpaFactor;
if (i == FD_YAW && currentPidProfile->yaw_type == YAW_TYPE_DIFF_THRUST) { if (i == FD_YAW && currentPidProfile->yaw_type == YAW_TYPE_DIFF_THRUST) {
@ -389,7 +389,7 @@ static void updateStermTpaFactors(void) {
} }
#endif // USE_WING #endif // USE_WING
static float wingAdjustSetpoint(float currentPidSetpoint, int axis) static float FAST_CODE_NOINLINE wingAdjustSetpoint(float currentPidSetpoint, int axis)
{ {
#ifdef USE_WING #ifdef USE_WING
float adjustedSetpoint = currentPidSetpoint; float adjustedSetpoint = currentPidSetpoint;
@ -775,7 +775,7 @@ static FAST_CODE_NOINLINE float applyAcroTrainer(int axis, const rollAndPitchTri
} }
#endif // USE_ACRO_TRAINER #endif // USE_ACRO_TRAINER
static float accelerationLimit(int axis, float currentPidSetpoint) static float FAST_CODE_NOINLINE accelerationLimit(int axis, float currentPidSetpoint)
{ {
static float previousSetpoint[XYZ_AXIS_COUNT]; static float previousSetpoint[XYZ_AXIS_COUNT];
const float currentVelocity = currentPidSetpoint - previousSetpoint[axis]; const float currentVelocity = currentPidSetpoint - previousSetpoint[axis];
@ -801,7 +801,7 @@ static void rotateVector(float v[XYZ_AXIS_COUNT], const float rotation[XYZ_AXIS_
} }
} }
STATIC_UNIT_TESTED void rotateItermAndAxisError(void) STATIC_UNIT_TESTED FAST_CODE_NOINLINE void rotateItermAndAxisError(void)
{ {
if (pidRuntime.itermRotation if (pidRuntime.itermRotation
#if defined(USE_ABSOLUTE_CONTROL) #if defined(USE_ABSOLUTE_CONTROL)
@ -833,7 +833,7 @@ STATIC_UNIT_TESTED void rotateItermAndAxisError(void)
#if defined(USE_ITERM_RELAX) #if defined(USE_ITERM_RELAX)
#if defined(USE_ABSOLUTE_CONTROL) #if defined(USE_ABSOLUTE_CONTROL)
STATIC_UNIT_TESTED void applyAbsoluteControl(const int axis, const float gyroRate, float *currentPidSetpoint, float *itermErrorRate) STATIC_UNIT_TESTED FAST_CODE_NOINLINE void applyAbsoluteControl(const int axis, const float gyroRate, float *currentPidSetpoint, float *itermErrorRate)
{ {
if (pidRuntime.acGain > 0 || debugMode == DEBUG_AC_ERROR) { if (pidRuntime.acGain > 0 || debugMode == DEBUG_AC_ERROR) {
const float setpointLpf = pt1FilterApply(&pidRuntime.acLpf[axis], *currentPidSetpoint); const float setpointLpf = pt1FilterApply(&pidRuntime.acLpf[axis], *currentPidSetpoint);
@ -1035,7 +1035,7 @@ static float getTpaFactor(const pidProfile_t *pidProfile, int axis, term_e term)
} }
} }
static float getSterm(int axis, const pidProfile_t *pidProfile, float setpoint) static float FAST_CODE_NOINLINE getSterm(int axis, const pidProfile_t *pidProfile, float setpoint)
{ {
#ifdef USE_WING #ifdef USE_WING
float sTerm = setpoint / getMaxRcRate(axis) * 1000.0f * float sTerm = setpoint / getMaxRcRate(axis) * 1000.0f *
@ -1054,7 +1054,7 @@ static float getSterm(int axis, const pidProfile_t *pidProfile, float setpoint)
#endif #endif
} }
NOINLINE static void calculateSpaValues(const pidProfile_t *pidProfile) NOINLINE static void FAST_CODE_NOINLINE calculateSpaValues(const pidProfile_t *pidProfile)
{ {
#ifdef USE_WING #ifdef USE_WING
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
@ -1068,7 +1068,7 @@ NOINLINE static void calculateSpaValues(const pidProfile_t *pidProfile)
#endif // USE_WING #endif // USE_WING
} }
NOINLINE static void applySpa(int axis, const pidProfile_t *pidProfile) NOINLINE static void FAST_CODE_NOINLINE applySpa(int axis, const pidProfile_t *pidProfile)
{ {
#ifdef USE_WING #ifdef USE_WING
spaMode_e mode = pidProfile->spa_mode[axis]; spaMode_e mode = pidProfile->spa_mode[axis];