ArduCopter - fixed typo in motor filtering for octa, octa_quad and y6 that is suppose to correct for props speeding up faster than they slow down.

This commit is contained in:
rmackay9 2012-03-06 22:19:19 +09:00
parent 29aea35eae
commit 8af43c4a19
3 changed files with 4 additions and 4 deletions

View File

@ -163,7 +163,7 @@ 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 m = 0; m <= 8; m++){
for(int8_t m = 1; m <= 8; m++){
int c = ch_of_mot(m);
if(motor_filtered[c] < motor_out[c]){
motor_filtered[c] = (motor_out[c] + motor_filtered[c]) / 2;

View File

@ -113,7 +113,7 @@ 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 m = 0; m <= 8; m++){
for(int8_t m = 1; m <= 8; m++){
int i = ch_of_mot(m);
if(motor_filtered[i] < motor_out[i]){
motor_filtered[i] = (motor_out[i] + motor_filtered[i]) / 2;

View File

@ -119,8 +119,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 m = 0; m <= 6; m++){
int i = ch_of_mot(m);
for(int8_t m = 1; 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{