From dbccd6a3999387c2227bd0bc83cf562f275f8d75 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 26 Apr 2018 22:00:42 +1000 Subject: [PATCH] GCS_MAVLink: use rc() method to get rc singleton --- libraries/GCS_MAVLink/GCS_Common.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index b61a680b55..ffce7bdfab 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -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