Skip to content

Commit

Permalink
imx9/px4io: Cleanups
Browse files Browse the repository at this point in the history
- Stop also tx dma in the interrupt / short packet receive
- No need to clear the uart errors in _stop_dma, errors are cleared in uart irq

Signed-off-by: Jukka Laitinen <[email protected]>
  • Loading branch information
jlaitine committed Sep 30, 2024
1 parent 3d79b88 commit 36bddac
Showing 1 changed file with 6 additions and 12 deletions.
18 changes: 6 additions & 12 deletions platforms/nuttx/src/px4/nxp/imx9/px4io_serial/px4io_serial.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,6 +77,7 @@ ArchPX4IOSerial::~ArchPX4IOSerial()
{
/* Stop any ongoing DMA transfer */

_waiting_for_dma = false;
_stop_dma();

/* Detach our interrupt handler */
Expand Down Expand Up @@ -261,14 +262,15 @@ ArchPX4IOSerial::_bus_exchange(IOPacket *_packet)

ret = nxsem_tickwait_uninterruptible(&_recv_sem, MSEC2TICK(10));

if (ret == -ETIMEDOUT) {
if (ret != OK) {
_waiting_for_dma = false;
_stop_dma();

nxsem_reset(&_recv_sem, 0);
perf_count(_pc_timeouts);
perf_cancel(_pc_txns); /* don't count this as a transaction */
}

if (ret == OK) {
} else {
/* Check packet CRC */

uint8_t crc = _current_packet->crc;
Expand Down Expand Up @@ -348,7 +350,7 @@ ArchPX4IOSerial::_do_interrupt()
* call the callback function. Stopping a non-running dma has no effect.
*/

imx9_dmach_stop(_rx_dma);
_stop_dma();
}

/* count uart errors */
Expand All @@ -361,10 +363,6 @@ ArchPX4IOSerial::_do_interrupt()
void
ArchPX4IOSerial::_stop_dma()
{
/* Mark that we don't care about any DMA data any more */

_waiting_for_dma = false;

/* Stop the DMA channels */

imx9_dmach_stop(_tx_dma);
Expand All @@ -375,8 +373,4 @@ ArchPX4IOSerial::_stop_dma()
while (getreg32(PX4IO_SERIAL_BASE + IMX9_LPUART_STAT_OFFSET) & LPUART_STAT_RDRF) {
getreg32(PX4IO_SERIAL_BASE + IMX9_LPUART_DATA_OFFSET);
}

/* Clear any error status flags */

modreg32(ERR_FLAGS_MASK, ERR_FLAGS_MASK, PX4IO_SERIAL_BASE + IMX9_LPUART_STAT_OFFSET);
}

0 comments on commit 36bddac

Please sign in to comment.