AP_Mount: use rc() method to get rc singleton

This commit is contained in:
Peter Barker 2018-04-26 22:00:01 +10:00 committed by Randy Mackay
parent 80a4083fc7
commit 2489234fcf

View File

@ -83,7 +83,7 @@ void AP_Mount_Backend::control(int32_t pitch_or_lat, int32_t roll_or_lon, int32_
// update_targets_from_rc - updates angle targets using input from receiver // update_targets_from_rc - updates angle targets using input from receiver
void AP_Mount_Backend::update_targets_from_rc() void AP_Mount_Backend::update_targets_from_rc()
{ {
#define rc_ch(i) RC_Channels::rc_channel(i-1) #define rc_ch(i) rc().channel(i-1)
uint8_t roll_rc_in = _state._roll_rc_in; uint8_t roll_rc_in = _state._roll_rc_in;
uint8_t tilt_rc_in = _state._tilt_rc_in; uint8_t tilt_rc_in = _state._tilt_rc_in;