Copter: allow passthru for ch 9 ~ 14

Based on work by Emile Castelnuovo
This commit is contained in:
Randy Mackay 2014-09-23 22:55:19 +09:00
parent c2c5807ec7
commit 41c576044f

View File

@ -93,6 +93,13 @@ static void read_radio()
g.rc_7.set_pwm(periods[6]);
g.rc_8.set_pwm(periods[7]);
// read channels 9 ~ 14
for (uint8_t i=8; i<RC_MAX_CHANNELS; i++) {
if (RC_Channel::rc_channel(i) != NULL) {
RC_Channel::rc_channel(i)->set_pwm(RC_Channel::rc_channel(i)->read());
}
}
// flag we must have an rc receiver attached
if (!failsafe.rc_override_active) {
ap.rc_receiver_present = true;