mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
AP_Networking: fix memory error generated by CAN mcast driver
This commit is contained in:
parent
300e5ccedd
commit
42e2e23464
@ -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) {
|
||||
|
Loading…
Reference in New Issue
Block a user