mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP_DroneCAN: fixed queue ordering bug in sending DroneCAN frames
this caused RTK RTCM data to be corrupted on send
This commit is contained in:
parent
0cfd9c2ed5
commit
dc8366c31e
@ -197,7 +197,12 @@ void CanardInterface::processTx(bool raw_commands_only = false) {
|
||||
bool write = true;
|
||||
bool read = false;
|
||||
ifaces[iface]->select(read, write, &txmsg, 0);
|
||||
if ((AP_HAL::native_micros64() < txf->deadline_usec) && (txf->iface_mask & (1U<<iface)) && write) {
|
||||
if (!write) {
|
||||
// if there is no space then we need to start from the
|
||||
// top of the queue, so wait for the next loop
|
||||
break;
|
||||
}
|
||||
if ((txf->iface_mask & (1U<<iface)) && (AP_HAL::native_micros64() < txf->deadline_usec)) {
|
||||
// try sending to interfaces, clearing the mask if we succeed
|
||||
if (ifaces[iface]->send(txmsg, txf->deadline_usec, 0) > 0) {
|
||||
txf->iface_mask &= ~(1U<<iface);
|
||||
|
Loading…
Reference in New Issue
Block a user