mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
fixed quad PWM clipping
this adopts the simpler approach suggested by Jason. git-svn-id: https://arducopter.googlecode.com/svn/trunk@2936 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
87a260656e
commit
580f981d30
@ -59,9 +59,9 @@ static void output_motors_armed()
|
||||
* is at its maximum output
|
||||
*/
|
||||
for (int i=CH_1; i<=CH_4; i++) {
|
||||
if (motor_out[i] > out_max && motor_out[i] > out_min) {
|
||||
/* note that i^1 is the 'opposite' motor for a quad */
|
||||
motor_out[i^1] *= ((float)out_max - out_min) / (motor_out[i] - out_min);
|
||||
if (motor_out[i] > out_max) {
|
||||
// note that i^1 is the opposite motor
|
||||
motor_out[i^1] -= motor_out[i] - out_max;
|
||||
motor_out[i] = out_max;
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user