AP_Networking: fix memory error generated by CAN mcast driver

This commit is contained in:
bugobliterator 2024-12-18 17:42:30 +11:00 committed by Peter Barker
parent 300e5ccedd
commit 42e2e23464

View File

@ -182,7 +182,11 @@ void AP_Networking_CAN::mcast_server(void)
const uint16_t timeout_us = 2000;
while (frame_buffers[bus]->peek(frame)) {
auto retcode = get_caniface(bus)->send(frame,
auto *cbus = get_caniface(bus);
if (cbus == nullptr) {
break;
}
auto retcode = cbus->send(frame,
AP_HAL::micros64() + timeout_us,
AP_HAL::CANIface::IsMAVCAN);
if (retcode == 0) {