mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
GCS_MAVLink: allow use of RC_CHANNELS message on AVR too
can have up to 11 channels
This commit is contained in:
parent
33a3254d8b
commit
7a5ec6d75b
@ -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)
|
||||
|
Loading…
Reference in New Issue
Block a user