mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-23 16:25:31 +03:00
Introduce better naming consistency for some union members. remove type
prefix from a typedef. Conflicts: obj/cleanflight_OLIMEXINO.hex src/flight_common.c
This commit is contained in:
parent
dcbb82c845
commit
4a23491d49
16 changed files with 68 additions and 68 deletions
|
@ -35,8 +35,8 @@ pidControllerFuncPtr pid_controller = pidMultiWii; // which pid controller are w
|
|||
|
||||
void resetRollAndPitchTrims(rollAndPitchTrims_t *rollAndPitchTrims)
|
||||
{
|
||||
rollAndPitchTrims->trims.roll = 0;
|
||||
rollAndPitchTrims->trims.pitch = 0;
|
||||
rollAndPitchTrims->values.roll = 0;
|
||||
rollAndPitchTrims->values.pitch = 0;
|
||||
}
|
||||
|
||||
void resetErrorAngle(void)
|
||||
|
@ -84,7 +84,7 @@ static void pidBaseflight(pidProfile_t *pidProfile, controlRateConfig_t *control
|
|||
AngleRate = (float)((controlRateConfig->yawRate + 10) * rcCommand[YAW]) / 50.0f;
|
||||
} else {
|
||||
// calculate error and limit the angle to 50 degrees max inclination
|
||||
errorAngle = (constrain(rcCommand[axis] + GPS_angle[axis], -500, +500) - inclination.rawAngles[axis] + angleTrim->raw[axis]) / 10.0f; // 16 bits is ok here
|
||||
errorAngle = (constrain(rcCommand[axis] + GPS_angle[axis], -500, +500) - inclination.raw[axis] + angleTrim->raw[axis]) / 10.0f; // 16 bits is ok here
|
||||
|
||||
if (shouldAutotune()) {
|
||||
errorAngle = autotune(rcAliasToAngleIndexMap[axis], &inclination, errorAngle);
|
||||
|
@ -94,7 +94,7 @@ static void pidBaseflight(pidProfile_t *pidProfile, controlRateConfig_t *control
|
|||
// it's the ANGLE mode - control is angle based, so control loop is needed
|
||||
AngleRate = errorAngle * pidProfile->A_level;
|
||||
} else {
|
||||
//control is GYRO based (ACRO and HORIZON - direct sticks control is applied to rate PID
|
||||
//control is GYRO based (ACRO and HORIZON - direct sticks control is applied to rate PID
|
||||
AngleRate = (float)((controlRateConfig->rollPitchRate + 20) * rcCommand[axis]) / 50.0f; // 200dps to 1200dps max yaw rate
|
||||
if (f.HORIZON_MODE) {
|
||||
// mix up angle error to desired AngleRate to add a little auto-level feel
|
||||
|
@ -156,12 +156,12 @@ static void pidMultiWii(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
|
|||
if ((f.ANGLE_MODE || f.HORIZON_MODE) && (axis == FD_ROLL || axis == FD_PITCH)) { // MODE relying on ACC
|
||||
// observe max inclination
|
||||
errorAngle = constrain(2 * rcCommand[axis] + GPS_angle[axis], -((int) max_angle_inclination),
|
||||
+max_angle_inclination) - inclination.rawAngles[axis] + angleTrim->raw[axis];
|
||||
+max_angle_inclination) - inclination.raw[axis] + angleTrim->raw[axis];
|
||||
|
||||
if (shouldAutotune()) {
|
||||
errorAngle = DEGREES_TO_DECIDEGREES(autotune(rcAliasToAngleIndexMap[axis], &inclination, DECIDEGREES_TO_DEGREES(errorAngle)));
|
||||
}
|
||||
|
||||
|
||||
PTermACC = errorAngle * pidProfile->P8[PIDLEVEL] / 100; // 32 bits is needed for calculation: errorAngle*P8[PIDLEVEL] could exceed 32768 16 bits is ok for result
|
||||
PTermACC = constrain(PTermACC, -pidProfile->D8[PIDLEVEL] * 5, +pidProfile->D8[PIDLEVEL] * 5);
|
||||
|
||||
|
@ -224,7 +224,7 @@ static void pidRewrite(pidProfile_t *pidProfile, controlRateConfig_t *controlRat
|
|||
} 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
|
||||
+max_angle_inclination) - inclination.raw[axis] + angleTrim->raw[axis]; // 16 bits is ok here
|
||||
|
||||
if (shouldAutotune()) {
|
||||
errorAngle = DEGREES_TO_DECIDEGREES(autotune(rcAliasToAngleIndexMap[axis], &inclination, DECIDEGREES_TO_DEGREES(errorAngle)));
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue