mirror of https://github.com/ArduPilot/ardupilot
parent
4f504b0729
commit
9603236de4
|
@ -398,8 +398,10 @@ static void set_servos(void)
|
||||||
|
|
||||||
|
|
||||||
// push out the PWM values
|
// push out the PWM values
|
||||||
|
if (g.mix_mode == 0) {
|
||||||
g.channel_roll.calc_pwm();
|
g.channel_roll.calc_pwm();
|
||||||
g.channel_pitch.calc_pwm();
|
g.channel_pitch.calc_pwm();
|
||||||
|
}
|
||||||
g.channel_throttle.calc_pwm();
|
g.channel_throttle.calc_pwm();
|
||||||
g.channel_rudder.calc_pwm();
|
g.channel_rudder.calc_pwm();
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue