mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
temp remove filter for quad motors during testing. It's unlikely this filter did anything at all to be honest.
This commit is contained in:
parent
43b3e1ccd1
commit
df812dd78a
@ -102,7 +102,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 i = MOT_1; i <= MOT_4; i++){
|
||||
/*for(int8_t i = MOT_1; i <= MOT_4; i++){
|
||||
if(motor_filtered[i] < motor_out[i]){
|
||||
motor_filtered[i] = (motor_out[i] + motor_filtered[i]) / 2;
|
||||
}else{
|
||||
@ -110,11 +110,38 @@ static void output_motors_armed()
|
||||
motor_filtered[i] = motor_out[i];
|
||||
}
|
||||
}
|
||||
|
||||
APM_RC.OutputCh(MOT_1, motor_filtered[MOT_1]);
|
||||
APM_RC.OutputCh(MOT_2, motor_filtered[MOT_2]);
|
||||
APM_RC.OutputCh(MOT_3, motor_filtered[MOT_3]);
|
||||
APM_RC.OutputCh(MOT_4, motor_filtered[MOT_4]);
|
||||
*/
|
||||
|
||||
|
||||
/*
|
||||
if(g.rc_7.radio_in > 1700){
|
||||
for(int8_t i = MOT_1; i <= MOT_4; i++){
|
||||
motor_out[i] = (motor_previous[i] * 3 + motor_out[i]) / 4;
|
||||
motor_previous[i] = motor_out[i];
|
||||
}
|
||||
|
||||
APM_RC.OutputCh(MOT_1, motor_out[MOT_1]);
|
||||
APM_RC.OutputCh(MOT_2, motor_out[MOT_2]);
|
||||
APM_RC.OutputCh(MOT_3, motor_out[MOT_3]);
|
||||
APM_RC.OutputCh(MOT_4, motor_out[MOT_4]);
|
||||
}else{
|
||||
APM_RC.OutputCh(MOT_1, motor_out[MOT_1]);
|
||||
APM_RC.OutputCh(MOT_2, motor_out[MOT_2]);
|
||||
APM_RC.OutputCh(MOT_3, motor_out[MOT_3]);
|
||||
APM_RC.OutputCh(MOT_4, motor_out[MOT_4]);
|
||||
}
|
||||
//*/
|
||||
|
||||
|
||||
APM_RC.OutputCh(MOT_1, motor_out[MOT_1]);
|
||||
APM_RC.OutputCh(MOT_2, motor_out[MOT_2]);
|
||||
APM_RC.OutputCh(MOT_3, motor_out[MOT_3]);
|
||||
APM_RC.OutputCh(MOT_4, motor_out[MOT_4]);
|
||||
|
||||
|
||||
#if INSTANT_PWM == 1
|
||||
// InstantPWM
|
||||
|
Loading…
Reference in New Issue
Block a user