GCS_MAVLink: add nullptr check in gcs_out_of_space_to_send
If a library were to send on a channel for which we have not allocated a GCS_MAVLINK this could lead to a nullptr dereference. We do some odd things in uAvionix in terms of which channel to send on, so worth a check.
This commit is contained in:
parent
26d714e9a9
commit
74978ac577
@ -355,7 +355,11 @@ bool GCS::out_of_time() const
|
||||
|
||||
void gcs_out_of_space_to_send(mavlink_channel_t chan)
|
||||
{
|
||||
gcs().chan(chan)->out_of_space_to_send();
|
||||
GCS_MAVLINK *link = gcs().chan(chan);
|
||||
if (link == nullptr) {
|
||||
return;
|
||||
}
|
||||
link->out_of_space_to_send();
|
||||
}
|
||||
|
||||
/*
|
||||
|
Loading…
Reference in New Issue
Block a user