Copter: output any servo channels on motor output

if we have any auxillary servo channels we need to calculate the
output value
This commit is contained in:
Andrew Tridgell 2017-04-17 16:32:34 +10:00 committed by Randy Mackay
parent 032bfad79f
commit ebde6e1ce3

View File

@ -290,6 +290,9 @@ void Copter::motors_output()
ap.in_arming_delay = false;
}
// output any servo channels
SRV_Channels::calc_pwm();
// check if we are performing the motor test
if (ap.motor_test) {
motor_test_output();