Files
kunlun/driver/src/hal/vfs_uart.c
2024-10-23 09:59:28 +08:00

1261 lines
31 KiB
C

/****************************************************************************
Copyright(c) 2019 by Aerospace C.Power (Chongqing) Microelectronics. ALL RIGHTS RESERVED.
This Information is proprietary to Aerospace C.Power (Chongqing) Microelectronics and MAY NOT
be copied by any method or incorporated into another program without
the express written consent of Aerospace C.Power. This Information or any portion
thereof remains the property of Aerospace C.Power. The Information contained herein
is believed to be accurate and Aerospace C.Power assumes no responsibility or
liability for its use in any way and conveys no license or title under
any patent or copyright and makes no representation or warranty that this
Information is free from patent or copyright infringement.
****************************************************************************/
/* os shim includes */
#include "os_types.h"
#include "os_mem.h"
#include "iot_module.h"
#include "iot_errno.h"
#include "iot_io.h"
#include "iot_gpio_api.h"
#include "iot_board.h"
#include "iot_uart_api.h"
#include "iot_mem_pool.h"
#include "iot_plc_led.h"
#include "iot_uart_h.h"
#include "uart.h"
#include "gpio_hw.h"
#include "vfs_uart.h"
#include "termios.h"
#include <string.h>
#include "os_task.h"
#include "dma_uart.h"
uart_info *g_uart_info = NULL;
extern struct uart_ctrl g_uart_ext_driver;
struct uart_ctrl g_uart_ctrl = {0};
struct uart_ctrl *p_uart_ext_ctrl = NULL;
struct uart_ctrl *p_uart_vp_ctrl = NULL;
/* Initialized with board-ID. */
int g_uart_ext_num = 0;
//#define RS485_DEBUG_TEST
#define UART_RS485_PORT_INVALID (-1)
struct uart_rs485_ctrl
{
int dir_gpio;
#ifdef RS485_DEBUG_TEST
uint32_t cnt_rxi;
uint32_t cnt_rti;
uint32_t cnt_txi;
uint32_t cnt_txd;
uint32_t cnt_rx_ovfl;
uint32_t cnt_rx_ring_ovfl_byte;
uint32_t cnt_tx_size;
uint32_t cnt_rx_size;
int fd;
int int_ena;
int int_raw;
int int_sts;
int base;
#endif
};
struct uart_ir_ctrl
{
int port;
int tx_pin;
int rx_pin;
bool_t ir_loopback;
};
struct uart_ir_ctrl g_uart_ir_port =
{
.port = 0xFF,
.tx_pin = 0,
.rx_pin = 0,
.ir_loopback = false,
};
/* RS485 port config */
struct uart_rs485_config
{
int port_type;
int gpio_type;
};
#define RS485_PORT_NUM 2
static const struct uart_rs485_config uart_rs485_cfg[RS485_PORT_NUM] =
{
{
.port_type = UART_RS485_PORT,
.gpio_type = GPIO_RS485_TXE,
},
{
.port_type = UART_RS485_PORT_2,
.gpio_type = GPIO_RS485_TXE_2,
},
};
struct uart_rs485_ctrl *g_uart_rs485_port = NULL;
static int g_uart_rs485_num = 0;
extern void dma_hw_stop_recieve(int dev);
#ifdef RS485_DEBUG_TEST
#include "os_task.h"
void rs485_int_cnt_print(uint8_t port_idx)
{
struct uart_rs485_ctrl tmp;
if (port_idx >= g_uart_rs485_num){
return ;
}
os_disable_irq();
tmp = g_uart_rs485_port[port_idx];
g_uart_rs485_port[port_idx].int_ena
= *(volatile int*)(g_uart_rs485_port[port_idx].base+0x4);
g_uart_rs485_port[port_idx].int_raw
= *(volatile int*)(g_uart_rs485_port[port_idx].base+0xc);
g_uart_rs485_port[port_idx].int_sts
= *(volatile int*)(g_uart_rs485_port[port_idx].base+0x10);
os_enable_irq();
iot_printf("\r\n RS485 Port:%02d", tmp.port);
iot_printf("\r\n Port Fd:%02d", tmp.fd);
iot_printf("\r\n TXI:%06d", tmp.cnt_txi);
iot_printf("\r\n TXD:%06d", tmp.cnt_txd);
iot_printf("\r\n RXI:%06d", tmp.cnt_rxi);
iot_printf("\r\n RTI:%06d", tmp.cnt_rti);
iot_printf("\r\n RX-OVFL:%06d", tmp.cnt_rx_ovfl);
iot_printf("\r\n RING-DROP:%06d", tmp.cnt_rx_ring_ovfl_byte);
iot_printf("\r\n TX_BYTES:%06d", tmp.cnt_tx_size);
iot_printf("\r\n RX_BYTES:%06d", tmp.cnt_rx_size);
iot_printf("\r\n UP_LY_RX:%06d", rcvd_byte);
iot_printf("\r\n INT_ENA:0x%08x", tmp.int_ena);
iot_printf("\r\n INT_STS:0x%08x", tmp.int_sts);
iot_printf("\r\n INT_RAW:0x%08x", tmp.int_raw);
iot_printf("\r\n BASE_ADDR:0x%08x\r\n", tmp.base);
}
#endif
static uart_info * uart_info_get(int fd)
{
uart_info *p_uart = NULL;
if (NULL == g_uart_info) {
return NULL;
}
if ((USART1_FILENO <= fd)
&& ((USART1_FILENO + IOT_UART_PORT_NUM_ONCHIP - 1) >= fd)) {
p_uart = &g_uart_info[fd - USART1_FILENO];
} else if (((USART1_FILENO + IOT_UART_PORT_NUM_ONCHIP) <= fd) &&
((USART1_FILENO + IOT_UART_PORT_NUM_ONCHIP + g_uart_ext_num - 1)
>= fd)) {
p_uart = &g_uart_info[fd - USART1_FILENO];
} else {
return NULL;
}
if (NULL == p_uart->drv) {
IOT_ASSERT(0);
p_uart = NULL;
}
return p_uart;
}
static int _macro_to_speed(speed_t c_speed)
{
int speed = 0;
switch(c_speed) {
case B2400:
speed = 2400;
break;
case B9600:
speed = 9600;
break;
case B19200:
speed = 19200;
break;
case B38400:
speed = 398400;
break;
case B57600:
speed = 57600;
break;
case B115200:
speed = 115200;
break;
}
return speed;
}
speed_t cfgetospeed(const struct termios *termios_p)
{
return termios_p->c_ospeed;
}
speed_t cfgetispeed(const struct termios *termios_p)
{
return termios_p->c_ispeed;
}
int cfsetispeed(struct termios *termios_p, speed_t speed)
{
termios_p->c_ispeed = speed;
return 0;
}
int cfsetospeed(struct termios* termios_p, speed_t speed)
{
termios_p->c_ospeed = speed;
return 0;
}
int cfsetspeed(struct termios* termios_p, speed_t speed)
{
termios_p->c_ispeed = speed;
termios_p->c_ospeed = speed;
return 0;
}
int tcgetattr(int fd, struct termios* termios_p)
{
return 0;
}
int tcsetattr(int fd, int optional_actions, const struct termios* termios_p)
{
int baud, data, stop, parity, pport;
uart_info *uart;
if((uart = uart_info_get(fd)) == NULL) {
return -1;
}
pport = iot_uart_lport_to_pport(uart->port);
uart->termios = *termios_p;
baud = _macro_to_speed(termios_p->c_ospeed);
/* Configure Word Length */
if (termios_p->c_cflag & CS8) {
data = 8;
}
/* Configure Stop bits */
if (termios_p->c_cflag & CSTOPB) {
stop = 2;
} else {
stop = 1;
}
/* Configure parity */
if (!(termios_p->c_cflag & PARENB)) {
parity = 0;
} else if (termios_p->c_cflag & PARODD) {
parity = 1;
} else {
parity = 2;
}
uart->drv->config(pport, baud, data, stop, parity);
return 0;
}
int uart_config(int fd, int baud, int data, int stop, int parity)
{
uart_info *uart;
int pport;
if((uart = uart_info_get(fd)) == NULL){
return -1;
}
pport = iot_uart_lport_to_pport(uart->port);
uart->drv->config(pport, baud, data, stop, parity);
return 0;
}
static bool_t IRAM_ATTR uart_rs485_port_check(int port,uint8_t *idx)
{
if (port >= g_uart_rs485_num) {
return false;
}
if (GPIO_NO_VALID == g_uart_rs485_port[port].dir_gpio) {
return false;
}
*idx = port;
return true;
}
static void uart_rs485_start(int gpio)
{
iot_gpio_value_set(gpio, 1);
iot_plc_led_request(IOT_PLC_LED_REQ_PLC_485_TX);
}
static void IRAM_ATTR uart_rs485_stop(int gpio)
{
iot_gpio_value_set(gpio, 0);
}
uint32_t IRAM_ATTR uart_handler(uint32_t vector, iot_addrword_t data)
{
uint32_t port = (uint32_t)data;
uart_info *uart = &g_uart_info[port];
uint32_t status;
int32_t c, pport;
uint32_t value = 0;
uint8_t index;
pport = iot_uart_lport_to_pport(port);
status = (uint32_t)uart->drv->get_int_status(pport);
#ifdef RS485_DEBUG_TEST
if (uart_rs485_port_check(port,&index)) {
g_uart_rs485_port[index].int_ena
|= *(volatile int*)(g_uart_rs485_port[index].base+0x4);
g_uart_rs485_port[index].int_raw
|= *(volatile int*)(g_uart_rs485_port[index].base+0xc);
g_uart_rs485_port[index].int_sts
|= *(volatile int*)(g_uart_rs485_port[index].base+0x10);
}
#endif
if ( status ){
if( status & (UART_RTI| UART_RXI)) {
value |= 1 << (2*port);
while (1) {
#ifdef UART_ASYNC_OPERATION
if(uart->async_mode) {
int read_size;
read_size = min(uart->rx_info.size, UART_ASYNC_READ_ONCE)
read_size = uart->drv->gets(pport, uart->rx_info.p_buf,
read_size);
if(read_size == -1 || read_size == -ERR_AGAIN) {
break;
}
if(uart->rx_info.size == read_size)
{
uart->drv->clear_int(pport, UART_RXI|UART_RTI);
uart->rx_info.cb(uart->rx_info.param, 0);
}
}
else {
#endif
c = uart->drv->getc(pport);
if (c == -ERR_AGAIN) {
break;
}
iot_ringbuf_put(&uart->rx_rb, (uint8_t)c);
#ifdef UART_ASYNC_OPERATION
}
#endif
}
uart->drv->clear_int_status(pport, (UART_RTI| UART_RXI));
#ifdef RS485_DEBUG_TEST
if (uart_rs485_port_check(port,&index)) {
if(status & UART_RXI)
g_uart_rs485_port[index].cnt_rxi++;
if(status & UART_RTI)
g_uart_rs485_port[index].cnt_rti++;
}
#endif
}
if( status & UART_TXI) {
value |= 1 << (2*port+1);
#if UART_TXBUF_SUPPORT
while(1) {
if(uart->drv->txfifo_full(pport))
break;
c = iot_ringbuf_get(&uart->tx_rb);
if( c == -1){
uart->drv->clear_int(pport, UART_TXI);
value |= 1 << (2*port+1);
break;
}
uart->drv->putc(pport, c);
}
#else
uart->drv->clear_int(pport, UART_TXI);
#endif
uart->drv->clear_int_status(pport, UART_TXI);
#ifdef RS485_DEBUG_TEST
if (uart_rs485_port_check(port,&index))
g_uart_rs485_port[index].cnt_txi++;
#endif
}
if( status & UART_TX_DONE) {
if (uart_rs485_port_check(port,&index)){
/* Add for RS485 to clear 0x00 in the fifo. */
int rx_cnt;
rx_cnt = uart->drv->rx_fifo_cnt(pport);
if(rx_cnt > 0)
{
while(rx_cnt--)
{
(void)uart->drv->getc(pport);
}
}
if (GPIO_NO_VALID != g_uart_rs485_port[index].dir_gpio)
uart_rs485_stop(g_uart_rs485_port[index].dir_gpio);
#ifdef RS485_DEBUG_TEST
g_uart_rs485_port[index].cnt_txd++;
#endif
}
if(port == g_uart_ir_port.port){
uart->drv->tx_disable(pport, g_uart_ir_port.tx_pin);
uart->drv->rx_enable(pport, g_uart_ir_port.rx_pin);
}
uart->drv->clear_int_status(pport, UART_TX_DONE);
}
if(status & UART_OVR_FL)
{
uart->drv->clear_int(pport, UART_OVR_FL);
uart->drv->clear_int_status(pport, UART_OVR_FL);
uart->drv->reset_fifo(pport);
uart->drv->set_int(pport, UART_OVR_FL);
#ifdef RS485_DEBUG_TEST
if (uart_rs485_port_check(port,&index))
g_uart_rs485_port[index].cnt_rx_ovfl++;
#endif
}
if(status & UART_RX_BRK)
{
uart->drv->clear_int(pport, UART_RX_BRK);
uart->drv->clear_int_status(pport, UART_RX_BRK);
uart->drv->set_int(pport, UART_RX_BRK);
}
if(status & UART_TX_BRK)
{
uart->drv->clear_int(pport, UART_TX_BRK);
uart->drv->clear_int_status(pport, UART_TX_BRK);
uart->drv->set_int(pport, UART_TX_BRK);
}
/* only kl3 support idle interrupt */
if(status & UART_RX_IDLE)
{
uart->drv->clear_int(pport, UART_RX_IDLE);
uart->drv->clear_int_status(pport, UART_RX_IDLE);
uart->drv->set_int(pport, UART_RX_IDLE);
dma_hw_stop_recieve(uart_dma_p_2_d(pport));
}
if ( value ) {
os_set_task_event_with_v_from_isr(uart->task_h, value);
}
}
return 0;
}
void uart_ext_interrupt_proc(uart_info *uart)
{
uint32_t status;
int32_t pport, read_size, fifo_cnt;
uint32_t value = 0;
uint32_t lport = uart->port;
uint8_t recv_buffer[UART_EXT_RX_BUF_LEN];
pport = iot_uart_lport_to_pport(lport);
status = (uint32_t)uart->drv->get_int_status(pport);
if ((!status) || (iot_uart_is_onchip((uint8_t)lport))) {
return;
}
if( status & (UART_RTI| UART_RXI)) {
value |= 1 << (2*lport);
fifo_cnt = uart->drv->rx_fifo_cnt(pport);
while (fifo_cnt > 0) {
read_size = (fifo_cnt >= UART_EXT_RX_BUF_LEN)
? UART_EXT_RX_BUF_LEN : fifo_cnt;
read_size = uart->drv->gets(pport, recv_buffer, read_size);
if(read_size == -1 || read_size == -ERR_AGAIN) {
break;
}
iot_ringbuf_puts(&uart->rx_rb, recv_buffer, read_size);
fifo_cnt -= read_size;
}
uart->drv->clear_int_status(pport, (UART_RTI| UART_RXI));
}
if( status & UART_TXI) {
value |= 1 << (2*lport+1);
#if UART_TXBUF_SUPPORT
while(1) {
if(uart->drv->txfifo_full(pport))
break;
c = iot_ringbuf_get(&uart->tx_rb);
if( c == -1){
uart->drv->clear_int(pport, UART_TXI);
value |= 1 << (2*lport+1);
break;
}
uart->drv->putc(pport, c);
}
#else
uart->drv->clear_int(pport, UART_TXI);
#endif
uart->drv->clear_int_status(pport, UART_TXI);
}
if( status & UART_TX_DONE) {
if(PORT_TYPE_RS485 == uart->type)
{
int rx_cnt;
rx_cnt = uart->drv->rx_fifo_cnt(pport);
if(rx_cnt > 0)
{
while(rx_cnt--)
{
(void)uart->drv->getc(pport);
}
}
if (GPIO_NO_VALID != uart->txe_pin){
uart_rs485_stop(uart->txe_pin);
}
}
uart->drv->clear_int_status(pport, UART_TX_DONE);
}
if(status & UART_OVR_FL)
{
uart->drv->clear_int(pport, UART_OVR_FL);
uart->drv->clear_int_status(pport, UART_OVR_FL);
uart->drv->reset_fifo(pport);
uart->drv->set_int(pport, UART_OVR_FL);
}
if(status & UART_RX_BRK)
{
uart->drv->clear_int(pport, UART_RX_BRK);
uart->drv->clear_int_status(pport, UART_RX_BRK);
uart->drv->set_int(pport, UART_RX_BRK);
}
if(status & UART_TX_BRK)
{
uart->drv->clear_int(pport, UART_TX_BRK);
uart->drv->clear_int_status(pport, UART_TX_BRK);
uart->drv->set_int(pport, UART_TX_BRK);
}
if ( value ) {
os_set_task_event_with_v(uart->task_h, value);
}
return;
}
void uart_ext_handler_uart_task(void)
{
int pport;
uart_info *puart;
uint8_t uport_gpio = iot_board_get_gpio(GPIO_EXT_UART_INT);
for (pport = 0; pport < g_uart_ext_num; pport++) {
/* Walk all external ports when interrupt occurs. */
puart = uart_info_get(iot_uart_pport_to_lport(UART_TYPE_EXT, pport));
if ((NULL != puart) && (puart->used)) {
uart_ext_interrupt_proc(puart);
}
}
/* Enable gpio interrupt. */
if (GPIO_NO_VALID != uport_gpio) {
iot_gpio_interrupt_enable(uport_gpio, 1);
}
return;
}
/* This function is running in task env. */
void uart_ext_handler_share_task(int data)
{
(void)data;
iot_uart_task_post_ext_isr_event();
return;
}
int uart_disable_rs485(int fd)
{
uart_info *uart;
int port;
if ((uart = uart_info_get(fd)) == NULL){
return -1;
}
port = uart->port;
if (GPIO_NO_VALID != g_uart_rs485_port[port].dir_gpio) {
uart_rs485_stop(g_uart_rs485_port[port].dir_gpio);
iot_gpio_close(g_uart_rs485_port[port].dir_gpio);
g_uart_rs485_port[port].dir_gpio = GPIO_NO_VALID;
}
return 0;
}
int uart_enable_rs485(int fd, int dir_gpio)
{
uart_info *uart;
int port;
if ((uart = uart_info_get(fd)) == NULL){
return -1;
}
if (GPIO_NO_VALID == dir_gpio) {
return -1;
}
port = uart->port;
uart_disable_rs485(fd);
g_uart_rs485_port[port].dir_gpio = dir_gpio;
iot_gpio_open_as_output(dir_gpio);
uart_rs485_stop(dir_gpio);
return 0;
}
int uart_open(const char* dev, int flags, void* priv)
{
int fd, pport;
uart_info *uart = NULL;
uint8_t index;
if (strcmp(dev, "/dev/ttyS0") == 0) {
fd = USART1_FILENO;
}
else if (strcmp(dev, "/dev/ttyS1") == 0) {
fd = USART2_FILENO;
}
else if (strcmp(dev, "/dev/ttyS2") == 0) {
fd = USART3_FILENO;
}
else if (strcmp(dev, "/dev/ttyS3") == 0) {
fd = USART4_FILENO;
}
else if (strcmp(dev, "/dev/ttyS4") == 0) {
fd = USART5_FILENO;
}
else if (strcmp(dev, "/dev/ttyS5") == 0) {
fd = USART6_FILENO;
}
else if (strcmp(dev, "/dev/ttyS6") == 0) {
fd = USART7_FILENO;
}
else if (strcmp(dev, "/dev/ttyS7") == 0) {
fd = USART8_FILENO;
}
else {
iot_printf("invalid param, unsupported device.\n");
return -1;
}
uart = uart_info_get(fd);
if (NULL == uart) {
iot_printf("invalid uart fd %d.\n", fd);
return -1;
}
pport = iot_uart_lport_to_pport(uart->port);
if(!os_atomic_check_set((int*)&(uart->used), 0, 1)){
iot_printf("this uart device is used.\n");
return -1;
}
if (uart_rs485_port_check(uart->port,&index)) {
uart_enable_rs485(uart->port, g_uart_rs485_port[index].dir_gpio);
}
uart->task_h = (os_task_h)priv;
uart->drv->init(pport);
if(uart->port == iot_board_get_uart(UART_IR_PORT)){
uint8_t tx_pin = iot_board_get_gpio(GPIO_IR_TXD);
g_uart_ir_port.port = uart->port;
g_uart_ir_port.tx_pin = tx_pin;
g_uart_ir_port.rx_pin = iot_board_get_gpio(GPIO_IR_RXD);
IOT_ASSERT(tx_pin < 49);
/*enable IRDA*/
uart->drv->set_irda(pport, tx_pin);
uart->drv->tx_disable(pport, tx_pin);
iot_printf("IR enabled on port:%d, TX gpio:%d\n", uart->port, tx_pin);
}
if (iot_uart_is_onchip(uart->port)) {
iot_interrupt_attach( uart->handle);
iot_interrupt_unmask( uart->handle);
} else {
if (iot_board_check_uart_is_rs485(uart->port)) {
uart->drv->enable_rs485(pport);
}
uint8_t int_gpio = iot_board_get_gpio(GPIO_EXT_UART_INT);
if (GPIO_NO_VALID != int_gpio) {
if ((ERR_OK != iot_gpio_open_as_interrupt(int_gpio))
|| (ERR_OK != iot_gpio_interrupt_config(int_gpio, GPIO_INT_LEVEL_HIGH,
uart_ext_handler_share_task, 0, GPIO_INT_FUNC_ENABLE_AUTOSTOP))
|| (ERR_OK != iot_gpio_set_pull_mode(int_gpio, GPIO_PULL_DOWN))
|| (ERR_OK != iot_gpio_interrupt_enable(int_gpio, 1))) {
IOT_ASSERT(0);
return ERR_FAIL;
}
}
uart->drv->set_int(pport, UART_RXI | UART_RTI);
}
iot_printf("uart_open lport %d, pport %d OK!\n",
uart->port, pport);
return fd;
}
int uart_select(int fd, int max_len, uint32_t millisec)
{
uart_info *uart;
int ret;
if((uart = uart_info_get(fd)) == NULL)
return -1;
ret = iot_ringbuf_elements(&uart->rx_rb)?1:0;
return ret;
}
int uart_read(int fd, uint8_t* buf, size_t count)
{
uart_info *uart;
int ret;
if((uart = uart_info_get(fd)) == NULL)
return -1;
ret = iot_ringbuf_gets(&uart->rx_rb, buf, count);
return ret;
}
int uart_write(int fd, uint8_t* buf, size_t count)
{
int i = 0, pport;
uart_info *uart;
uint8_t index;
#if UART_TXBUF_SUPPORT
int c;
#else
uint8_t* p = (uint8_t*)buf;
#endif
if((uart = uart_info_get(fd)) == NULL){
return -1;
}
pport = iot_uart_lport_to_pport(uart->port);
if (uart_rs485_port_check(uart->port,&index)) {
if (GPIO_NO_VALID != g_uart_rs485_port[index].dir_gpio)
uart_rs485_start(g_uart_rs485_port[index].dir_gpio);
}
if(uart->port == g_uart_ir_port.port){
if(!g_uart_ir_port.ir_loopback) {
uart->drv->rx_disable(pport, g_uart_ir_port.rx_pin);
}
uart->drv->tx_enable(pport, g_uart_ir_port.tx_pin);
}
if (iot_uart_is_external(uart->port)) {
if ((PORT_TYPE_RS485 == uart->type)
&& (GPIO_NO_VALID != uart->txe_pin)){
uart_rs485_start(uart->txe_pin);
}
}
#if UART_TXBUF_SUPPORT
i = iot_ringbuf_puts(&uart->tx_rb, buf, count);
while(1) {
if(uart->drv->txfifo_full(pport))
break;
c = iot_ringbuf_get(&uart->tx_rb);
if( c == -1){
break;
}
uart->drv->putc(pport, c);
}
#else
i = uart->drv->puts(pport, p, count);
#endif
if ((i > 0) && (iot_uart_is_onchip(uart->port))) {
if (uart_rs485_port_check(uart->port,&index)) {
uart->drv->clear_int_status(pport, UART_TXI|UART_TX_DONE);
uart->drv->set_int(pport, UART_TXI|UART_TX_DONE);
#ifdef RS485_DEBUG_TEST
g_uart_rs485_port[index].cnt_tx_size += i;
rs485_int_cnt_print(index);
#endif
} else if(uart->port == g_uart_ir_port.port){
uart->drv->clear_int_status(pport, UART_TXI|UART_TX_DONE);
uart->drv->set_int(pport, UART_TXI|UART_TX_DONE);
} else {
uart->drv->clear_int_status(uart->port, UART_TXI);
uart->drv->set_int(pport, UART_TXI);
}
}
return i;
}
int uart_undo_all_interrupts(int fd)
{
uart_info *uart;
int pport;
if ((uart = uart_info_get(fd)) == NULL) {
return -1;
}
pport = iot_uart_lport_to_pport(uart->port);
uart->drv->clear_int(pport, 0xFFFFFFFF);
uart->drv->clear_int_status(pport, 0xFFFFFFFF);
uart->drv->reset_fifo(pport);
/* kl3 need uart rx idle interrupt to stop dma transfer */
#if TARGET_VERSION == TARGET_KUNLUN3
return 0;
#endif
if (iot_uart_is_onchip(uart->port)) {
iot_interrupt_mask(uart->handle);
iot_interrupt_detach(uart->handle);
} else {
/* clear all interrputs. */
uart->drv->clear_int(pport, -1);
}
return 0;
}
int uart_close(int fd)
{
uart_info *uart;
if((uart = uart_info_get(fd)) == NULL)
return -1;
(void)uart_undo_all_interrupts(fd);
(void)os_atomic_check_set((int*)&(uart->used), 1, 0);
return 0;
}
int uart_threshold_set(int fd, int type, int thr)
{
uart_info *uart;
int pport, ret;
if((uart = uart_info_get(fd)) == NULL){
return -1;
}
pport = iot_uart_lport_to_pport(uart->port);
ret = uart->drv->threshold(pport, type, thr);
return ret;
}
int uart_flow_ctrl_set(int fd, int type, int thr)
{
uart_info *uart;
int pport, ret;
if((uart = uart_info_get(fd)) == NULL){
return -1;
}
pport = iot_uart_lport_to_pport(uart->port);
ret = uart->drv->flow_ctrl(pport, type, thr);
return ret;
}
int uart_brk_set(int fd, int value)
{
uart_info *uart;
int pport, ret;
if((uart = uart_info_get(fd)) == NULL){
return -1;
}
pport = iot_uart_lport_to_pport(uart->port);
ret = uart->drv->set_brk(pport, value);
return ret;
}
static int uart_rxbuf_alloc(uart_info *uart)
{
uint8_t *rx_buf = NULL;
uint32_t buf_len;
if (uart->port == 0) {
buf_len = UART0_RX_Q_LEN;
}
else {
if (uart->port == iot_board_get_uart(UART_ICC_PORT)) {
buf_len = UART_ICC_Q_LEN;
} else {
buf_len = UART_RX_Q_LEN;
}
}
rx_buf = (uint8_t *)os_mem_malloc(IOT_DRIVER_MID, buf_len);
if(rx_buf != NULL){
iot_ringbuf_init(&uart->rx_rb, rx_buf, buf_len);
} else {
IOT_ASSERT(0);
return 1;
}
return 0;
}
static int uart_rxbuf_free(uart_info *uart)
{
if ((NULL != uart) && (NULL != uart->rx_rb.data)) {
os_mem_free(uart->rx_rb.data);
}
return 0;
}
void uart_set_ir_loopback(uint8_t port, bool_t en)
{
if(port == g_uart_ir_port.port) {
g_uart_ir_port.ir_loopback = en;
}
}
#if UART_TXBUF_SUPPORT
static int uart_txbuf_alloc(uart_info *uart)
{
uint8_t *tx_buf = NULL;
tx_buf = (uint8_t *)os_mem_malloc(IOT_DRIVER_MID, UART_TX_Q_LEN);
if(tx_buf != NULL){
iot_ringbuf_init(&uart->tx_rb, tx_buf, UART_TX_Q_LEN);
} else {
IOT_ASSERT(0);
return 1;
}
return 0;
}
static int uart_txbuf_free(uart_info *uart)
{
if ((NULL != uart) && (NULL != uart->tx_rb.data)) {
os_mem_free(uart->tx_rb.data);
}
return 0;
}
#endif
static int uart_is_in_use(uint8_t uart_port)
{
uint32_t port_type;
int ret = 0;
for (port_type = UART_TYPE_MIN; port_type <= UART_TYPE_MAX; port_type++) {
if (uart_port == iot_board_get_uart(port_type)) {
ret = 1;
break;
}
}
return ret;
}
int uart_external_port_init(uint8_t max_port, uart_info* puart)
{
uint8_t txe_name[]= {GPIO_EXT_RS485_TXE1, GPIO_EXT_RS485_TXE2,
GPIO_EXT_RS485_TXE3, GPIO_EXT_RS485_TXE4};
uint8_t pport;
uint32_t lport;
if (0 == max_port) {
return ERR_OK;
}
#if IOT_EXTERNAL_UART_PORT_ENABLE
p_uart_ext_ctrl = &g_uart_ext_driver;
#endif
for (pport = 0; pport < max_port; pport++) {
lport = iot_uart_pport_to_lport(UART_TYPE_EXT, pport);
puart->port = lport;
/* TODO : Get from board_info */
puart->type = PORT_TYPE_RS485;
if (PORT_TYPE_RS485 == puart->type) {
puart->txe_pin = iot_board_get_gpio(txe_name[pport]);
} else {
puart->txe_pin = GPIO_NO_VALID;
}
puart->irq = gpio_hw_get_int_vector(); /* Not used. */
puart->termios.c_ispeed = B9600;
puart->termios.c_ospeed = B9600;
puart->termios.c_cflag = CS8 | ~CSTOPB | ~PARENB;
puart->drv = p_uart_ext_ctrl;
if (uart_is_in_use(puart->port)) {
if (uart_rxbuf_alloc(puart)) {
return ERR_FAIL;
}
}
#if UART_TXBUF_SUPPORT
if(uart_txbuf_alloc(puart)) {
return ERR_FAIL;
}
#endif
puart++;
}
return ERR_OK;
}
int uart_onchip_port_init(uart_info* puart)
{
uint8_t port, print_port;
int vec;
print_port = iot_board_get_uart(UART_PRINT);
for (port = 0; port < IOT_UART_PORT_NUM_ONCHIP; port++) {
puart->port = iot_uart_pport_to_lport(UART_TYPE_OC, port);
puart->txe_pin = GPIO_NO_VALID;
puart->termios.c_ispeed = B9600;
puart->termios.c_ospeed = B9600;
puart->termios.c_cflag = CS8 | ~CSTOPB | ~PARENB;
puart->drv = &g_uart_ctrl;
if (print_port != puart->port) {
vec = puart->drv->get_vector(port);
puart->handle = iot_interrupt_create(vec,
HAL_INTR_PRI_4, (iot_addrword_t)puart->port, uart_handler);
puart->irq = vec;
if (uart_is_in_use(puart->port)) {
if (uart_rxbuf_alloc(puart)) {
return ERR_FAIL;
}
}
#if UART_TXBUF_SUPPORT
uart_txbuf_alloc(puart);
#endif
}
puart++;
}
return ERR_OK;
}
int system_uart_deinit();
int system_uart_init()
{
/* Get external port num. */
// 外置串口数目 目前是0
uint8_t port = iot_board_get_external_uart_port_num();
uart_info *p_uart_info = NULL;
int i;
// 获得串口api
g_uart_ctrl = uart_e_ctrl;
g_uart_ext_num = (int)port;
port = IOT_UART_PORT_NUM_ONCHIP + g_uart_ext_num;
if (NULL == (p_uart_info
= os_mem_malloc(IOT_DRIVER_MID, port * sizeof(*p_uart_info)))) {
return 1;
}
os_mem_set(p_uart_info, 0x0, port * sizeof(*p_uart_info));
g_uart_rs485_num = IOT_UART_PORT_NUM_ONCHIP + g_uart_ext_num;
if (NULL == (g_uart_rs485_port
= os_mem_malloc(IOT_DRIVER_MID,
g_uart_rs485_num * sizeof(struct uart_rs485_ctrl)))) {
return 1;
}
os_mem_set(g_uart_rs485_port, 0x0,
g_uart_rs485_num * sizeof(struct uart_rs485_ctrl));
// 初始化所有串口,设置中断回调函数,除了打印串口
if (ERR_OK != uart_onchip_port_init(p_uart_info)) {
goto error_out;
}
// 外置串口数量为0 这里直接返回成功
if (ERR_OK != uart_external_port_init(g_uart_ext_num,
p_uart_info + IOT_UART_PORT_NUM_ONCHIP)) {
goto error_out;
}
g_uart_info = p_uart_info;
for(i = 0; i < g_uart_rs485_num; i++) {
g_uart_rs485_port[i].dir_gpio = GPIO_NO_VALID;
}
for (i = 0; i < RS485_PORT_NUM; i++) {
uint8_t t_port = iot_board_get_uart(uart_rs485_cfg[i].port_type);
if(t_port < port)
{
g_uart_rs485_port[t_port].dir_gpio
= iot_board_get_gpio(uart_rs485_cfg[i].gpio_type);
}
}
#ifdef RS485_DEBUG_TEST
for (i = 0; i < RS485_PORT_NUM; i++) {
if(0 == g_uart_rs485_port[i].port)
{
g_uart_rs485_port[i].fd = USART1_FILENO;
g_uart_rs485_port[i].base = 0x44001000;
}
else if(1 == g_uart_rs485_port[i].port)
{
g_uart_rs485_port[i].fd = USART2_FILENO;
g_uart_rs485_port[i].base = 0x44005000;
}
else if(2 == g_uart_rs485_port[i].port)
{
g_uart_rs485_port[i].fd = USART3_FILENO;
g_uart_rs485_port[i].base = 0x44006000;
}
else
{
g_uart_rs485_port[i].fd = USART4_FILENO;
g_uart_rs485_port[i].base = 0x44010000;
}
g_uart_rs485_port[i].cnt_rxi = 0;
g_uart_rs485_port[i].cnt_rti = 0;
g_uart_rs485_port[i].cnt_txd = 0;
g_uart_rs485_port[i].cnt_txi = 0;
g_uart_rs485_port[i].cnt_tx_size = 0;
g_uart_rs485_port[i].cnt_rx_size = 0;
g_uart_rs485_port[i].cnt_rx_ring_ovfl_byte = 0;
g_uart_rs485_port[i].cnt_rx_ovfl = 0;
g_uart_rs485_port[i].int_ena = 0;
g_uart_rs485_port[i].int_raw = 0;
g_uart_rs485_port[i].int_sts = 0;
}
#endif
return 0;
error_out:
g_uart_info = p_uart_info;
system_uart_deinit();
return 1;
}
int system_uart_deinit()
{
uint8_t port, print_port = iot_board_get_uart(UART_PRINT);
if (NULL == g_uart_info) {
return 0;
}
for (port = 0; port < g_uart_ext_num + IOT_UART_PORT_NUM_ONCHIP;
port++) {
if (print_port != port) {
uart_rxbuf_free(g_uart_info + port);
#if UART_TXBUF_SUPPORT
uart_txbuf_free(g_uart_info + port);
#endif
}
}
os_mem_free(g_uart_info);
g_uart_info = NULL;
g_uart_ext_num = 0;
return 0;
}