mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-17 13:25:30 +03:00
Fix broken Level Modes
This commit is contained in:
parent
a3c1f6e168
commit
c45475b8af
1 changed files with 2 additions and 2 deletions
|
@ -174,7 +174,7 @@ static void pidLuxFloat(const pidProfile_t *pidProfile, const controlRateConfig_
|
||||||
// ACRO mode, control is GYRO based, direct sticks control is applied to rate PID
|
// ACRO mode, control is GYRO based, direct sticks control is applied to rate PID
|
||||||
AngleRate = calculateRate(axis, controlRateConfig);
|
AngleRate = calculateRate(axis, controlRateConfig);
|
||||||
|
|
||||||
if (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) {
|
if ((FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) && axis != YAW) {
|
||||||
// calculate error angle and limit the angle to the max inclination
|
// calculate error angle and limit the angle to the max inclination
|
||||||
#ifdef GPS
|
#ifdef GPS
|
||||||
const float errorAngle = (constrain(2 * rcCommand[axis] + GPS_angle[axis], -((int) max_angle_inclination),
|
const float errorAngle = (constrain(2 * rcCommand[axis] + GPS_angle[axis], -((int) max_angle_inclination),
|
||||||
|
@ -299,7 +299,7 @@ static void pidMultiWiiRewrite(const pidProfile_t *pidProfile, const controlRate
|
||||||
// -----Get the desired angle rate depending on flight mode
|
// -----Get the desired angle rate depending on flight mode
|
||||||
AngleRateTmp = (int32_t)calculateRate(axis, controlRateConfig);
|
AngleRateTmp = (int32_t)calculateRate(axis, controlRateConfig);
|
||||||
|
|
||||||
if (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) {
|
if ((FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) && axis != YAW) {
|
||||||
// calculate error angle and limit the angle to max configured inclination
|
// calculate error angle and limit the angle to max configured inclination
|
||||||
#ifdef GPS
|
#ifdef GPS
|
||||||
const int32_t errorAngle = constrain(2 * rcCommand[axis] + GPS_angle[axis], -((int) max_angle_inclination),
|
const int32_t errorAngle = constrain(2 * rcCommand[axis] + GPS_angle[axis], -((int) max_angle_inclination),
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue