AP_DroneCAN: move tx frame to loop context

prevent contents from previous frame being used
This commit is contained in:
Andrew Tridgell 2023-06-07 14:50:41 +10:00
parent e1dd452b66
commit f0a0a4cfa9
1 changed files with 1 additions and 1 deletions

View File

@ -174,7 +174,6 @@ void CanardInterface::processTx(bool raw_commands_only = false) {
if (txq == nullptr) {
return;
}
AP_HAL::CANFrame txmsg {};
// scan through list of pending transfers
while (true) {
auto txf = &txq->frame;
@ -188,6 +187,7 @@ void CanardInterface::processTx(bool raw_commands_only = false) {
}
continue;
}
AP_HAL::CANFrame txmsg {};
txmsg.dlc = AP_HAL::CANFrame::dataLengthToDlc(txf->data_len);
memcpy(txmsg.data, txf->data, txf->data_len);
txmsg.id = (txf->id | AP_HAL::CANFrame::FlagEFF);