GCS_MAVLink: use rc() method to get rc singleton

This commit is contained in:
Peter Barker 2018-04-26 22:00:42 +10:00 committed by Randy Mackay
parent f4c93dc697
commit dbccd6a399

View File

@ -1002,8 +1002,8 @@ void GCS_MAVLINK::send_radio_in()
uint32_t now = AP_HAL::millis();
mavlink_status_t *status = mavlink_get_channel_status(chan);
uint16_t values[18];
RC_Channels::get_radio_in(values, 18);
uint16_t values[18] = {};
rc().get_radio_in(values, 18);
if (status && (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1)) {
// for mavlink1 send RC_CHANNELS_RAW, for compatibility with OSD implementations