mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
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
|
// no selector switch enabled
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
RC_Channel *selchan = RC_Channels::rc_channel(selector-1);
|
RC_Channel *selchan = rc().channel(selector-1);
|
||||||
if (selchan == nullptr) {
|
if (selchan == nullptr) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -173,7 +173,7 @@ void AP_Tuning::check_input(uint8_t flightmode)
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
RC_Channel *chan = RC_Channels::rc_channel(channel-1);
|
RC_Channel *chan = rc().channel(channel-1);
|
||||||
if (chan == nullptr) {
|
if (chan == nullptr) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user