ArduCopter motors_y6: rewrite loop in terms of motors

This commit is contained in:
Pat Hickey 2012-01-01 20:15:18 -05:00
parent ac7f6a5602
commit 927e60d85b
1 changed files with 2 additions and 3 deletions

View File

@ -108,9 +108,8 @@ static void output_motors_armed()
// this filter slows the acceleration of motors vs the deceleration
// Idea by Denny Rowland to help with his Yaw issue
for(int8_t i = CH_1; i <= CH_8; i++ ) {
if(i == CH_5 || i == CH_6)
continue;
for(int8_t m = 0; m <= 6; m++ ) {
int i = ch_of_mot(m);
if(motor_filtered[i] < motor_out[i]){
motor_filtered[i] = (motor_out[i] + motor_filtered[i]) / 2;
}else{