Search K
Appearance
Appearance
gpio-rs485.patch
diff --git a/Documentation/devicetree/bindings/serial/fsl-imx-uart.txt b/Documentation/devicetree/bindings/serial/fsl-imx-uart.txt
index 35ae1fb..9a0e120 100644
--- a/Documentation/devicetree/bindings/serial/fsl-imx-uart.txt
+++ b/Documentation/devicetree/bindings/serial/fsl-imx-uart.txt
@@ -6,6 +6,7 @@ Required properties:
- interrupts : Should contain uart interrupt
Optional properties:
+- fsl,rs485-gpio-txen : Indicate a GPIO is used as TXEN instead of RTS
- fsl,uart-has-rtscts : Indicate the uart has rts and cts
- fsl,irda-mode : Indicate the uart supports irda mode
- fsl,dte-mode : Indicate the uart works in DTE mode. The uart works
diff --git a/drivers/tty/serial/imx.c b/drivers/tty/serial/imx.c
index c9bd603..0390990 100644
--- a/drivers/tty/serial/imx.c
+++ b/drivers/tty/serial/imx.c
@@ -21,6 +21,7 @@
#define SUPPORT_SYSRQ
#endif
+#include <linux/gpio.h>
#include <linux/module.h>
#include <linux/ioport.h>
#include <linux/init.h>
@@ -37,6 +38,7 @@
#include <linux/slab.h>
#include <linux/of.h>
#include <linux/of_device.h>
+#include <linux/of_gpio.h>
#include <linux/io.h>
#include <linux/dma-mapping.h>
@@ -224,6 +226,7 @@ struct imx_port {
unsigned short trcv_delay; /* transceiver delay */
struct clk *clk_ipg;
struct clk *clk_per;
+ int txen_gpio;
const struct imx_uart_data *devdata;
/* DMA fields */
@@ -393,16 +396,38 @@ static void imx_stop_tx(struct uart_port *port)
temp = readl(port->membase + UCR1);
writel(temp & ~UCR1_TXMPTYEN, port->membase + UCR1);
+ if(sport->txen_gpio != -1 && readl(port->membase + USR2) & USR2_TXDC){
+ //mdelay(5);
+ //while(!(readl(sport->port.membase + uts_reg(sport)) & UTS_TXEMPTY)){
+ // udelay(1);
+ //}
+ gpio_set_value(sport->txen_gpio, 0);
+
+ /* disable shifter empty irq */
+ temp = readl(port->membase + UCR4);
+ temp &= ~UCR4_TCEN;
+ writel(temp, port->membase + UCR4);
+ }
+
/* in rs485 mode disable transmitter if shifter is empty */
if (port->rs485.flags & SER_RS485_ENABLED &&
readl(port->membase + USR2) & USR2_TXDC) {
- temp = readl(port->membase + UCR2);
- if (port->rs485.flags & SER_RS485_RTS_AFTER_SEND)
- temp &= ~UCR2_CTS;
- else
- temp |= UCR2_CTS;
- writel(temp, port->membase + UCR2);
+ if(sport->txen_gpio != -1){
+ if(port->rs485.flags & SER_RS485_RTS_AFTER_SEND)
+ gpio_set_value(sport->txen_gpio, 1);
+ else
+ gpio_set_value(sport->txen_gpio, 0);
+
+ }else{
+ temp = readl(port->membase + UCR2);
+ if(port->rs485.flags & SER_RS485_RTS_AFTER_SEND)
+ temp &= ~UCR2_CTS;
+ else
+ temp |= UCR2_CTS;
+ writel(temp, port->membase + UCR2);
+ }
+ /* disable shifter empty irq */
temp = readl(port->membase + UCR4);
temp &= ~UCR4_TCEN;
writel(temp, port->membase + UCR4);
@@ -595,15 +620,32 @@ static void imx_start_tx(struct uart_port *port)
struct imx_port *sport = (struct imx_port *)port;
unsigned long temp;
+ if(sport->txen_gpio != -1){
+ gpio_set_value(sport->txen_gpio, 1);
+
+ /*enable shifter empty irq */
+ temp = readl(port->membase + UCR4);
+ temp |= UCR4_TCEN;
+ writel(temp, port->membase + UCR4);
+ }
if (port->rs485.flags & SER_RS485_ENABLED) {
- /* enable transmitter and shifter empty irq */
- temp = readl(port->membase + UCR2);
- if (port->rs485.flags & SER_RS485_RTS_ON_SEND)
+ /* enable transmitter */
+ if(sport->txen_gpio != -1){
+ if (port->rs485.flags & SER_RS485_RTS_ON_SEND)
+ gpio_set_value(sport->txen_gpio, 1);
+ else
+ gpio_set_value(sport->txen_gpio, 0);
+ }
+ else{
+ temp = readl(port->membase + UCR2);
+ if (port->rs485.flags & SER_RS485_RTS_ON_SEND)
temp &= ~UCR2_CTS;
- else
+ else
temp |= UCR2_CTS;
- writel(temp, port->membase + UCR2);
+ writel(temp, port->membase + UCR2);
+ }
+ /*enable shifter empty irq */
temp = readl(port->membase + UCR4);
temp |= UCR4_TCEN;
writel(temp, port->membase + UCR4);
@@ -653,6 +695,9 @@ static irqreturn_t imx_txint(int irq, void *dev_id)
unsigned long flags;
spin_lock_irqsave(&sport->port.lock, flags);
+
+ //if(sport->txen_gpio != -1)
+ // printk("bkq%d\n", __LINE__);
imx_transmit_buffer(sport);
spin_unlock_irqrestore(&sport->port.lock, flags);
return IRQ_HANDLED;
@@ -1326,7 +1371,9 @@ imx_set_termios(struct uart_port *port, struct ktermios *termios,
if (sport->have_rtscts) {
ucr2 &= ~UCR2_IRTS;
- if (port->rs485.flags & SER_RS485_ENABLED) {
+ if ((port->rs485.flags & SER_RS485_ENABLED) &&
+ (sport->txen_gpio == -1))
+ {
/*
* RTS is mandatory for rs485 operation, so keep
* it under manual control and keep transmitter
@@ -1341,7 +1388,8 @@ imx_set_termios(struct uart_port *port, struct ktermios *termios,
} else {
termios->c_cflag &= ~CRTSCTS;
}
- } else if (port->rs485.flags & SER_RS485_ENABLED)
+ } else if (port->rs485.flags & SER_RS485_ENABLED &&
+ sport->txen_gpio == -1)
/* disable transmitter */
if (!(port->rs485.flags & SER_RS485_RTS_AFTER_SEND))
ucr2 |= UCR2_CTS;
@@ -1587,20 +1635,27 @@ static int imx_rs485_config(struct uart_port *port,
rs485conf->flags |= SER_RS485_RX_DURING_TX;
/* RTS is required to control the transmitter */
- if (!sport->have_rtscts)
+ if (sport->txen_gpio == -1 && !sport->have_rtscts)
rs485conf->flags &= ~SER_RS485_ENABLED;
if (rs485conf->flags & SER_RS485_ENABLED) {
- unsigned long temp;
-
/* disable transmitter */
- temp = readl(sport->port.membase + UCR2);
- temp &= ~UCR2_CTSC;
- if (rs485conf->flags & SER_RS485_RTS_AFTER_SEND)
+ if(sport->txen_gpio != -1){
+ if(port->rs485.flags & SER_RS485_RTS_AFTER_SEND)
+ gpio_set_value(sport->txen_gpio, 1);
+ else
+ gpio_set_value(sport->txen_gpio, 0);
+ }else{
+ unsigned long temp;
+
+ temp = readl(sport->port.membase + UCR2);
+ temp &= ~UCR2_CTSC;
+ if (rs485conf->flags & SER_RS485_RTS_AFTER_SEND)
temp &= ~UCR2_CTS;
- else
+ else
temp |= UCR2_CTS;
- writel(temp, sport->port.membase + UCR2);
+ writel(temp, sport->port.membase + UCR2);
+ }
}
port->rs485 = *rs485conf;
@@ -1939,6 +1994,15 @@ static int serial_imx_probe_dt(struct imx_port *sport,
if (of_get_property(np, "fsl,dte-mode", NULL))
sport->dte_mode = 1;
+ if (of_find_property(np, "fsl,rs485-gpio-txen", NULL))
+ sport->txen_gpio = of_get_named_gpio(np, "fsl,rs485-gpio-txen", 0);
+ else
+ sport->txen_gpio = -1;
+ if (gpio_is_valid(sport->txen_gpio))
+ devm_gpio_request_one(&pdev->dev, sport->txen_gpio,
+ GPIOF_OUT_INIT_LOW, "rs485-txen");
+ else
+ sport->txen_gpio = -1;
sport->devdata = of_id->data;
return 0;
patch -p1 < gpio-rs485.patch
pinctrl_485r1: 485r1grp {
fsl,pins = <
MX6UL_PAD_UART2_TX_DATA__UART2_DCE_TX 0x1b0b1
MX6UL_PAD_UART2_RX_DATA__UART2_DCE_RX 0x1b0b1
>;
};
pinctrl_uart4_txen: uart4_txengpr {
fsl,pins = <
MX6UL_PAD_JTAG_TCK__GPIO1_IO14 0x17059 /* TXEN */
>;
};
&uart2 {
pinctrl-names = "default";
pinctrl-0 = <&pinctrl_485r1 &pinctrl_uart4_txen>;
dmas = <>;
dma-names = "";
fsl,rs485-gpio-txen = <&gpio1 18 0>;
status = "okay";
};
uart_test.c
#include <stdio.h>
#include <termios.h>
#include <linux/ioctl.h>
#include <linux/serial.h>
#include <asm-generic/ioctls.h> /* TIOCGRS485 + TIOCSRS485 ioctl definitions */
#include <unistd.h>
#include <errno.h>
#include <fcntl.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <string.h>
#include <stdlib.h>
#include <getopt.h>
/**
* @brief: set the properties of serial port
* @Param: fd: file descriptor
* @Param: nSpeed: Baud Rate
* @Param: nBits: character size
* @Param: nEvent: parity of serial port
* @Param: nStop: stop bits
*/
typedef enum {DISABLE = 0, ENABLE} RS485_ENABLE_t;
int set_port(int fd, int nSpeed, int nBits, char nEvent, int nStop)
{
struct termios newtio, oldtio;
memset(&oldtio, 0, sizeof(oldtio));
/* save the old serial port configuration */
if(tcgetattr(fd, &oldtio) != 0) {
perror("set_port/tcgetattr");
return -1;
}
memset(&newtio, 0, sizeof(newtio));
/* ignore modem control lines and enable receiver */
newtio.c_cflag = newtio.c_cflag |= CLOCAL | CREAD;
newtio.c_cflag &= ~CSIZE;
/* set character size */
switch (nBits) {
case 8:
newtio.c_cflag |= CS8;
break;
case 7:
newtio.c_cflag |= CS7;
break;
case 6:
newtio.c_cflag |= CS6;
break;
case 5:
newtio.c_cflag |= CS5;
break;
default:
newtio.c_cflag |= CS8;
break;
}
/* set the parity */
switch (nEvent) {
case 'o':
case 'O':
newtio.c_cflag |= PARENB;
newtio.c_cflag |= PARODD;
newtio.c_iflag |= (INPCK | ISTRIP);
break;
case 'e':
case 'E':
newtio.c_cflag |= PARENB;
newtio.c_cflag &= ~PARODD;
newtio.c_iflag |= (INPCK | ISTRIP);
break;
case 'n':
case 'N':
newtio.c_cflag &= ~PARENB;
break;
default:
newtio.c_cflag &= ~PARENB;
break;
}
/* set the stop bits */
switch (nStop) {
case 1:
newtio.c_cflag &= ~CSTOPB;
break;
case 2:
newtio.c_cflag |= CSTOPB;
break;
default:
newtio.c_cflag &= ~CSTOPB;
break;
}
/* set output and input baud rate */
switch (nSpeed) {
case 0:
cfsetospeed(&newtio, B0);
cfsetispeed(&newtio, B0);
break;
case 50:
cfsetospeed(&newtio, B50);
cfsetispeed(&newtio, B50);
break;
case 75:
cfsetospeed(&newtio, B75);
cfsetispeed(&newtio, B75);
break;
case 110:
cfsetospeed(&newtio, B110);
cfsetispeed(&newtio, B110);
break;
case 134:
cfsetospeed(&newtio, B134);
cfsetispeed(&newtio, B134);
break;
case 150:
cfsetospeed(&newtio, B150);
cfsetispeed(&newtio, B150);
break;
case 200:
cfsetospeed(&newtio, B200);
cfsetispeed(&newtio, B200);
break;
case 300:
cfsetospeed(&newtio, B300);
cfsetispeed(&newtio, B300);
break;
case 600:
cfsetospeed(&newtio, B600);
cfsetispeed(&newtio, B600);
break;
case 1200:
cfsetospeed(&newtio, B1200);
cfsetispeed(&newtio, B1200);
break;
case 1800:
cfsetospeed(&newtio, B1800);
cfsetispeed(&newtio, B1800);
break;
case 2400:
cfsetospeed(&newtio, B2400);
cfsetispeed(&newtio, B2400);
break;
case 4800:
cfsetospeed(&newtio, B4800);
cfsetispeed(&newtio, B4800);
break;
case 9600:
cfsetospeed(&newtio, B9600);
cfsetispeed(&newtio, B9600);
break;
case 19200:
cfsetospeed(&newtio, B19200);
cfsetispeed(&newtio, B19200);
break;
case 38400:
cfsetospeed(&newtio, B38400);
cfsetispeed(&newtio, B38400);
break;
case 57600:
cfsetospeed(&newtio, B57600);
cfsetispeed(&newtio, B57600);
break;
case 115200:
cfsetospeed(&newtio, B115200);
cfsetispeed(&newtio, B115200);
break;
case 230400:
cfsetospeed(&newtio, B230400);
cfsetispeed(&newtio, B230400);
break;
default:
cfsetospeed(&newtio, B115200);
cfsetispeed(&newtio, B115200);
break;
}
/* set timeout in deciseconds for non-canonical read */
newtio.c_cc[VTIME] = 0;
/* set minimum number of characters for non-canonical read */
newtio.c_cc[VMIN] = 0;
/* flushes data received but not read */
tcflush(fd, TCIFLUSH);
/* set the parameters associated with the terminal from
the termios structure and the change occurs immediately */
if((tcsetattr(fd, TCSANOW, &newtio))!=0)
{
perror("set_port/tcsetattr");
return -1;
}
return 0;
}
/**
* @brief: open serial port
* @Param: dir: serial device path
*/
int open_port(char *dir)
{
int fd ;
fd = open(dir, O_RDWR);
if(fd < 0) {
perror("open_port");
}
return fd;
}
/**
* @brief: print usage message
* @Param: stream: output device
* @Param: exit_code: error code which want to exit
*/
void print_usage (FILE *stream, int exit_code)
{
fprintf(stream, "Usage: option [ dev... ] \n");
fprintf(stream,
"\t-h --help Display this usage information.\n"
"\t-d --device The device ttyS[0-3] or ttySCMA[0-1]\n"
"\t-b --baudrate Set the baud rate you can select\n"
"\t [230400, 115200, 57600, 38400, 19200, 9600, 4800, 2400, 1200, 300]\n"
"\t-s --string Write the device data\n"
"\t-e --1 or 0 , Write 1 to enable rs485_mode(only at atmel)\n");
exit(exit_code);
}
/**
* @brief: main function
* @Param: argc: number of parameters
* @Param: argv: parameters list
*/
int rs485_enable(const int fd, const RS485_ENABLE_t enable)
{
struct serial_rs485 rs485conf;
int res;
/* Get configure from device */
res = ioctl(fd, TIOCGRS485, &rs485conf);
if (res < 0) {
perror("Ioctl error on getting 485 configure:");
close(fd);
return res;
}
/* Set enable/disable to configure */
if (enable) { // Enable rs485 mode
rs485conf.flags |= SER_RS485_ENABLED;
} else { // Disable rs485 mode
rs485conf.flags &= ~(SER_RS485_ENABLED);
}
rs485conf.delay_rts_before_send = 0x00000004;
/* Set configure to device */
res = ioctl(fd, TIOCSRS485, &rs485conf);
if (res < 0) {
perror("Ioctl error on setting 485 configure:");
close(fd);
}
return res;
}
int main(int argc, char *argv[])
{
char *write_buf = "0123456789";
char read_buf[100];
int fd, i, len, nread,r;
pid_t pid;
int next_option;
extern struct termios oldtio;
int speed ;
char *device;
int spee_flag = 0, device_flag = 0;
const char *const short_options = "hd:s:b:e:";
const struct option long_options[] = {
{ "help", 0, NULL, 'h'},
{ "device", 1, NULL, 'd'},
{ "string", 1, NULL, 's'},
{ "baudrate", 1, NULL, 'b'},
{ NULL, 0, NULL, 0 }
};
if (argc < 2) {
print_usage (stdout, 0);
exit(0);
}
while (1) {
next_option = getopt_long (argc, argv, short_options, long_options, NULL);
if (next_option < 0)
break;
switch (next_option) {
case 'h':
print_usage (stdout, 0);
break;
case 'd':
device = optarg;
device_flag = 1;
break;
case 'b':
speed = atoi(optarg);
spee_flag = 1;
break;
case 's':
write_buf = optarg;
break;
case 'e':
r = atoi(optarg);
break;
case '?':
print_usage (stderr, 1);
break;
default:
abort ();
}
}
if ((!device_flag)||(!spee_flag)) {
print_usage (stderr, 1);
exit(0);
}
/* open serial port */
fd = open_port(device);
if (fd < 0) {
perror("open failed");
return -1;
}
if(r)
{
rs485_enable(fd,ENABLE);
}
/* set serial port */
i = set_port(fd, speed, 8, 'N', 1);
if (i < 0) {
perror("set_port failed");
return -1;
}
while (1) {
/* if new data is available on the serial port, read and print it out */
nread = read(fd ,read_buf ,sizeof(read_buf));
if (nread > 0) {
printf("RECV[%3d]: ", nread);
for(i = 0; i < nread; i++)
printf("0x%02x ", read_buf[i]);
printf("\n");
write(fd, read_buf, nread);//自己添加
}else{
printf("read error\n");
sleep(1);
}
}
/* restore the old configuration */
tcsetattr(fd, TCSANOW, &oldtio);
close(fd);
return 0;
}
uart_test -d /dev/ttymxc2 -b 115200