Browse Source

Ensure that rcRate great than 1.0 doesn't cause stability issues when

aircraft is inverted.  See #281.
master
Dominic Clifton 10 years ago
parent
commit
98b258e83f
  1. 3
      src/main/flight/flight.c

3
src/main/flight/flight.c

@ -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…
Cancel
Save