From 6e9e9dcdfab0114b7c1d67e92475fe363c889575 Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Tue, 3 Apr 2018 19:19:44 -0700 Subject: [PATCH] GCS_MAVlink: Use RC_Channels instead of hal.rcin --- libraries/GCS_MAVLink/GCS_Common.cpp | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index eb2c23c61d..3a6877f1be 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -957,8 +957,7 @@ void GCS_MAVLINK::send_radio_in(uint8_t receiver_rssi) mavlink_status_t *status = mavlink_get_channel_status(chan); uint16_t values[18]; - memset(values, 0, sizeof(values)); - hal.rcin->read(values, 18); + RC_Channels::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 @@ -983,7 +982,7 @@ void GCS_MAVLINK::send_radio_in(uint8_t receiver_rssi) mavlink_msg_rc_channels_send( chan, now, - hal.rcin->num_channels(), + RC_Channels::get_valid_channel_count(), values[0], values[1], values[2], @@ -1715,7 +1714,7 @@ MAV_RESULT GCS_MAVLINK::handle_rc_bind(const mavlink_command_long_t &packet) // initiate bind procedure. We accept the DSM type from either // param1 or param2 due to a past mixup with what parameter is the // right one - if (!hal.rcin->rc_bind(packet.param2>0?packet.param2:packet.param1)) { + if (!RC_Channels::receiver_bind(packet.param2>0?packet.param2:packet.param1)) { return MAV_RESULT_FAILED; } return MAV_RESULT_ACCEPTED;