Browse Source

GCS_MAVLink: allow use of RC_CHANNELS message on AVR too

can have up to 11 channels
mission-4.1.18
Andrew Tridgell 10 years ago
parent
commit
7a5ec6d75b
  1. 2
      libraries/GCS_MAVLink/GCS_Common.cpp

2
libraries/GCS_MAVLink/GCS_Common.cpp

@ -1015,7 +1015,6 @@ void GCS_MAVLINK::send_radio_in(uint8_t receiver_rssi) @@ -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) @@ -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)

Loading…
Cancel
Save