Copter: support 18 input channels in MAVLink

This commit is contained in:
Andrew Tridgell 2014-03-25 14:44:59 +11:00
parent 4ac529a0dd
commit 78ba1a33aa
1 changed files with 26 additions and 0 deletions

View File

@ -427,6 +427,32 @@ static void NOINLINE send_radio_in(mavlink_channel_t chan)
g.rc_7.radio_in,
g.rc_8.radio_in,
receiver_rssi);
if (hal.rcin->num_channels() > 8 &&
comm_get_txspace(chan) - MAVLINK_NUM_NON_PAYLOAD_BYTES >= MAVLINK_MSG_ID_RC_CHANNELS_LEN) {
mavlink_msg_rc_channels_send(
chan,
millis(),
hal.rcin->num_channels(),
hal.rcin->read(CH_1),
hal.rcin->read(CH_2),
hal.rcin->read(CH_3),
hal.rcin->read(CH_4),
hal.rcin->read(CH_5),
hal.rcin->read(CH_6),
hal.rcin->read(CH_7),
hal.rcin->read(CH_8),
hal.rcin->read(CH_9),
hal.rcin->read(CH_10),
hal.rcin->read(CH_11),
hal.rcin->read(CH_12),
hal.rcin->read(CH_13),
hal.rcin->read(CH_14),
hal.rcin->read(CH_15),
hal.rcin->read(CH_16),
hal.rcin->read(CH_17),
hal.rcin->read(CH_18),
receiver_rssi);
}
}
static void NOINLINE send_radio_out(mavlink_channel_t chan)