Plane: Remove manual polling of flap input channel

This commit is contained in:
Michael du Breuil 2018-06-02 14:12:29 -07:00 committed by Andrew Tridgell
parent cc772710ec
commit 47c0048499

View File

@ -403,7 +403,6 @@ void Plane::set_servos_flaps(void)
// work out any manual flap input // work out any manual flap input
RC_Channel *flapin = RC_Channels::rc_channel(g.flapin_channel-1); RC_Channel *flapin = RC_Channels::rc_channel(g.flapin_channel-1);
if (flapin != nullptr && !failsafe.rc_failsafe && failsafe.throttle_counter == 0) { if (flapin != nullptr && !failsafe.rc_failsafe && failsafe.throttle_counter == 0) {
flapin->input();
manual_flap_percent = flapin->percent_input(); manual_flap_percent = flapin->percent_input();
} }