mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-15 12:25:20 +03:00
Ensure that rcRate great than 1.0 doesn't cause stability issues when
aircraft is inverted. See #281.
This commit is contained in:
parent
98343af7a2
commit
98b258e83f
1 changed files with 2 additions and 1 deletions
|
@ -189,7 +189,8 @@ static void pidMultiWii(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
|
|||
UNUSED(controlRateConfig);
|
||||
|
||||
// **** PITCH & ROLL & YAW PID ****
|
||||
prop = max(abs(rcCommand[PITCH]), abs(rcCommand[ROLL])); // range [0;500]
|
||||
prop = min(max(abs(rcCommand[PITCH]), abs(rcCommand[ROLL])), 500); // range [0;500]
|
||||
|
||||
for (axis = 0; axis < 3; axis++) {
|
||||
if ((FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) && (axis == FD_ROLL || axis == FD_PITCH)) { // MODE relying on ACC
|
||||
// observe max inclination
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue