AM335x Linux uart 串口(rs485rs232)无法正常通信的一种解决方法
先大概說說我是如何解決rs485(uart4)&rs233(uart5)的通信問題。
首先,在kernel-AGV/drivers/tty/serial/omap-serial.c中確定串口的默認時鐘頻率。
接著,在kernel/arch/arm/mach-omap2/board-ipc335x.c和kernel/arch/arm/mach-omap2/mux33xx.c中查看uart4(和流控腳)&uart5的配置;說明一下,board-ipc335x.c這個文件是根據evm板進行的更改,與各位的板級配置文件名可能不一致。
?
?
?
?從而確認板級配置沒有問題。
進一步的,查看uart_omap_port_set_rts_gpio函數的定義,將gpio設置成rts_gpio;
?重點查看drivers/tty/serial目錄,找到8250.c文件。通過更改nr_uarts的賦值達成目的,
/*static unsigned int nr_uarts = CONFIG_SERIAL_8250_RUNTIME_UARTS;*/ static unsigned int nr_uarts = 5; //支持uart0~5 static void __init serial8250_isa_init_ports(void) {struct uart_8250_port *up;static int first = 1;int i, irqflag = 0;if (!first)return;first = 0;for (i = 0; i < nr_uarts; i++) {struct uart_8250_port *up = &serial8250_ports[i];up->port.line = i;spin_lock_init(&up->port.lock);init_timer(&up->timer);up->timer.function = serial8250_timeout;/** ALPHA_KLUDGE_MCR needs to be killed.*/up->mcr_mask = ~ALPHA_KLUDGE_MCR;up->mcr_force = ALPHA_KLUDGE_MCR;up->port.ops = &serial8250_pops;}if (share_irqs)irqflag = IRQF_SHARED;for (i = 0, up = serial8250_ports;i < ARRAY_SIZE(old_serial_port) && i < nr_uarts;i++, up++) {up->port.iobase = old_serial_port[i].port;up->port.irq = irq_canonicalize(old_serial_port[i].irq);up->port.irqflags = old_serial_port[i].irqflags;up->port.uartclk = old_serial_port[i].baud_base * 16;up->port.flags = old_serial_port[i].flags;up->port.hub6 = old_serial_port[i].hub6;up->port.membase = old_serial_port[i].iomem_base;up->port.iotype = old_serial_port[i].io_type;up->port.regshift = old_serial_port[i].iomem_reg_shift;set_io_from_upio(&up->port);up->port.irqflags |= irqflag;if (serial8250_isa_config != NULL)serial8250_isa_config(i, &up->port, &up->capabilities);} }此時uart4&uart5雖然可以正常使用,但是rs485(uart4)仍然不能正常通訊,最后查閱documentation目錄下的serial-rs485.txt;如下:
??????????????????????? RS485 SERIAL COMMUNICATIONS
1. INTRODUCTION
?? EIA-485, also known as TIA/EIA-485 or RS-485, is a standard defining the
?? electrical characteristics of drivers and receivers for use in balanced
?? digital multipoint systems.
?? This standard is widely used for communications in industrial automation
?? because it can be used effectively over long distances and in electrically
?? noisy environments.
2. HARDWARE-RELATED CONSIDERATIONS
?? Some CPUs/UARTs (e.g., Atmel AT91 or 16C950 UART) contain a built-in
?? half-duplex mode capable of automatically controlling line direction by
?? toggling RTS or DTR signals. That can be used to control external
?? half-duplex hardware like an RS485 transceiver or any RS232-connected
?? half-duplex devices like some modems.
?? For these microcontrollers, the Linux driver should be made capable of
?? working in both modes, and proper ioctls (see later) should be made
?? available at user-level to allow switching from one mode to the other, and
?? vice versa.
3. DATA STRUCTURES ALREADY AVAILABLE IN THE KERNEL
?? The Linux kernel provides the serial_rs485 structure (see [1]) to handle
?? RS485 communications. This data structure is used to set and configure RS485
?? parameters in the platform data and in ioctls.
?? The device tree can also provide RS485 boot time parameters (see [2]
?? for bindings). The driver is in charge of filling this data structure from
?? the values given by the device tree.
?? Any driver for devices capable of working both as RS232 and RS485 should
?? provide at least the following ioctls:
??? - TIOCSRS485 (typically associated with number 0x542F). This ioctl is used
????? to enable/disable RS485 mode from user-space
??? - TIOCGRS485 (typically associated with number 0x542E). This ioctl is used
????? to get RS485 mode from kernel-space (i.e., driver) to user-space.
?? In other words, the serial driver should contain a code similar to the next
?? one:
?? ?static struct uart_ops atmel_pops = {
?? ??? ?/* ... */
?? ??? ?.ioctl?? ??? ?= handle_ioctl,
?? ?};
?? ?static int handle_ioctl(struct uart_port *port,
?? ??? ?unsigned int cmd,
?? ??? ?unsigned long arg)
?? ?{
?? ??? ?struct serial_rs485 rs485conf;
?? ??? ?switch (cmd) {
?? ??? ?case TIOCSRS485:
?? ??? ??? ?if (copy_from_user(&rs485conf,
?? ??? ??? ??? ?(struct serial_rs485 *) arg,
?? ??? ??? ??? ?sizeof(rs485conf)))
?? ??? ??? ??? ??? ?return -EFAULT;
?? ??? ??? ?/* ... */
?? ??? ??? ?break;
?? ??? ?case TIOCGRS485:
?? ??? ??? ?if (copy_to_user((struct serial_rs485 *) arg,
?? ??? ??? ??? ?...,
?? ??? ??? ??? ?sizeof(rs485conf)))
?? ??? ??? ??? ??? ?return -EFAULT;
?? ??? ??? ?/* ... */
?? ??? ??? ?break;
?? ??? ?/* ... */
?? ??? ?}
?? ?}
4. USAGE FROM USER-LEVEL
?? From user-level, RS485 configuration can be get/set using the previous
?? ioctls. For instance, to set RS485 you can use the following code:
?? ?#include <linux/serial.h>
?? ?/* Driver-specific ioctls: */
?? ?#define TIOCGRS485????? 0x542E
?? ?#define TIOCSRS485????? 0x542F
?? ?/* Open your specific device (e.g., /dev/mydevice): */
?? ?int fd = open ("/dev/mydevice", O_RDWR);
?? ?if (fd < 0) {
?? ??? ?/* Error handling. See errno. */
?? ?}
?? ?struct serial_rs485 rs485conf;
?? ?/* Enable RS485 mode: */
?? ?rs485conf.flags |= SER_RS485_ENABLED;
?? ?/* Set logical level for RTS pin equal to 1 when sending: */
?? ?rs485conf.flags |= SER_RS485_RTS_ON_SEND;
?? ?/* or, set logical level for RTS pin equal to 0 when sending: */
?? ?rs485conf.flags &= ~(SER_RS485_RTS_ON_SEND);
?? ?/* Set logical level for RTS pin equal to 1 after sending: */
?? ?rs485conf.flags |= SER_RS485_RTS_AFTER_SEND;
?? ?/* or, set logical level for RTS pin equal to 0 after sending: */
?? ?rs485conf.flags &= ~(SER_RS485_RTS_AFTER_SEND);
?? ?/* Set rts delay before send, if needed: */
?? ?rs485conf.delay_rts_before_send = ...;
?? ?/* Set rts delay after send, if needed: */
?? ?rs485conf.delay_rts_after_send = ...;
?? ?/* Set this flag if you want to receive data even whilst sending data */
?? ?rs485conf.flags |= SER_RS485_RX_DURING_TX;
?? ?if (ioctl (fd, TIOCSRS485, &rs485conf) < 0) {
?? ??? ?/* Error handling. See errno. */
?? ?}
?? ?/* Use read() and write() syscalls here... */
?? ?/* Close the device when finished: */
?? ?if (close (fd) < 0) {
?? ??? ?/* Error handling. See errno. */
?? ?}
5. REFERENCES
?[1]?? ?include/linux/serial.h
?[2]?? ?Documentation/devicetree/bindings/serial/rs485.txt
根據serial-rs485.txt給出的提示,在Linux下編譯下面的代碼,將生成的二進制可執行文件放入AM335x內核的文件系統中,執行它即可實現rs485通信(之所以需要執行該程序,是因為底層驅動配置中沒有配置對應uart作為rs485的功能)。
#include <stdio.h> #include <stdlib.h> #include <unistd.h> #include <sys/types.h> #include <sys/stat.h> #include <linux/serial.h> #include <fcntl.h> #include <termios.h> #include <errno.h> #include <sys/ioctl.h>#define FALSE -1 #define TRUE 0 /* Driver-specific ioctls: */ #define TIOCGRS485 0x542E #define TIOCSRS485 0x542Fvoid set_speed(int fd, int speed){ int speed_arr[] = { B115200, B38400, B19200, B9600, B4800, B2400, B1200, B300,B38400, B19200, B9600, B4800, B2400, B1200, B300, }; int name_arr[] = { 115200, 38400, 19200, 9600, 4800, 2400, 1200, 300, 38400, 19200, 9600, 4800, 2400, 1200, 300, }; int i; int status; struct termios Opt; tcgetattr(fd, &Opt); for ( i= 0; i < sizeof(speed_arr) / sizeof(int); i++) { if (speed == name_arr[i]) { tcflush(fd, TCIOFLUSH); cfsetispeed(&Opt, speed_arr[i]); cfsetospeed(&Opt, speed_arr[i]); status = tcsetattr(fd, TCSANOW, &Opt); if (status != 0) { perror("tcsetattr fd1"); return; } tcflush(fd,TCIOFLUSH); } } } int set_Parity(int fd,int databits,int stopbits,int parity) { struct termios options; if ( tcgetattr( fd,&options) != 0) { perror("SetupSerial 1"); return(FALSE); } options.c_cflag &= ~CSIZE; switch (databits) { case 7: options.c_cflag |= CS7; break; case 8: options.c_cflag |= CS8; break; default: fprintf(stderr,"Unsupported data size\n"); return (FALSE); } switch (parity) { case 'n': case 'N': options.c_cflag &= ~PARENB; /* Clear parity enable */ options.c_iflag &= ~INPCK; /* Enable parity checking */ break; case 'o': case 'O': options.c_cflag |= (PARODD | PARENB); options.c_iflag |= INPCK; /* Disnable parity checking */ break; case 'e': case 'E': options.c_cflag |= PARENB; /* Enable parity */ options.c_cflag &= ~PARODD; options.c_iflag |= INPCK; /* Disnable parity checking */ break; case 'S': case 's': /*as no parity*/ options.c_cflag &= ~PARENB; options.c_cflag &= ~CSTOPB;break; default: fprintf(stderr,"Unsupported parity\n"); return (FALSE); } switch (stopbits) { case 1: options.c_cflag &= ~CSTOPB; break; case 2: options.c_cflag |= CSTOPB; break; default: fprintf(stderr,"Unsupported stop bits\n"); return (FALSE); } /* Set input parity option */ if (parity != 'n') options.c_iflag |= INPCK; tcflush(fd,TCIFLUSH); options.c_cc[VTIME] = 150; options.c_cc[VMIN] = 0; /* Update the options and do it NOW */ if (tcsetattr(fd,TCSANOW,&options) != 0) { perror("SetupSerial 3"); return (FALSE); } return (TRUE); }int read_datatty(int fd, unsigned char *rcv_buf, int TimeOut, int Len) {int retval;fd_set rfds;struct timeval tv;int ret, pos;tv.tv_sec = TimeOut / 1000; //set the rcv wait timetv.tv_usec = TimeOut % 1000 * 1000; //100000us = 0.1spos = 0;while (1){FD_ZERO(&rfds);FD_SET(fd, &rfds);retval = select(fd + 1, &rfds, NULL, NULL, &tv);if (retval == -1){perror("select()");break;}else if (retval){ret = read(fd, rcv_buf + pos, 1);if (-1 == ret){printf("read error\n");break;}pos++;if (Len <= pos){break;}}else{printf("select_timeout\n");break;}}return pos; }int main() { int fdO4; int ret;fdO4 = open("/dev/ttyO4",O_RDWR);if(fdO4 == -1) { perror("serialport error\n"); }else { printf("open "); printf("%s",ttyname(fdO4)); printf(" successfully\n"); } struct serial_rs485 rs485conf;/* Enable RS485 mode: */rs485conf.flags |= SER_RS485_ENABLED;/* Set logical level for RTS pin equal to 1 when sending: */rs485conf.flags |= SER_RS485_RTS_ON_SEND;/* Set logical level for RTS pin equal to 0 after sending: */rs485conf.flags &= ~(SER_RS485_RTS_AFTER_SEND);/* Set this flag if you want to receive data even whilst sending data *//*rs485conf.flags |= SER_RS485_RX_DURING_TX;*/if (ioctl (fdO4, TIOCSRS485, &rs485conf) < 0) {printf("ioctl Error\n");}set_speed(fdO4,115200); if (set_Parity(fdO4,8,1,'N') == FALSE) { printf("Set Parity Error\n"); exit(-1); }unsigned char recvbuf[20] = { 0 };const unsigned char sendbuf[] ={ 0x08, 0x03, 0x00, 0x04, 0x00, 0x04, 0x05, 0x51 };ret = write(fdO4, sendbuf, 8);if (ret == -1){printf("write device error\n");}else if (ret == 8){printf("write_suc\n");} read_datatty(fdO4, recvbuf, 2000, 14);for(int i = 1; i < 14; i++) {printf("%x ",recvbuf[i]);}printf("\n");close(fdO4);return 0; }一階段結束,然后我們來大致分析下uart初始化過程;
首先是uart驅動框架
uart驅動架構:
?
Linux tty subsystem:
在論述串口初始化之前,將簡要說明一些重要的數據結構;順便插一句,對于通用串口控制器,THR(發送保持寄存器)、RHR(接收保持寄存器)、IER(中斷使能寄存器)、FCR(緩沖控制寄存器)、LCR(控制寄存器)、LSR(狀態寄存器)、MCR(模式控制寄存器)、MSR(模式狀態寄存器)
struct uart_driver : 用于描述串口結構,一個串口對應一個串口驅動
struct uart_driver {
struct module?? *owner; //模塊所有者
const char? *driver_name;?? //驅動名
const char? *dev_name;? //設備名
int? major; //主設備號
int? minor; //次設備號
int? nr;??? //支持串口個數
struct console? *cons;//控制臺設備
//下面兩個變量應被初始化為NULL
//tty_driver在函數register_uart_driver中被賦值,同時state也會被分配空間
//最后通過uart_add_one_port添加uart_state->uart_port
struct uart_state?? *state; //串口狀態,下層(串口驅動層)
struct tty_driver?? *tty_driver; //tty相關
};
struct uart_port : 串口端口結構體,有幾個串口就對應幾個uart_port
struct uart_port {
spinlock_t? lock;
unsigned long?? iobase; //io端口基地址(物理地址)
unsigned char __iomem?? *membase; //io內存基地址(虛擬地址)
unsigned int??? (*serial_in)(struct uart_port *, int); //串口讀函數
void??? (*serial_out)(struct uart_port *, int, int); //串口寫方法
void??? (*set_termios)(struct uart_port *,struct ktermios *new,struct ktermios *old); //串口配置方法函數
void??? (*pm)(struct uart_port *, unsigned int state,unsigned int old);
unsigned int??? irq;??? //中斷號
unsigned long?? irqflags;?? //中斷標志
unsigned int??? uartclk;?? //串口時鐘
unsigned int??? fifosize;?? //fifo大小
unsigned char?? x_char;
unsigned char?? regshift;?? //寄存器偏移值
unsigned char?? iotype; //io訪問類型
unsigned char?? unused1;
unsigned int??? read_status_mask;
unsigned int??? ignore_status_mask;
struct uart_state?? *state; //uart_state結構體
struct uart_icount? icount; //串口使用計數
struct console? *cons;? //console控制臺
#if defined(CONFIG_SERIAL_CORE_CONSOLE) || defined(SUPPORT_SYSRQ)
unsigned long?? sysrq;
#endif
upf_t?? flags;
unsigned int??? mctrl;
unsigned int??? timeout;
unsigned int??? type; //串口類型
const struct uart_ops?? *ops;?? //串口操作函數集
unsigned int??? custom_divisor;
unsigned int??? line;?? //端口號
resource_size_t mapbase; //串口寄存器基地址(物理地址)
struct device?? *dev;?? //設備文件
unsigned char?? hub6;
unsigned char?? suspended;
unsigned char?? irq_wake;
unsigned char?? unused[2];
void??? *private_data;
};
struct uart_ops : 串口相關操作函數集
struct uart_ops {
unsigned int??? (*tx_empty)(struct uart_port *);??? //發送緩沖區為空
void??? (*set_mctrl)(struct uart_port *, unsigned int mctrl);?? //設置串口modem控制模式
unsigned int??? (*get_mctrl)(struct uart_port *);?? //獲取串口modem控制模式
void??? (*stop_tx)(struct uart_port *); //停止發送
void??? (*start_tx)(struct uart_port *);??? //開始發送
void??? (*send_xchar)(struct uart_port *, char ch);
void??? (*stop_rx)(struct uart_port *); //停止接收
void??? (*enable_ms)(struct uart_port *);?? //使能modem狀態信息
void??? (*break_ctl)(struct uart_port *, int ctl);
int (*startup)(struct uart_port *); //打開串口
void??? (*shutdown)(struct uart_port *);??? //關閉串口
void??? (*flush_buffer)(struct uart_port *);
void??? (*set_termios)(struct uart_port *, struct ktermios *new,struct ktermios *old);? //設置串口參數
void??? (*set_ldisc)(struct uart_port *, int new);
void??? (*pm)(struct uart_port *, unsigned int state,unsigned int oldstate);
int (*set_wake)(struct uart_port *, unsigned int state);
const char *(*type)(struct uart_port *);
void??? (*release_port)(struct uart_port *);??? //釋放端口
int (*request_port)(struct uart_port *);??? //請求端口
void??? (*config_port)(struct uart_port *, int);??? //配置端口
int (*verify_port)(struct uart_port *, struct serial_struct *); //校驗端口
int (*ioctl)(struct uart_port *, unsigned int, unsigned long);? //控制
#ifdef CONFIG_CONSOLE_POLL
void??? (*poll_put_char)(struct uart_port *, unsigned char);
int (*poll_get_char)(struct uart_port *);
#endif
};
struct uart_state : 描述串口狀態信息
struct uart_state {
struct tty_port port;
int???? pm_state; //電源狀態
struct circ_buf xmit; //數據緩沖區
struct tasklet_struct?? tlet;
struct uart_port??? *uart_port;//指向對應的串口結構
};
uart初始化:
大致為:分配一個struct uart_driver用于定義并描述串口,再調用uart_register_driver注冊串口驅動,最后調用uart_add_one_port添加端口到串口設備。
static struct uart_driver serial8250_reg = {
.owner????????????????? = THIS_MODULE,
.driver_name???????? = “serial”,
.dev_name??????????? = “ttyS”,
.major?????????????????? = TTY_MAJAOR,
.minor????????????????? = 64,
.cons??????????????????? = SERIAL8250_CONSOLE,
};
static int __init serial8250_init(void)
{
?????? int ret;
?????? if (nr_uarts > UART_NR)
????????????? nr_uarts = UART_NR;
?????? printk(KERN_INFO "Serial: 8250/16550 driver, "
????????????? "%d ports, IRQ sharing %sabled\n", nr_uarts,
????????????? share_irqs ? "en" : "dis");
#ifdef CONFIG_SPARC
?????? ret = sunserial_register_minors(&serial8250_reg, UART_NR);
#else
?????? serial8250_reg.nr = UART_NR; //串口數量
?????? ret = uart_register_driver(&serial8250_reg); //注冊串口驅動
#endif
?????? if (ret)
????????????? goto out;
?????? serial8250_isa_devs = platform_device_alloc("serial8250",
????????????????????????????????????????? ??? PLAT8250_DEV_LEGACY);
?????? if (!serial8250_isa_devs) {
????????????? ret = -ENOMEM;
????????????? goto unreg_uart_drv;
?????? }
?????? ret = platform_device_add(serial8250_isa_devs);
?????? if (ret)
????????????? goto put_dev;
?????? serial8250_register_ports(&serial8250_reg, &serial8250_isa_devs->dev);
?????? ret = platform_driver_register(&serial8250_isa_driver);
?????? if (ret == 0)
????????????? goto out;
?????? platform_device_del(serial8250_isa_devs);
put_dev:
?????? platform_device_put(serial8250_isa_devs);
unreg_uart_drv:
#ifdef CONFIG_SPARC
?????? sunserial_unregister_minors(&serial8250_reg, UART_NR);
#else
?????? uart_unregister_driver(&serial8250_reg);
#endif
out:
?????? return ret;
}
int uart_register_driver(struct uart_driver *drv)
{
?????? struct tty_driver *normal;
?????? int i, retval;
?????? BUG_ON(drv->state);
?????? /*
?????? ?* Maybe we should be using a slab cache for this, especially if
?????? ?* we have a large number of ports to handle.
?????? ?*/
?????? drv->state = kzalloc(sizeof(struct uart_state) * drv->nr, GFP_KERNEL);
?????? if (!drv->state)
????????????? goto out;
?????? normal = alloc_tty_driver(drv->nr);
?????? if (!normal)
????????????? goto out_kfree;
?????? drv->tty_driver = normal; //賦值給uart_driver結構的tty_driver成員
?????? //對tty_driver成員指向的結構初始化
?????? normal->owner?????????? = drv->owner;
?????? normal->driver_name? = drv->driver_name;
?????? normal->name??????????? = drv->dev_name;
?????? normal->major??????????? = drv->major;
?????? normal->minor_start?? = drv->minor;
?????? normal->type????????????? = TTY_DRIVER_TYPE_SERIAL;
?????? normal->subtype??????? = SERIAL_TYPE_NORMAL;
?????? normal->init_termios?? = tty_std_termios; // drivers/tty/tty_io.c
?????? normal->init_termios.c_cflag = B9600 | CS8 | CREAD | HUPCL | CLOCAL;
?????? normal->init_termios.c_ispeed = normal->init_termios.c_ospeed = 9600;
?????? normal->flags???????????? = TTY_DRIVER_REAL_RAW | TTY_DRIVER_DYNAMIC_DEV;
?????? normal->driver_state??? = drv;
?????? //將tty_driver結構的normal操作指向uart_ops ,即tty_ops封裝uart_ops
tty_set_operations(normal, &uart_ops);
?????? /*
?????? ?* Initialise the UART state(s).
?????? ?*/
?????? for (i = 0; i < drv->nr; i++) {
????????????? struct uart_state *state = drv->state + i;
????????????? struct tty_port *port = &state->port;
?????? ?????? tty_port_init(port);
????????????? port->ops = &uart_port_ops;
????????????? port->close_delay???? = 500;??? /* .5 seconds */
????????????? port->closing_wait??? = 30000; /* 30 seconds */
?????? }
?????? retval = tty_register_driver(normal);
?????? if (retval >= 0)
????????????? return retval;
?????? put_tty_driver(normal);
out_kfree:
?????? kfree(drv->state);
out:
?????? return -ENOMEM;
}
//初始化uart_port
static void __init serial8250_isa_init_ports(void)
{
?????? struct uart_8250_port *up;
?????? static int first = 1;
?????? int i, irqflag = 0;
?????? if (!first)
????????????? return;
?????? first = 0;
?????? for (i = 0; i < nr_uarts; i++) {
????????????? struct uart_8250_port *up = &serial8250_ports[i];
????????????? up->port.line = i; //串口號,i==0對應串口0
????????????? spin_lock_init(&up->port.lock);
????????????? init_timer(&up->timer); //初始化定時器
????????????? up->timer.function = serial8250_timeout; //初始化定時器超時函數
????????????? /*
????????????? ?* ALPHA_KLUDGE_MCR needs to be killed.
????????????? ?*/
????????????? up->mcr_mask = ~ALPHA_KLUDGE_MCR;
????????????? up->mcr_force = ALPHA_KLUDGE_MCR;
????????????? up->port.ops = &serial8250_pops;
?????? }
/******************************************
static struct uart_ops serial8250_pops = {
.tx_empty?= serial8250_tx_empty,
.set_mctrl?= serial8250_set_mctrl,
.get_mctrl?= serial8250_get_mctrl,
.stop_tx?= serial8250_stop_tx,
.start_tx?= serial8250_start_tx,
.stop_rx?= serial8250_stop_rx,
.enable_ms?= serial8250_enable_ms,
.break_ctl?= serial8250_break_ctl,
.startup?= serial8250_startup,
.shutdown?= serial8250_shutdown,
.set_termios?= serial8250_set_termios,
.set_ldisc?= serial8250_set_ldisc,
.pm??= serial8250_pm,
.type??= serial8250_type,
.release_port?= serial8250_release_port,
.request_port?= serial8250_request_port,
.config_port?= serial8250_config_port,
.verify_port?= serial8250_verify_port,
#ifdef CONFIG_CONSOLE_POLL
.poll_get_char = serial8250_get_poll_char,
.poll_put_char = serial8250_put_poll_char,
#endif
};
******************************************/
?????? if (share_irqs) //中斷是否共享
????????????? irqflag = IRQF_SHARED;
?????? for (i = 0, up = serial8250_ports;
?????? ???? i < ARRAY_SIZE(old_serial_port) && i < nr_uarts;
?????? ???? i++, up++) {
????????????? up->port.iobase?? = old_serial_port[i].port;
????????????? up->port.irq????? = irq_canonicalize(old_serial_port[i].irq);
????????????? up->port.irqflags = old_serial_port[i].irqflags;
????????????? up->port.uartclk? = old_serial_port[i].baud_base * 16;
????????????? up->port.flags??? = old_serial_port[i].flags;
????????????? up->port.hub6???? = old_serial_port[i].hub6;
????????????? up->port.membase? = old_serial_port[i].iomem_base;
????????????? up->port.iotype?? = old_serial_port[i].io_type;
????????????? up->port.regshift = old_serial_port[i].iomem_reg_shift;
????????????? set_io_from_upio(&up->port);
????????????? up->port.irqflags |= irqflag;
????????????? if (serial8250_isa_config != NULL)
???????????????????? serial8250_isa_config(i, &up->port, &up->capabilities);
?????? }
}
/**
?*??? uart_add_one_port - attach a driver-defined port structure
?*??? @drv: pointer to the uart low level driver structure for this port
?*??? @uport: uart port structure to use for this port.
?*
?*??? This allows the driver to register its own uart_port structure
?*??? with the core driver.? The main purpose is to allow the low
?*??? level uart drivers to expand uart_port, rather than having yet
?*??? more levels of structures.
?*/
int uart_add_one_port(struct uart_driver *drv, struct uart_port *uport)
{
?????? struct uart_state *state;
?????? struct tty_port *port;
?????? int ret = 0;
?????? struct device *tty_dev;
?????? BUG_ON(in_interrupt());
?????? if (uport->line >= drv->nr)
????????????? return -EINVAL;
?????? state = drv->state + uport->line;
?????? port = &state->port;
?????? mutex_lock(&port_mutex);
?????? mutex_lock(&port->mutex);
?????? if (state->uart_port) {
????????????? ret = -EINVAL;
????????????? goto out;
?????? }
?????? state->uart_port = uport;
?????? state->pm_state = -1;
?????? uport->cons = drv->cons;
?????? uport->state = state;
?????? /*
?????? ?* If this port is a console, then the spinlock is already
?????? ?* initialised.
?????? ?*/
?????? if (!(uart_console(uport) && (uport->cons->flags & CON_ENABLED))) {
????????????? spin_lock_init(&uport->lock);
????????????? lockdep_set_class(&uport->lock, &port_lock_key);
?????? }
//進行port的自動配置,在未進行serial8250_probe()時,串口的port->iobase(io基地址)、port->mapbase(串口寄存器基地址)、port->membase(io內存基地址)都為空,所以函數進去會立即返回,即未配置成功。
//當進行完serial8250_probe()函數時,還會調用uart_add_one_port(),再到這個函數配置時就會配置成功
?????? uart_configure_port(drv, state, uport);
?????? /*
?????? ?* Register the port whether it's detected or not.? This allows
?????? ?* setserial to be used to alter this ports parameters.
?????? ?*/
?????? tty_dev = tty_register_device(drv->tty_driver, uport->line, uport->dev);
?????? if (likely(!IS_ERR(tty_dev))) {
????????????? device_init_wakeup(tty_dev, 1);
????????????? device_set_wakeup_enable(tty_dev, 0);
?????? } else
????????????? printk(KERN_ERR "Cannot register tty device on line %d\n",
????????????? ?????? uport->line);
?????? /*
?????? ?* Ensure UPF_DEAD is not set.
?????? ?*/
?????? uport->flags &= ~UPF_DEAD;
?out:
?????? mutex_unlock(&port->mutex);
?????? mutex_unlock(&port_mutex);
?????? return ret;
}
static void
uart_configure_port(struct uart_driver *drv, struct uart_state *state,
????????????? ??? struct uart_port *port)
{
?????? unsigned int flags;
?????? /*
?????? ?* If there isn't a port here, don't do anything further.
?????? ?*/
?????? //未調用serial8250_probe()之前,會從這里直接返回
?????? if (!port->iobase && !port->mapbase && !port->membase)
????????????? return;
?????? /*
?????? ?* Now do the auto configuration stuff.? Note that config_port
?????? ?* is expected to claim the resources and map the port for us.
?????? ?*/
?????? flags = 0;
?????? if (port->flags & UPF_AUTO_IRQ)
????????????? flags |= UART_CONFIG_IRQ;
?????? if (port->flags & UPF_BOOT_AUTOCONF) {
????????????? if (!(port->flags & UPF_FIXED_TYPE)) { //經過probe()函數,已設置該標志,不執行???????????????
port->type = PORT_UNKNOWN;
???????????????????? flags |= UART_CONFIG_TYPE;
????????????? }
//調用設備的自動配置函數,即serial8250_config_port()
????????????? port->ops->config_port(port, flags); }
?????? if (port->type != PORT_UNKNOWN) {
????????????? unsigned long flags;
????????????? uart_report_port(drv, port); //打印串口信息
????????????? /* Power up port for set_mctrl() */
????????????? uart_change_pm(state, 0);
????????????? /*
????????????? ?* Ensure that the modem control lines are de-activated.
????????????? ?* keep the DTR setting that is set in uart_set_options()
????????????? ?* We probably don't need a spinlock around this, but
????????????? ?*/
????????????? spin_lock_irqsave(&port->lock, flags);
????????????? port->ops->set_mctrl(port, port->mctrl & TIOCM_DTR);
????????????? spin_unlock_irqrestore(&port->lock, flags);
????????????? /*
????????????? ?* If this driver supports console, and it hasn't been
????????????? ?* successfully registered yet, try to re-register it.
????????????? ?* It may be that the port was not available.
????????????? ?*/
????????????? if (port->cons && !(port->cons->flags & CON_ENABLED))
???????????????????? register_console(port->cons);
????????????? /*
????????????? ?* Power down all ports by default, except the
????????????? ?* console if we have one.
????????????? ?*/
????????????? if (!uart_console(port))
???????????????????? uart_change_pm(state, 3);
?????? }
}
/*
?* Register a set of serial devices attached to a platform device.? The
?* list is terminated with a zero flags entry, which means we expect
?* all entries to have at least UPF_BOOT_AUTOCONF set.
?*/
static int __devinit serial8250_probe(struct platform_device *dev)
{
?????? struct plat_serial8250_port *p = dev->dev.platform_data;
?????? struct uart_port port;
?????? int ret, i, irqflag = 0;
?????? memset(&port, 0, sizeof(struct uart_port));
?????? if (share_irqs)
????????????? irqflag = IRQF_SHARED;
?????? for (i = 0; p && p->flags != 0; p++, i++) {
????????????? port.iobase?????????? = p->iobase;
????????????? port.membase????? = p->membase;
????????????? port.irq????????? ?????? = p->irq;
????????????? port.irqflags????????? = p->irqflags;
????????????? port.uartclk?????????? = p->uartclk;
????????????? port.regshift????????? = p->regshift;
????????????? port.iotype??????????? = p->iotype;
????????????? port.flags????????????? = p->flags;
????????????? port.mapbase?????? = p->mapbase;
????????????? port.hub6???????????? = p->hub6;
????????????? port.private_data?? = p->private_data;
????????????? port.type??????? ?????? = p->type;
????????????? port.serial_in???????? = p->serial_in;
????????????? port.serial_out?????? = p->serial_out;
????????????? port.handle_irq???? = p->handle_irq;
????????????? port.set_termios??? = p->set_termios;
????????????? port.pm??????????????? = p->pm;
????????????? port.dev???????? = &dev->dev;
????????????? port.irqflags?? |= irqflag;
????????????? ret = serial8250_register_port(&port);
????????????? if (ret < 0) {
???????????????????? dev_err(&dev->dev, "unable to register port at index %d "
??????????????????????????? "(IO%lx MEM%llx IRQ%d): %d\n", i,
??????????????????????????? p->iobase, (unsigned long long)p->mapbase,
??????????????????????????? p->irq, ret);
????????????? }
?????? }
?????? return 0;
}
以上,基本就是uart初始化過程,當然忽略了platform_device、platform_drive;串口中的驅動分兩層,首先是基于控制臺的驅動,即serial8250_console,還有一個是基于UART的驅動,相當于我們在實際使用串口時,使用的set_termois,start_tx,stop_tx,start_rx,stop_rx等函數。本文只談論了基于uart的驅動,跳過基于console的驅動原因是uart4&uart5并不用作為控制臺。
文中存在不妥之處,還請指出,謝謝!
?
總結
以上是生活随笔為你收集整理的AM335x Linux uart 串口(rs485rs232)无法正常通信的一种解决方法的全部內容,希望文章能夠幫你解決所遇到的問題。
- 上一篇: 易语言多线程大漠多线程脚本主副线程
- 下一篇: 远程开关机命令