HAL_ChibiOS: allow for MCAST UDP with no CAN link

this allows the CAN interface to operate without a CAN cable, allowing
for bridging of MCAST UDP CAN
This commit is contained in:
Andrew Tridgell 2024-09-08 12:37:52 +10:00
parent db18d37ed2
commit 05d43fd00b
2 changed files with 24 additions and 0 deletions

View File

@ -379,6 +379,17 @@ int16_t CANIface::send(const AP_HAL::CANFrame& frame, uint64_t tx_deadline,
if ((can_->TXFQS & FDCAN_TXFQS_TFQF) != 0) {
stats.tx_overflow++;
if (stats.tx_success == 0) {
/*
if we have never successfully transmitted a frame
then we may be operating with just MAVCAN or UDP
MCAST. Consider the frame sent if the send
succeeds. This allows for UDP MCAST and MAVCAN to
operate fully when the CAN bus has no cable plugged
in
*/
return AP_HAL::CANIface::send(frame, tx_deadline, flags);
}
return 0; //we don't have free space
}
index = ((can_->TXFQS & FDCAN_TXFQS_TFQPI) >> FDCAN_TXFQS_TFQPI_Pos);

View File

@ -325,6 +325,19 @@ int16_t CANIface::send(const AP_HAL::CANFrame& frame, uint64_t tx_deadline,
txmailbox = 2;
} else {
PERF_STATS(stats.tx_overflow);
#if !defined(HAL_BOOTLOADER_BUILD)
if (stats.tx_success == 0) {
/*
if we have never successfully transmitted a frame
then we may be operating with just MAVCAN or UDP
MCAST. Consider the frame sent if the send
succeeds. This allows for UDP MCAST and MAVCAN to
operate fully when the CAN bus has no cable plugged
in
*/
return AP_HAL::CANIface::send(frame, tx_deadline, flags);
}
#endif
return 0; // No transmission for you.
}