mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_Periph: detect dead interfaces in CAN transmit logic
when an interface has not managed to send a packet for 2s then no longer consider a failed send a reason to keep the packet in the transmit queue
This commit is contained in:
parent
9afc30671f
commit
5c8a29b47e
@ -1101,7 +1101,8 @@ void AP_Periph_FW::processTx(void)
|
||||
#endif
|
||||
// push message with 1s timeout
|
||||
bool sent = true;
|
||||
const uint64_t deadline = AP_HAL::micros64() + 1000000;
|
||||
const uint64_t now_us = AP_HAL::micros64();
|
||||
const uint64_t deadline = now_us + 1000000U;
|
||||
// try sending to all interfaces
|
||||
for (auto &_ins : instances) {
|
||||
if (_ins.iface == NULL) {
|
||||
@ -1118,7 +1119,17 @@ void AP_Periph_FW::processTx(void)
|
||||
}
|
||||
#endif
|
||||
if (_ins.iface->send(txmsg, deadline, 0) <= 0) {
|
||||
sent = false;
|
||||
/*
|
||||
We were not able to queue the frame for
|
||||
sending. Only mark the send as failing if the
|
||||
interface is active. We consider an interface as
|
||||
active if it has had a successful transmit in the
|
||||
last 2 seconds
|
||||
*/
|
||||
const auto *stats = _ins.iface->get_statistics();
|
||||
if (stats == nullptr || now_us - stats->last_transmit_us < 2000000UL) {
|
||||
sent = false;
|
||||
}
|
||||
}
|
||||
}
|
||||
if (sent) {
|
||||
|
Loading…
Reference in New Issue
Block a user