mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-23 16:25:31 +03:00
Ensure that Lux's pid controller observes the max_angle_inclination
setting.
This commit is contained in:
parent
ab0296c991
commit
9b6e8feeea
1 changed files with 3 additions and 2 deletions
|
@ -101,8 +101,9 @@ static void pidBaseflight(pidProfile_t *pidProfile, controlRateConfig_t *control
|
|||
// YAW is always gyro-controlled (MAG correction is applied to rcCommand) 100dps to 1100dps max yaw rate
|
||||
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.raw[axis] + angleTrim->raw[axis]) / 10.0f; // 16 bits is ok here
|
||||
// calculate error and limit the angle to the max inclination
|
||||
errorAngle = (constrain(rcCommand[axis] + GPS_angle[axis], -((int) max_angle_inclination),
|
||||
+max_angle_inclination) - inclination.raw[axis] + angleTrim->raw[axis]) / 10.0f; // 16 bits is ok here
|
||||
|
||||
if (shouldAutotune()) {
|
||||
errorAngle = autotune(rcAliasToAngleIndexMap[axis], &inclination, errorAngle);
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue