mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 18:48:30 -04:00
HAL_ChibiOS: fixed tx_len on tx DMA timeout
This commit is contained in:
parent
8431a677d9
commit
e3b68876a9
@ -955,15 +955,15 @@ void RCOutput::send_pulses_DMAR(pwm_group &group, uint32_t buffer_length)
|
||||
void RCOutput::dma_irq_callback(void *p, uint32_t flags)
|
||||
{
|
||||
pwm_group *group = (pwm_group *)p;
|
||||
chSysLockFromISR();
|
||||
dmaStreamDisable(group->dma);
|
||||
if (group->in_serial_dma && irq.waiter) {
|
||||
// tell the waiting process we've done the DMA
|
||||
chSysLockFromISR();
|
||||
chEvtSignalI(irq.waiter, serial_event_mask);
|
||||
chSysUnlockFromISR();
|
||||
} else {
|
||||
group->dma_handle->unlock_from_IRQ();
|
||||
}
|
||||
chSysUnlockFromISR();
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -324,22 +324,20 @@ void UARTDriver::dma_tx_deallocate(Shared_DMA *ctx)
|
||||
void UARTDriver::tx_complete(void* self, uint32_t flags)
|
||||
{
|
||||
UARTDriver* uart_drv = (UARTDriver*)self;
|
||||
chSysLockFromISR();
|
||||
if (!uart_drv->tx_bounce_buf_ready) {
|
||||
// reset timeout
|
||||
chSysLockFromISR();
|
||||
chVTResetI(&uart_drv->tx_timeout);
|
||||
chSysUnlockFromISR();
|
||||
|
||||
uart_drv->_last_write_completed_us = AP_HAL::micros();
|
||||
uart_drv->tx_bounce_buf_ready = true;
|
||||
if (uart_drv->unbuffered_writes && uart_drv->_writebuf.available()) {
|
||||
// trigger a rapid send of next bytes
|
||||
chSysLockFromISR();
|
||||
chEvtSignalI(uart_thread_ctx, EVENT_MASK(uart_drv->serial_num));
|
||||
chSysUnlockFromISR();
|
||||
}
|
||||
uart_drv->dma_handle->unlock_from_IRQ();
|
||||
}
|
||||
chSysUnlockFromISR();
|
||||
}
|
||||
|
||||
|
||||
@ -375,7 +373,7 @@ void UARTDriver::rxbuff_full_irq(void* self, uint32_t flags)
|
||||
if (!uart_drv->sdef.dma_rx) {
|
||||
return;
|
||||
}
|
||||
uint8_t len = RX_BOUNCE_BUFSIZE - uart_drv->rxdma->stream->NDTR;
|
||||
uint8_t len = RX_BOUNCE_BUFSIZE - dmaStreamGetTransactionSize(uart_drv->rxdma);
|
||||
if (len == 0) {
|
||||
return;
|
||||
}
|
||||
@ -605,7 +603,7 @@ void UARTDriver::check_dma_tx_completion(void)
|
||||
chSysLock();
|
||||
if (!tx_bounce_buf_ready) {
|
||||
if (!(txdma->stream->CR & STM32_DMA_CR_EN)) {
|
||||
if (txdma->stream->NDTR == 0) {
|
||||
if (dmaStreamGetTransactionSize(txdma) == 0) {
|
||||
tx_bounce_buf_ready = true;
|
||||
_last_write_completed_us = AP_HAL::micros();
|
||||
chVTResetI(&tx_timeout);
|
||||
@ -623,12 +621,14 @@ void UARTDriver::check_dma_tx_completion(void)
|
||||
void UARTDriver::handle_tx_timeout(void *arg)
|
||||
{
|
||||
UARTDriver* uart_drv = (UARTDriver*)arg;
|
||||
chSysLockFromISR();
|
||||
if (!uart_drv->tx_bounce_buf_ready) {
|
||||
uart_drv->tx_len = 0; // fix for n sent
|
||||
dmaStreamDisable(uart_drv->txdma);
|
||||
uart_drv->tx_len -= dmaStreamGetTransactionSize(uart_drv->txdma);
|
||||
uart_drv->tx_bounce_buf_ready = true;
|
||||
uart_drv->dma_handle->unlock_from_IRQ();
|
||||
}
|
||||
chSysUnlockFromISR();
|
||||
}
|
||||
|
||||
/*
|
||||
@ -767,7 +767,7 @@ void UARTDriver::_timer_tick(void)
|
||||
//if not, it might be because the DMA interrupt was silenced
|
||||
//let's handle that here so that we can continue receiving
|
||||
if (!(rxdma->stream->CR & STM32_DMA_CR_EN)) {
|
||||
uint8_t len = RX_BOUNCE_BUFSIZE - rxdma->stream->NDTR;
|
||||
uint8_t len = RX_BOUNCE_BUFSIZE - dmaStreamGetTransactionSize(rxdma);
|
||||
if (len != 0) {
|
||||
_readbuf.write(rx_bounce_buf, len);
|
||||
|
||||
|
@ -164,7 +164,6 @@ void Shared_DMA::unlock_from_lockzone(void)
|
||||
void Shared_DMA::unlock_from_IRQ(void)
|
||||
{
|
||||
osalDbgAssert(have_lock, "must have lock");
|
||||
chSysLockFromISR();
|
||||
if (stream_id2 != SHARED_DMA_NONE) {
|
||||
chBSemSignalI(&locks[stream_id2].semaphore);
|
||||
}
|
||||
@ -172,7 +171,6 @@ void Shared_DMA::unlock_from_IRQ(void)
|
||||
chBSemSignalI(&locks[stream_id1].semaphore);
|
||||
}
|
||||
have_lock = false;
|
||||
chSysUnlockFromISR();
|
||||
}
|
||||
|
||||
/*
|
||||
|
Loading…
Reference in New Issue
Block a user