From 7a5ec6d75bc4510719102adbbf1d0d9744e1d5a6 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 8 Feb 2015 17:10:07 +1100 Subject: [PATCH] GCS_MAVLink: allow use of RC_CHANNELS message on AVR too can have up to 11 channels --- libraries/GCS_MAVLink/GCS_Common.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 9475c3a2ce..aa97ed13bf 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -1015,7 +1015,6 @@ void GCS_MAVLINK::send_radio_in(uint8_t receiver_rssi) values[7], receiver_rssi); -#if HAL_CPU_CLASS > HAL_CPU_CLASS_16 if (hal.rcin->num_channels() > 8 && comm_get_txspace(chan) >= MAVLINK_MSG_ID_RC_CHANNELS_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) { mavlink_msg_rc_channels_send( @@ -1042,7 +1041,6 @@ void GCS_MAVLINK::send_radio_in(uint8_t receiver_rssi) hal.rcin->read(CH_18), receiver_rssi); } -#endif } void GCS_MAVLINK::send_raw_imu(const AP_InertialSensor &ins, const Compass &compass)