From 8eda401052191bee0eb913435bb7847dc08d662f Mon Sep 17 00:00:00 2001
From: Daisuke Mizobuchi <mizo@atmark-techno.com>
Date: Wed, 16 Jul 2025 08:54:38 +0900
Subject: [PATCH] serial: imx_rpmsg: change tty driver to uart driver

Since a physical device exists you should use the uart driver.

The tty driver does not support some operations unless specifically
implemented (for example the TIOCGSERIAL ioctl fails). The uart driver
provides generic operations (serial_core.c: uart_ops).

The irq and baud_base will not be set, but this is not a problem as
resource management is handled by the M33 firmware.

armadillo:~# setserial -a /dev/ttyrpmsg1
/dev/ttyrpmsg1, Line 1, UART: undefined, Port: 0x0000, IRQ: 0
        Baud_base: 0, close_delay: 50, divisor: 0
        closing_wait: 3000
        Flags: spd_normal

Change-Id: I1c804deaef3bb3bb40436c05d9f598c4add79782
Signed-off-by: Daisuke Mizobuchi <mizo@atmark-techno.com>
---
 drivers/tty/serial/imx_rpmsg.c   | 528 +++++++++++++++++--------------
 include/uapi/linux/serial_core.h |   3 +
 2 files changed, 295 insertions(+), 236 deletions(-)

diff --git a/drivers/tty/serial/imx_rpmsg.c b/drivers/tty/serial/imx_rpmsg.c
index 1d5575d79795..9c3a200b2487 100644
--- a/drivers/tty/serial/imx_rpmsg.c
+++ b/drivers/tty/serial/imx_rpmsg.c
@@ -15,10 +15,16 @@
 #include <linux/rpmsg.h>
 #include <linux/slab.h>
 #include <linux/tty.h>
-#include <linux/tty_driver.h>
 #include <linux/tty_flip.h>
+#include <linux/serial_core.h>
+#include <linux/serial.h>
 #include <linux/virtio.h>
 
+#include "serial_mctrl_gpio.h"
+
+#define DRIVER_NAME	"IMX-rpmsg-uart"
+#define DEV_NAME	"ttyrpmsg"
+
 #define RPMSG_TIMEOUT   1000
 /* Further improvement: could count compatible nodes with e.g.
  * `for_each_compatible_node(dn, NULL, "xxx") count++;`
@@ -80,15 +86,18 @@ struct srtm_tty_init_payload {
  * @port:		TTY port data
  */
 struct imx_rpmsg_port {
-	struct tty_port		port;
+	struct uart_port	port;
 	spinlock_t		rx_lock;
 	struct rpmsg_device	*rpdev;
 	struct platform_device	*pdev;
-	struct tty_driver	*driver;
+
+	struct work_struct	tx_work;
+	bool			force_end_work;
+
+	struct mctrl_gpios	*gpios;
 
 	struct mutex		tx_lock;
 	struct completion	cmd_complete;
-	u8			port_idx;
 	u8			last_retcode;
 	u8			last_request_id;
 	u16			inflight_request_id;
@@ -111,12 +120,12 @@ struct imx_rpmsg_tty_msg {
 	} __packed __aligned(1);
 } __packed __aligned(1);
 
-#define imx_rpmsg_uart_msg_size(s) (sizeof(struct imx_rpmsg_tty_msg) - \
+#define imx_rpmsg_uart_msg_size(s) (sizeof(struct imx_rpmsg_tty_msg) -	\
 				    RPMSG_MAX_SIZE + s)
 
 struct rpmsg_uart {
 	struct rpmsg_device *rpdev;
-	struct imx_rpmsg_port *ports[IMX_RPMSG_UART_PORT_PER_SOC_MAX];
+	struct imx_rpmsg_port *rports[IMX_RPMSG_UART_PORT_PER_SOC_MAX];
 	struct ida ida;
 };
 
@@ -128,9 +137,10 @@ static int imx_rpmsg_uart_cb(struct rpmsg_device *rpdev, void *data, int len,
 			     void *priv, u32 src)
 {
 	struct imx_rpmsg_tty_msg *msg = data;
-	struct imx_rpmsg_port *port;
-	unsigned char *buf;
-	int space;
+	struct imx_rpmsg_port *rport;
+	struct uart_port *port;
+	struct tty_port *tport;
+	int copied;
 
 	dev_dbg(&rpdev->dev, "msg(<- src 0x%x) len %d\n", src, len);
 	print_hex_dump_debug(__func__, DUMP_PREFIX_NONE, 16, 1,
@@ -141,11 +151,13 @@ static int imx_rpmsg_uart_cb(struct rpmsg_device *rpdev, void *data, int len,
 		return 0;
 	}
 	if (msg->port_idx >= IMX_RPMSG_UART_PORT_PER_SOC_MAX
-	    || !uart_rpmsg.ports[msg->port_idx]) {
+	    || !uart_rpmsg.rports[msg->port_idx]) {
 		dev_err(&rpdev->dev, "port_idx %d too large\n", msg->port_idx);
 		return 0;
 	}
-	port = uart_rpmsg.ports[msg->port_idx];
+	rport = uart_rpmsg.rports[msg->port_idx];
+	port = &rport->port;
+	tport = &port->state->port;
 
 	if (msg->header.type == TTY_RPMSG_RESPONSE) {
 		/* 1 for ret */
@@ -155,22 +167,22 @@ static int imx_rpmsg_uart_cb(struct rpmsg_device *rpdev, void *data, int len,
 			return 0;
 		}
 		/* ack for baudrate or tx */
-		spin_lock_irq(&port->request_id_lock);
-		if (msg->request_id != port->inflight_request_id) {
+		spin_lock_irq(&rport->request_id_lock);
+		if (msg->request_id != rport->inflight_request_id) {
 			/* non-wait message are always 0xffff */
-			if (port->inflight_request_id != 0xffff)
+			if (rport->inflight_request_id != 0xffff)
 				dev_warn(&rpdev->dev,
 					 "received unexpected id %x (expected %x)\n",
-					 msg->request_id, port->inflight_request_id);
-			spin_unlock_irq(&port->request_id_lock);
+					 msg->request_id, rport->inflight_request_id);
+			spin_unlock_irq(&rport->request_id_lock);
 			return 0;
 		}
 		/* don't process duplicates */
-		port->inflight_request_id = 0xffff;
-		port->last_retcode = msg->retcode;
-		spin_unlock_irq(&port->request_id_lock);
+		rport->inflight_request_id = 0xffff;
+		rport->last_retcode = msg->retcode;
+		spin_unlock_irq(&rport->request_id_lock);
 
-		complete(&port->cmd_complete);
+		complete(&rport->cmd_complete);
 		return 0;
 	}
 	if (msg->header.type != TTY_RPMSG_NOTIFICATION) {
@@ -178,28 +190,28 @@ static int imx_rpmsg_uart_cb(struct rpmsg_device *rpdev, void *data, int len,
 		return 0;
 	}
 	if (len < imx_rpmsg_uart_msg_size(msg->len)) {
-		dev_err(&rpdev->dev, "Short message, expected at least %zd, got %d\n",
+		dev_err(&rpdev->dev,
+			"Short message, expected at least %zd, got %d\n",
 			imx_rpmsg_uart_msg_size(msg->len), len);
 		return 0;
 	}
 
-	spin_lock_bh(&port->rx_lock);
-	space = tty_prepare_flip_string(&port->port, &buf, msg->len);
-	if (space <= 0) {
-		dev_err(&rpdev->dev, "No memory for tty_prepare_flip_string\n");
-		spin_unlock_bh(&port->rx_lock);
-		return 0;
+	spin_lock_bh(&rport->rx_lock);
+	copied = tty_insert_flip_string(tport, msg->buf, msg->len);
+	if (copied != msg->len) {
+		dev_err(&rpdev->dev, "Only copied %d instead of %d bytes\n",
+			copied, msg->len);
 	}
-
-	memcpy(buf, msg->buf, msg->len);
-	tty_flip_buffer_push(&port->port);
-	spin_unlock_bh(&port->rx_lock);
+	tty_flip_buffer_push(tport);
+	port->icount.rx += copied;
+	spin_unlock_bh(&rport->rx_lock);
 
 	return 0;
 }
 
-static int tty_send_and_wait(struct imx_rpmsg_port *port, struct imx_rpmsg_tty_msg *msg,
-			     const void *data, size_t len, bool wait)
+static int imx_rpmsg_uart_send_and_wait(struct imx_rpmsg_port *rport,
+					struct imx_rpmsg_tty_msg *msg,
+					const void *data, size_t len, bool wait)
 {
 	int err;
 
@@ -211,135 +223,196 @@ static int tty_send_and_wait(struct imx_rpmsg_port *port, struct imx_rpmsg_tty_m
 	msg->header.minor = TTY_RPMSG_MINOR;
 	msg->header.type = TTY_RPMSG_REQUEST;
 	msg->len = len;
-	msg->port_idx = port->port_idx;
+	msg->port_idx = rport->port.line;
 	memcpy(msg->buf, data, len);
 
-	reinit_completion(&port->cmd_complete);
-	mutex_lock(&port->tx_lock);
-	spin_lock_irq(&port->request_id_lock);
-	port->inflight_request_id = port->last_request_id++;
-	spin_unlock_irq(&port->request_id_lock);
-	msg->request_id = port->inflight_request_id;
+	reinit_completion(&rport->cmd_complete);
+	mutex_lock(&rport->tx_lock);
+	spin_lock_irq(&rport->request_id_lock);
+	rport->inflight_request_id = rport->last_request_id++;
+	spin_unlock_irq(&rport->request_id_lock);
+	msg->request_id = rport->inflight_request_id;
 	if (!wait)
-		port->inflight_request_id = 0xffff;
+		rport->inflight_request_id = 0xffff;
 
-	err = rpmsg_send(port->rpdev->ept, msg,
-				 imx_rpmsg_uart_msg_size(len));
+	err = rpmsg_send(rport->rpdev->ept, msg, imx_rpmsg_uart_msg_size(len));
 	if (err) {
-		dev_err(&port->rpdev->dev, "rpmsg_send failed: %d\n", err);
+		dev_err(&rport->rpdev->dev, "rpmsg_send failed: %d\n", err);
 		goto err_out;
 	}
 	if (!wait) {
-		mutex_unlock(&port->tx_lock);
+		mutex_unlock(&rport->tx_lock);
 		return 0;
 	}
-	err = wait_for_completion_timeout(&port->cmd_complete, msecs_to_jiffies(RPMSG_TIMEOUT));
+	err = wait_for_completion_timeout(&rport->cmd_complete,
+					  msecs_to_jiffies(RPMSG_TIMEOUT));
 	if (!err) {
 		/* don't process late replies - lock here ensures
 		 * we're not completing the next call */
-		spin_lock_irq(&port->request_id_lock);
-		port->inflight_request_id = 0xffff;
-		spin_unlock_irq(&port->request_id_lock);
-		dev_err(&port->rpdev->dev, "rpmsg_send timeout\n");
+		spin_lock_irq(&rport->request_id_lock);
+		rport->inflight_request_id = 0xffff;
+		spin_unlock_irq(&rport->request_id_lock);
+		dev_err(&rport->rpdev->dev, "rpmsg_send timeout\n");
 		err = -ETIMEDOUT;
 		goto err_out;
 	}
-	if (port->last_retcode != 0) {
-		dev_err(&port->rpdev->dev, "rpmsg error for %d: %d\n",
-			msg->header.cmd, port->last_retcode);
+	if (rport->last_retcode != 0) {
+		dev_err(&rport->rpdev->dev, "rpmsg error for %d: %d\n",
+			msg->header.cmd, rport->last_retcode);
 		err = -EINVAL;
 		goto err_out;
 	}
 	err = 0;
 
 err_out:
-	mutex_unlock(&port->tx_lock);
+	mutex_unlock(&rport->tx_lock);
 
 	return err;
 }
 
-static int imx_rpmsg_uart_install(struct tty_driver *driver,
-				  struct tty_struct *tty)
+static void imx_rpmsg_uart_tx_work(struct work_struct *ws)
 {
-	struct imx_rpmsg_port *port = driver->driver_state;
+	struct imx_rpmsg_port *rport = container_of(ws, struct imx_rpmsg_port,
+						    tx_work);
+	struct uart_port *port = &rport->port;
+	struct circ_buf *xmit = &port->state->xmit;
+	struct imx_rpmsg_tty_msg msg = {
+		.header.cmd = TTY_RPMSG_COMMAND_PAYLOAD,
+	};
+	int len;
+	int ret;
+
+	if (port->x_char) {
+		/* Send next char */
+		ret = imx_rpmsg_uart_send_and_wait(rport, &msg, &port->x_char,
+						   1, true);
+		if (ret)
+			dev_err(&rport->rpdev->dev, "tx dropped XON/XOFF character\n");
+		else
+			port->icount.tx++;
+		port->x_char = 0;
+		return;
+	}
 
-	return tty_port_install(&port->port, driver, tty);
+	while (!uart_circ_empty(xmit) && !uart_tx_stopped(port) &&
+	       !rport->force_end_work) {
+
+		if (xmit->tail < xmit->head || xmit->head == 0)
+			len = min(uart_circ_chars_pending(xmit), RPMSG_MAX_SIZE);
+		else
+			len = min(UART_XMIT_SIZE - xmit->tail, RPMSG_MAX_SIZE);
+
+		/* send a message to our remote processor */
+		ret = imx_rpmsg_uart_send_and_wait(rport, &msg,
+						   &xmit->buf[xmit->tail],
+						   len, true);
+		if (ret) {
+			/* The type of error cannot be determined, so
+			 * the error count cannot be incremented. */
+			dev_err(&rport->rpdev->dev, "tx dropped at most %d bytes\n",
+				len);
+		} else {
+			/* Add data to send */
+			port->icount.tx += len;
+		}
+		xmit->tail = (xmit->tail + len) & (UART_XMIT_SIZE - 1);
+	}
+
+	if (uart_circ_chars_pending(xmit) < WAKEUP_CHARS)
+		uart_write_wakeup(&rport->port);
 }
 
-static int imx_rpmsg_uart_open(struct tty_struct *tty, struct file *filp)
+static unsigned int imx_rpmsg_uart_tx_empty(struct uart_port *port)
 {
-	return tty_port_open(tty->port, tty, filp);
+	return TIOCSER_TEMT;
 }
 
-static void imx_rpmsg_uart_close(struct tty_struct *tty, struct file *filp)
+static void imx_rpmsg_uart_set_mctrl(struct uart_port *port, unsigned int mctrl)
 {
-	return tty_port_close(tty->port, tty, filp);
+	struct imx_rpmsg_port *rport = (struct imx_rpmsg_port *)port;
+
+	mctrl_gpio_set(rport->gpios, mctrl);
 }
 
-static int imx_rpmsg_uart_write(struct tty_struct *tty,
-				const unsigned char *buf, int total)
+static unsigned int imx_rpmsg_uart_get_mctrl(struct uart_port *port)
 {
-	struct imx_rpmsg_tty_msg msg = {
-		.header.cmd = TTY_RPMSG_COMMAND_PAYLOAD,
-	};
-	int remain, ret = 0;
-	const unsigned char *tbuf;
-	int tlen;
-	struct imx_rpmsg_port *port = container_of(tty->port,
-						   struct imx_rpmsg_port, port);
-	struct rpmsg_device *rpdev = port->rpdev;
-
-	if (buf == NULL) {
-		dev_err(&rpdev->dev, "buf shouldn't be null.\n");
-		return -ENOMEM;
-	}
+	struct imx_rpmsg_port *rport = (struct imx_rpmsg_port *)port;
+	int ret = TIOCM_CTS | TIOCM_DSR | TIOCM_CAR;
 
-	remain = total;
-	tbuf = buf;
-	do {
-		tlen = remain > RPMSG_MAX_SIZE ? RPMSG_MAX_SIZE : remain;
+	mctrl_gpio_get(rport->gpios, &ret);
 
-		/* send a message to our remote processor */
-		ret = tty_send_and_wait(port, &msg, tbuf, tlen, true);
-		if (ret)
-			return ret;
+	return ret;
+}
 
-		if (remain > RPMSG_MAX_SIZE) {
-			remain -= RPMSG_MAX_SIZE;
-			tbuf += RPMSG_MAX_SIZE;
-		} else {
-			remain = 0;
-		}
-	} while (remain > 0);
+static void imx_rpmsg_uart_stop_tx(struct uart_port *port)
+{
+	/* Nothing to do */
+}
+
+static void imx_rpmsg_uart_start_tx(struct uart_port *port)
+{
+	struct imx_rpmsg_port *rport = (struct imx_rpmsg_port *)port;
+
+	schedule_work(&rport->tx_work);
+}
 
-	return total;
+static void imx_rpmsg_uart_stop_rx(struct uart_port *port)
+{
+	/* Nothing to do */
 }
 
-static int imx_rpmsg_uart_write_room(struct tty_struct *tty)
+static void imx_rpmsg_uart_enable_ms(struct uart_port *port)
 {
-	/* report the space in the rpmsg buffer */
-	return RPMSG_MAX_SIZE;
+	struct imx_rpmsg_port *rport = (struct imx_rpmsg_port *)port;
+
+	mctrl_gpio_enable_ms(rport->gpios);
 }
 
-static int imx_rpmsg_uart_set_cflag(struct imx_rpmsg_port *port,
-				    tcflag_t cflag)
+static int _imx_rpmsg_uart_send_activate(struct imx_rpmsg_port *rport,
+					 bool activate_)
 {
 	struct imx_rpmsg_tty_msg msg = {
-		.header.cmd = TTY_RPMSG_COMMAND_SET_CFLAG,
+		.header.cmd = TTY_RPMSG_COMMAND_ACTIVATE,
 	};
+	uint8_t activate = activate_;
 
-	return tty_send_and_wait(port, (void *)&msg, &cflag, sizeof(cflag), true);
+	return imx_rpmsg_uart_send_and_wait(rport, (void *)&msg,
+					    &activate, sizeof(activate), true);
 }
 
-static void imx_rpmsg_uart_set_termios(struct tty_struct *tty,
-				       struct ktermios *old)
+static int imx_rpmsg_uart_startup(struct uart_port *port)
 {
-	struct imx_rpmsg_port *port = container_of(tty->port,
-						   struct imx_rpmsg_port, port);
+	struct imx_rpmsg_port *rport = (struct imx_rpmsg_port *)port;
+
+	rport->force_end_work = false;
+
+	return _imx_rpmsg_uart_send_activate(rport, true);
+}
+
+static void imx_rpmsg_uart_shutdown(struct uart_port *port)
+{
+	struct imx_rpmsg_port *rport = (struct imx_rpmsg_port *)port;
+
+	rport->force_end_work = true;
+	cancel_work_sync(&rport->tx_work);
+
+	mctrl_gpio_disable_ms(rport->gpios);
+
+	_imx_rpmsg_uart_send_activate(rport, false);
+}
+
+static void
+imx_rpmsg_uart_set_termios(struct uart_port *port, struct ktermios *termios,
+			   struct ktermios *old)
+{
+	struct imx_rpmsg_port *rport = (struct imx_rpmsg_port *)port;
 	unsigned int old_csize = old ? old->c_cflag & CSIZE : CS8;
-	tcflag_t cflag = tty->termios.c_cflag;
+	tcflag_t cflag = termios->c_cflag;
+	struct imx_rpmsg_tty_msg msg = {
+		.header.cmd = TTY_RPMSG_COMMAND_SET_CFLAG,
+	};
 
-	if (cflag == old->c_cflag)
+	if (!old || cflag == old->c_cflag)
 		return;
 
 	/*
@@ -367,66 +440,52 @@ static void imx_rpmsg_uart_set_termios(struct tty_struct *tty,
 	if ((cflag & CSIZE) == CS7)
 		cflag |= PARENB;
 
-	imx_rpmsg_uart_set_cflag(port, cflag);
-}
-
-static const struct tty_operations imx_rpmsg_uart_ops = {
-	.install		= imx_rpmsg_uart_install,
-	.open			= imx_rpmsg_uart_open,
-	.close			= imx_rpmsg_uart_close,
-	.write			= imx_rpmsg_uart_write,
-	.write_room		= imx_rpmsg_uart_write_room,
-	.set_termios		= imx_rpmsg_uart_set_termios,
-};
-
-static int imx_rpmsg_uart_send_activate(struct imx_rpmsg_port *port, bool activate_)
-{
-	struct imx_rpmsg_tty_msg msg = {
-		.header.cmd = TTY_RPMSG_COMMAND_ACTIVATE,
-	};
-	uint8_t activate = activate_;
-
-	return tty_send_and_wait(port, (void *)&msg, &activate, sizeof(activate), true);
+	imx_rpmsg_uart_send_and_wait(rport, (void *)&msg, &cflag, sizeof(cflag),
+				     true);
 }
 
-static int imx_rpmsg_uart_activate(struct tty_port *tty_port, struct tty_struct *tty)
+static const char *imx_rpmsg_uart_type(struct uart_port *port)
 {
-	struct imx_rpmsg_port *port = container_of(tty_port,
-						   struct imx_rpmsg_port, port);
-
-	WARN_ONCE(tty->port != tty_port,
-			"port activate called with weird port?");
-
-	return imx_rpmsg_uart_send_activate(port, true);
+	return DRIVER_NAME;
 }
 
-static void imx_rpmsg_uart_shutdown(struct tty_port *tty_port)
+static void imx_rpmsg_uart_config_port(struct uart_port *port, int flags)
 {
-	struct imx_rpmsg_port *port = container_of(tty_port,
-						   struct imx_rpmsg_port, port);
+	struct imx_rpmsg_port *rport = (struct imx_rpmsg_port *)port;
 
-	imx_rpmsg_uart_send_activate(port, false);
+	if (flags & UART_CONFIG_TYPE)
+		rport->port.type = PORT_IMX_RPMSG;
 }
 
-static struct tty_port_operations imx_rpmsg_port_ops = {
-	.activate = imx_rpmsg_uart_activate,
-	.shutdown = imx_rpmsg_uart_shutdown,
+static const struct uart_ops imx_rpmsg_uart_ops = {
+	.tx_empty	= imx_rpmsg_uart_tx_empty,
+	.set_mctrl	= imx_rpmsg_uart_set_mctrl,
+	.get_mctrl	= imx_rpmsg_uart_get_mctrl,
+	.stop_tx	= imx_rpmsg_uart_stop_tx,
+	.start_tx	= imx_rpmsg_uart_start_tx,
+	.stop_rx	= imx_rpmsg_uart_stop_rx,
+	.enable_ms	= imx_rpmsg_uart_enable_ms,
+	.startup	= imx_rpmsg_uart_startup,
+	.shutdown	= imx_rpmsg_uart_shutdown,
+	.set_termios	= imx_rpmsg_uart_set_termios,
+	.type		= imx_rpmsg_uart_type,
+	.config_port	= imx_rpmsg_uart_config_port,
 };
 
-#define READ_PROP_OR_RETURN(group, name) \
-		ret = of_property_read_u32(np, #name, &init. group . name); \
-		if (ret) { \
-			dev_err(dev, "%pOF: error reading prop %s: %d\n", \
-				np, #name, ret); \
-			return ret; \
-		}
-static int imx_rpmsg_uart_init_remote(struct imx_rpmsg_port *port,
+#define READ_PROP_OR_RETURN(group, name)				\
+	ret = of_property_read_u32(np, #name, &init. group . name);	\
+	if (ret) {							\
+		dev_err(dev, "%pOF: error reading prop %s: %d\n",	\
+			np, #name, ret);				\
+		return ret;						\
+	}
+static int imx_rpmsg_uart_init_remote(struct imx_rpmsg_port *rport,
 				      tcflag_t cflag)
 {
 	struct imx_rpmsg_tty_msg msg = {
 		.header.cmd = TTY_RPMSG_COMMAND_INIT,
 	};
-	struct device *dev = &port->pdev->dev;
+	struct device *dev = &rport->pdev->dev;
 	struct device_node *np = dev->of_node;
 	struct srtm_tty_init_payload init = { 0 };
 	int ret;
@@ -448,11 +507,13 @@ static int imx_rpmsg_uart_init_remote(struct imx_rpmsg_port *port,
 			 * mandatory if enabled */
 			READ_PROP_OR_RETURN(lpuart, rs485_de_gpio);
 		}
+
 		ret = of_property_read_u32(np, "suspend_wakeup_gpio",
 					   &init.lpuart.suspend_wakeup_gpio);
 		if (ret < 0) {
-			dev_info(dev, "%pOF: no suspend wakeup gpio set, will not wake up\n",
-					np);
+			dev_info(dev,
+				 "%pOF: no suspend wakeup gpio set, will not wake up\n",
+				 np);
 			/* setting wakeup will error out m33-side and fail suspend */
 			init.lpuart.suspend_wakeup_gpio = -1;
 		}
@@ -481,8 +542,9 @@ static int imx_rpmsg_uart_init_remote(struct imx_rpmsg_port *port,
 		ret = of_property_read_u32(np, "suspend_wakeup_gpio",
 					   &init.flexio.suspend_wakeup_gpio);
 		if (ret < 0) {
-			dev_info(dev, "%pOF: no suspend wakeup gpio set, will not wake up\n",
-					np);
+			dev_info(dev,
+				 "%pOF: no suspend wakeup gpio set, will not wake up\n",
+				 np);
 			/* setting wakeup will error out m33-side and fail suspend */
 			init.flexio.suspend_wakeup_gpio = -1;
 		}
@@ -493,113 +555,98 @@ static int imx_rpmsg_uart_init_remote(struct imx_rpmsg_port *port,
 		return -EINVAL;
 	}
 
-	return tty_send_and_wait(port, (void *)&msg, &init, sizeof(init), true);
+	return imx_rpmsg_uart_send_and_wait(rport, (void *)&msg, &init,
+					    sizeof(init), true);
 }
 #undef READ_PROP_OR_RETURN
 
+static struct uart_driver imx_rpmsg_uart_driver = {
+	.owner          = THIS_MODULE,
+	.driver_name    = DRIVER_NAME,
+	.dev_name       = DEV_NAME,
+	.major          = UNNAMED_MAJOR,
+	.minor          = 0,
+	.nr             = IMX_RPMSG_UART_PORT_PER_SOC_MAX,
+};
+
 static int imx_rpmsg_uart_platform_probe(struct platform_device *pdev)
 {
-	int ret, of_id, id = -1;
-	struct imx_rpmsg_port *port;
-	struct tty_driver *driver;
+	int of_id, id = -1;
+	struct imx_rpmsg_port *rport;
+	struct ktermios init_termios;
 	struct rpmsg_device *rpdev = uart_rpmsg.rpdev;
-	struct device *dev;
+	int ret;
 
 	/* defer probing until we can process rpmsg replies */
 	if (!rpdev)
 		return -EPROBE_DEFER;
 
-	port = devm_kzalloc(&pdev->dev, sizeof(*port), GFP_KERNEL);
-	if (!port)
+	rport = devm_kzalloc(&pdev->dev, sizeof(*rport), GFP_KERNEL);
+	if (!rport)
 		return -ENOMEM;
 
-	driver = tty_alloc_driver(1, TTY_DRIVER_UNNUMBERED_NODE);
-	if (IS_ERR(driver))
-		return PTR_ERR(driver);
-
 	of_id = of_alias_get_id(pdev->dev.of_node, "ttyrpmsg");
 	if (of_id >= 0)
 		id = ida_simple_get(&uart_rpmsg.ida, of_id, of_id + 1, GFP_KERNEL);
 	if (id < 0)
 		id = ida_simple_get(&uart_rpmsg.ida, 0, 0, GFP_KERNEL);
 	if (of_id >= 0 && id != of_id)
-		dev_warn(&pdev->dev, "Alias ID %d not available - got %d\n", of_id, id);
+		dev_warn(&pdev->dev, "Alias ID %d not available - got %d\n",
+			 of_id, id);
 	if (id >= IMX_RPMSG_UART_PORT_PER_SOC_MAX) {
 		dev_err(&pdev->dev, "id %d higher than max %d\n",
 			id, IMX_RPMSG_UART_PORT_PER_SOC_MAX);
 		ret = -ERANGE;
 		goto error;
 	}
+	rport->port.line = id;
 
-	driver->driver_name = "imx_rpmsg";
-	driver->name = kasprintf(GFP_KERNEL, "ttyrpmsg%d", id);
-	driver->major = UNNAMED_MAJOR;
-	driver->minor_start = 0;
-	driver->type = TTY_DRIVER_TYPE_CONSOLE;
-	driver->init_termios = tty_std_termios;
-	/* use dynamic dev to bind tty to parent dev */
-	driver->flags = TTY_DRIVER_DYNAMIC_DEV | TTY_DRIVER_UNNUMBERED_NODE;
-	tty_termios_encode_baud_rate(&driver->init_termios,
-				     IMX_RPMSG_DEFAULT_BAUD,
-				     IMX_RPMSG_DEFAULT_BAUD);
+	rport->port.dev = &pdev->dev;
+	rport->port.type = PORT_IMX_RPMSG;
+	rport->port.iotype = UPIO_MEM;
+	rport->port.fifosize = 8;
+	rport->port.ops = &imx_rpmsg_uart_ops;
+	rport->port.flags = UPF_BOOT_AUTOCONF;
 
-	tty_set_operations(driver, &imx_rpmsg_uart_ops);
-
-	tty_port_init(&port->port);
-	port->port.ops = &imx_rpmsg_port_ops;
-	port->port.low_latency = port->port.flags | ASYNC_LOW_LATENCY;
-	port->rpdev = rpdev;
-	port->pdev = pdev;
-	port->port_idx = id;
-	driver->driver_state = port;
-	port->driver = driver;
-	spin_lock_init(&port->rx_lock);
-	init_completion(&port->cmd_complete);
-	mutex_init(&port->tx_lock);
-	spin_lock_init(&port->request_id_lock);
-
-	platform_set_drvdata(pdev, port);
-	uart_rpmsg.ports[id] = port;
-
-	if (of_property_read_bool(pdev->dev.of_node, "rpmsg-tty-no-echo")) {
-		driver->init_termios.c_lflag &= ~ECHO;
-	}
+	rport->rpdev = rpdev;
+	rport->pdev = pdev;
+
+	spin_lock_init(&rport->rx_lock);
+	init_completion(&rport->cmd_complete);
+	mutex_init(&rport->tx_lock);
+	spin_lock_init(&rport->request_id_lock);
+
+	platform_set_drvdata(pdev, rport);
+	uart_rpmsg.rports[id] = rport;
 
 	/*
 	 * set the baud rate to our remote processor's UART, and tell
 	 * remote processor about this channel
 	 */
-	ret = imx_rpmsg_uart_init_remote(port, driver->init_termios.c_cflag);
+	init_termios = tty_std_termios;
+	tty_termios_encode_baud_rate(&init_termios,
+				     IMX_RPMSG_DEFAULT_BAUD,
+				     IMX_RPMSG_DEFAULT_BAUD);
+	ret = imx_rpmsg_uart_init_remote(rport, init_termios.c_cflag);
 	if (ret)
-		goto error_port;
+		goto error;
 
-	ret = tty_register_driver(port->driver);
-	if (ret < 0) {
-		dev_err(&pdev->dev,
-			"Couldn't install rpmsg tty driver: ret %d\n", ret);
-		goto error_port;
-	}
-	dev = tty_register_device(port->driver, 0, &pdev->dev);
-	if (IS_ERR(dev)) {
-		ret = PTR_ERR(dev);
-		dev_err(&pdev->dev,
-			"Couldn't register rpmsg tty device: ret %d\n", ret);
-		goto error_register;
-	}
+	if (of_property_read_bool(pdev->dev.of_node, "rpmsg-tty-no-echo"))
+		init_termios.c_lflag &= ~ECHO;
+	imx_rpmsg_uart_driver.tty_driver->init_termios = init_termios;
+
+	INIT_WORK(&rport->tx_work, imx_rpmsg_uart_tx_work);
+	ret = uart_add_one_port(&imx_rpmsg_uart_driver, &rport->port);
+	if (ret)
+		goto error;
 
 	device_set_wakeup_capable(&pdev->dev, true);
 
-	dev_info(&pdev->dev, "Initialized ttyrpmsg%d!\n", port->port_idx);
+	dev_info(&pdev->dev, "Initialized ttyrpmsg%d!\n", rport->port.line);
 
 	return 0;
 
-error_register:
-	tty_unregister_driver(port->driver);
-error_port:
-	tty_port_destroy(&port->port);
 error:
-	put_tty_driver(driver);
-	port->driver = NULL;
 	ida_free(&uart_rpmsg.ida, id);
 
 	return ret;
@@ -607,17 +654,11 @@ static int imx_rpmsg_uart_platform_probe(struct platform_device *pdev)
 
 static int imx_rpmsg_uart_platform_remove(struct platform_device *pdev)
 {
-	struct imx_rpmsg_port *port = platform_get_drvdata(pdev);
+	struct imx_rpmsg_port *rport = platform_get_drvdata(pdev);
 
 	dev_info(&pdev->dev, "rpmsg tty driver is removed\n");
 
-	tty_unregister_device(port->driver, 0);
-	tty_unregister_driver(port->driver);
-	kfree(port->driver->name);
-	put_tty_driver(port->driver);
-	tty_port_destroy(&port->port);
-	port->driver = NULL;
-	return 0;
+	return uart_add_one_port(&imx_rpmsg_uart_driver, &rport->port);
 }
 
 static int __maybe_unused imx_rpmsg_uart_suspend(struct device *dev)
@@ -625,10 +666,11 @@ static int __maybe_unused imx_rpmsg_uart_suspend(struct device *dev)
 	struct imx_rpmsg_tty_msg msg = {
 		.header.cmd = TTY_RPMSG_COMMAND_SET_WAKE,
 	};
-	struct imx_rpmsg_port *port = dev_get_drvdata(dev);
+	struct imx_rpmsg_port *rport = dev_get_drvdata(dev);
 	bool enable = device_may_wakeup(dev);
 
-	return tty_send_and_wait(port, (void *)&msg, &enable, sizeof(enable), true);
+	return imx_rpmsg_uart_send_and_wait(rport, (void *)&msg, &enable,
+					    sizeof(enable), true);
 }
 
 static int __maybe_unused imx_rpmsg_uart_resume(struct device *dev)
@@ -657,26 +699,40 @@ static struct platform_driver imx_rpmsg_uart_platform_driver = {
 
 static int imx_rpmsg_uart_rpmsg_probe(struct rpmsg_device *rpdev)
 {
-	int rc;
+	int ret;
 
 	dev_info(&rpdev->dev, "new channel: 0x%x -> 0x%x!\n",
-			rpdev->src, rpdev->dst);
+		 rpdev->src, rpdev->dst);
+
 	ida_init(&uart_rpmsg.ida);
 
-	rc = platform_driver_register(&imx_rpmsg_uart_platform_driver);
+	ret = uart_register_driver(&imx_rpmsg_uart_driver);
+	if (ret)
+		return ret;
+
+	ret = platform_driver_register(&imx_rpmsg_uart_platform_driver);
+	if (ret != 0)
+		goto err;
 
 	/* platform_driver_register() calls the platform probe immediately,
 	 * but we need it to process rpmsg replies so only set rpdev last
 	 * to make the first platform probe defer */
 	uart_rpmsg.rpdev = rpdev;
-	return rc;
+
+	return ret;
+
+err:
+	uart_unregister_driver(&imx_rpmsg_uart_driver);
+	return ret;
 }
 
 static void imx_rpmsg_uart_rpmsg_remove(struct rpmsg_device *rpdev)
 {
 	dev_info(&rpdev->dev, "uart channel removed\n");
-	platform_driver_unregister(&imx_rpmsg_uart_platform_driver);
+
 	uart_rpmsg.rpdev = NULL;
+	platform_driver_unregister(&imx_rpmsg_uart_platform_driver);
+	uart_unregister_driver(&imx_rpmsg_uart_driver);
 	ida_destroy(&uart_rpmsg.ida);
 }
 
diff --git a/include/uapi/linux/serial_core.h b/include/uapi/linux/serial_core.h
index 851b982f8c4b..4f5c0bd59aa1 100644
--- a/include/uapi/linux/serial_core.h
+++ b/include/uapi/linux/serial_core.h
@@ -279,4 +279,7 @@
 /* Freescale LINFlexD UART */
 #define PORT_LINFLEXUART	122
 
+/* i.MX RPMSG UART */
+#define PORT_IMX_RPMSG	123
+
 #endif /* _UAPILINUX_SERIAL_CORE_H */
-- 
2.39.5

