AP_DroneCAN: properly convert timeout to deadline for aux frames

The timeout specified for auxiliary driver frames was passed to the
driver where a deadline was expected. The transmission was then started
after its "deadline", thereby causing it to be canceled and the data
lost if the frame could not be sent immediately.

Fix by converting the timeout to a deadline before passing to the
driver. The conversion is done in the Canard interface code as it
already does other conversions from timeouts to deadlines.
This commit is contained in:
Thomas Watson 2024-10-04 14:26:53 -05:00 committed by Andrew Tridgell
parent 47d391fc6d
commit e9e7eba799
1 changed files with 2 additions and 1 deletions

View File

@ -458,12 +458,13 @@ bool CanardInterface::add_11bit_driver(CANSensor *sensor)
// handler for outgoing frames for auxillary drivers
bool CanardInterface::write_aux_frame(AP_HAL::CANFrame &out_frame, const uint64_t timeout_us)
{
const uint64_t tx_deadline_us = AP_HAL::micros64() + timeout_us;
bool ret = false;
for (uint8_t iface = 0; iface < num_ifaces; iface++) {
if (ifaces[iface] == NULL) {
continue;
}
ret |= ifaces[iface]->send(out_frame, timeout_us, 0) > 0;
ret |= ifaces[iface]->send(out_frame, tx_deadline_us, 0) > 0;
}
return ret;
}