GCS_MAVLink: check for null comm_port before writing

this was found when adding debug code to write to a specific channel
This commit is contained in:
Andrew Tridgell 2021-08-28 10:54:07 +10:00
parent 8102629dfb
commit dc252aa8f5

View File

@ -90,7 +90,7 @@ uint16_t comm_get_txspace(mavlink_channel_t chan)
*/
void comm_send_buffer(mavlink_channel_t chan, const uint8_t *buf, uint8_t len)
{
if (!valid_channel(chan)) {
if (!valid_channel(chan) || mavlink_comm_port[chan] == nullptr) {
return;
}
if (gcs_alternative_active[chan]) {