AP_Tuning: adapt to new RC_Channel API

This commit is contained in:
Andrew Tridgell 2017-01-05 16:13:19 +11:00
parent f73f3bedda
commit ede66aae17
1 changed files with 2 additions and 2 deletions

View File

@ -64,7 +64,7 @@ void AP_Tuning::check_selector_switch(void)
// no selector switch enabled
return;
}
RC_Channel *selchan = RC_Channel::rc_channel(selector-1);
RC_Channel *selchan = RC_Channels::rc_channel(selector-1);
if (selchan == nullptr) {
return;
}
@ -172,7 +172,7 @@ void AP_Tuning::check_input(uint8_t flightmode)
return;
}
RC_Channel *chan = RC_Channel::rc_channel(channel-1);
RC_Channel *chan = RC_Channels::rc_channel(channel-1);
if (chan == nullptr) {
return;
}