mirror of https://github.com/ArduPilot/ardupilot
AP_Tuning: use rc() method to get rc singleton
This commit is contained in:
parent
497746c3d0
commit
c209152d13
|
@ -65,7 +65,7 @@ void AP_Tuning::check_selector_switch(void)
|
|||
// no selector switch enabled
|
||||
return;
|
||||
}
|
||||
RC_Channel *selchan = RC_Channels::rc_channel(selector-1);
|
||||
RC_Channel *selchan = rc().channel(selector-1);
|
||||
if (selchan == nullptr) {
|
||||
return;
|
||||
}
|
||||
|
@ -173,7 +173,7 @@ void AP_Tuning::check_input(uint8_t flightmode)
|
|||
return;
|
||||
}
|
||||
|
||||
RC_Channel *chan = RC_Channels::rc_channel(channel-1);
|
||||
RC_Channel *chan = rc().channel(channel-1);
|
||||
if (chan == nullptr) {
|
||||
return;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue