mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-21 15:25:36 +03:00
Luxfloat Level Mode (rcCommand scaled to max_angle_inclination)
This commit is contained in:
parent
a687e35065
commit
77effd3b71
1 changed files with 4 additions and 4 deletions
|
@ -149,11 +149,11 @@ static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
|
|||
} else {
|
||||
// calculate error and limit the angle to the max inclination
|
||||
#ifdef GPS
|
||||
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
|
||||
errorAngle = (constrainf(((float)rcCommand[axis] * ((float)max_angle_inclination / 500.0f)) + GPS_angle[axis], -((int) max_angle_inclination),
|
||||
+max_angle_inclination) - inclination.raw[axis] + angleTrim->raw[axis]) / 10.0f;
|
||||
#else
|
||||
errorAngle = (constrain(rcCommand[axis], -((int) max_angle_inclination),
|
||||
+max_angle_inclination) - inclination.raw[axis] + angleTrim->raw[axis]) / 10.0f; // 16 bits is ok here
|
||||
errorAngle = (constrainf((float)rcCommand[axis] * ((float)max_angle_inclination / 500.0f), -((int) max_angle_inclination),
|
||||
+max_angle_inclination) - inclination.raw[axis] + angleTrim->raw[axis]) / 10.0f;
|
||||
#endif
|
||||
|
||||
#ifdef AUTOTUNE
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue