mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
HAL_ChibiOS: removed wait on CAN peripheral in H7
these wait busy loops can take a very long time, and end up causing interrupts to be lost elsewhere in the system, causing lost bytes on UARTs We should not have while loops waiting on peripharals like this. If we do need to wait for a flag to clear then it needs to be done in a low priority thread, or we need to check for completion in a timer CAN still seems to work with this change, but needs flight testing
This commit is contained in:
parent
d017a9a60d
commit
0ec6210184
@ -721,8 +721,6 @@ void CanIface::pollErrorFlagsFromISR()
|
||||
if (((1 << pending_tx_[i].index) & can_->TXBRP)) {
|
||||
can_->TXBCR = 1 << pending_tx_[i].index; // Goodnight sweet transmission
|
||||
error_cnt_++;
|
||||
//Wait for Cancelation to finish
|
||||
while (!(can_->TXBCF & (1 << pending_tx_[i].index))) {}
|
||||
served_aborts_cnt_++;
|
||||
}
|
||||
}
|
||||
@ -736,8 +734,6 @@ void CanIface::discardTimedOutTxMailboxes(uavcan::MonotonicTime current_time)
|
||||
if (((1 << pending_tx_[i].index) & can_->TXBRP) && pending_tx_[i].deadline < current_time) {
|
||||
can_->TXBCR = 1 << pending_tx_[i].index; // Goodnight sweet transmission
|
||||
error_cnt_++;
|
||||
//Wait for Cancelation to finish
|
||||
while (!(can_->TXBCF & (1 << pending_tx_[i].index))) {}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user