mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-05 13:14:03 -04:00
ArduCopter motors_octa_quad: rewrite loop in terms of motors
This commit is contained in:
parent
e2be119433
commit
7f4c994346
@ -118,9 +118,8 @@ static void output_motors_armed()
|
|||||||
|
|
||||||
// this filter slows the acceleration of motors vs the deceleration
|
// this filter slows the acceleration of motors vs the deceleration
|
||||||
// Idea by Denny Rowland to help with his Yaw issue
|
// Idea by Denny Rowland to help with his Yaw issue
|
||||||
for(int8_t i = CH_1; i <= CH_11; i++ ) {
|
for(int8_t m = 0; i <= 8; m++ ) {
|
||||||
if(i == CH_5 || i == CH_6 || i == CH_9)
|
int i = ch_of_mot(m);
|
||||||
continue;
|
|
||||||
if(motor_filtered[i] < motor_out[i]){
|
if(motor_filtered[i] < motor_out[i]){
|
||||||
motor_filtered[i] = (motor_out[i] + motor_filtered[i]) / 2;
|
motor_filtered[i] = (motor_out[i] + motor_filtered[i]) / 2;
|
||||||
}else{
|
}else{
|
||||||
|
Loading…
Reference in New Issue
Block a user