mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_DroneCAN: don't hold semaphore during CAN send
this mirrors the changes in the networking code, and ensures we don't hold a semaphore that may be held by the main thread when we are doing CAN sends
This commit is contained in:
parent
2ba3ac0a9e
commit
77fbe1dcfb
@ -74,6 +74,9 @@ void AP_DroneCAN_Serial::update(void)
|
||||
if (p.writebuffer == nullptr || p.node <= 0 || p.idx < 0) {
|
||||
continue;
|
||||
}
|
||||
uavcan_tunnel_Targetted pkt {};
|
||||
uint32_t n = 0;
|
||||
{
|
||||
WITH_SEMAPHORE(p.sem);
|
||||
uint32_t avail;
|
||||
const bool send_keepalive = now_ms - p.last_send_ms > 500;
|
||||
@ -81,8 +84,7 @@ void AP_DroneCAN_Serial::update(void)
|
||||
if (!send_keepalive && (ptr == nullptr || avail <= 0)) {
|
||||
continue;
|
||||
}
|
||||
uavcan_tunnel_Targetted pkt {};
|
||||
auto n = MIN(avail, sizeof(pkt.buffer.data));
|
||||
n = MIN(avail, sizeof(pkt.buffer.data));
|
||||
pkt.target_node = p.node;
|
||||
pkt.protocol.protocol = UAVCAN_TUNNEL_PROTOCOL_UNDEFINED;
|
||||
pkt.buffer.len = n;
|
||||
@ -92,8 +94,9 @@ void AP_DroneCAN_Serial::update(void)
|
||||
if (ptr != nullptr) {
|
||||
memcpy(pkt.buffer.data, ptr, n);
|
||||
}
|
||||
|
||||
}
|
||||
if (targetted->broadcast(pkt)) {
|
||||
WITH_SEMAPHORE(p.sem);
|
||||
p.writebuffer->advance(n);
|
||||
p.last_send_ms = now_ms;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user