2023-02-10 07:27:56

by ChiaWei Wang

[permalink] [raw]
Subject: [PATCH 0/4] arm: aspeed: Add UART with DMA support

This patch series add the serial driver with DMA support for
AST26xx UART and VUART devices.

Chia-Wei Wang (4):
dt-bindings: aspeed: Add UART controller
soc: aspeed: Add UART DMA support
serial: 8250: Add Aspeed UART driver
ARM: dts: aspeed-g6: Add UDMA node

.../bindings/serial/aspeed,uart.yaml | 81 +++
arch/arm/boot/dts/aspeed-g6.dtsi | 7 +
drivers/soc/aspeed/Kconfig | 9 +
drivers/soc/aspeed/Makefile | 1 +
drivers/soc/aspeed/aspeed-udma.c | 447 ++++++++++++++++
drivers/tty/serial/8250/8250_aspeed.c | 502 ++++++++++++++++++
drivers/tty/serial/8250/Kconfig | 8 +
drivers/tty/serial/8250/Makefile | 1 +
include/linux/soc/aspeed/aspeed-udma.h | 34 ++
9 files changed, 1090 insertions(+)
create mode 100644 Documentation/devicetree/bindings/serial/aspeed,uart.yaml
create mode 100644 drivers/soc/aspeed/aspeed-udma.c
create mode 100644 drivers/tty/serial/8250/8250_aspeed.c
create mode 100644 include/linux/soc/aspeed/aspeed-udma.h

--
2.25.1



2023-02-10 07:27:58

by ChiaWei Wang

[permalink] [raw]
Subject: [PATCH 4/4] ARM: dts: aspeed-g6: Add UDMA node

Add the device tree node for UART DMA controller.

Signed-off-by: Chia-Wei Wang <[email protected]>
---
arch/arm/boot/dts/aspeed-g6.dtsi | 7 +++++++
1 file changed, 7 insertions(+)

diff --git a/arch/arm/boot/dts/aspeed-g6.dtsi b/arch/arm/boot/dts/aspeed-g6.dtsi
index cc2f8b785917..3f4e9da8f6c7 100644
--- a/arch/arm/boot/dts/aspeed-g6.dtsi
+++ b/arch/arm/boot/dts/aspeed-g6.dtsi
@@ -850,6 +850,13 @@ fsim1: fsi@1e79b100 {
clocks = <&syscon ASPEED_CLK_GATE_FSICLK>;
status = "disabled";
};
+
+ udma: uart-dma@1e79e000 {
+ compatible = "aspeed,ast2600-udma";
+ reg = <0x1e79e000 0x400>;
+ interrupts = <GIC_SPI 56 IRQ_TYPE_LEVEL_HIGH>;
+ status = "disabled";
+ };
};
};
};
--
2.25.1


2023-02-10 07:28:00

by ChiaWei Wang

[permalink] [raw]
Subject: [PATCH 1/4] dt-bindings: aspeed: Add UART controller

Add dt-bindings for Aspeed UART controller.

Signed-off-by: Chia-Wei Wang <[email protected]>
---
.../bindings/serial/aspeed,uart.yaml | 81 +++++++++++++++++++
1 file changed, 81 insertions(+)
create mode 100644 Documentation/devicetree/bindings/serial/aspeed,uart.yaml

diff --git a/Documentation/devicetree/bindings/serial/aspeed,uart.yaml b/Documentation/devicetree/bindings/serial/aspeed,uart.yaml
new file mode 100644
index 000000000000..10c457d6a72e
--- /dev/null
+++ b/Documentation/devicetree/bindings/serial/aspeed,uart.yaml
@@ -0,0 +1,81 @@
+# SPDX-License-Identifier: (GPL-2.0-only OR BSD-2-Clause)
+%YAML 1.2
+---
+$id: http://devicetree.org/schemas/serial/aspeed,uart.yaml#
+$schema: http://devicetree.org/meta-schemas/core.yaml#
+
+title: Aspeed Universal Asynchronous Receiver/Transmitter
+
+maintainers:
+ - Chia-Wei Wang <[email protected]>
+
+allOf:
+ - $ref: serial.yaml#
+
+description: |
+ The Aspeed UART is based on the basic 8250 UART and compatible
+ with 16550A, with support for DMA
+
+properties:
+ compatible:
+ const: aspeed,ast2600-uart
+
+ reg:
+ description: The base address of the UART register bank
+ maxItems: 1
+
+ clocks:
+ description: The clock the baudrate is derived from
+ maxItems: 1
+
+ interrupts:
+ description: The IRQ number of the device
+ maxItems: 1
+
+ dma-mode:
+ type: boolean
+ description: Enable DMA
+
+ dma-channel:
+ $ref: /schemas/types.yaml#/definitions/uint32
+ description: The channel number to be used in the DMA engine
+
+ virtual:
+ type: boolean
+ description: Indicate virtual UART
+
+ sirq:
+ $ref: /schemas/types.yaml#/definitions/uint32
+ description: The serial IRQ number on LPC bus interface
+
+ sirq-polarity:
+ $ref: /schemas/types.yaml#/definitions/uint32
+ description: The serial IRQ polarity on LPC bus interface
+
+ pinctrl-0: true
+
+ pinctrl_names:
+ const: default
+
+required:
+ - compatible
+ - reg
+ - clocks
+ - interrupts
+
+unevaluatedProperties: false
+
+examples:
+ - |
+ #include <dt-bindings/interrupt-controller/arm-gic.h>
+ #include <dt-bindings/clock/ast2600-clock.h>
+
+ serial@1e783000 {
+ compatible = "aspeed,ast2600-uart";
+ reg = <0x1e783000 0x20>;
+ interrupts = <GIC_SPI 47 IRQ_TYPE_LEVEL_LOW>;
+ clocks = <&syscon ASPEED_CLK_GATE_UART1CLK>;
+ pinctrl-0 = <&pinctrl_txd1_default &pinctrl_rxd1_default>;
+ dma-mode;
+ dma-channel = <0>;
+ };
--
2.25.1


2023-02-10 07:28:02

by ChiaWei Wang

[permalink] [raw]
Subject: [PATCH 3/4] serial: 8250: Add Aspeed UART driver

Add the driver for Aspeed UART/VUART devices, which are 16550A
compatible. It is an wrapper to cover the generic 16550A operation
while exetending DMA feature for the devices.

Signed-off-by: Chia-Wei Wang <[email protected]>
---
drivers/tty/serial/8250/8250_aspeed.c | 502 ++++++++++++++++++++++++++
drivers/tty/serial/8250/Kconfig | 8 +
drivers/tty/serial/8250/Makefile | 1 +
3 files changed, 511 insertions(+)
create mode 100644 drivers/tty/serial/8250/8250_aspeed.c

diff --git a/drivers/tty/serial/8250/8250_aspeed.c b/drivers/tty/serial/8250/8250_aspeed.c
new file mode 100644
index 000000000000..2eaa59ee6d27
--- /dev/null
+++ b/drivers/tty/serial/8250/8250_aspeed.c
@@ -0,0 +1,502 @@
+// SPDX-License-Identifier: GPL-2.0
+/*
+ * Copyright (C) ASPEED Technology Inc.
+ */
+#include <linux/device.h>
+#include <linux/io.h>
+#include <linux/module.h>
+#include <linux/serial_8250.h>
+#include <linux/serial_reg.h>
+#include <linux/of.h>
+#include <linux/of_irq.h>
+#include <linux/of_platform.h>
+#include <linux/platform_device.h>
+#include <linux/clk.h>
+#include <linux/reset.h>
+#include <linux/dma-mapping.h>
+#include <linux/circ_buf.h>
+#include <linux/tty_flip.h>
+#include <linux/pm_runtime.h>
+#include <linux/soc/aspeed/aspeed-udma.h>
+
+#include "8250.h"
+
+#define DEVICE_NAME "aspeed-uart"
+
+/* offsets for the aspeed virtual uart registers */
+#define VUART_GCRA 0x20
+#define VUART_GCRA_VUART_EN BIT(0)
+#define VUART_GCRA_SIRQ_POLARITY BIT(1)
+#define VUART_GCRA_DISABLE_HOST_TX_DISCARD BIT(5)
+#define VUART_GCRB 0x24
+#define VUART_GCRB_HOST_SIRQ_MASK GENMASK(7, 4)
+#define VUART_GCRB_HOST_SIRQ_SHIFT 4
+#define VUART_ADDRL 0x28
+#define VUART_ADDRH 0x2c
+
+#define DMA_TX_BUFSZ PAGE_SIZE
+#define DMA_RX_BUFSZ (64 * 1024)
+
+struct uart_ops ast8250_pops;
+
+struct ast8250_vuart {
+ u32 port;
+ u32 sirq;
+ u32 sirq_pol;
+};
+
+struct ast8250_udma {
+ u32 ch;
+
+ u32 tx_rbsz;
+ u32 rx_rbsz;
+
+ dma_addr_t tx_addr;
+ dma_addr_t rx_addr;
+
+ struct circ_buf *tx_rb;
+ struct circ_buf *rx_rb;
+
+ bool tx_tmout_dis;
+ bool rx_tmout_dis;
+};
+
+struct ast8250_data {
+ int line;
+
+ u8 __iomem *regs;
+
+ bool is_vuart;
+ bool use_dma;
+
+ struct reset_control *rst;
+ struct clk *clk;
+
+ struct ast8250_vuart vuart;
+ struct ast8250_udma dma;
+};
+
+static void ast8250_dma_tx_complete(int tx_rb_rptr, void *id)
+{
+ u32 count;
+ unsigned long flags;
+ struct uart_port *port = (struct uart_port *)id;
+ struct ast8250_data *data = port->private_data;
+
+ spin_lock_irqsave(&port->lock, flags);
+
+ count = CIRC_CNT(tx_rb_rptr, port->state->xmit.tail, data->dma.tx_rbsz);
+ port->state->xmit.tail = tx_rb_rptr;
+ port->icount.tx += count;
+
+ if (uart_circ_chars_pending(&port->state->xmit) < WAKEUP_CHARS)
+ uart_write_wakeup(port);
+
+ spin_unlock_irqrestore(&port->lock, flags);
+}
+
+static void ast8250_dma_rx_complete(int rx_rb_wptr, void *id)
+{
+ unsigned long flags;
+ struct uart_port *up = (struct uart_port *)id;
+ struct tty_port *tp = &up->state->port;
+ struct ast8250_data *data = up->private_data;
+ struct ast8250_udma *dma = &data->dma;
+ struct circ_buf *rx_rb = dma->rx_rb;
+ u32 rx_rbsz = dma->rx_rbsz;
+ u32 count = 0;
+
+ spin_lock_irqsave(&up->lock, flags);
+
+ rx_rb->head = rx_rb_wptr;
+
+ dma_sync_single_for_cpu(up->dev,
+ dma->rx_addr, dma->rx_rbsz, DMA_FROM_DEVICE);
+
+ while (CIRC_CNT(rx_rb->head, rx_rb->tail, rx_rbsz)) {
+ count = CIRC_CNT_TO_END(rx_rb->head, rx_rb->tail, rx_rbsz);
+
+ tty_insert_flip_string(tp, rx_rb->buf + rx_rb->tail, count);
+
+ rx_rb->tail += count;
+ rx_rb->tail %= rx_rbsz;
+
+ up->icount.rx += count;
+ }
+
+ if (count) {
+ aspeed_udma_set_rx_rptr(data->dma.ch, rx_rb->tail);
+ tty_flip_buffer_push(tp);
+ }
+
+ spin_unlock_irqrestore(&up->lock, flags);
+}
+
+static void ast8250_dma_start_tx(struct uart_port *port)
+{
+ struct ast8250_data *data = port->private_data;
+ struct ast8250_udma *dma = &data->dma;
+ struct circ_buf *tx_rb = dma->tx_rb;
+
+ dma_sync_single_for_device(port->dev,
+ dma->tx_addr, dma->tx_rbsz, DMA_TO_DEVICE);
+
+ aspeed_udma_set_tx_wptr(dma->ch, tx_rb->head);
+}
+
+static void ast8250_dma_pops_hook(struct uart_port *port)
+{
+ static int first = 1;
+
+ if (first) {
+ ast8250_pops = *port->ops;
+ ast8250_pops.start_tx = ast8250_dma_start_tx;
+ }
+
+ first = 0;
+ port->ops = &ast8250_pops;
+}
+
+static void ast8250_vuart_init(struct ast8250_data *data)
+{
+ u8 reg;
+ struct ast8250_vuart *vuart = &data->vuart;
+
+ /* IO port address */
+ writeb((u8)(vuart->port >> 0), data->regs + VUART_ADDRL);
+ writeb((u8)(vuart->port >> 8), data->regs + VUART_ADDRH);
+
+ /* SIRQ number */
+ reg = readb(data->regs + VUART_GCRB);
+ reg &= ~VUART_GCRB_HOST_SIRQ_MASK;
+ reg |= ((vuart->sirq << VUART_GCRB_HOST_SIRQ_SHIFT) & VUART_GCRB_HOST_SIRQ_MASK);
+ writeb(reg, data->regs + VUART_GCRB);
+
+ /* SIRQ polarity */
+ reg = readb(data->regs + VUART_GCRA);
+ if (vuart->sirq_pol)
+ reg |= VUART_GCRA_SIRQ_POLARITY;
+ else
+ reg &= ~VUART_GCRA_SIRQ_POLARITY;
+ writeb(reg, data->regs + VUART_GCRA);
+}
+
+static void ast8250_vuart_set_host_tx_discard(struct ast8250_data *data, bool discard)
+{
+ u8 reg;
+
+ reg = readb(data->regs + VUART_GCRA);
+ if (discard)
+ reg &= ~VUART_GCRA_DISABLE_HOST_TX_DISCARD;
+ else
+ reg |= VUART_GCRA_DISABLE_HOST_TX_DISCARD;
+ writeb(reg, data->regs + VUART_GCRA);
+}
+
+static void ast8250_vuart_set_enable(struct ast8250_data *data, bool enable)
+{
+ u8 reg;
+
+ reg = readb(data->regs + VUART_GCRA);
+ if (enable)
+ reg |= VUART_GCRA_VUART_EN;
+ else
+ reg &= ~VUART_GCRA_VUART_EN;
+ writeb(reg, data->regs + VUART_GCRA);
+}
+
+static int ast8250_handle_irq(struct uart_port *port)
+{
+ u32 iir = port->serial_in(port, UART_IIR);
+
+ return serial8250_handle_irq(port, iir);
+}
+
+static int ast8250_startup(struct uart_port *port)
+{
+ int rc = 0;
+ struct ast8250_data *data = port->private_data;
+ struct ast8250_udma *dma;
+
+ if (data->is_vuart)
+ ast8250_vuart_set_host_tx_discard(data, false);
+
+ if (data->use_dma) {
+ dma = &data->dma;
+
+ dma->tx_rbsz = DMA_TX_BUFSZ;
+ dma->rx_rbsz = DMA_RX_BUFSZ;
+
+ /*
+ * We take the xmit buffer passed from upper layers as
+ * the DMA TX buffer and allocate a new buffer for the
+ * RX use.
+ *
+ * To keep the TX/RX operation consistency, we use the
+ * streaming DMA interface instead of the coherent one
+ */
+ dma->tx_rb = &port->state->xmit;
+ dma->rx_rb->buf = kzalloc(data->dma.rx_rbsz, GFP_KERNEL);
+ if (IS_ERR_OR_NULL(dma->rx_rb->buf)) {
+ dev_err(port->dev, "failed to allcoate RX DMA buffer\n");
+ rc = -ENOMEM;
+ goto out;
+ }
+
+ dma->tx_addr = dma_map_single(port->dev, dma->tx_rb->buf,
+ dma->tx_rbsz, DMA_TO_DEVICE);
+ if (dma_mapping_error(port->dev, dma->tx_addr)) {
+ dev_err(port->dev, "failed to map streaming TX DMA region\n");
+ rc = -ENOMEM;
+ goto free_dma_n_out;
+ }
+
+ dma->rx_addr = dma_map_single(port->dev, dma->rx_rb->buf,
+ dma->rx_rbsz, DMA_FROM_DEVICE);
+ if (dma_mapping_error(port->dev, dma->rx_addr)) {
+ dev_err(port->dev, "failed to map streaming RX DMA region\n");
+ rc = -ENOMEM;
+ goto free_dma_n_out;
+ }
+
+ rc = aspeed_udma_request_tx_chan(dma->ch, dma->tx_addr, dma->tx_rb,
+ dma->tx_rbsz, ast8250_dma_tx_complete,
+ port, dma->tx_tmout_dis);
+ if (rc) {
+ dev_err(port->dev, "failed to request DMA TX channel\n");
+ goto free_dma_n_out;
+ }
+
+ rc = aspeed_udma_request_rx_chan(dma->ch, dma->rx_addr, dma->rx_rb,
+ dma->rx_rbsz, ast8250_dma_rx_complete,
+ port, dma->rx_tmout_dis);
+ if (rc) {
+ dev_err(port->dev, "failed to request DMA RX channel\n");
+ goto free_dma_n_out;
+ }
+
+ ast8250_dma_pops_hook(port);
+
+ aspeed_udma_tx_chan_ctrl(dma->ch, ASPEED_UDMA_OP_ENABLE);
+ aspeed_udma_rx_chan_ctrl(dma->ch, ASPEED_UDMA_OP_ENABLE);
+ }
+
+ memset(&port->icount, 0, sizeof(port->icount));
+ return serial8250_do_startup(port);
+
+free_dma_n_out:
+ kfree(dma->rx_rb->buf);
+out:
+ return rc;
+}
+
+static void ast8250_shutdown(struct uart_port *port)
+{
+ int rc;
+ struct ast8250_data *data = port->private_data;
+ struct ast8250_udma *dma;
+
+ if (data->use_dma) {
+ dma = &data->dma;
+
+ aspeed_udma_tx_chan_ctrl(dma->ch, ASPEED_UDMA_OP_RESET);
+ aspeed_udma_rx_chan_ctrl(dma->ch, ASPEED_UDMA_OP_RESET);
+
+ aspeed_udma_tx_chan_ctrl(dma->ch, ASPEED_UDMA_OP_DISABLE);
+ aspeed_udma_rx_chan_ctrl(dma->ch, ASPEED_UDMA_OP_DISABLE);
+
+ rc = aspeed_udma_free_tx_chan(dma->ch);
+ if (rc)
+ dev_err(port->dev, "failed to free DMA TX channel, rc=%d\n", rc);
+
+ rc = aspeed_udma_free_rx_chan(dma->ch);
+ if (rc)
+ dev_err(port->dev, "failed to free DMA TX channel, rc=%d\n", rc);
+
+ dma_unmap_single(port->dev, dma->tx_addr,
+ dma->tx_rbsz, DMA_TO_DEVICE);
+ dma_unmap_single(port->dev, dma->rx_addr,
+ dma->rx_rbsz, DMA_FROM_DEVICE);
+
+ kfree(dma->rx_rb->buf);
+ }
+
+ if (data->is_vuart)
+ ast8250_vuart_set_host_tx_discard(data, true);
+
+ serial8250_do_shutdown(port);
+}
+
+static int __maybe_unused ast8250_suspend(struct device *dev)
+{
+ struct ast8250_data *data = dev_get_drvdata(dev);
+
+ serial8250_suspend_port(data->line);
+
+ return 0;
+}
+
+static int __maybe_unused ast8250_resume(struct device *dev)
+{
+ struct ast8250_data *data = dev_get_drvdata(dev);
+
+ serial8250_resume_port(data->line);
+
+ return 0;
+}
+
+static int ast8250_probe(struct platform_device *pdev)
+{
+ int rc;
+ struct uart_8250_port uart = {};
+ struct uart_port *port = &uart.port;
+ struct device *dev = &pdev->dev;
+ struct ast8250_data *data;
+
+ struct resource *res;
+ u32 irq;
+
+ data = devm_kzalloc(dev, sizeof(*data), GFP_KERNEL);
+ if (data == NULL)
+ return -ENOMEM;
+
+ data->dma.rx_rb = devm_kzalloc(dev, sizeof(data->dma.rx_rb), GFP_KERNEL);
+ if (data->dma.rx_rb == NULL)
+ return -ENOMEM;
+
+ irq = platform_get_irq(pdev, 0);
+ if (irq < 0)
+ return irq;
+
+ res = platform_get_resource(pdev, IORESOURCE_MEM, 0);
+ if (res == NULL) {
+ dev_err(dev, "failed to get register base\n");
+ return -ENODEV;
+ }
+
+ data->regs = devm_ioremap(dev, res->start, resource_size(res));
+ if (IS_ERR(data->regs)) {
+ dev_err(dev, "failed to map registers\n");
+ return PTR_ERR(data->regs);
+ }
+
+ data->clk = devm_clk_get(dev, NULL);
+ if (IS_ERR(data->clk)) {
+ dev_err(dev, "failed to get clocks\n");
+ return -ENODEV;
+ }
+
+ rc = clk_prepare_enable(data->clk);
+ if (rc) {
+ dev_err(dev, "failed to enable clock\n");
+ return rc;
+ }
+
+ data->rst = devm_reset_control_get_optional_exclusive(dev, NULL);
+ if (!IS_ERR(data->rst))
+ reset_control_deassert(data->rst);
+
+ data->is_vuart = of_property_read_bool(dev->of_node, "virtual");
+ if (data->is_vuart) {
+ rc = of_property_read_u32(dev->of_node, "port", &data->vuart.port);
+ if (rc) {
+ dev_err(dev, "failed to get VUART port address\n");
+ return -ENODEV;
+ }
+
+ rc = of_property_read_u32(dev->of_node, "sirq", &data->vuart.sirq);
+ if (rc) {
+ dev_err(dev, "failed to get VUART SIRQ number\n");
+ return -ENODEV;
+ }
+
+ rc = of_property_read_u32(dev->of_node, "sirq-polarity", &data->vuart.sirq_pol);
+ if (rc) {
+ dev_err(dev, "failed to get VUART SIRQ polarity\n");
+ return -ENODEV;
+ }
+
+ ast8250_vuart_init(data);
+ ast8250_vuart_set_host_tx_discard(data, true);
+ ast8250_vuart_set_enable(data, true);
+ }
+
+ data->use_dma = of_property_read_bool(dev->of_node, "dma-mode");
+ if (data->use_dma) {
+ rc = of_property_read_u32(dev->of_node, "dma-channel", &data->dma.ch);
+ if (rc) {
+ dev_err(dev, "failed to get DMA channel\n");
+ return -ENODEV;
+ }
+
+ data->dma.tx_tmout_dis = of_property_read_bool(dev->of_node,
+ "dma-tx-timeout-disable");
+ data->dma.rx_tmout_dis = of_property_read_bool(dev->of_node,
+ "dma-rx-timeout-disable");
+ }
+
+ spin_lock_init(&port->lock);
+ port->dev = dev;
+ port->type = PORT_16550A;
+ port->irq = irq;
+ port->line = of_alias_get_id(dev->of_node, "serial");
+ port->handle_irq = ast8250_handle_irq;
+ port->mapbase = res->start;
+ port->mapsize = resource_size(res);
+ port->membase = data->regs;
+ port->uartclk = clk_get_rate(data->clk);
+ port->regshift = 2;
+ port->iotype = UPIO_MEM32;
+ port->flags = UPF_FIXED_TYPE | UPF_FIXED_PORT | UPF_SHARE_IRQ;
+ port->startup = ast8250_startup;
+ port->shutdown = ast8250_shutdown;
+ port->private_data = data;
+ uart.bugs |= UART_BUG_TXRACE;
+
+ data->line = serial8250_register_8250_port(&uart);
+ if (data->line < 0) {
+ dev_err(dev, "failed to register 8250 port\n");
+ return data->line;
+ }
+
+ pm_runtime_set_active(&pdev->dev);
+ pm_runtime_enable(&pdev->dev);
+
+ platform_set_drvdata(pdev, data);
+ return 0;
+}
+
+static int ast8250_remove(struct platform_device *pdev)
+{
+ struct ast8250_data *data = platform_get_drvdata(pdev);
+
+ if (data->is_vuart)
+ ast8250_vuart_set_enable(data, false);
+
+ serial8250_unregister_port(data->line);
+ return 0;
+}
+
+static const struct dev_pm_ops ast8250_pm_ops = {
+ SET_SYSTEM_SLEEP_PM_OPS(ast8250_suspend, ast8250_resume)
+};
+
+static const struct of_device_id ast8250_of_match[] = {
+ { .compatible = "aspeed,ast2600-uart" },
+};
+
+static struct platform_driver ast8250_platform_driver = {
+ .driver = {
+ .name = DEVICE_NAME,
+ .pm = &ast8250_pm_ops,
+ .of_match_table = ast8250_of_match,
+ },
+ .probe = ast8250_probe,
+ .remove = ast8250_remove,
+};
+
+module_platform_driver(ast8250_platform_driver);
+
+MODULE_AUTHOR("Chia-Wei Wang <[email protected]>");
+MODULE_LICENSE("GPL");
+MODULE_DESCRIPTION("Aspeed UART Driver");
diff --git a/drivers/tty/serial/8250/Kconfig b/drivers/tty/serial/8250/Kconfig
index b0f62345bc84..d8ecc261d8c4 100644
--- a/drivers/tty/serial/8250/Kconfig
+++ b/drivers/tty/serial/8250/Kconfig
@@ -538,6 +538,14 @@ config SERIAL_8250_BCM7271
including DMA support and high accuracy BAUD rates, say
Y to this option. If unsure, say N.

+config SERIAL_8250_ASPEED
+ tristate "Aspeed serial port support"
+ depends on SERIAL_8250 && ARCH_ASPEED
+ help
+ If you have a system using an Aspeed AST26xx SoCs and wish to
+ make use of its UARTs and VUARTs, which are 16550A compatible
+ and include DMA support, say Y to this option. If unsure, say N.
+
config SERIAL_OF_PLATFORM
tristate "Devicetree based probing for 8250 ports"
depends on SERIAL_8250 && OF
diff --git a/drivers/tty/serial/8250/Makefile b/drivers/tty/serial/8250/Makefile
index 1615bfdde2a0..7f05b7ed422b 100644
--- a/drivers/tty/serial/8250/Makefile
+++ b/drivers/tty/serial/8250/Makefile
@@ -42,6 +42,7 @@ obj-$(CONFIG_SERIAL_8250_PERICOM) += 8250_pericom.o
obj-$(CONFIG_SERIAL_8250_PXA) += 8250_pxa.o
obj-$(CONFIG_SERIAL_8250_TEGRA) += 8250_tegra.o
obj-$(CONFIG_SERIAL_8250_BCM7271) += 8250_bcm7271.o
+obj-$(CONFIG_SERIAL_8250_ASPEED) += 8250_aspeed.o
obj-$(CONFIG_SERIAL_OF_PLATFORM) += 8250_of.o

CFLAGS_8250_ingenic.o += -I$(srctree)/scripts/dtc/libfdt
--
2.25.1


2023-02-10 07:28:05

by ChiaWei Wang

[permalink] [raw]
Subject: [PATCH 2/4] soc: aspeed: Add UART DMA support

This driver provides DMA support for AST26xx UART and VUART
devices. It is useful to offload CPU overhead while using
UART/VUART for binary file transfer.

Signed-off-by: Chia-Wei Wang <[email protected]>
---
drivers/soc/aspeed/Kconfig | 9 +
drivers/soc/aspeed/Makefile | 1 +
drivers/soc/aspeed/aspeed-udma.c | 447 +++++++++++++++++++++++++
include/linux/soc/aspeed/aspeed-udma.h | 34 ++
4 files changed, 491 insertions(+)
create mode 100644 drivers/soc/aspeed/aspeed-udma.c
create mode 100644 include/linux/soc/aspeed/aspeed-udma.h

diff --git a/drivers/soc/aspeed/Kconfig b/drivers/soc/aspeed/Kconfig
index f579ee0b5afa..c3bb238bea75 100644
--- a/drivers/soc/aspeed/Kconfig
+++ b/drivers/soc/aspeed/Kconfig
@@ -52,6 +52,15 @@ config ASPEED_SOCINFO
help
Say yes to support decoding of ASPEED BMC information.

+config ASPEED_UDMA
+ tristate "Aspeed UDMA Engine Driver"
+ default ARCH_ASPEED
+ help
+ Enable support for the Aspeed UDMA Engine found on the
+ Aspeed AST26xx SOCs. The UDMA engine provides UART DMA
+ operations between the memory buffer and UART/VUART
+ FIFO data.
+
endmenu

endif
diff --git a/drivers/soc/aspeed/Makefile b/drivers/soc/aspeed/Makefile
index b35d74592964..5aeabafee1d4 100644
--- a/drivers/soc/aspeed/Makefile
+++ b/drivers/soc/aspeed/Makefile
@@ -4,3 +4,4 @@ obj-$(CONFIG_ASPEED_LPC_SNOOP) += aspeed-lpc-snoop.o
obj-$(CONFIG_ASPEED_UART_ROUTING) += aspeed-uart-routing.o
obj-$(CONFIG_ASPEED_P2A_CTRL) += aspeed-p2a-ctrl.o
obj-$(CONFIG_ASPEED_SOCINFO) += aspeed-socinfo.o
+obj-$(CONFIG_ASPEED_UDMA) += aspeed-udma.o
diff --git a/drivers/soc/aspeed/aspeed-udma.c b/drivers/soc/aspeed/aspeed-udma.c
new file mode 100644
index 000000000000..95898fbd6ed8
--- /dev/null
+++ b/drivers/soc/aspeed/aspeed-udma.c
@@ -0,0 +1,447 @@
+// SPDX-License-Identifier: GPL-2.0-or-later
+/*
+ * Copyright (C) Aspeed Technology Inc.
+ */
+#include <linux/io.h>
+#include <linux/module.h>
+#include <linux/interrupt.h>
+#include <linux/module.h>
+#include <linux/of.h>
+#include <linux/of_device.h>
+#include <linux/platform_device.h>
+#include <linux/dma-mapping.h>
+#include <linux/spinlock.h>
+#include <linux/soc/aspeed/aspeed-udma.h>
+#include <linux/delay.h>
+
+#define DEVICE_NAME "aspeed-udma"
+
+/* UART DMA registers offset */
+#define UDMA_TX_DMA_EN 0x000
+#define UDMA_RX_DMA_EN 0x004
+#define UDMA_TIMEOUT_TIMER 0x00c
+#define UDMA_TX_DMA_RST 0x020
+#define UDMA_RX_DMA_RST 0x024
+#define UDMA_TX_DMA_INT_EN 0x030
+#define UDMA_TX_DMA_INT_STAT 0x034
+#define UDMA_RX_DMA_INT_EN 0x038
+#define UDMA_RX_DMA_INT_STAT 0x03c
+
+#define UDMA_CHX_OFF(x) ((x) * 0x20)
+#define UDMA_CHX_TX_RD_PTR(x) (0x040 + UDMA_CHX_OFF(x))
+#define UDMA_CHX_TX_WR_PTR(x) (0x044 + UDMA_CHX_OFF(x))
+#define UDMA_CHX_TX_BUF_BASE(x) (0x048 + UDMA_CHX_OFF(x))
+#define UDMA_CHX_TX_CTRL(x) (0x04c + UDMA_CHX_OFF(x))
+#define UDMA_TX_CTRL_TMOUT_DISABLE BIT(4)
+#define UDMA_TX_CTRL_BUFSZ_MASK GENMASK(3, 0)
+#define UDMA_TX_CTRL_BUFSZ_SHIFT 0
+#define UDMA_CHX_RX_RD_PTR(x) (0x050 + UDMA_CHX_OFF(x))
+#define UDMA_CHX_RX_WR_PTR(x) (0x054 + UDMA_CHX_OFF(x))
+#define UDMA_CHX_RX_BUF_BASE(x) (0x058 + UDMA_CHX_OFF(x))
+#define UDMA_CHX_RX_CTRL(x) (0x05c + UDMA_CHX_OFF(x))
+#define UDMA_RX_CTRL_TMOUT_DISABLE BIT(4)
+#define UDMA_RX_CTRL_BUFSZ_MASK GENMASK(3, 0)
+#define UDMA_RX_CTRL_BUFSZ_SHIFT 0
+
+#define UDMA_MAX_CHANNEL 14
+#define UDMA_TIMEOUT 0x200
+
+enum aspeed_udma_bufsz_code {
+ UDMA_BUFSZ_CODE_1KB,
+ UDMA_BUFSZ_CODE_4KB,
+ UDMA_BUFSZ_CODE_16KB,
+ UDMA_BUFSZ_CODE_64KB,
+
+ /*
+ * 128KB and above are supported ONLY for
+ * virtual UARTs. For physical UARTs, the
+ * size code is wrapped around at the 64K
+ * boundary.
+ */
+ UDMA_BUFSZ_CODE_128KB,
+ UDMA_BUFSZ_CODE_256KB,
+ UDMA_BUFSZ_CODE_512KB,
+ UDMA_BUFSZ_CODE_1024KB,
+ UDMA_BUFSZ_CODE_2048KB,
+ UDMA_BUFSZ_CODE_4096KB,
+ UDMA_BUFSZ_CODE_8192KB,
+ UDMA_BUFSZ_CODE_16384KB,
+};
+
+struct aspeed_udma_chan {
+ dma_addr_t dma_addr;
+
+ struct circ_buf *rb;
+ u32 rb_sz;
+
+ aspeed_udma_cb_t cb;
+ void *cb_arg;
+
+ bool dis_tmout;
+};
+
+struct aspeed_udma {
+ struct device *dev;
+ u8 __iomem *regs;
+ int irq;
+ struct aspeed_udma_chan tx_chs[UDMA_MAX_CHANNEL];
+ struct aspeed_udma_chan rx_chs[UDMA_MAX_CHANNEL];
+ spinlock_t lock;
+};
+
+struct aspeed_udma udma[1];
+
+static int aspeed_udma_get_bufsz_code(u32 buf_sz)
+{
+ switch (buf_sz) {
+ case 0x400:
+ return UDMA_BUFSZ_CODE_1KB;
+ case 0x1000:
+ return UDMA_BUFSZ_CODE_4KB;
+ case 0x4000:
+ return UDMA_BUFSZ_CODE_16KB;
+ case 0x10000:
+ return UDMA_BUFSZ_CODE_64KB;
+ case 0x20000:
+ return UDMA_BUFSZ_CODE_128KB;
+ case 0x40000:
+ return UDMA_BUFSZ_CODE_256KB;
+ case 0x80000:
+ return UDMA_BUFSZ_CODE_512KB;
+ case 0x100000:
+ return UDMA_BUFSZ_CODE_1024KB;
+ case 0x200000:
+ return UDMA_BUFSZ_CODE_2048KB;
+ case 0x400000:
+ return UDMA_BUFSZ_CODE_4096KB;
+ case 0x800000:
+ return UDMA_BUFSZ_CODE_8192KB;
+ case 0x1000000:
+ return UDMA_BUFSZ_CODE_16384KB;
+ default:
+ return -1;
+ }
+
+ return -1;
+}
+
+static u32 aspeed_udma_get_tx_rptr(u32 ch_no)
+{
+ return readl(udma->regs + UDMA_CHX_TX_RD_PTR(ch_no));
+}
+
+static u32 aspeed_udma_get_rx_wptr(u32 ch_no)
+{
+ return readl(udma->regs + UDMA_CHX_RX_WR_PTR(ch_no));
+}
+
+static void aspeed_udma_set_ptr(u32 ch_no, u32 ptr, bool is_tx)
+{
+ writel(ptr, udma->regs +
+ ((is_tx) ? UDMA_CHX_TX_WR_PTR(ch_no) : UDMA_CHX_RX_RD_PTR(ch_no)));
+}
+
+void aspeed_udma_set_tx_wptr(u32 ch_no, u32 wptr)
+{
+ aspeed_udma_set_ptr(ch_no, wptr, true);
+}
+EXPORT_SYMBOL(aspeed_udma_set_tx_wptr);
+
+void aspeed_udma_set_rx_rptr(u32 ch_no, u32 rptr)
+{
+ aspeed_udma_set_ptr(ch_no, rptr, false);
+}
+EXPORT_SYMBOL(aspeed_udma_set_rx_rptr);
+
+static int aspeed_udma_free_chan(u32 ch_no, bool is_tx)
+{
+ u32 reg;
+ unsigned long flags;
+
+ if (ch_no > UDMA_MAX_CHANNEL)
+ return -EINVAL;
+
+ spin_lock_irqsave(&udma->lock, flags);
+
+ reg = readl(udma->regs +
+ ((is_tx) ? UDMA_TX_DMA_INT_EN : UDMA_RX_DMA_INT_EN));
+ reg &= ~(0x1 << ch_no);
+
+ writel(reg, udma->regs +
+ ((is_tx) ? UDMA_TX_DMA_INT_EN : UDMA_RX_DMA_INT_EN));
+
+ spin_unlock_irqrestore(&udma->lock, flags);
+
+ return 0;
+}
+
+int aspeed_udma_free_tx_chan(u32 ch_no)
+{
+ return aspeed_udma_free_chan(ch_no, true);
+}
+EXPORT_SYMBOL(aspeed_udma_free_tx_chan);
+
+int aspeed_udma_free_rx_chan(u32 ch_no)
+{
+ return aspeed_udma_free_chan(ch_no, false);
+}
+EXPORT_SYMBOL(aspeed_udma_free_rx_chan);
+
+static int aspeed_udma_request_chan(u32 ch_no, dma_addr_t addr,
+ struct circ_buf *rb, u32 rb_sz,
+ aspeed_udma_cb_t cb, void *id, bool dis_tmout, bool is_tx)
+{
+ int retval = 0;
+ int rbsz_code;
+
+ u32 reg;
+ unsigned long flags;
+ struct aspeed_udma_chan *ch;
+
+ if (ch_no > UDMA_MAX_CHANNEL) {
+ retval = -EINVAL;
+ goto out;
+ }
+
+ if (IS_ERR_OR_NULL(rb) || IS_ERR_OR_NULL(rb->buf)) {
+ retval = -EINVAL;
+ goto out;
+ }
+
+ rbsz_code = aspeed_udma_get_bufsz_code(rb_sz);
+ if (rbsz_code < 0) {
+ retval = -EINVAL;
+ goto out;
+ }
+
+ spin_lock_irqsave(&udma->lock, flags);
+
+ if (is_tx) {
+ reg = readl(udma->regs + UDMA_TX_DMA_INT_EN);
+ if (reg & (0x1 << ch_no)) {
+ retval = -EBUSY;
+ goto unlock_n_out;
+ }
+
+ reg |= (0x1 << ch_no);
+ writel(reg, udma->regs + UDMA_TX_DMA_INT_EN);
+
+ reg = readl(udma->regs + UDMA_CHX_TX_CTRL(ch_no));
+ reg |= (dis_tmout) ? UDMA_TX_CTRL_TMOUT_DISABLE : 0;
+ reg |= (rbsz_code << UDMA_TX_CTRL_BUFSZ_SHIFT) & UDMA_TX_CTRL_BUFSZ_MASK;
+ writel(reg, udma->regs + UDMA_CHX_TX_CTRL(ch_no));
+
+ writel(addr, udma->regs + UDMA_CHX_TX_BUF_BASE(ch_no));
+ } else {
+ reg = readl(udma->regs + UDMA_RX_DMA_INT_EN);
+ if (reg & (0x1 << ch_no)) {
+ retval = -EBUSY;
+ goto unlock_n_out;
+ }
+
+ reg |= (0x1 << ch_no);
+ writel(reg, udma->regs + UDMA_RX_DMA_INT_EN);
+
+ reg = readl(udma->regs + UDMA_CHX_RX_CTRL(ch_no));
+ reg |= (dis_tmout) ? UDMA_RX_CTRL_TMOUT_DISABLE : 0;
+ reg |= (rbsz_code << UDMA_RX_CTRL_BUFSZ_SHIFT) & UDMA_RX_CTRL_BUFSZ_MASK;
+ writel(reg, udma->regs + UDMA_CHX_RX_CTRL(ch_no));
+
+ writel(addr, udma->regs + UDMA_CHX_RX_BUF_BASE(ch_no));
+ }
+
+ ch = (is_tx) ? &udma->tx_chs[ch_no] : &udma->rx_chs[ch_no];
+ ch->rb = rb;
+ ch->rb_sz = rb_sz;
+ ch->cb = cb;
+ ch->cb_arg = id;
+ ch->dma_addr = addr;
+ ch->dis_tmout = dis_tmout;
+
+unlock_n_out:
+ spin_unlock_irqrestore(&udma->lock, flags);
+out:
+ return 0;
+}
+
+int aspeed_udma_request_tx_chan(u32 ch_no, dma_addr_t addr,
+ struct circ_buf *rb, u32 rb_sz,
+ aspeed_udma_cb_t cb, void *id, bool dis_tmout)
+{
+ return aspeed_udma_request_chan(ch_no, addr, rb, rb_sz, cb, id,
+ dis_tmout, true);
+}
+EXPORT_SYMBOL(aspeed_udma_request_tx_chan);
+
+int aspeed_udma_request_rx_chan(u32 ch_no, dma_addr_t addr,
+ struct circ_buf *rb, u32 rb_sz,
+ aspeed_udma_cb_t cb, void *id, bool dis_tmout)
+{
+ return aspeed_udma_request_chan(ch_no, addr, rb, rb_sz, cb, id,
+ dis_tmout, false);
+}
+EXPORT_SYMBOL(aspeed_udma_request_rx_chan);
+
+static void aspeed_udma_chan_ctrl(u32 ch_no, u32 op, bool is_tx)
+{
+ unsigned long flags;
+ u32 reg_en, reg_rst;
+ u32 reg_en_off = (is_tx) ? UDMA_TX_DMA_EN : UDMA_RX_DMA_EN;
+ u32 reg_rst_off = (is_tx) ? UDMA_TX_DMA_RST : UDMA_TX_DMA_RST;
+
+ if (ch_no > UDMA_MAX_CHANNEL)
+ return;
+
+ spin_lock_irqsave(&udma->lock, flags);
+
+ reg_en = readl(udma->regs + reg_en_off);
+ reg_rst = readl(udma->regs + reg_rst_off);
+
+ switch (op) {
+ case ASPEED_UDMA_OP_ENABLE:
+ reg_en |= (0x1 << ch_no);
+ writel(reg_en, udma->regs + reg_en_off);
+ break;
+ case ASPEED_UDMA_OP_DISABLE:
+ reg_en &= ~(0x1 << ch_no);
+ writel(reg_en, udma->regs + reg_en_off);
+ break;
+ case ASPEED_UDMA_OP_RESET:
+ reg_en &= ~(0x1 << ch_no);
+ writel(reg_en, udma->regs + reg_en_off);
+
+ reg_rst |= (0x1 << ch_no);
+ writel(reg_rst, udma->regs + reg_rst_off);
+
+ udelay(100);
+
+ reg_rst &= ~(0x1 << ch_no);
+ writel(reg_rst, udma->regs + reg_rst_off);
+ break;
+ default:
+ break;
+ }
+
+ spin_unlock_irqrestore(&udma->lock, flags);
+}
+
+void aspeed_udma_tx_chan_ctrl(u32 ch_no, enum aspeed_udma_ops op)
+{
+ aspeed_udma_chan_ctrl(ch_no, op, true);
+}
+EXPORT_SYMBOL(aspeed_udma_tx_chan_ctrl);
+
+void aspeed_udma_rx_chan_ctrl(u32 ch_no, enum aspeed_udma_ops op)
+{
+ aspeed_udma_chan_ctrl(ch_no, op, false);
+}
+EXPORT_SYMBOL(aspeed_udma_rx_chan_ctrl);
+
+static irqreturn_t aspeed_udma_isr(int irq, void *arg)
+{
+ u32 bit;
+ unsigned long tx_stat = readl(udma->regs + UDMA_TX_DMA_INT_STAT);
+ unsigned long rx_stat = readl(udma->regs + UDMA_RX_DMA_INT_STAT);
+
+ if (udma != (struct aspeed_udma *)arg)
+ return IRQ_NONE;
+
+ if (tx_stat == 0 && rx_stat == 0)
+ return IRQ_NONE;
+
+ for_each_set_bit(bit, &tx_stat, UDMA_MAX_CHANNEL) {
+ writel((0x1 << bit), udma->regs + UDMA_TX_DMA_INT_STAT);
+ if (udma->tx_chs[bit].cb)
+ udma->tx_chs[bit].cb(aspeed_udma_get_tx_rptr(bit),
+ udma->tx_chs[bit].cb_arg);
+ }
+
+ for_each_set_bit(bit, &rx_stat, UDMA_MAX_CHANNEL) {
+ writel((0x1 << bit), udma->regs + UDMA_RX_DMA_INT_STAT);
+ if (udma->rx_chs[bit].cb)
+ udma->rx_chs[bit].cb(aspeed_udma_get_rx_wptr(bit),
+ udma->rx_chs[bit].cb_arg);
+ }
+
+ return IRQ_HANDLED;
+}
+
+static int aspeed_udma_probe(struct platform_device *pdev)
+{
+ int i, rc;
+ struct resource *res;
+ struct device *dev = &pdev->dev;
+
+ res = platform_get_resource(pdev, IORESOURCE_MEM, 0);
+ if (IS_ERR_OR_NULL(res)) {
+ dev_err(dev, "failed to get register base\n");
+ return -ENODEV;
+ }
+
+ udma->regs = devm_ioremap_resource(dev, res);
+ if (IS_ERR_OR_NULL(udma->regs)) {
+ dev_err(dev, "failed to map registers\n");
+ return PTR_ERR(udma->regs);
+ }
+
+ /* disable for safety */
+ writel(0x0, udma->regs + UDMA_TX_DMA_EN);
+ writel(0x0, udma->regs + UDMA_RX_DMA_EN);
+
+ udma->irq = platform_get_irq(pdev, 0);
+ if (udma->irq < 0) {
+ dev_err(dev, "failed to get IRQ number\n");
+ return -ENODEV;
+ }
+
+ rc = devm_request_irq(dev, udma->irq, aspeed_udma_isr,
+ IRQF_SHARED, DEVICE_NAME, udma);
+ if (rc) {
+ dev_err(dev, "failed to request IRQ handler\n");
+ return rc;
+ }
+
+ for (i = 0; i < UDMA_MAX_CHANNEL; ++i) {
+ writel(0, udma->regs + UDMA_CHX_TX_WR_PTR(i));
+ writel(0, udma->regs + UDMA_CHX_RX_RD_PTR(i));
+ }
+
+ writel(0xffffffff, udma->regs + UDMA_TX_DMA_RST);
+ writel(0x0, udma->regs + UDMA_TX_DMA_RST);
+
+ writel(0xffffffff, udma->regs + UDMA_RX_DMA_RST);
+ writel(0x0, udma->regs + UDMA_RX_DMA_RST);
+
+ writel(0x0, udma->regs + UDMA_TX_DMA_INT_EN);
+ writel(0xffffffff, udma->regs + UDMA_TX_DMA_INT_STAT);
+ writel(0x0, udma->regs + UDMA_RX_DMA_INT_EN);
+ writel(0xffffffff, udma->regs + UDMA_RX_DMA_INT_STAT);
+
+ writel(UDMA_TIMEOUT, udma->regs + UDMA_TIMEOUT_TIMER);
+
+ spin_lock_init(&udma->lock);
+
+ dev_set_drvdata(dev, udma);
+
+ return 0;
+}
+
+static const struct of_device_id aspeed_udma_match[] = {
+ { .compatible = "aspeed,ast2600-udma" },
+ { },
+};
+
+static struct platform_driver aspeed_udma_driver = {
+ .driver = {
+ .name = DEVICE_NAME,
+ .of_match_table = aspeed_udma_match,
+
+ },
+ .probe = aspeed_udma_probe,
+};
+
+module_platform_driver(aspeed_udma_driver);
+
+MODULE_AUTHOR("Chia-Wei Wang <[email protected]>");
+MODULE_LICENSE("GPL");
+MODULE_DESCRIPTION("Aspeed UDMA Engine Driver");
diff --git a/include/linux/soc/aspeed/aspeed-udma.h b/include/linux/soc/aspeed/aspeed-udma.h
new file mode 100644
index 000000000000..4ec95d726ede
--- /dev/null
+++ b/include/linux/soc/aspeed/aspeed-udma.h
@@ -0,0 +1,34 @@
+/* SPDX-License-Identifier: GPL-2.0-only */
+/*
+ * Copyright (C) Aspeed Technology Inc.
+ */
+#ifndef __ASPEED_UDMA_H__
+#define __ASPEED_UDMA_H__
+
+#include <linux/circ_buf.h>
+
+typedef void (*aspeed_udma_cb_t)(int rb_rwptr, void *id);
+
+enum aspeed_udma_ops {
+ ASPEED_UDMA_OP_ENABLE,
+ ASPEED_UDMA_OP_DISABLE,
+ ASPEED_UDMA_OP_RESET,
+};
+
+void aspeed_udma_set_tx_wptr(u32 ch_no, u32 wptr);
+void aspeed_udma_set_rx_rptr(u32 ch_no, u32 rptr);
+
+void aspeed_udma_tx_chan_ctrl(u32 ch_no, enum aspeed_udma_ops op);
+void aspeed_udma_rx_chan_ctrl(u32 ch_no, enum aspeed_udma_ops op);
+
+int aspeed_udma_request_tx_chan(u32 ch_no, dma_addr_t addr,
+ struct circ_buf *rb, u32 rb_sz,
+ aspeed_udma_cb_t cb, void *id, bool en_tmout);
+int aspeed_udma_request_rx_chan(u32 ch_no, dma_addr_t addr,
+ struct circ_buf *rb, u32 rb_sz,
+ aspeed_udma_cb_t cb, void *id, bool en_tmout);
+
+int aspeed_udma_free_tx_chan(u32 ch_no);
+int aspeed_udma_free_rx_chan(u32 ch_no);
+
+#endif
--
2.25.1


2023-02-10 09:12:43

by Krzysztof Kozlowski

[permalink] [raw]
Subject: Re: [PATCH 1/4] dt-bindings: aspeed: Add UART controller

On 10/02/2023 08:26, Chia-Wei Wang wrote:
> Add dt-bindings for Aspeed UART controller.

Describe the hardware. What's the difference against existing Aspeed
UART used everywhere?

>
> Signed-off-by: Chia-Wei Wang <[email protected]>
> ---
> .../bindings/serial/aspeed,uart.yaml | 81 +++++++++++++++++++
> 1 file changed, 81 insertions(+)
> create mode 100644 Documentation/devicetree/bindings/serial/aspeed,uart.yaml

Filename: aspeed,ast2600-uart.yaml
(unless you are adding here more compatibles, but your const suggests
that it's not going to happen)

>
> diff --git a/Documentation/devicetree/bindings/serial/aspeed,uart.yaml b/Documentation/devicetree/bindings/serial/aspeed,uart.yaml
> new file mode 100644
> index 000000000000..10c457d6a72e
> --- /dev/null
> +++ b/Documentation/devicetree/bindings/serial/aspeed,uart.yaml
> @@ -0,0 +1,81 @@
> +# SPDX-License-Identifier: (GPL-2.0-only OR BSD-2-Clause)
> +%YAML 1.2
> +---
> +$id: http://devicetree.org/schemas/serial/aspeed,uart.yaml#
> +$schema: http://devicetree.org/meta-schemas/core.yaml#
> +
> +title: Aspeed Universal Asynchronous Receiver/Transmitter

This title matches other Aspeed UARTs, so aren't you duplicating bindings?

> +
> +maintainers:
> + - Chia-Wei Wang <[email protected]>
> +
> +allOf:
> + - $ref: serial.yaml#
> +
> +description: |
> + The Aspeed UART is based on the basic 8250 UART and compatible
> + with 16550A, with support for DMA
> +
> +properties:
> + compatible:
> + const: aspeed,ast2600-uart
> +
> + reg:
> + description: The base address of the UART register bank

Drop description

> + maxItems: 1
> +
> + clocks:
> + description: The clock the baudrate is derived from
> + maxItems: 1
> +
> + interrupts:
> + description: The IRQ number of the device

Drop description

> + maxItems: 1
> +
> + dma-mode:
> + type: boolean
> + description: Enable DMA

Drop property. DMA is enabled on presence of dmas.

> +
> + dma-channel:
> + $ref: /schemas/types.yaml#/definitions/uint32
> + description: The channel number to be used in the DMA engine

That's not a correct DMA property. dmas and dma-names
git grep dma -- Documentation/devicetree/bindings/


> +
> + virtual:
> + type: boolean
> + description: Indicate virtual UART

Virtual means not existing in real world? We do not describe in DTS
non-existing devices. Drop entire property.

> +
> + sirq:
> + $ref: /schemas/types.yaml#/definitions/uint32
> + description: The serial IRQ number on LPC bus interface

Drop entire property.

> +
> + sirq-polarity:
> + $ref: /schemas/types.yaml#/definitions/uint32
> + description: The serial IRQ polarity on LPC bus interface

Drop entire property.

> +
> + pinctrl-0: true
> +
> + pinctrl_names:
> + const: default


Drop both, you do no not need them.

> +
> +required:
> + - compatible
> + - reg
> + - clocks
> + - interrupts
> +
> +unevaluatedProperties: false
> +

Best regards,
Krzysztof


2023-02-10 09:14:00

by Krzysztof Kozlowski

[permalink] [raw]
Subject: Re: [PATCH 2/4] soc: aspeed: Add UART DMA support

On 10/02/2023 08:26, Chia-Wei Wang wrote:
> This driver provides DMA support for AST26xx UART and VUART
> devices. It is useful to offload CPU overhead while using
> UART/VUART for binary file transfer.
>
> Signed-off-by: Chia-Wei Wang <[email protected]>
> ---
> drivers/soc/aspeed/Kconfig | 9 +
> drivers/soc/aspeed/Makefile | 1 +
> drivers/soc/aspeed/aspeed-udma.c | 447 +++++++++++++++++++++++++
> include/linux/soc/aspeed/aspeed-udma.h | 34 ++

NAK.

DMA drivers do not go to soc, but to dma subsystem.

> 4 files changed, 491 insertions(+)
> create mode 100644 drivers/soc/aspeed/aspeed-udma.c
> create mode 100644 include/linux/soc/aspeed/aspeed-udma.h
>

(...)

> +
> + return 0;
> +}
> +
> +static const struct of_device_id aspeed_udma_match[] = {
> + { .compatible = "aspeed,ast2600-udma" },

Undocumented compatible.

Please run scripts/checkpatch.pl and fix reported warnings.



Best regards,
Krzysztof


2023-02-10 09:14:56

by Krzysztof Kozlowski

[permalink] [raw]
Subject: Re: [PATCH 4/4] ARM: dts: aspeed-g6: Add UDMA node

On 10/02/2023 08:26, Chia-Wei Wang wrote:
> Add the device tree node for UART DMA controller.
>
> Signed-off-by: Chia-Wei Wang <[email protected]>
> ---
> arch/arm/boot/dts/aspeed-g6.dtsi | 7 +++++++
> 1 file changed, 7 insertions(+)
>
> diff --git a/arch/arm/boot/dts/aspeed-g6.dtsi b/arch/arm/boot/dts/aspeed-g6.dtsi
> index cc2f8b785917..3f4e9da8f6c7 100644
> --- a/arch/arm/boot/dts/aspeed-g6.dtsi
> +++ b/arch/arm/boot/dts/aspeed-g6.dtsi
> @@ -850,6 +850,13 @@ fsim1: fsi@1e79b100 {
> clocks = <&syscon ASPEED_CLK_GATE_FSICLK>;
> status = "disabled";
> };
> +
> + udma: uart-dma@1e79e000 {

Node names should be generic.
https://devicetree-specification.readthedocs.io/en/latest/chapter2-devicetree-basics.html#generic-names-recommendation

> + compatible = "aspeed,ast2600-udma";

Please run scripts/checkpatch.pl and fix reported warnings.



Best regards,
Krzysztof


2023-02-10 10:00:43

by kernel test robot

[permalink] [raw]
Subject: Re: [PATCH 2/4] soc: aspeed: Add UART DMA support

Hi Chia-Wei,

Thank you for the patch! Perhaps something to improve:

[auto build test WARNING on tty/tty-testing]
[also build test WARNING on tty/tty-next tty/tty-linus robh/for-next driver-core/driver-core-testing driver-core/driver-core-next driver-core/driver-core-linus usb/usb-testing usb/usb-next usb/usb-linus linus/master v6.2-rc7 next-20230210]
[If your patch is applied to the wrong git tree, kindly drop us a note.
And when submitting patch, we suggest to use '--base' as documented in
https://git-scm.com/docs/git-format-patch#_base_tree_information]

url: https://github.com/intel-lab-lkp/linux/commits/Chia-Wei-Wang/dt-bindings-aspeed-Add-UART-controller/20230210-152832
base: https://git.kernel.org/pub/scm/linux/kernel/git/gregkh/tty.git tty-testing
patch link: https://lore.kernel.org/r/20230210072643.2772-3-chiawei_wang%40aspeedtech.com
patch subject: [PATCH 2/4] soc: aspeed: Add UART DMA support
config: sh-allmodconfig (https://download.01.org/0day-ci/archive/20230210/[email protected]/config)
compiler: sh4-linux-gcc (GCC) 12.1.0
reproduce (this is a W=1 build):
wget https://raw.githubusercontent.com/intel/lkp-tests/master/sbin/make.cross -O ~/bin/make.cross
chmod +x ~/bin/make.cross
# https://github.com/intel-lab-lkp/linux/commit/b1e3a89584657d9b0398f3f46b09dc4229835fa3
git remote add linux-review https://github.com/intel-lab-lkp/linux
git fetch --no-tags linux-review Chia-Wei-Wang/dt-bindings-aspeed-Add-UART-controller/20230210-152832
git checkout b1e3a89584657d9b0398f3f46b09dc4229835fa3
# save the config file
mkdir build_dir && cp config build_dir/.config
COMPILER_INSTALL_PATH=$HOME/0day COMPILER=gcc-12.1.0 make.cross W=1 O=build_dir ARCH=sh olddefconfig
COMPILER_INSTALL_PATH=$HOME/0day COMPILER=gcc-12.1.0 make.cross W=1 O=build_dir ARCH=sh SHELL=/bin/bash drivers/soc/aspeed/

If you fix the issue, kindly add following tag where applicable
| Reported-by: kernel test robot <[email protected]>
| Link: https://lore.kernel.org/oe-kbuild-all/[email protected]/

All warnings (new ones prefixed by >>):

drivers/soc/aspeed/aspeed-udma.c: In function 'aspeed_udma_request_chan':
>> drivers/soc/aspeed/aspeed-udma.c:194:13: warning: variable 'retval' set but not used [-Wunused-but-set-variable]
194 | int retval = 0;
| ^~~~~~


vim +/retval +194 drivers/soc/aspeed/aspeed-udma.c

189
190 static int aspeed_udma_request_chan(u32 ch_no, dma_addr_t addr,
191 struct circ_buf *rb, u32 rb_sz,
192 aspeed_udma_cb_t cb, void *id, bool dis_tmout, bool is_tx)
193 {
> 194 int retval = 0;
195 int rbsz_code;
196
197 u32 reg;
198 unsigned long flags;
199 struct aspeed_udma_chan *ch;
200
201 if (ch_no > UDMA_MAX_CHANNEL) {
202 retval = -EINVAL;
203 goto out;
204 }
205
206 if (IS_ERR_OR_NULL(rb) || IS_ERR_OR_NULL(rb->buf)) {
207 retval = -EINVAL;
208 goto out;
209 }
210
211 rbsz_code = aspeed_udma_get_bufsz_code(rb_sz);
212 if (rbsz_code < 0) {
213 retval = -EINVAL;
214 goto out;
215 }
216
217 spin_lock_irqsave(&udma->lock, flags);
218
219 if (is_tx) {
220 reg = readl(udma->regs + UDMA_TX_DMA_INT_EN);
221 if (reg & (0x1 << ch_no)) {
222 retval = -EBUSY;
223 goto unlock_n_out;
224 }
225
226 reg |= (0x1 << ch_no);
227 writel(reg, udma->regs + UDMA_TX_DMA_INT_EN);
228
229 reg = readl(udma->regs + UDMA_CHX_TX_CTRL(ch_no));
230 reg |= (dis_tmout) ? UDMA_TX_CTRL_TMOUT_DISABLE : 0;
231 reg |= (rbsz_code << UDMA_TX_CTRL_BUFSZ_SHIFT) & UDMA_TX_CTRL_BUFSZ_MASK;
232 writel(reg, udma->regs + UDMA_CHX_TX_CTRL(ch_no));
233
234 writel(addr, udma->regs + UDMA_CHX_TX_BUF_BASE(ch_no));
235 } else {
236 reg = readl(udma->regs + UDMA_RX_DMA_INT_EN);
237 if (reg & (0x1 << ch_no)) {
238 retval = -EBUSY;
239 goto unlock_n_out;
240 }
241
242 reg |= (0x1 << ch_no);
243 writel(reg, udma->regs + UDMA_RX_DMA_INT_EN);
244
245 reg = readl(udma->regs + UDMA_CHX_RX_CTRL(ch_no));
246 reg |= (dis_tmout) ? UDMA_RX_CTRL_TMOUT_DISABLE : 0;
247 reg |= (rbsz_code << UDMA_RX_CTRL_BUFSZ_SHIFT) & UDMA_RX_CTRL_BUFSZ_MASK;
248 writel(reg, udma->regs + UDMA_CHX_RX_CTRL(ch_no));
249
250 writel(addr, udma->regs + UDMA_CHX_RX_BUF_BASE(ch_no));
251 }
252
253 ch = (is_tx) ? &udma->tx_chs[ch_no] : &udma->rx_chs[ch_no];
254 ch->rb = rb;
255 ch->rb_sz = rb_sz;
256 ch->cb = cb;
257 ch->cb_arg = id;
258 ch->dma_addr = addr;
259 ch->dis_tmout = dis_tmout;
260
261 unlock_n_out:
262 spin_unlock_irqrestore(&udma->lock, flags);
263 out:
264 return 0;
265 }
266

--
0-DAY CI Kernel Test Service
https://github.com/intel/lkp-tests

2023-02-10 10:36:27

by Paul Menzel

[permalink] [raw]
Subject: Re: [PATCH 3/4] serial: 8250: Add Aspeed UART driver

Dear Chia-Wei,


Thank you for your patch.

Am 10.02.23 um 08:26 schrieb Chia-Wei Wang:
> Add the driver for Aspeed UART/VUART devices, which are 16550A
> compatible. It is an wrapper to cover the generic 16550A operation

a wrapper

> while exetending DMA feature for the devices.

extending

Is this for all ASPEED devices or only current ones?

How did you test this? What is the maximum transfer speed?

There are other serial drivers also supporting DMA, and those seem to
use DMAengine?

$ git grep dmaengine drivers/tty/serial/8250/

> Signed-off-by: Chia-Wei Wang <[email protected]>
> ---
> drivers/tty/serial/8250/8250_aspeed.c | 502 ++++++++++++++++++++++++++
> drivers/tty/serial/8250/Kconfig | 8 +
> drivers/tty/serial/8250/Makefile | 1 +
> 3 files changed, 511 insertions(+)
> create mode 100644 drivers/tty/serial/8250/8250_aspeed.c
>
> diff --git a/drivers/tty/serial/8250/8250_aspeed.c b/drivers/tty/serial/8250/8250_aspeed.c
> new file mode 100644
> index 000000000000..2eaa59ee6d27
> --- /dev/null
> +++ b/drivers/tty/serial/8250/8250_aspeed.c
> @@ -0,0 +1,502 @@
> +// SPDX-License-Identifier: GPL-2.0
> +/*
> + * Copyright (C) ASPEED Technology Inc.
> + */
> +#include <linux/device.h>
> +#include <linux/io.h>
> +#include <linux/module.h>
> +#include <linux/serial_8250.h>
> +#include <linux/serial_reg.h>
> +#include <linux/of.h>
> +#include <linux/of_irq.h>
> +#include <linux/of_platform.h>
> +#include <linux/platform_device.h>
> +#include <linux/clk.h>
> +#include <linux/reset.h>
> +#include <linux/dma-mapping.h>
> +#include <linux/circ_buf.h>
> +#include <linux/tty_flip.h>
> +#include <linux/pm_runtime.h>
> +#include <linux/soc/aspeed/aspeed-udma.h>
> +
> +#include "8250.h"
> +
> +#define DEVICE_NAME "aspeed-uart"
> +
> +/* offsets for the aspeed virtual uart registers */
> +#define VUART_GCRA 0x20
> +#define VUART_GCRA_VUART_EN BIT(0)
> +#define VUART_GCRA_SIRQ_POLARITY BIT(1)
> +#define VUART_GCRA_DISABLE_HOST_TX_DISCARD BIT(5)
> +#define VUART_GCRB 0x24
> +#define VUART_GCRB_HOST_SIRQ_MASK GENMASK(7, 4)
> +#define VUART_GCRB_HOST_SIRQ_SHIFT 4
> +#define VUART_ADDRL 0x28
> +#define VUART_ADDRH 0x2c
> +
> +#define DMA_TX_BUFSZ PAGE_SIZE
> +#define DMA_RX_BUFSZ (64 * 1024)

Maybe add the unit to the macro name?

> +
> +struct uart_ops ast8250_pops;
> +
> +struct ast8250_vuart {
> + u32 port;

Does it need to be a fixed length type, or can you use `unsigned int`? [1]

[1]: https://notabs.org/coding/smallIntsBigPenalty.htm

> + u32 sirq;
> + u32 sirq_pol;
> +};
> +
> +struct ast8250_udma {
> + u32 ch;
> +
> + u32 tx_rbsz;
> + u32 rx_rbsz;
> +
> + dma_addr_t tx_addr;
> + dma_addr_t rx_addr;
> +
> + struct circ_buf *tx_rb;
> + struct circ_buf *rx_rb;
> +
> + bool tx_tmout_dis;

I’d write `disabled`.

> + bool rx_tmout_dis;
> +};
> +
> +struct ast8250_data {
> + int line;
> +
> + u8 __iomem *regs;
> +
> + bool is_vuart;
> + bool use_dma;
> +
> + struct reset_control *rst;
> + struct clk *clk;
> +
> + struct ast8250_vuart vuart;
> + struct ast8250_udma dma;
> +};
> +
> +static void ast8250_dma_tx_complete(int tx_rb_rptr, void *id)
> +{
> + u32 count;
> + unsigned long flags;
> + struct uart_port *port = (struct uart_port *)id;
> + struct ast8250_data *data = port->private_data;
> +
> + spin_lock_irqsave(&port->lock, flags);
> +
> + count = CIRC_CNT(tx_rb_rptr, port->state->xmit.tail, data->dma.tx_rbsz);
> + port->state->xmit.tail = tx_rb_rptr;
> + port->icount.tx += count;
> +
> + if (uart_circ_chars_pending(&port->state->xmit) < WAKEUP_CHARS)
> + uart_write_wakeup(port);
> +
> + spin_unlock_irqrestore(&port->lock, flags);
> +}
> +
> +static void ast8250_dma_rx_complete(int rx_rb_wptr, void *id)
> +{
> + unsigned long flags;
> + struct uart_port *up = (struct uart_port *)id;
> + struct tty_port *tp = &up->state->port;
> + struct ast8250_data *data = up->private_data;
> + struct ast8250_udma *dma = &data->dma;
> + struct circ_buf *rx_rb = dma->rx_rb;
> + u32 rx_rbsz = dma->rx_rbsz;
> + u32 count = 0;
> +
> + spin_lock_irqsave(&up->lock, flags);
> +
> + rx_rb->head = rx_rb_wptr;
> +
> + dma_sync_single_for_cpu(up->dev,
> + dma->rx_addr, dma->rx_rbsz, DMA_FROM_DEVICE);
> +
> + while (CIRC_CNT(rx_rb->head, rx_rb->tail, rx_rbsz)) {
> + count = CIRC_CNT_TO_END(rx_rb->head, rx_rb->tail, rx_rbsz);
> +
> + tty_insert_flip_string(tp, rx_rb->buf + rx_rb->tail, count);
> +
> + rx_rb->tail += count;
> + rx_rb->tail %= rx_rbsz;
> +
> + up->icount.rx += count;
> + }
> +
> + if (count) {
> + aspeed_udma_set_rx_rptr(data->dma.ch, rx_rb->tail);
> + tty_flip_buffer_push(tp);
> + }
> +
> + spin_unlock_irqrestore(&up->lock, flags);
> +}
> +
> +static void ast8250_dma_start_tx(struct uart_port *port)
> +{
> + struct ast8250_data *data = port->private_data;
> + struct ast8250_udma *dma = &data->dma;
> + struct circ_buf *tx_rb = dma->tx_rb;
> +
> + dma_sync_single_for_device(port->dev,
> + dma->tx_addr, dma->tx_rbsz, DMA_TO_DEVICE);
> +
> + aspeed_udma_set_tx_wptr(dma->ch, tx_rb->head);
> +}
> +
> +static void ast8250_dma_pops_hook(struct uart_port *port)
> +{
> + static int first = 1;
> +
> + if (first) {
> + ast8250_pops = *port->ops;
> + ast8250_pops.start_tx = ast8250_dma_start_tx;
> + }
> +
> + first = 0;
> + port->ops = &ast8250_pops;
> +}
> +
> +static void ast8250_vuart_init(struct ast8250_data *data)
> +{
> + u8 reg;
> + struct ast8250_vuart *vuart = &data->vuart;
> +
> + /* IO port address */
> + writeb((u8)(vuart->port >> 0), data->regs + VUART_ADDRL);
> + writeb((u8)(vuart->port >> 8), data->regs + VUART_ADDRH);
> +
> + /* SIRQ number */
> + reg = readb(data->regs + VUART_GCRB);
> + reg &= ~VUART_GCRB_HOST_SIRQ_MASK;
> + reg |= ((vuart->sirq << VUART_GCRB_HOST_SIRQ_SHIFT) & VUART_GCRB_HOST_SIRQ_MASK);
> + writeb(reg, data->regs + VUART_GCRB);
> +
> + /* SIRQ polarity */
> + reg = readb(data->regs + VUART_GCRA);
> + if (vuart->sirq_pol)
> + reg |= VUART_GCRA_SIRQ_POLARITY;
> + else
> + reg &= ~VUART_GCRA_SIRQ_POLARITY;
> + writeb(reg, data->regs + VUART_GCRA);
> +}
> +
> +static void ast8250_vuart_set_host_tx_discard(struct ast8250_data *data, bool discard)
> +{
> + u8 reg;
> +
> + reg = readb(data->regs + VUART_GCRA);
> + if (discard)
> + reg &= ~VUART_GCRA_DISABLE_HOST_TX_DISCARD;
> + else
> + reg |= VUART_GCRA_DISABLE_HOST_TX_DISCARD;
> + writeb(reg, data->regs + VUART_GCRA);
> +}
> +
> +static void ast8250_vuart_set_enable(struct ast8250_data *data, bool enable)
> +{
> + u8 reg;
> +
> + reg = readb(data->regs + VUART_GCRA);
> + if (enable)
> + reg |= VUART_GCRA_VUART_EN;
> + else
> + reg &= ~VUART_GCRA_VUART_EN;
> + writeb(reg, data->regs + VUART_GCRA);
> +}
> +
> +static int ast8250_handle_irq(struct uart_port *port)
> +{
> + u32 iir = port->serial_in(port, UART_IIR);
> +
> + return serial8250_handle_irq(port, iir);
> +}
> +
> +static int ast8250_startup(struct uart_port *port)
> +{
> + int rc = 0;
> + struct ast8250_data *data = port->private_data;
> + struct ast8250_udma *dma;
> +
> + if (data->is_vuart)
> + ast8250_vuart_set_host_tx_discard(data, false);
> +
> + if (data->use_dma) {
> + dma = &data->dma;
> +
> + dma->tx_rbsz = DMA_TX_BUFSZ;
> + dma->rx_rbsz = DMA_RX_BUFSZ;
> +
> + /*
> + * We take the xmit buffer passed from upper layers as
> + * the DMA TX buffer and allocate a new buffer for the
> + * RX use.
> + *
> + * To keep the TX/RX operation consistency, we use the
> + * streaming DMA interface instead of the coherent one
> + */
> + dma->tx_rb = &port->state->xmit;
> + dma->rx_rb->buf = kzalloc(data->dma.rx_rbsz, GFP_KERNEL);
> + if (IS_ERR_OR_NULL(dma->rx_rb->buf)) {
> + dev_err(port->dev, "failed to allcoate RX DMA buffer\n");
> + rc = -ENOMEM;
> + goto out;
> + }
> +
> + dma->tx_addr = dma_map_single(port->dev, dma->tx_rb->buf,
> + dma->tx_rbsz, DMA_TO_DEVICE);
> + if (dma_mapping_error(port->dev, dma->tx_addr)) {
> + dev_err(port->dev, "failed to map streaming TX DMA region\n");
> + rc = -ENOMEM;
> + goto free_dma_n_out;
> + }
> +
> + dma->rx_addr = dma_map_single(port->dev, dma->rx_rb->buf,
> + dma->rx_rbsz, DMA_FROM_DEVICE);
> + if (dma_mapping_error(port->dev, dma->rx_addr)) {
> + dev_err(port->dev, "failed to map streaming RX DMA region\n");
> + rc = -ENOMEM;
> + goto free_dma_n_out;
> + }
> +
> + rc = aspeed_udma_request_tx_chan(dma->ch, dma->tx_addr, dma->tx_rb,
> + dma->tx_rbsz, ast8250_dma_tx_complete,
> + port, dma->tx_tmout_dis);
> + if (rc) {
> + dev_err(port->dev, "failed to request DMA TX channel\n");
> + goto free_dma_n_out;
> + }
> +
> + rc = aspeed_udma_request_rx_chan(dma->ch, dma->rx_addr, dma->rx_rb,
> + dma->rx_rbsz, ast8250_dma_rx_complete,
> + port, dma->rx_tmout_dis);
> + if (rc) {
> + dev_err(port->dev, "failed to request DMA RX channel\n");
> + goto free_dma_n_out;
> + }
> +
> + ast8250_dma_pops_hook(port);
> +
> + aspeed_udma_tx_chan_ctrl(dma->ch, ASPEED_UDMA_OP_ENABLE);
> + aspeed_udma_rx_chan_ctrl(dma->ch, ASPEED_UDMA_OP_ENABLE);
> + }
> +
> + memset(&port->icount, 0, sizeof(port->icount));
> + return serial8250_do_startup(port);
> +
> +free_dma_n_out:
> + kfree(dma->rx_rb->buf);
> +out:
> + return rc;
> +}
> +
> +static void ast8250_shutdown(struct uart_port *port)
> +{
> + int rc;
> + struct ast8250_data *data = port->private_data;
> + struct ast8250_udma *dma;
> +
> + if (data->use_dma) {
> + dma = &data->dma;
> +
> + aspeed_udma_tx_chan_ctrl(dma->ch, ASPEED_UDMA_OP_RESET);
> + aspeed_udma_rx_chan_ctrl(dma->ch, ASPEED_UDMA_OP_RESET);
> +
> + aspeed_udma_tx_chan_ctrl(dma->ch, ASPEED_UDMA_OP_DISABLE);
> + aspeed_udma_rx_chan_ctrl(dma->ch, ASPEED_UDMA_OP_DISABLE);
> +
> + rc = aspeed_udma_free_tx_chan(dma->ch);
> + if (rc)
> + dev_err(port->dev, "failed to free DMA TX channel, rc=%d\n", rc);
> +
> + rc = aspeed_udma_free_rx_chan(dma->ch);
> + if (rc)
> + dev_err(port->dev, "failed to free DMA TX channel, rc=%d\n", rc);
> +
> + dma_unmap_single(port->dev, dma->tx_addr,
> + dma->tx_rbsz, DMA_TO_DEVICE);
> + dma_unmap_single(port->dev, dma->rx_addr,
> + dma->rx_rbsz, DMA_FROM_DEVICE);
> +
> + kfree(dma->rx_rb->buf);
> + }
> +
> + if (data->is_vuart)
> + ast8250_vuart_set_host_tx_discard(data, true);
> +
> + serial8250_do_shutdown(port);
> +}
> +
> +static int __maybe_unused ast8250_suspend(struct device *dev)
> +{
> + struct ast8250_data *data = dev_get_drvdata(dev);
> +
> + serial8250_suspend_port(data->line);
> +
> + return 0;
> +}
> +
> +static int __maybe_unused ast8250_resume(struct device *dev)
> +{
> + struct ast8250_data *data = dev_get_drvdata(dev);
> +
> + serial8250_resume_port(data->line);
> +
> + return 0;
> +}
> +
> +static int ast8250_probe(struct platform_device *pdev)
> +{
> + int rc;
> + struct uart_8250_port uart = {};
> + struct uart_port *port = &uart.port;
> + struct device *dev = &pdev->dev;
> + struct ast8250_data *data;
> +
> + struct resource *res;
> + u32 irq;
> +
> + data = devm_kzalloc(dev, sizeof(*data), GFP_KERNEL);
> + if (data == NULL)
> + return -ENOMEM;
> +
> + data->dma.rx_rb = devm_kzalloc(dev, sizeof(data->dma.rx_rb), GFP_KERNEL);
> + if (data->dma.rx_rb == NULL)
> + return -ENOMEM;
> +
> + irq = platform_get_irq(pdev, 0);
> + if (irq < 0)
> + return irq;
> +
> + res = platform_get_resource(pdev, IORESOURCE_MEM, 0);
> + if (res == NULL) {
> + dev_err(dev, "failed to get register base\n");
> + return -ENODEV;
> + }
> +
> + data->regs = devm_ioremap(dev, res->start, resource_size(res));
> + if (IS_ERR(data->regs)) {
> + dev_err(dev, "failed to map registers\n");
> + return PTR_ERR(data->regs);
> + }
> +
> + data->clk = devm_clk_get(dev, NULL);
> + if (IS_ERR(data->clk)) {
> + dev_err(dev, "failed to get clocks\n");
> + return -ENODEV;
> + }
> +
> + rc = clk_prepare_enable(data->clk);
> + if (rc) {
> + dev_err(dev, "failed to enable clock\n");
> + return rc;
> + }
> +
> + data->rst = devm_reset_control_get_optional_exclusive(dev, NULL);
> + if (!IS_ERR(data->rst))
> + reset_control_deassert(data->rst);
> +
> + data->is_vuart = of_property_read_bool(dev->of_node, "virtual");
> + if (data->is_vuart) {
> + rc = of_property_read_u32(dev->of_node, "port", &data->vuart.port);
> + if (rc) {
> + dev_err(dev, "failed to get VUART port address\n");
> + return -ENODEV;
> + }
> +
> + rc = of_property_read_u32(dev->of_node, "sirq", &data->vuart.sirq);
> + if (rc) {
> + dev_err(dev, "failed to get VUART SIRQ number\n");
> + return -ENODEV;
> + }
> +
> + rc = of_property_read_u32(dev->of_node, "sirq-polarity", &data->vuart.sirq_pol);
> + if (rc) {
> + dev_err(dev, "failed to get VUART SIRQ polarity\n");
> + return -ENODEV;
> + }
> +
> + ast8250_vuart_init(data);
> + ast8250_vuart_set_host_tx_discard(data, true);
> + ast8250_vuart_set_enable(data, true);
> + }
> +
> + data->use_dma = of_property_read_bool(dev->of_node, "dma-mode");
> + if (data->use_dma) {
> + rc = of_property_read_u32(dev->of_node, "dma-channel", &data->dma.ch);
> + if (rc) {
> + dev_err(dev, "failed to get DMA channel\n");
> + return -ENODEV;
> + }
> +
> + data->dma.tx_tmout_dis = of_property_read_bool(dev->of_node,
> + "dma-tx-timeout-disable");
> + data->dma.rx_tmout_dis = of_property_read_bool(dev->of_node,
> + "dma-rx-timeout-disable");
> + }
> +
> + spin_lock_init(&port->lock);
> + port->dev = dev;
> + port->type = PORT_16550A;
> + port->irq = irq;
> + port->line = of_alias_get_id(dev->of_node, "serial");
> + port->handle_irq = ast8250_handle_irq;
> + port->mapbase = res->start;
> + port->mapsize = resource_size(res);
> + port->membase = data->regs;
> + port->uartclk = clk_get_rate(data->clk);
> + port->regshift = 2;
> + port->iotype = UPIO_MEM32;
> + port->flags = UPF_FIXED_TYPE | UPF_FIXED_PORT | UPF_SHARE_IRQ;
> + port->startup = ast8250_startup;
> + port->shutdown = ast8250_shutdown;
> + port->private_data = data;
> + uart.bugs |= UART_BUG_TXRACE;
> +
> + data->line = serial8250_register_8250_port(&uart);
> + if (data->line < 0) {
> + dev_err(dev, "failed to register 8250 port\n");
> + return data->line;
> + }
> +
> + pm_runtime_set_active(&pdev->dev);
> + pm_runtime_enable(&pdev->dev);
> +
> + platform_set_drvdata(pdev, data);
> + return 0;
> +}
> +
> +static int ast8250_remove(struct platform_device *pdev)
> +{
> + struct ast8250_data *data = platform_get_drvdata(pdev);
> +
> + if (data->is_vuart)
> + ast8250_vuart_set_enable(data, false);
> +
> + serial8250_unregister_port(data->line);
> + return 0;
> +}
> +
> +static const struct dev_pm_ops ast8250_pm_ops = {
> + SET_SYSTEM_SLEEP_PM_OPS(ast8250_suspend, ast8250_resume)
> +};
> +
> +static const struct of_device_id ast8250_of_match[] = {
> + { .compatible = "aspeed,ast2600-uart" },
> +};
> +
> +static struct platform_driver ast8250_platform_driver = {
> + .driver = {
> + .name = DEVICE_NAME,
> + .pm = &ast8250_pm_ops,
> + .of_match_table = ast8250_of_match,
> + },
> + .probe = ast8250_probe,
> + .remove = ast8250_remove,
> +};
> +
> +module_platform_driver(ast8250_platform_driver);
> +
> +MODULE_AUTHOR("Chia-Wei Wang <[email protected]>");
> +MODULE_LICENSE("GPL");

Should it be GPL v2?

> +MODULE_DESCRIPTION("Aspeed UART Driver");
> diff --git a/drivers/tty/serial/8250/Kconfig b/drivers/tty/serial/8250/Kconfig
> index b0f62345bc84..d8ecc261d8c4 100644
> --- a/drivers/tty/serial/8250/Kconfig
> +++ b/drivers/tty/serial/8250/Kconfig
> @@ -538,6 +538,14 @@ config SERIAL_8250_BCM7271
> including DMA support and high accuracy BAUD rates, say
> Y to this option. If unsure, say N.
>
> +config SERIAL_8250_ASPEED
> + tristate "Aspeed serial port support"
> + depends on SERIAL_8250 && ARCH_ASPEED
> + help
> + If you have a system using an Aspeed AST26xx SoCs and wish to
> + make use of its UARTs and VUARTs, which are 16550A compatible
> + and include DMA support, say Y to this option. If unsure, say N.
> +
> config SERIAL_OF_PLATFORM
> tristate "Devicetree based probing for 8250 ports"
> depends on SERIAL_8250 && OF
> diff --git a/drivers/tty/serial/8250/Makefile b/drivers/tty/serial/8250/Makefile
> index 1615bfdde2a0..7f05b7ed422b 100644
> --- a/drivers/tty/serial/8250/Makefile
> +++ b/drivers/tty/serial/8250/Makefile
> @@ -42,6 +42,7 @@ obj-$(CONFIG_SERIAL_8250_PERICOM) += 8250_pericom.o
> obj-$(CONFIG_SERIAL_8250_PXA) += 8250_pxa.o
> obj-$(CONFIG_SERIAL_8250_TEGRA) += 8250_tegra.o
> obj-$(CONFIG_SERIAL_8250_BCM7271) += 8250_bcm7271.o
> +obj-$(CONFIG_SERIAL_8250_ASPEED) += 8250_aspeed.o
> obj-$(CONFIG_SERIAL_OF_PLATFORM) += 8250_of.o
>
> CFLAGS_8250_ingenic.o += -I$(srctree)/scripts/dtc/libfdt

Kind regards,

Paul

2023-02-10 13:41:10

by Ilpo Järvinen

[permalink] [raw]
Subject: Re: [PATCH 3/4] serial: 8250: Add Aspeed UART driver

On Fri, 10 Feb 2023, Paul Menzel wrote:

> > +MODULE_LICENSE("GPL");
>
> Should it be GPL v2?

No, it should. "GPL" is the correct for in MOUDLE_LICENSE(). SPDX lines
are a different thing and more precise.

--
i.


2023-02-10 13:52:16

by Ilpo Järvinen

[permalink] [raw]
Subject: Re: [PATCH 3/4] serial: 8250: Add Aspeed UART driver

On Fri, 10 Feb 2023, Chia-Wei Wang wrote:

> Add the driver for Aspeed UART/VUART devices, which are 16550A
> compatible. It is an wrapper to cover the generic 16550A operation
> while exetending DMA feature for the devices.
>
> Signed-off-by: Chia-Wei Wang <[email protected]>
> ---
> drivers/tty/serial/8250/8250_aspeed.c | 502 ++++++++++++++++++++++++++
> drivers/tty/serial/8250/Kconfig | 8 +
> drivers/tty/serial/8250/Makefile | 1 +

Hi,

Before I look any further into this, could you please explain why this is
made to be entirely separate from what we have in
drivers/tty/serial/8250/8250_aspeed_vuart.c
?

I quickly went through some functions and they've significant parts in
common with no variations at all in many functions and you're defines
are 1:1 too (except for the DMA buf sizes). It would seem much better to
add the missing functionality into 8250_aspeed_vuart.c rather than
creating something from scratch with large overlap with existing code.

If you intend to keep it as a separate one, you should have a rather good
justification for it.


--
i.


2023-02-13 01:45:22

by ChiaWei Wang

[permalink] [raw]
Subject: RE: [PATCH 3/4] serial: 8250: Add Aspeed UART driver

> From: Ilpo Järvinen <[email protected]>
> Sent: Friday, February 10, 2023 9:52 PM
>
> On Fri, 10 Feb 2023, Chia-Wei Wang wrote:
>
> > Add the driver for Aspeed UART/VUART devices, which are 16550A
> > compatible. It is an wrapper to cover the generic 16550A operation
> > while exetending DMA feature for the devices.
> >
> > Signed-off-by: Chia-Wei Wang <[email protected]>
> > ---
> > drivers/tty/serial/8250/8250_aspeed.c | 502
> ++++++++++++++++++++++++++
> > drivers/tty/serial/8250/Kconfig | 8 +
> > drivers/tty/serial/8250/Makefile | 1 +
>
> Hi,
>
> Before I look any further into this, could you please explain why this is made to
> be entirely separate from what we have in
> drivers/tty/serial/8250/8250_aspeed_vuart.c
> ?
>
> I quickly went through some functions and they've significant parts in common
> with no variations at all in many functions and you're defines are 1:1 too
> (except for the DMA buf sizes). It would seem much better to add the missing
> functionality into 8250_aspeed_vuart.c rather than creating something from
> scratch with large overlap with existing code.
>
> If you intend to keep it as a separate one, you should have a rather good
> justification for it.

Yes, the main difference is the UART DMA support.
However, due to the UDMA design is not quite fit to the DMAEngine, the implementation is kind of hacking.
We thought leaving the original VUART driver unimpacted would be better.
The UDMA covers both UART and VUART DMA support, and so do the new 8250_aspeed.c.

Regards,
Chiawei

2023-02-13 01:46:29

by ChiaWei Wang

[permalink] [raw]
Subject: RE: [PATCH 4/4] ARM: dts: aspeed-g6: Add UDMA node

> From: Krzysztof Kozlowski <[email protected]>
> Sent: Friday, February 10, 2023 5:14 PM
>
> On 10/02/2023 08:26, Chia-Wei Wang wrote:
> > Add the device tree node for UART DMA controller.
> >
> > Signed-off-by: Chia-Wei Wang <[email protected]>
> > ---
> > arch/arm/boot/dts/aspeed-g6.dtsi | 7 +++++++
> > 1 file changed, 7 insertions(+)
> >
> > diff --git a/arch/arm/boot/dts/aspeed-g6.dtsi
> b/arch/arm/boot/dts/aspeed-g6.dtsi
> > index cc2f8b785917..3f4e9da8f6c7 100644
> > --- a/arch/arm/boot/dts/aspeed-g6.dtsi
> > +++ b/arch/arm/boot/dts/aspeed-g6.dtsi
> > @@ -850,6 +850,13 @@ fsim1: fsi@1e79b100 {
> > clocks = <&syscon ASPEED_CLK_GATE_FSICLK>;
> > status = "disabled";
> > };
> > +
> > + udma: uart-dma@1e79e000 {
>
> Node names should be generic.
> https://devicetree-specification.readthedocs.io/en/latest/chapter2-devicetree-
> basics.html#generic-names-recommendation
>
> > + compatible = "aspeed,ast2600-udma";
>
> Please run scripts/checkpatch.pl and fix reported warnings.

Thanks for reminding. Will add the dt-bindings for UDMA as well.

Regards,
Chiawei

2023-02-13 01:50:21

by ChiaWei Wang

[permalink] [raw]
Subject: RE: [PATCH 2/4] soc: aspeed: Add UART DMA support

> From: Krzysztof Kozlowski <[email protected]>
> Sent: Friday, February 10, 2023 5:14 PM
>
> On 10/02/2023 08:26, Chia-Wei Wang wrote:
> > This driver provides DMA support for AST26xx UART and VUART devices.
> > It is useful to offload CPU overhead while using UART/VUART for binary
> > file transfer.
> >
> > Signed-off-by: Chia-Wei Wang <[email protected]>
> > ---
> > drivers/soc/aspeed/Kconfig | 9 +
> > drivers/soc/aspeed/Makefile | 1 +
> > drivers/soc/aspeed/aspeed-udma.c | 447
> +++++++++++++++++++++++++
> > include/linux/soc/aspeed/aspeed-udma.h | 34 ++
>
> NAK.
>
> DMA drivers do not go to soc, but to dma subsystem.

The UDMA is dedicated only to UART use and is not fully fit to the DMAEngine subsystem.
For example, the suspend/resume operations of common DMA engine are not supported.
After observing certain existing DMA implementation in other soc folders, we put UDMA in the soc/aspeed as well.
If it is not appropriate, should we integrate UDMA into the UART driver or try to make UDMA DMAEngine based?

Regards,
Chiawei

2023-02-13 01:57:37

by ChiaWei Wang

[permalink] [raw]
Subject: RE: [PATCH 1/4] dt-bindings: aspeed: Add UART controller

> From: Krzysztof Kozlowski <[email protected]>
> Sent: Friday, February 10, 2023 5:13 PM
>
> On 10/02/2023 08:26, Chia-Wei Wang wrote:
> > Add dt-bindings for Aspeed UART controller.
>
> Describe the hardware. What's the difference against existing Aspeed UART
> used everywhere?

The description will be revised to explain more for UART and Virtual UART controllers.

>
> >
> > Signed-off-by: Chia-Wei Wang <[email protected]>
> > ---
> > .../bindings/serial/aspeed,uart.yaml | 81
> +++++++++++++++++++
> > 1 file changed, 81 insertions(+)
> > create mode 100644
> > Documentation/devicetree/bindings/serial/aspeed,uart.yaml
>
> Filename: aspeed,ast2600-uart.yaml
> (unless you are adding here more compatibles, but your const suggests that it's
> not going to happen)
>
> >
> > diff --git a/Documentation/devicetree/bindings/serial/aspeed,uart.yaml
> > b/Documentation/devicetree/bindings/serial/aspeed,uart.yaml
> > new file mode 100644
> > index 000000000000..10c457d6a72e
> > --- /dev/null
> > +++ b/Documentation/devicetree/bindings/serial/aspeed,uart.yaml
> > @@ -0,0 +1,81 @@
> > +# SPDX-License-Identifier: (GPL-2.0-only OR BSD-2-Clause) %YAML 1.2
> > +---
> > +$id: http://devicetree.org/schemas/serial/aspeed,uart.yaml#
> > +$schema: http://devicetree.org/meta-schemas/core.yaml#
> > +
> > +title: Aspeed Universal Asynchronous Receiver/Transmitter
>
> This title matches other Aspeed UARTs, so aren't you duplicating bindings?
>
> > +
> > +maintainers:
> > + - Chia-Wei Wang <[email protected]>
> > +
> > +allOf:
> > + - $ref: serial.yaml#
> > +
> > +description: |
> > + The Aspeed UART is based on the basic 8250 UART and compatible
> > + with 16550A, with support for DMA
> > +
> > +properties:
> > + compatible:
> > + const: aspeed,ast2600-uart
> > +
> > + reg:
> > + description: The base address of the UART register bank
>
> Drop description

Will revise as suggested.

>
> > + maxItems: 1
> > +
> > + clocks:
> > + description: The clock the baudrate is derived from
> > + maxItems: 1
> > +
> > + interrupts:
> > + description: The IRQ number of the device
>
> Drop description

Will revise as suggested.

>
> > + maxItems: 1
> > +
> > + dma-mode:
> > + type: boolean
> > + description: Enable DMA
>
> Drop property. DMA is enabled on presence of dmas.
>
> > +
> > + dma-channel:
> > + $ref: /schemas/types.yaml#/definitions/uint32
> > + description: The channel number to be used in the DMA engine
>
> That's not a correct DMA property. dmas and dma-names git grep dma --
> Documentation/devicetree/bindings/
>
>
> > +
> > + virtual:
> > + type: boolean
> > + description: Indicate virtual UART
>
> Virtual means not existing in real world? We do not describe in DTS
> non-existing devices. Drop entire property.

The virtual property indicates it is a Virtual UART device.
VUART of Aspeed SoC is actually a FIFO exposed in the 16550A UART interface.
The one head of the FIFO is exposed to Host via eSPI/LPC and the other one is for BMC.
There is no physical serial link between Host and BMC. And thus named as Virtual UART.

>
> > +
> > + sirq:
> > + $ref: /schemas/types.yaml#/definitions/uint32
> > + description: The serial IRQ number on LPC bus interface
>
> Drop entire property.

Mandatory for Virtual UART

>
> > +
> > + sirq-polarity:
> > + $ref: /schemas/types.yaml#/definitions/uint32
> > + description: The serial IRQ polarity on LPC bus interface
>
> Drop entire property.

Mandatory for Virtual UART

>
> > +
> > + pinctrl-0: true
> > +
> > + pinctrl_names:
> > + const: default
>
>
> Drop both, you do no not need them.

Will revise as suggested

>
> > +
> > +required:
> > + - compatible
> > + - reg
> > + - clocks
> > + - interrupts
> > +
> > +unevaluatedProperties: false
> > +

Regards,
Chiawei

2023-02-13 04:18:33

by ChiaWei Wang

[permalink] [raw]
Subject: RE: [PATCH 3/4] serial: 8250: Add Aspeed UART driver

> From: Paul Menzel <[email protected]>
> Sent: Friday, February 10, 2023 6:35 PM
>
> Dear Chia-Wei,
>
>
> Thank you for your patch.
>
> Am 10.02.23 um 08:26 schrieb Chia-Wei Wang:
> > Add the driver for Aspeed UART/VUART devices, which are 16550A
> > compatible. It is an wrapper to cover the generic 16550A operation
>
> a wrapper
>
> > while exetending DMA feature for the devices.
>
> extending
>
> Is this for all ASPEED devices or only current ones?

There is major design change of UDMA.
Therefore, this patch is for AST2600 only.

>
> How did you test this? What is the maximum transfer speed?

Yes.
I can't remember the precise data. The experiment was done like 2 years ago.
But it should be above 2MB/s

>
> There are other serial drivers also supporting DMA, and those seem to use
> DMAengine?
>
> $ git grep dmaengine drivers/tty/serial/8250/
>

Yes.
The UDMA design is dedicated to, and tightly coupled with each UART/VUART devices.
And UDMA does not support common DMA control such as suspend/resume.

We found certain discussions in the old mailing list saying that if a DMA controller is not fully fit into the DMAEngine subsystem,
placing the implementation in the soc folder might be an option.

Regards,
Chiawei

2023-02-13 08:26:42

by Krzysztof Kozlowski

[permalink] [raw]
Subject: Re: [PATCH 1/4] dt-bindings: aspeed: Add UART controller

On 13/02/2023 02:57, ChiaWei Wang wrote:
>> From: Krzysztof Kozlowski <[email protected]>
>> Sent: Friday, February 10, 2023 5:13 PM
>>
>> On 10/02/2023 08:26, Chia-Wei Wang wrote:
>>> Add dt-bindings for Aspeed UART controller.
>>
>> Describe the hardware. What's the difference against existing Aspeed UART
>> used everywhere?
>
> The description will be revised to explain more for UART and Virtual UART controllers.
>
>>
>>>
>>> Signed-off-by: Chia-Wei Wang <[email protected]>
>>> ---
>>> .../bindings/serial/aspeed,uart.yaml | 81
>> +++++++++++++++++++
>>> 1 file changed, 81 insertions(+)
>>> create mode 100644
>>> Documentation/devicetree/bindings/serial/aspeed,uart.yaml
>>
>> Filename: aspeed,ast2600-uart.yaml
>> (unless you are adding here more compatibles, but your const suggests that it's
>> not going to happen)
>>
>>>
>>> diff --git a/Documentation/devicetree/bindings/serial/aspeed,uart.yaml
>>> b/Documentation/devicetree/bindings/serial/aspeed,uart.yaml
>>> new file mode 100644
>>> index 000000000000..10c457d6a72e
>>> --- /dev/null
>>> +++ b/Documentation/devicetree/bindings/serial/aspeed,uart.yaml
>>> @@ -0,0 +1,81 @@
>>> +# SPDX-License-Identifier: (GPL-2.0-only OR BSD-2-Clause) %YAML 1.2
>>> +---
>>> +$id: http://devicetree.org/schemas/serial/aspeed,uart.yaml#
>>> +$schema: http://devicetree.org/meta-schemas/core.yaml#
>>> +
>>> +title: Aspeed Universal Asynchronous Receiver/Transmitter
>>
>> This title matches other Aspeed UARTs, so aren't you duplicating bindings?
>>
>>> +
>>> +maintainers:
>>> + - Chia-Wei Wang <[email protected]>
>>> +
>>> +allOf:
>>> + - $ref: serial.yaml#
>>> +
>>> +description: |
>>> + The Aspeed UART is based on the basic 8250 UART and compatible
>>> + with 16550A, with support for DMA
>>> +
>>> +properties:
>>> + compatible:
>>> + const: aspeed,ast2600-uart
>>> +
>>> + reg:
>>> + description: The base address of the UART register bank
>>
>> Drop description
>
> Will revise as suggested.
>
>>
>>> + maxItems: 1
>>> +
>>> + clocks:
>>> + description: The clock the baudrate is derived from
>>> + maxItems: 1
>>> +
>>> + interrupts:
>>> + description: The IRQ number of the device
>>
>> Drop description
>
> Will revise as suggested.
>
>>
>>> + maxItems: 1
>>> +
>>> + dma-mode:
>>> + type: boolean
>>> + description: Enable DMA
>>
>> Drop property. DMA is enabled on presence of dmas.
>>
>>> +
>>> + dma-channel:
>>> + $ref: /schemas/types.yaml#/definitions/uint32
>>> + description: The channel number to be used in the DMA engine
>>
>> That's not a correct DMA property. dmas and dma-names git grep dma --
>> Documentation/devicetree/bindings/
>>
>>
>>> +
>>> + virtual:
>>> + type: boolean
>>> + description: Indicate virtual UART
>>
>> Virtual means not existing in real world? We do not describe in DTS
>> non-existing devices. Drop entire property.
>
> The virtual property indicates it is a Virtual UART device.

vuart already has its bindings, so you do not need this in such case.

> VUART of Aspeed SoC is actually a FIFO exposed in the 16550A UART interface.
> The one head of the FIFO is exposed to Host via eSPI/LPC and the other one is for BMC.
> There is no physical serial link between Host and BMC. And thus named as Virtual UART.

I don't understand what is the virtual in terms of hardware. How you
route your serial lines does not change the type of the device. You need
to describe the hardware in Devicetree, not some concepts for system.

>
>>
>>> +
>>> + sirq:
>>> + $ref: /schemas/types.yaml#/definitions/uint32
>>> + description: The serial IRQ number on LPC bus interface
>>
>> Drop entire property.
>
> Mandatory for Virtual UART

It's not a explanation why this is a property suitable for Devicetree.
IRQ numbers are given via interrupts field.

>
>>
>>> +
>>> + sirq-polarity:
>>> + $ref: /schemas/types.yaml#/definitions/uint32
>>> + description: The serial IRQ polarity on LPC bus interface
>>
>> Drop entire property.
>
> Mandatory for Virtual UART
>

Same here, this is a flag for interrupts field.


Best regards,
Krzysztof


2023-02-13 08:31:39

by Krzysztof Kozlowski

[permalink] [raw]
Subject: Re: [PATCH 2/4] soc: aspeed: Add UART DMA support

On 13/02/2023 02:50, ChiaWei Wang wrote:
>> From: Krzysztof Kozlowski <[email protected]>
>> Sent: Friday, February 10, 2023 5:14 PM
>>
>> On 10/02/2023 08:26, Chia-Wei Wang wrote:
>>> This driver provides DMA support for AST26xx UART and VUART devices.
>>> It is useful to offload CPU overhead while using UART/VUART for binary
>>> file transfer.
>>>
>>> Signed-off-by: Chia-Wei Wang <[email protected]>
>>> ---
>>> drivers/soc/aspeed/Kconfig | 9 +
>>> drivers/soc/aspeed/Makefile | 1 +
>>> drivers/soc/aspeed/aspeed-udma.c | 447
>> +++++++++++++++++++++++++
>>> include/linux/soc/aspeed/aspeed-udma.h | 34 ++
>>
>> NAK.
>>
>> DMA drivers do not go to soc, but to dma subsystem.
>
> The UDMA is dedicated only to UART use and is not fully fit to the DMAEngine subsystem.
> For example, the suspend/resume operations of common DMA engine are not supported.
> After observing certain existing DMA implementation in other soc folders, we put UDMA in the soc/aspeed as well.
> If it is not appropriate, should we integrate UDMA into the UART driver or try to make UDMA DMAEngine based?


You did not Cc dma folks, so how would I know... Maybe soc is right
place if the DMA driver is not suitable for other consumers than UART.
Maybe not.

Best regards,
Krzysztof


2023-02-13 08:33:41

by Krzysztof Kozlowski

[permalink] [raw]
Subject: Re: [PATCH 1/4] dt-bindings: aspeed: Add UART controller

On 10/02/2023 10:12, Krzysztof Kozlowski wrote:
> On 10/02/2023 08:26, Chia-Wei Wang wrote:
>> Add dt-bindings for Aspeed UART controller.
>
> Describe the hardware. What's the difference against existing Aspeed
> UART used everywhere?

I expect the answer here. You are adding duplicated driver and bindings
instead of merging with existing ones. That's common issue and
explanation "it is different" is not enough.

Best regards,
Krzysztof


2023-02-13 08:54:54

by Ilpo Järvinen

[permalink] [raw]
Subject: RE: [PATCH 3/4] serial: 8250: Add Aspeed UART driver

On Mon, 13 Feb 2023, ChiaWei Wang wrote:

> > From: Ilpo J?rvinen <[email protected]>
> > Sent: Friday, February 10, 2023 9:52 PM
> >
> > On Fri, 10 Feb 2023, Chia-Wei Wang wrote:
> >
> > > Add the driver for Aspeed UART/VUART devices, which are 16550A
> > > compatible. It is an wrapper to cover the generic 16550A operation
> > > while exetending DMA feature for the devices.
> > >
> > > Signed-off-by: Chia-Wei Wang <[email protected]>
> > > ---
> > > drivers/tty/serial/8250/8250_aspeed.c | 502
> > ++++++++++++++++++++++++++
> > > drivers/tty/serial/8250/Kconfig | 8 +
> > > drivers/tty/serial/8250/Makefile | 1 +
> >
> > Hi,
> >
> > Before I look any further into this, could you please explain why this is made to
> > be entirely separate from what we have in
> > drivers/tty/serial/8250/8250_aspeed_vuart.c
> > ?
> >
> > I quickly went through some functions and they've significant parts in common
> > with no variations at all in many functions and you're defines are 1:1 too
> > (except for the DMA buf sizes). It would seem much better to add the missing
> > functionality into 8250_aspeed_vuart.c rather than creating something from
> > scratch with large overlap with existing code.
> >
> > If you intend to keep it as a separate one, you should have a rather good
> > justification for it.
>
> Yes, the main difference is the UART DMA support.
> However, due to the UDMA design is not quite fit to the DMAEngine, the implementation is kind of hacking.
> We thought leaving the original VUART driver unimpacted would be better.
> The UDMA covers both UART and VUART DMA support, and so do the new 8250_aspeed.c.

To me it seems rather weak reasoning.

If you want to go to this path, then you need to anyway share the common
code between those two drivers rather than duplicating it. It's likely
more work for you than just putting it all into the existing driver and
having just a mostly separated setup() for 2600 case.

The DMA functions should probably also depend on SERIAL_8250_DMA anyway
and the driver should fallback to non-DMA if SERIAL_8250_DMA is not set
which is yet another reason to use the existing code.

--
i.