chen
2024-11-08 cc432b761c884a0bd8e9d83db0a4e26109fc08b1
keil/include/drivers/mk_uart.c
对比新文件
@@ -0,0 +1,941 @@
/*
 * Copyright (c) 2019-2023 Beijing Hanwei Innovation Technology Ltd. Co. and
 * its subsidiaries and affiliates (collectly called MKSEMI).
 *
 * All rights reserved.
 *
 * Redistribution and use in source and binary forms, with or without
 * modification, are permitted provided that the following conditions are met:
 *
 * 1. Redistributions of source code must retain the above copyright notice,
 *    this list of conditions and the following disclaimer.
 *
 * 2. Redistributions in binary form, except as embedded into an MKSEMI
 *    integrated circuit in a product or a software update for such product,
 *    must reproduce the above copyright notice, this list of conditions and
 *    the following disclaimer in the documentation and/or other materials
 *    provided with the distribution.
 *
 * 3. Neither the name of MKSEMI nor the names of its contributors may be used
 *    to endorse or promote products derived from this software without
 *    specific prior written permission.
 *
 * 4. This software, with or without modification, must only be used with a
 *    MKSEMI integrated circuit.
 *
 * 5. Any software provided in binary form under this license must not be
 *    reverse engineered, decompiled, modified and/or disassembled.
 *
 * THIS SOFTWARE IS PROVIDED BY MKSEMI "AS IS" AND ANY EXPRESS OR IMPLIED
 * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
 * MERCHANTABILITY, NONINFRINGEMENT, AND FITNESS FOR A PARTICULAR PURPOSE ARE
 * DISCLAIMED. IN NO EVENT SHALL MKSEMI OR CONTRIBUTORS BE LIABLE FOR ANY
 * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
 * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
 * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
 * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
 * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 */
#include "mk_uart.h"
#include "mk_trace.h"
#include "mk_clock.h"
#include "mk_reset.h"
#include "mk_dma.h"
#include "mk_misc.h"
static struct UART_HANDLE_T uart_handle[UART_MAX_NUM] = {
    {
        .base = UART0,
        .irq = UART0_IRQn,
        .dma_rx_ch = DMA_CH4,
        .dma_tx_ch = DMA_CH5,
    },
    {
        .base = UART1,
        .irq = UART1_IRQn,
        .dma_rx_ch = DMA_CH6,
        .dma_tx_ch = DMA_CH7,
    },
};
//脪脝脰虏
uint32_t SerialKeyPressed(uint8_t *key)//脜脨露脧脢媒戮脻脢脟路帽脢脮碌陆碌脛 MK8000脨脼赂脛
{
    uint32_t status = uart_handle[1].base->STATUS;
    if (status & UART_STATUS_DR_MSK)
    {
        //Serial0PutString("鲁脡鹿娄陆脫脢脮ing");
        //uart_receive(UART_ID1,test_buf,10,NULL);
        *key = (uint8_t)uart_handle[1].base->RX_DATA;
        //uart_rx_fifo_clear(UART_ID1);
        return 1;
    }
    else
    {
        return 0;
    }
}
void SerialPutChar(uint8_t c)
{
    while (uart_handle[0].base->TX_FL)
    {
    }
    uart_send(UART_ID1, &c, 1, NULL);
}
void Serial_PutString(uint8_t *s)
{
    while (*s != '\0')
    {
        SerialPutChar(*s);
        s++;
    }
}
void Serial0PutChar(uint8_t c)
{   //脜脨露脧脢媒戮脻禄潞麓忙脟酶脦陋驴脮录麓脡脧脪禄赂枚脳脰陆脷脢媒戮脻脪脩戮颅卤禄脣脥碌陆路垄脣脥录脛麓忙脝梅路垄脣脥鲁枚脠楼脕脣
    // wait TX FIFO empty
    while (uart_handle[0].base->TX_FL)
    {
    }
    uart_send(UART_ID0, &c, 1, NULL);
}
void Serial0_PutString(uint8_t *s)
{
    while (*s != '\0')
    {
        Serial0PutChar(*s);
        s++;
    }
}
static const struct UART_DIVISOR_T baud_table[] = {
    {89, 6, 32},  // 1200
    {20, 3, 33},  // 2400
    {69, 1, 40},  // 4800
    {130, 0, 50}, // 9600
    {65, 0, 50},  // 19200
    {25, 0, 65},  // 38400
    {19, 0, 57},  // 57600     --  0.03%
    {3, 0, 181},  // 115200    -- -0.25%
    {6, 0, 45},   // 230400    --  0.31%
    {3, 0, 45},   // 460800    --  0.31%
    {2, 0, 34},   // 921600    -- -0.43%
    {1, 0, 34},   // 1843200   -- -0.43%
    {1, 0, 62},   // 1000000   -- -0.65%
    {1, 0, 32},   // 2000000   -- -2.5%
};
#if UART_DMA_MODE_EN
static void uart_dma_callback(void *ch, uint32_t err_code);
static void uart_dma_abort_callback(void *ch, uint32_t err_code);
#endif
static int uart_state_set(enum UART_DEV_T id, enum UART_STATE_T state)
{
    int ret = DRV_OK;
    uint32_t lock = int_lock();
    // update state
    switch (uart_handle[id].state)
    {
    case UART_STATE_READY:
        uart_handle[id].state = state;
        break;
    case UART_STATE_BUSY_RX:
        if (state == UART_STATE_BUSY_TX)
        {
            uart_handle[id].state = UART_STATE_BUSY_TX_RX;
        }
        else
        {
            ret = DRV_BUSY;
        }
        break;
    case UART_STATE_BUSY_TX:
        if (state == UART_STATE_BUSY_RX)
        {
            uart_handle[id].state = UART_STATE_BUSY_TX_RX;
        }
        else
        {
            ret = DRV_BUSY;
        }
        break;
    case UART_STATE_BUSY_TX_RX:
        ret = DRV_BUSY;
        break;
    case UART_STATE_RESET:
    case UART_STATE_TIMEOUT:
    case UART_STATE_ERROR:
        ret = DRV_ERROR;
        break;
    }
    int_unlock(lock);
    return ret;
}
static void uart_state_clear(enum UART_DEV_T id, enum UART_STATE_T state)
{
    uint32_t lock = int_lock();
    // update state
    uart_handle[id].state &= ~state;
    if (uart_handle[id].state == 0)
    {
        uart_handle[id].state = UART_STATE_READY;
    }
    int_unlock(lock);
}
enum UART_STATE_T uart_state_get(enum UART_DEV_T id)
{
    return uart_handle[id].state;
}
bool uart_tx_in_progress(enum UART_DEV_T id)
{
    return ((uart_handle[id].state & UART_STATE_BUSY_TX) && (uart_handle[id].base->STATUS & UART_STATUS_BUSY_MSK));
}
bool uart_fifo_busy(enum UART_DEV_T id)
{
    // UART is not enabled but RX is pulled low
    return ((uart_handle[id].state != UART_STATE_RESET) && (uart_handle[id].base->STATUS & UART_STATUS_BUSY_MSK));
}
void uart_rx_fifo_clear(enum UART_DEV_T id)
{
    // clear FIFO
    while (uart_handle[id].base->STATUS & UART_STATUS_RFNE_MSK)
    {
        uart_handle[id].base->RX_DATA;
    }
}
void uart_baud_set(enum UART_DEV_T id, enum UART_BAUD_T baud)
{
    ASSERT((id < UART_MAX_NUM) && (baud < BAUD_MAX), "Paramter invalid");
    // fraction
    clock_set_divider(id > 0 ? CLOCK_UART1_FDIV : CLOCK_UART0_FDIV, baud_table[baud].fraction);
    // set DLAB to access DLL and DLH registers
    uint32_t reg = uart_handle[id].base->CTRL1 | UART_CTRL1_DLAB_MSK;
    uart_handle[id].base->CTRL1 = reg;
    uint32_t dl = UART_DIVISOR_H(baud_table[baud].dlh) + baud_table[baud].dll;
    uart_handle[id].base->DIVISOR = dl;
    // clear DLAB
    reg &= (uint32_t)~UART_CTRL1_DLAB_MSK;
    uart_handle[id].base->CTRL1 = reg;
    // need to wait at least x cycles after the baud rate is set where
    // x = 32 * uart_divisor.  Assuming here that the uart clock is ~2
    // times slower than the processor clock.
    delay_us(dl);
}
int uart_open(enum UART_DEV_T id, struct UART_CFG_T *config)
{
    if ((id >= UART_MAX_NUM) && (config == NULL))
    {
        return DRV_ERROR;
    }
    else if (id == UART_ID0)
    {
        // enable UART0 clock
        clock_enable(CLOCK_UART0);
        reset_module(RESET_MODULE_UART0);
    }
    else if (id == UART_ID1)
    {
        // enable UART1 clock
        clock_enable(CLOCK_UART1);
        reset_module(RESET_MODULE_UART1);
    }
    // disable all uart interrupts
    uart_handle[id].base->INTR_EN &= ~UART_INTR_EN_ALL_MSK;
    // reset FIFO
    uart_handle[id].base->CTRL0 = UART_CTRL0_RX_FIFO_RESET_MSK | UART_CTRL0_TX_FIFO_RESET_MSK;
    // clear STATUS
    uart_handle[id].base->INTR_CLR =
        UART_INTR_CLR_THRE_INT_CLR_MSK | UART_INTR_CLR_BUSY_INT_CLR_MSK | UART_INTR_CLR_LSR_INT_CLR_MSK | UART_INTR_CLR_MSR_INT_CLR_MSK;
    // reset device handle
    uart_handle[id].tx_buff = NULL;
    uart_handle[id].tx_callback = NULL;
    uart_handle[id].tx_count = 0;
    uart_handle[id].tx_size = 0;
    uart_handle[id].rx_buff = NULL;
    uart_handle[id].rx_callback = NULL;
    uart_handle[id].rx_count = 0;
    uart_handle[id].rx_size = 0;
    uart_handle[id].dma_en = config->dma_en;
    uart_handle[id].int_rx = config->int_rx;
    uart_handle[id].int_tx = config->int_tx;
    // line settings
    uint32_t reg = (uint32_t)config->data | (uint32_t)(config->stop << UART_CTRL1_STOP_POS);
    if (config->parity == UART_PARITY_ODD)
    {
        reg |= (UART_CTRL1_PARITY_EN_MSK);
    }
    else if (config->parity == UART_PARITY_EVEN)
    {
        reg |= (UART_CTRL1_PARITY_EN_MSK | UART_CTRL1_EVEN_PARITY_MSK);
    }
    else if (config->parity == UART_PARITY_FORCE1)
    {
        reg |= (UART_CTRL1_PARITY_EN_MSK | UART_CTRL1_STICK_PARITY_MSK);
    }
    else if (config->parity == UART_PARITY_FORCE0)
    {
        reg |= (UART_CTRL1_PARITY_EN_MSK | UART_CTRL1_EVEN_PARITY_MSK | UART_CTRL1_STICK_PARITY_MSK);
    }
    uart_handle[id].base->CTRL1 = reg;
    // FIFO configure and enable
    reg = UART_CTRL0_RX_TRIGGER(config->rx_level) | UART_CTRL0_TX_TRIGGER(config->tx_level) | UART_CTRL0_DMA_MODE(uart_handle[id].dma_en) |
          UART_CTRL0_FIFO_ENABLE_MSK;
    uart_handle[id].base->CTRL0 = reg;
    uart_handle[id].ctrl0 = reg;
    if (config->flow == UART_FLOW_CONTROL_AUTO)
    {
        uart_handle[id].base->CTRL2 = UART_CTRL2_FLOW_CTRL_EN_MSK | UART_CTRL2_RTS_MSK;
    }
    // baud rate
    uart_baud_set(id, config->baud);
#if UART_INT_MODE_EN || UART_DMA_MODE_EN
    // enable IRQ
    if ((uart_handle[id].int_tx) || (uart_handle[id].int_rx) || (uart_handle[id].dma_en))
    {
        NVIC_SetPriority(uart_handle[id].irq, IRQ_PRIORITY_NORMAL);
        NVIC_ClearPendingIRQ(uart_handle[id].irq);
        NVIC_EnableIRQ(uart_handle[id].irq);
    }
#endif
    uart_handle[id].state = UART_STATE_READY;
    return DRV_OK;
}
int uart_close(enum UART_DEV_T id)
{
    if (id >= UART_MAX_NUM)
    {
        return DRV_ERROR;
    }
    // disable all uart interrupts
    uart_handle[id].base->INTR_EN &= ~UART_INTR_EN_ALL_MSK;
    // reset FIFO
    uart_handle[id].base->CTRL0 = UART_CTRL0_RX_FIFO_RESET_MSK | UART_CTRL0_TX_FIFO_RESET_MSK;
    // clear STATUS
    uart_handle[id].base->INTR_CLR =
        UART_INTR_CLR_THRE_INT_CLR_MSK | UART_INTR_CLR_BUSY_INT_CLR_MSK | UART_INTR_CLR_LSR_INT_CLR_MSK | UART_INTR_CLR_MSR_INT_CLR_MSK;
#if UART_INT_MODE_EN || UART_DMA_MODE_EN
    if ((uart_handle[id].int_tx) || (uart_handle[id].int_rx) || (uart_handle[id].dma_en))
    {
        NVIC_DisableIRQ(uart_handle[id].irq);
        NVIC_ClearPendingIRQ(uart_handle[id].irq);
    }
#endif
    if (id == UART_ID0)
    {
        // disable UART0 clock
        clock_disable(CLOCK_UART0);
    }
    else if (id == UART_ID1)
    {
        // disable UART1 clock
        clock_disable(CLOCK_UART1);
    }
    uart_handle[id].state = UART_STATE_RESET;
    return DRV_OK;
}
#if defined(__GNUC__)
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wcast-qual"
#endif
int uart_send(enum UART_DEV_T id, uint8_t *tx_buf, uint32_t len, drv_callback_t callback)
{
    if ((tx_buf == 0) || (len == 0))
    {
        return DRV_ERROR;
    }
    // update state
    int ret = uart_state_set(id, UART_STATE_BUSY_TX);
    if (ret != DRV_OK)
    {
        return ret;
    }
    uart_handle[id].tx_buff = tx_buf;
    uart_handle[id].tx_count = 0;
    uart_handle[id].tx_size = len;
    uart_handle[id].tx_callback = callback;
    if (uart_handle[id].dma_en)
    {
#if UART_DMA_MODE_EN
        struct DMA_CH_CFG_T uart_tx_dma_cfg = {
            .fifo_th = DMA_FIFO_TH_1,
            .src_burst_size = DMA_SRC_BURST_SIZE_1,
            .src_width = DMA_WIDTH_1B,
            .dst_width = DMA_WIDTH_1B,
            .src_addr_ctrl = DMA_ADDR_INC,
            .dst_addr_ctrl = DMA_ADDR_FIXED,
            .src_req_sel = DMA_REQ_MEM,
            .dst_req_sel = (id == UART_ID1 ? DMA_REQ_UART1_TX : DMA_REQ_UART0_TX),
        };
        dma_open(uart_handle[id].dma_tx_ch, &uart_tx_dma_cfg);
        dma_transfer(uart_handle[id].dma_tx_ch, tx_buf, (uint8_t *)&uart_handle[id].base->TX_DATA, len, uart_dma_callback);
#endif
    }
    else if (uart_handle[id].int_tx)
    {
#if UART_INT_MODE_EN
        // write data to FIFO
        while ((uart_handle[id].tx_count < uart_handle[id].tx_size) && (uart_handle[id].base->STATUS & UART_STATUS_TFNF_MSK))
        {
            uart_handle[id].base->TX_DATA = uart_handle[id].tx_buff[uart_handle[id].tx_count++];
        }
        // enable interrupts
        uart_handle[id].base->INTR_EN |= (UART_INTR_EN_PTIME_MSK | UART_INTR_EN_ETBEI_MSK);
#endif
    }
    else
    {
#if UART_POLL_MODE_EN
        // disable PTIME
        uint32_t reg = uart_handle[id].base->INTR_EN;
        if (reg & UART_INTR_EN_PTIME_MSK)
        {
            uart_handle[id].base->INTR_EN = reg & ~UART_INTR_EN_PTIME_MSK;
        }
        // polling
        uint32_t status = 0U;
        while (uart_handle[id].tx_count < uart_handle[id].tx_size)
        {
            status = uart_handle[id].base->STATUS;
            if (status & (UART_STATUS_OE_MSK | UART_STATUS_PE_MSK | UART_STATUS_FE_MSK | UART_STATUS_BI_MSK | UART_STATUS_RFE_MSK))
            {
                // TODO: user handle the error case
                uart_handle[id].base->INTR_CLR = UART_INTR_CLR_LSR_INT_CLR_MSK;
                status |= UART_ERR_LINE;
                ret = DRV_ERROR;
                break;
            }
            if (uart_handle[id].base->STATUS & UART_STATUS_TFNF_MSK)
            {
                uart_handle[id].base->TX_DATA = uart_handle[id].tx_buff[uart_handle[id].tx_count++];
            }
        }
        // wait TX FIFO empty
        while (uart_handle[id].base->TX_FL)
        {
        }
        // update state
        uart_state_clear(id, UART_STATE_BUSY_TX);
        if (uart_handle[id].tx_callback)
        {
            uart_handle[id].tx_callback(&id, status);
        }
#endif
    }
    return ret;
}
int uart_receive(enum UART_DEV_T id, uint8_t *rx_buf, uint32_t len, drv_callback_t callback)
{
    if ((rx_buf == 0) || (len == 0))
    {
        return DRV_ERROR;
    }
    // update state
    int ret = uart_state_set(id, UART_STATE_BUSY_RX);
    if (ret != DRV_OK)
    {
        return ret;
    }
    uart_handle[id].rx_buff = rx_buf;
    uart_handle[id].rx_count = 0;
    uart_handle[id].rx_size = len;
    uart_handle[id].rx_callback = callback;
    // fix TX output low level when host MCU reset
    uint32_t err_code = uart_handle[id].base->STATUS;
    if (err_code & (UART_STATUS_FE_MSK | UART_STATUS_BI_MSK | UART_STATUS_RFE_MSK))
    {
        // reset FIFO
        uart_handle[id].base->CTRL0 = UART_CTRL0_RX_FIFO_RESET_MSK | UART_CTRL0_TX_FIFO_RESET_MSK;
        // clear STATUS
        uart_handle[id].base->INTR_CLR =
            UART_INTR_CLR_THRE_INT_CLR_MSK | UART_INTR_CLR_BUSY_INT_CLR_MSK | UART_INTR_CLR_LSR_INT_CLR_MSK | UART_INTR_CLR_MSR_INT_CLR_MSK;
        uart_handle[id].base->CTRL0 = uart_handle[id].ctrl0;
    }
    if (uart_handle[id].dma_en)
    {
#if UART_DMA_MODE_EN
        struct DMA_CH_CFG_T uart_rx_dma_cfg = {
            .fifo_th = DMA_FIFO_TH_1,
            .src_burst_size = DMA_SRC_BURST_SIZE_1,
            .src_width = DMA_WIDTH_1B,
            .dst_width = DMA_WIDTH_1B,
            .src_addr_ctrl = DMA_ADDR_FIXED,
            .dst_addr_ctrl = DMA_ADDR_INC,
            .src_req_sel = (id == UART_ID1 ? DMA_REQ_UART1_RX : DMA_REQ_UART0_RX),
            .dst_req_sel = DMA_REQ_MEM,
        };
        uart_handle[id].dma_rx_err_state = 0;
        NVIC_ClearPendingIRQ(uart_handle[id].irq);
        // Enable Receiver Line Status Interrupt, used to obtain the error interrupt event triggered by the receiver
        uart_handle[id].base->INTR_EN = (UART_INTR_EN_ELCOLR_MSK | UART_INTR_EN_ELSI_MSK);
        dma_open(uart_handle[id].dma_rx_ch, &uart_rx_dma_cfg);
        dma_transfer(uart_handle[id].dma_rx_ch, (uint8_t *)&uart_handle[id].base->RX_DATA, rx_buf, len, uart_dma_callback);
#endif
    }
    else if (uart_handle[id].int_rx)
    {
#if UART_INT_MODE_EN
        // enable interrupts
        uart_handle[id].base->INTR_EN |= (UART_INTR_EN_PTIME_MSK | UART_INTR_EN_ELCOLR_MSK | UART_INTR_EN_ELSI_MSK | UART_INTR_EN_ERBFI_MSK);
#endif
    }
    else
    {
#if UART_POLL_MODE_EN
        // disable PTIME
        uint32_t reg = uart_handle[id].base->INTR_EN;
        if (reg & UART_INTR_EN_PTIME_MSK)
        {
            uart_handle[id].base->INTR_EN = reg & ~UART_INTR_EN_PTIME_MSK;
        }
        uint32_t status = 0U;
        // polling
        while (uart_handle[id].rx_count < uart_handle[id].rx_size)
        {
            status = uart_handle[id].base->STATUS;
            if (status & (UART_STATUS_OE_MSK | UART_STATUS_PE_MSK | UART_STATUS_FE_MSK | UART_STATUS_BI_MSK | UART_STATUS_RFE_MSK))
            {
                // TODO: user handle the error case
                // Clear error bits
                uart_handle[id].base->INTR_CLR = UART_INTR_CLR_LSR_INT_CLR_MSK;
                status |= UART_ERR_LINE;
                ret = DRV_ERROR;
                break;
            }
            if (status & UART_STATUS_DR_MSK)
            {
                uint8_t data = (uint8_t)uart_handle[id].base->RX_DATA;
                uart_handle[id].rx_buff[uart_handle[id].rx_count++] = data;
            }
        }
        // update state
        uart_state_clear(id, UART_STATE_BUSY_RX);
        if (uart_handle[id].rx_callback)
        {
            uart_handle[id].rx_callback(&id, status);
        }
#endif
    }
    return ret;
}
int uart_tx_abort_dma(enum UART_DEV_T id, drv_callback_t abort_tx_callback)
{
    int ret = DRV_ERROR;
#if UART_DMA_MODE_EN
    if (uart_handle[id].dma_en)
    {
        // reset tx FIFO, de-assert the DMA TX request
        uart_handle[id].base->CTRL0 = uart_handle[id].ctrl0 | UART_CTRL0_TX_FIFO_RESET_MSK;
        uart_handle[id].tx_abort_callback = abort_tx_callback;
        ret = dma_abort(uart_handle[id].dma_tx_ch, uart_dma_abort_callback);
    }
#endif
    return ret;
}
int uart_rx_abort_dma(enum UART_DEV_T id, drv_callback_t abort_rx_callback)
{
    int ret = DRV_ERROR;
#if UART_DMA_MODE_EN
    if (uart_handle[id].dma_en)
    {
        // RX err - disable interrupts
        uart_handle[id].base->INTR_EN &= ~(UART_INTR_EN_ELCOLR_MSK | UART_INTR_EN_ELSI_MSK);
        // reset rx FIFO, de-assert the DMA RX request
        uart_handle[id].base->CTRL0 = uart_handle[id].ctrl0 | UART_CTRL0_RX_FIFO_RESET_MSK;
        uart_handle[id].rx_abort_callback = abort_rx_callback;
        ret = dma_abort(uart_handle[id].dma_rx_ch, uart_dma_abort_callback);
    }
#endif
    return ret;
}
#if defined(__GNUC__)
#pragma GCC diagnostic pop
#endif
#if UART_DMA_MODE_EN
static void uart_dma_abort_callback(void *ch, uint32_t err_code)
{
    uint8_t ch_num = *(uint8_t *)ch;
    drv_callback_t usr_callback = NULL;
    enum UART_DEV_T id;
    if ((ch_num == uart_handle[UART_ID0].dma_tx_ch) || (ch_num == uart_handle[UART_ID1].dma_tx_ch))
    {
        id = (ch_num == uart_handle[UART_ID0].dma_tx_ch ? UART_ID0 : UART_ID1);
        // TX dma abort
        usr_callback = uart_handle[id].tx_abort_callback;
        // update state
        uart_state_clear(id, UART_STATE_BUSY_TX);
        uart_handle[id].tx_abort_callback = NULL;
        uart_handle[id].tx_buff = NULL;
        uart_handle[id].tx_callback = NULL;
        uart_handle[id].tx_count = 0;
        uart_handle[id].tx_size = 0;
    }
    else if ((ch_num == uart_handle[UART_ID0].dma_rx_ch) || (ch_num == uart_handle[UART_ID1].dma_rx_ch))
    {
        id = (ch_num == uart_handle[UART_ID0].dma_rx_ch ? UART_ID0 : UART_ID1);
        // RX dma abort
        usr_callback = uart_handle[id].rx_abort_callback;
        // update state
        uart_state_clear(id, UART_STATE_BUSY_RX);
        uart_handle[id].rx_abort_callback = NULL;
        uart_handle[id].rx_buff = NULL;
        uart_handle[id].rx_callback = NULL;
        uart_handle[id].rx_count = 0;
        uart_handle[id].rx_size = 0;
    }
    else
    {
        ASSERT(0, "Unexpected dma channel %d", ch_num);
    }
    // LOG_INFO(TRACE_MODULE_DRIVER, "uart_dma_abort_callback %d\r\n", ch_num);
    if (usr_callback)
    {
        usr_callback(&id, err_code);
    }
}
static void uart_dma_callback(void *ch, uint32_t err_code)
{
    uint8_t ch_num = *(uint8_t *)ch;
    drv_callback_t usr_callback = NULL;
    enum UART_DEV_T id;
    if ((ch_num == uart_handle[UART_ID0].dma_tx_ch) || (ch_num == uart_handle[UART_ID1].dma_tx_ch))
    {
        id = (ch_num == uart_handle[UART_ID0].dma_tx_ch ? UART_ID0 : UART_ID1);
        if (err_code == DMA_INT_TYPE_DONE)
        {
            // TX done
            usr_callback = uart_handle[id].tx_callback;
            // update state
            uart_state_clear(id, UART_STATE_BUSY_TX);
        }
        else
        {
            // update state
            if ((uart_handle[id].state == UART_STATE_BUSY_TX_RX) || (uart_handle[id].state == UART_STATE_BUSY_TX))
            {
                uart_handle[id].state = UART_STATE_ERROR;
            }
            else
            {
                ASSERT(0, "Unexpected uart %d state %d", id, uart_handle[id].state);
            }
        }
        uart_handle[id].tx_buff = NULL;
        uart_handle[id].tx_callback = NULL;
        uart_handle[id].tx_count = 0;
        uart_handle[id].tx_size = 0;
    }
    else if ((ch_num == uart_handle[UART_ID0].dma_rx_ch) || (ch_num == uart_handle[UART_ID1].dma_rx_ch))
    {
        id = (ch_num == uart_handle[UART_ID0].dma_rx_ch ? UART_ID0 : UART_ID1);
        if (err_code == DMA_INT_TYPE_DONE)
        {
            // If rx err occurs and UART rx also requests dma, this trigger of rx dma done will be ignored
            if (uart_handle[id].dma_rx_err_state)
            {
                uart_handle[id].dma_rx_err_state = 0;
                return;
            }
            // RX done
            usr_callback = uart_handle[id].rx_callback;
            // update state
            uart_state_clear(id, UART_STATE_BUSY_RX);
        }
        else
        {
            // update state
            if ((uart_handle[id].state == UART_STATE_BUSY_TX_RX) || (uart_handle[id].state == UART_STATE_BUSY_RX))
            {
                uart_handle[id].state = UART_STATE_ERROR;
            }
            else
            {
                ASSERT(0, "Unexpected uart %d state %d", id, uart_handle[id].state);
            }
        }
        uart_handle[id].rx_buff = NULL;
        uart_handle[id].rx_callback = NULL;
        uart_handle[id].rx_count = 0;
        uart_handle[id].rx_size = 0;
    }
    else
    {
        ASSERT(0, "Unexpected dma channel %d", ch_num);
    }
    if (usr_callback)
    {
        usr_callback(&id, err_code);
    }
}
#endif
// NOTE: This interrupt handler updates variables in the 'handle' structure.
// Any other code which modifies these variables must be guarded against shared data issues.
void uart_irq_handler(enum UART_DEV_T id)
{
    drv_callback_t usr_callback = NULL;
    uint32_t err_code = 0;
    // read interrupt ID
    uint8_t iid = uart_handle[id].base->INTR_STATUS & 0x0f;
    // If DMA is enabled, the uart interrupt handler is only used to handle the error events reported by the receiver
    if (uart_handle[id].dma_en)
    {
#if UART_DMA_MODE_EN
        err_code = uart_handle[id].base->STATUS;
        // iid == 0xC: The precondition that the timeout event will not be triggered is that the length of
        // the received data is an integer multiple of the RX FIFO level
        if ((err_code & UART_STATUS_ERROR_MSK) || (iid == 0x0C) || (iid == 0x01))
        {
            // RX err - disable interrupts
            uart_handle[id].base->INTR_EN &= ~UART_INTR_EN_ELSI_MSK;
            uart_handle[id].base->INTR_CLR = UART_INTR_CLR_LSR_INT_CLR_MSK;
            uart_handle[id].dma_rx_err_state = UART_ERR_LINE | iid;
            usr_callback = uart_handle[id].rx_callback;
            err_code = UART_ERR_LINE | iid;
            // update state
            uart_state_clear(id, UART_STATE_BUSY_RX);
            uart_handle[id].rx_buff = NULL;
            uart_handle[id].rx_callback = NULL;
            uart_handle[id].rx_count = 0;
            uart_handle[id].rx_size = 0;
        }
#endif
    }
    else
    {
#if UART_INT_MODE_EN
        switch (iid)
        {
            // modem status
        case 0x0:
            // clear int
            uart_handle[id].base->INTR_CLR = UART_INTR_CLR_MSR_INT_CLR_MSK;
            err_code = UART_ERR_MODEM | iid;
            break;
            // no interrupt pending
        case 0x1:
            break;
            // TX_DATA empty
        case 0x2:
            // clear int
            uart_handle[id].base->INTR_CLR = UART_INTR_CLR_THRE_INT_CLR_MSK;
            if ((uart_handle[id].state == UART_STATE_BUSY_TX) || (uart_handle[id].state == UART_STATE_BUSY_TX_RX))
            {
                if (uart_handle[id].tx_count == uart_handle[id].tx_size)
                {
                    // TX done - disable interrupt
                    uart_handle[id].base->INTR_EN &= ~UART_INTR_EN_ETBEI_MSK;
                    usr_callback = uart_handle[id].tx_callback;
                    // update state
                    uart_state_clear(id, UART_STATE_BUSY_TX);
                    uart_handle[id].tx_buff = NULL;
                    uart_handle[id].tx_callback = NULL;
                    uart_handle[id].tx_count = 0;
                    uart_handle[id].tx_size = 0;
                }
                else
                {
                    // TX continue - write data to FIFO
                    while ((uart_handle[id].tx_count < uart_handle[id].tx_size) && (uart_handle[id].base->STATUS & UART_STATUS_TFNF_MSK))
                    {
                        uart_handle[id].base->TX_DATA = uart_handle[id].tx_buff[uart_handle[id].tx_count++];
                    }
                }
            }
            else
            {
                // should not get this interrupt in any other state
                ASSERT(0, "Uart %d state goes wrong %d", id, uart_handle[id].state);
            }
            break;
            // timeout
        case 0xc:
            // No characters in or out of the RCVR FIFO during the last 4 character times and
            // there is at least 1 character in it during this time
            // received data available
        case 0x4:
            if ((uart_handle[id].state == UART_STATE_BUSY_RX) || (uart_handle[id].state == UART_STATE_BUSY_TX_RX))
            {
                // uint8_t len = uart_handle[id].base->RX_FL;
                while ((uart_handle[id].rx_count < uart_handle[id].rx_size) && (uart_handle[id].base->STATUS & UART_STATUS_RFNE_MSK))
                {
                    uint8_t data = (uint8_t)uart_handle[id].base->RX_DATA;
                    uart_handle[id].rx_buff[uart_handle[id].rx_count++] = data;
                }
                if (uart_handle[id].rx_count == uart_handle[id].rx_size)
                {
                    // RX done - disable interrupts
                    uart_handle[id].base->INTR_EN &= ~(UART_INTR_EN_ELSI_MSK | UART_INTR_EN_ERBFI_MSK);
                    usr_callback = uart_handle[id].rx_callback;
                    // update state
                    uart_state_clear(id, UART_STATE_BUSY_RX);
                    uart_handle[id].rx_buff = NULL;
                    uart_handle[id].rx_callback = NULL;
                    uart_handle[id].rx_count = 0;
                    uart_handle[id].rx_size = 0;
                }
            }
            else
            {
                // received unexpected data
            }
            break;
            // receiver line status
        case 0x6:
            // clear int
            uart_handle[id].base->INTR_CLR = UART_INTR_CLR_LSR_INT_CLR_MSK;
            err_code = UART_ERR_LINE | iid;
            break;
            // busy detect
        case 0x7:
            // clear int
            uart_handle[id].base->INTR_CLR = UART_INTR_CLR_BUSY_INT_CLR_MSK;
            err_code = UART_ERR_BUSY | iid;
            break;
        default:
            break;
        }
#endif
    }
    if (usr_callback)
    {
        usr_callback(&id, err_code);
    }
}
void UART0_IRQHandler(void)
{
    uart_irq_handler(UART_ID0);
}
void UART1_IRQHandler(void)
{
    uart_irq_handler(UART_ID1);
}
int uart_printf_init(enum UART_DEV_T id)
{
    struct UART_CFG_T uart_print_cfg = {
        .parity = UART_PARITY_NONE,
        .stop = UART_STOP_BITS_1,
        .data = UART_DATA_BITS_8,
        .flow = UART_FLOW_CONTROL_NONE,
        .tx_level = UART_TXFIFO_EMPTY,
        .rx_level = UART_RXFIFO_CHAR_1,
        .baud = BAUD_921600,
        .dma_en = false,
        .int_rx = false,
        .int_tx = false,
    };
    return uart_open(id, &uart_print_cfg);
}
#if TRACE_EN
__attribute__((__format__(__printf__, 2, 0))) void uart_printf(enum UART_DEV_T id, const char *fmt, ...)
{
    char buf[100] = {0};
    int len;
    va_list argp;
    va_start(argp, fmt);
    len = trace_format(buf, sizeof(buf), fmt, argp);
    va_end(argp);
    uart_send(id, (uint8_t *)buf, (uint32_t)(len > 0 ? len : 0), NULL);
}
#else
void uart_printf(enum UART_DEV_T id, const char *fmt, ...)
{
}
#endif