AP_MotorsMatrix - fixed stability patch issue in which it would not limit a motor's output unless an opposite motor had been defined. This would only have affected Y6 frames.

This commit is contained in:
rmackay9 2012-04-07 12:14:25 +09:00
parent 762b1ea0df
commit 53827f2e92
1 changed files with 4 additions and 4 deletions

View File

@ -146,14 +146,14 @@ void AP_MotorsMatrix::output_armed()
_rc_pitch->pwm_out * _pitch_factor[i] +
_rc_yaw->pwm_out*_yaw_factor[i];
}
// ensure motor is not below the minimum
motor_out[AP_MOTORS_MOT_1] = max(motor_out[AP_MOTORS_MOT_1], out_min);
}
// stability patch
for( i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++ ) {
if( motor_enabled[i] && opposite_motor[i] != AP_MOTORS_MATRIX_MOTOR_UNDEFINED && motor_out[i] > out_max ) {
motor_out[opposite_motor[i]] -= motor_out[i] - out_max;
if( motor_enabled[i] && motor_out[i] > out_max ) {
if( opposite_motor[i] != AP_MOTORS_MATRIX_MOTOR_UNDEFINED ) {
motor_out[opposite_motor[i]] -= motor_out[i] - out_max;
}
motor_out[i] = out_max;
}
}