mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-16 12:55:19 +03:00
Delete unnecessary code to reduce code size and improve maintainability by moving errorAngle initialisation to the conditional block where it is used.
This commit is contained in:
parent
420ba7d2c9
commit
56c2539e01
1 changed files with 5 additions and 6 deletions
|
@ -117,7 +117,7 @@ static void pidMultiWii(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
|
||||||
static void pidRewrite(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig, uint16_t max_angle_inclination,
|
static void pidRewrite(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig, uint16_t max_angle_inclination,
|
||||||
rollAndPitchTrims_t *angleTrim)
|
rollAndPitchTrims_t *angleTrim)
|
||||||
{
|
{
|
||||||
int32_t errorAngle = 0;
|
int32_t errorAngle;
|
||||||
int axis;
|
int axis;
|
||||||
int32_t delta, deltaSum;
|
int32_t delta, deltaSum;
|
||||||
static int32_t delta1[3], delta2[3];
|
static int32_t delta1[3], delta2[3];
|
||||||
|
@ -128,14 +128,13 @@ static void pidRewrite(pidProfile_t *pidProfile, controlRateConfig_t *controlRat
|
||||||
// ----------PID controller----------
|
// ----------PID controller----------
|
||||||
for (axis = 0; axis < 3; axis++) {
|
for (axis = 0; axis < 3; axis++) {
|
||||||
// -----Get the desired angle rate depending on flight mode
|
// -----Get the desired angle rate depending on flight mode
|
||||||
if ((f.ANGLE_MODE || f.HORIZON_MODE) && (axis == FD_PITCH || axis == FD_ROLL)) { // MODE relying on ACC
|
|
||||||
// calculate error and limit the angle to max configured inclination
|
|
||||||
errorAngle = constrain((rcCommand[axis] << 1) + GPS_angle[axis], -((int) max_angle_inclination),
|
|
||||||
+max_angle_inclination) - inclination.rawAngles[axis] + angleTrim->raw[axis]; // 16 bits is ok here
|
|
||||||
}
|
|
||||||
if (axis == FD_YAW) { // YAW is always gyro-controlled (MAG correction is applied to rcCommand)
|
if (axis == FD_YAW) { // YAW is always gyro-controlled (MAG correction is applied to rcCommand)
|
||||||
AngleRateTmp = (((int32_t)(controlRateConfig->yawRate + 27) * rcCommand[2]) >> 5);
|
AngleRateTmp = (((int32_t)(controlRateConfig->yawRate + 27) * rcCommand[2]) >> 5);
|
||||||
} else {
|
} else {
|
||||||
|
// calculate error and limit the angle to max configured inclination
|
||||||
|
errorAngle = constrain((rcCommand[axis] << 1) + GPS_angle[axis], -((int) max_angle_inclination),
|
||||||
|
+max_angle_inclination) - inclination.rawAngles[axis] + angleTrim->raw[axis]; // 16 bits is ok here
|
||||||
|
|
||||||
if (!f.ANGLE_MODE) { //control is GYRO based (ACRO and HORIZON - direct sticks control is applied to rate PID
|
if (!f.ANGLE_MODE) { //control is GYRO based (ACRO and HORIZON - direct sticks control is applied to rate PID
|
||||||
AngleRateTmp = ((int32_t)(controlRateConfig->rollPitchRate + 27) * rcCommand[axis]) >> 4;
|
AngleRateTmp = ((int32_t)(controlRateConfig->rollPitchRate + 27) * rcCommand[axis]) >> 4;
|
||||||
if (f.HORIZON_MODE) {
|
if (f.HORIZON_MODE) {
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue