Copter: fix symmetry in stability patch for Tricopters

Removes the "Increase opposing motors by 1/2 the overage of the high
motor" logic and merely moves all 3 motors down by the same amount if
one is over out_max. This eliminates the asymmetric scaling of
the previous logic when more than one motor is over out_max. This
resolves #537
This commit is contained in:
texlan 2013-09-12 10:39:40 -07:00 committed by Randy Mackay
parent 8f4665c4c7
commit 78acea820f

View File

@ -132,20 +132,20 @@ void AP_MotorsTri::output_armed()
// Tridge's stability patch // Tridge's stability patch
if(motor_out[AP_MOTORS_MOT_1] > out_max) { if(motor_out[AP_MOTORS_MOT_1] > out_max) {
motor_out[AP_MOTORS_MOT_2] -= (motor_out[AP_MOTORS_MOT_1] - out_max) >> 1; motor_out[AP_MOTORS_MOT_2] -= (motor_out[AP_MOTORS_MOT_1] - out_max);
motor_out[AP_MOTORS_MOT_4] -= (motor_out[AP_MOTORS_MOT_1] - out_max) >> 1; motor_out[AP_MOTORS_MOT_4] -= (motor_out[AP_MOTORS_MOT_1] - out_max);
motor_out[AP_MOTORS_MOT_1] = out_max; motor_out[AP_MOTORS_MOT_1] = out_max;
} }
if(motor_out[AP_MOTORS_MOT_2] > out_max) { if(motor_out[AP_MOTORS_MOT_2] > out_max) {
motor_out[AP_MOTORS_MOT_1] -= (motor_out[AP_MOTORS_MOT_2] - out_max) >> 1; motor_out[AP_MOTORS_MOT_1] -= (motor_out[AP_MOTORS_MOT_2] - out_max);
motor_out[AP_MOTORS_MOT_4] -= (motor_out[AP_MOTORS_MOT_2] - out_max) >> 1; motor_out[AP_MOTORS_MOT_4] -= (motor_out[AP_MOTORS_MOT_2] - out_max);
motor_out[AP_MOTORS_MOT_2] = out_max; motor_out[AP_MOTORS_MOT_2] = out_max;
} }
if(motor_out[AP_MOTORS_MOT_4] > out_max) { if(motor_out[AP_MOTORS_MOT_4] > out_max) {
motor_out[AP_MOTORS_MOT_1] -= (motor_out[AP_MOTORS_MOT_4] - out_max) >> 1; motor_out[AP_MOTORS_MOT_1] -= (motor_out[AP_MOTORS_MOT_4] - out_max);
motor_out[AP_MOTORS_MOT_2] -= (motor_out[AP_MOTORS_MOT_4] - out_max) >> 1; motor_out[AP_MOTORS_MOT_2] -= (motor_out[AP_MOTORS_MOT_4] - out_max);
motor_out[AP_MOTORS_MOT_4] = out_max; motor_out[AP_MOTORS_MOT_4] = out_max;
} }