diff --git a/ArduCopter/motors_y6.pde b/ArduCopter/motors_y6.pde index 6cbf7bbc06..e576e3ad9f 100644 --- a/ArduCopter/motors_y6.pde +++ b/ArduCopter/motors_y6.pde @@ -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{