Browse Source

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
master
Andrew Tridgell 5 years ago
parent
commit
555f56a8af
  1. 4
      libraries/AP_HAL_ChibiOS/CANFDIface.cpp

4
libraries/AP_HAL_ChibiOS/CANFDIface.cpp

@ -721,8 +721,6 @@ void CanIface::pollErrorFlagsFromISR() @@ -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) @@ -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…
Cancel
Save