mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
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:
parent
8102629dfb
commit
dc252aa8f5
@ -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]) {
|
||||
|
Loading…
Reference in New Issue
Block a user