From 8f9c4fcc96499d06533c868a74898bfb895a8a1f Mon Sep 17 00:00:00 2001 From: Tim Gover Date: Fri, 1 Nov 2024 19:42:17 +0000 Subject: [PATCH 1/5] raspberrypi-firmware: Add the RPI firmware UART APIs Add VideoCore mailbox definitions for the new RPi firmware UART. Signed-off-by: Tim Gover --- include/soc/bcm2835/raspberrypi-firmware.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/include/soc/bcm2835/raspberrypi-firmware.h b/include/soc/bcm2835/raspberrypi-firmware.h index b4bc8b675607c8..3e71d45477a422 100644 --- a/include/soc/bcm2835/raspberrypi-firmware.h +++ b/include/soc/bcm2835/raspberrypi-firmware.h @@ -98,6 +98,8 @@ enum rpi_firmware_property_tag { RPI_FIRMWARE_GET_REBOOT_FLAGS = 0x00030064, RPI_FIRMWARE_SET_REBOOT_FLAGS = 0x00038064, RPI_FIRMWARE_NOTIFY_DISPLAY_DONE = 0x00030066, + RPI_FIRMWARE_GET_SW_UART = 0x0003008a, + RPI_FIRMWARE_SET_SW_UART = 0x0003808a, /* Dispmanx TAGS */ RPI_FIRMWARE_FRAMEBUFFER_ALLOCATE = 0x00040001, From adb7163ff2738038bb67451b2f7debf09edd71bd Mon Sep 17 00:00:00 2001 From: Tim Gover Date: Fri, 1 Nov 2024 19:43:21 +0000 Subject: [PATCH 2/5] serial: core: Add the Raspberry Pi firmware UART id Assign a new serial core number for the RPi firmware UART. Signed-off-by: Tim Gover --- include/uapi/linux/serial_core.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/include/uapi/linux/serial_core.h b/include/uapi/linux/serial_core.h index add349889d0a39..6e0a49c65b1196 100644 --- a/include/uapi/linux/serial_core.h +++ b/include/uapi/linux/serial_core.h @@ -245,4 +245,7 @@ /* Sunplus UART */ #define PORT_SUNPLUS 123 +/* RPi firmware UART */ +#define PORT_RPI_FW 124 + #endif /* _UAPILINUX_SERIAL_CORE_H */ From eaeb419ef86af6b43ecdd8a3f8a52ac090b5f681 Mon Sep 17 00:00:00 2001 From: Tim Gover Date: Wed, 28 Aug 2024 09:46:50 +0100 Subject: [PATCH 3/5] serial: tty: Add a driver for the RPi firmware UART On Raspberry Pi 4 and earlier models the firmware provides a low speed (up to 115200 baud) bit-bashed UART on arbitrary GPIOs using the second VPU core. The firmware driver is designed to support 19200 baud. Higher rates up to 115200 seem to work but there may be more jitter. This can be useful for debug or managing additional low speed peripherals if the hardware PL011 and 8250 hardware UARTs are already used for console / bluetooth. The firmware driver requires a fixed core clock frequency and also requires the VPU PWM audio driver to be disabled (dtparam=audio=off) Runtime configuration is handled via the vc-mailbox APIs with the FIFO buffers being allocated in uncached VPU addressable memory. The FIFO pointers are stored in spare VideoCore multi-core sync registers in order to reduce the number of uncached SDRAM accesses thereby reducing jitter. Signed-off-by: Tim Gover --- drivers/tty/serial/Kconfig | 11 + drivers/tty/serial/Makefile | 1 + drivers/tty/serial/rpi-fw-uart.c | 563 +++++++++++++++++++++++++++++++ 3 files changed, 575 insertions(+) create mode 100644 drivers/tty/serial/rpi-fw-uart.c diff --git a/drivers/tty/serial/Kconfig b/drivers/tty/serial/Kconfig index bdc568a4ab6693..99b4808dbe2f78 100644 --- a/drivers/tty/serial/Kconfig +++ b/drivers/tty/serial/Kconfig @@ -1578,6 +1578,17 @@ config SERIAL_NUVOTON_MA35D1_CONSOLE but you can alter that using a kernel command line option such as "console=ttyNVTx". +config SERIAL_RPI_FW + tristate "Raspberry Pi Firmware software UART support" + depends on ARM_AMBA || COMPILE_TEST + select SERIAL_CORE + help + This selects the Raspberry Pi firmware UART. This is a bit-bashed + implementation running on the Raspbery Pi VPU core. + This is not supported on Raspberry Pi 5 or newer platforms. + + If unsure, say N. + endmenu config SERIAL_MCTRL_GPIO diff --git a/drivers/tty/serial/Makefile b/drivers/tty/serial/Makefile index 138abbc8973812..ef0cc5d6fc4cc8 100644 --- a/drivers/tty/serial/Makefile +++ b/drivers/tty/serial/Makefile @@ -88,6 +88,7 @@ obj-$(CONFIG_SERIAL_MILBEAUT_USIO) += milbeaut_usio.o obj-$(CONFIG_SERIAL_SIFIVE) += sifive.o obj-$(CONFIG_SERIAL_LITEUART) += liteuart.o obj-$(CONFIG_SERIAL_SUNPLUS) += sunplus-uart.o +obj-$(CONFIG_SERIAL_RPI_FW) += rpi-fw-uart.o # GPIOLIB helpers for modem control lines obj-$(CONFIG_SERIAL_MCTRL_GPIO) += serial_mctrl_gpio.o diff --git a/drivers/tty/serial/rpi-fw-uart.c b/drivers/tty/serial/rpi-fw-uart.c new file mode 100644 index 00000000000000..bcf6c8ac4a4f94 --- /dev/null +++ b/drivers/tty/serial/rpi-fw-uart.c @@ -0,0 +1,563 @@ +// SPDX-License-Identifier: GPL-2.0 +/* + * Copyright (c) 2024, Raspberry Pi Ltd. All rights reserved. + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#define RPI_FW_UART_RX_FIFO_RD 0xb0 +#define RPI_FW_UART_RX_FIFO_WR 0xb4 +#define RPI_FW_UART_TX_FIFO_RD 0xb8 +#define RPI_FW_UART_TX_FIFO_WR 0xbc + +#define RPI_FW_UART_FIFO_SIZE 32 +#define RPI_FW_UART_FIFO_SIZE_MASK (RPI_FW_UART_FIFO_SIZE - 1) + +#define RPI_FW_UART_MIN_VERSION 3 + +struct rpi_fw_uart_params { + u32 start; + u32 baud; + u32 data_bits; + u32 stop_bits; + u32 gpio_rx; + u32 gpio_tx; + u32 flags; + u32 fifosize; + u32 rx_buffer; + u32 tx_buffer; + u32 version; + u32 fifo_reg_base; +}; + +struct rpi_fw_uart { + struct uart_driver driver; + struct uart_port port; + struct rpi_firmware *firmware; + struct gpio_desc *rx_gpiod; + struct gpio_desc *tx_gpiod; + unsigned int rx_gpio; + unsigned int tx_gpio; + unsigned int baud; + unsigned int data_bits; + unsigned int stop_bits; + unsigned char __iomem *base; + size_t dma_buffer_size; + + struct hrtimer trigger_start_rx; + ktime_t rx_poll_delay; + void *rx_buffer; + dma_addr_t rx_buffer_dma_addr; + int rx_stop; + + void *tx_buffer; + dma_addr_t tx_buffer_dma_addr; +}; + +static unsigned int rpi_fw_uart_tx_is_full(struct uart_port *port) +{ + struct rpi_fw_uart *rfu = container_of(port, struct rpi_fw_uart, port); + u32 rd, wr; + + rd = readl(rfu->base + RPI_FW_UART_TX_FIFO_RD); + wr = readl(rfu->base + RPI_FW_UART_TX_FIFO_WR); + return ((wr + 1) & RPI_FW_UART_FIFO_SIZE_MASK) == rd; +} + +static unsigned int rpi_fw_uart_tx_is_empty(struct uart_port *port) +{ + struct rpi_fw_uart *rfu = container_of(port, struct rpi_fw_uart, port); + u32 rd, wr; + + if (!rfu->tx_buffer) + return 1; + + rd = readl(rfu->base + RPI_FW_UART_TX_FIFO_RD); + wr = readl(rfu->base + RPI_FW_UART_TX_FIFO_WR); + + return rd == wr; +} + +unsigned int rpi_fw_uart_rx_is_empty(struct uart_port *port) +{ + struct rpi_fw_uart *rfu = container_of(port, struct rpi_fw_uart, port); + u32 rd, wr; + + if (!rfu->rx_buffer) + return 1; + + rd = readl(rfu->base + RPI_FW_UART_RX_FIFO_RD); + wr = readl(rfu->base + RPI_FW_UART_RX_FIFO_WR); + + return rd == wr; +} + +static unsigned int rpi_fw_uart_tx_empty(struct uart_port *port) +{ + return rpi_fw_uart_tx_is_empty(port) ? TIOCSER_TEMT : 0; +} + +static void rpi_fw_uart_set_mctrl(struct uart_port *port, unsigned int mctrl) +{ + /* + * No hardware flow control, firmware automatically configures + * TX to output high and RX to input low. + */ + dev_dbg(port->dev, "%s mctrl %u\n", __func__, mctrl); +} + +static unsigned int rpi_fw_uart_get_mctrl(struct uart_port *port) +{ + /* No hardware flow control */ + return TIOCM_CTS; +} + +static void rpi_fw_uart_stop(struct uart_port *port) +{ + struct rpi_fw_uart_params msg = {.start = 0}; + struct rpi_fw_uart *rfu = container_of(port, struct rpi_fw_uart, port); + + hrtimer_cancel(&rfu->trigger_start_rx); + + if (rpi_firmware_property(rfu->firmware, + RPI_FIRMWARE_SET_SW_UART, + &msg, sizeof(msg))) + dev_warn(port->dev, + "Failed to shutdown rpi-fw uart. Firmware not configured?"); +} + +static void rpi_fw_uart_stop_tx(struct uart_port *port) +{ + /* No supported by the current firmware APIs. */ +} + +static void rpi_fw_uart_stop_rx(struct uart_port *port) +{ + struct rpi_fw_uart *rfu = container_of(port, struct rpi_fw_uart, port); + + rfu->rx_stop = 1; +} + +static unsigned int rpi_fw_write(struct uart_port *port, const char *s, + unsigned int count) +{ + struct rpi_fw_uart *rfu = container_of(port, struct rpi_fw_uart, port); + u8 *out = rfu->tx_buffer; + unsigned int consumed = 0; + + while (consumed < count && !rpi_fw_uart_tx_is_full(port)) { + u32 wp = readl(rfu->base + RPI_FW_UART_TX_FIFO_WR) + & RPI_FW_UART_FIFO_SIZE_MASK; + out[wp] = s[consumed++]; + wp = (wp + 1) & RPI_FW_UART_FIFO_SIZE_MASK; + writel(wp, rfu->base + RPI_FW_UART_TX_FIFO_WR); + } + return consumed; +} + +/* Called with port.lock taken */ +static void rpi_fw_uart_start_tx(struct uart_port *port) +{ + struct circ_buf *xmit; + + xmit = &port->state->xmit; + for (;;) { + unsigned int consumed; + unsigned long count = CIRC_CNT_TO_END(xmit->head, xmit->tail, + UART_XMIT_SIZE); + if (!count) + break; + + consumed = rpi_fw_write(port, &xmit->buf[xmit->tail], count); + uart_xmit_advance(port, consumed); + } + uart_write_wakeup(port); +} + +/* Called with port.lock taken */ +static void rpi_fw_uart_start_rx(struct uart_port *port) +{ + struct tty_port *tty_port = &port->state->port; + struct rpi_fw_uart *rfu = container_of(port, struct rpi_fw_uart, port); + int count = 0; + + /* + * RX is polled, read up to a full buffer of data before trying again + * so that this can be interrupted if the firmware is filling the + * buffer too fast + */ + while (!rpi_fw_uart_rx_is_empty(port) && count < port->fifosize) { + const u8 *in = rfu->rx_buffer; + u32 rp = readl(rfu->base + RPI_FW_UART_RX_FIFO_RD) + & RPI_FW_UART_FIFO_SIZE_MASK; + + tty_insert_flip_char(tty_port, in[rp], TTY_NORMAL); + rp = (rp + 1) & RPI_FW_UART_FIFO_SIZE_MASK; + writel(rp, rfu->base + RPI_FW_UART_RX_FIFO_RD); + count++; + } + if (count) + tty_flip_buffer_push(tty_port); +} + +static enum hrtimer_restart rpi_fw_uart_trigger_rx(struct hrtimer *t) +{ + unsigned long flags; + struct rpi_fw_uart *rfu = container_of(t, struct rpi_fw_uart, + trigger_start_rx); + + spin_lock_irqsave(&rfu->port.lock, flags); + if (rfu->rx_stop) { + spin_unlock_irqrestore(&rfu->port.lock, flags); + return HRTIMER_NORESTART; + } + + rpi_fw_uart_start_rx(&rfu->port); + spin_unlock_irqrestore(&rfu->port.lock, flags); + hrtimer_forward_now(t, rfu->rx_poll_delay); + return HRTIMER_RESTART; +} + +static void rpi_fw_uart_break_ctl(struct uart_port *port, int ctl) +{ + dev_dbg(port->dev, "%s ctl %d\n", __func__, ctl); +} + +static int rpi_fw_uart_configure(struct uart_port *port) +{ + struct rpi_fw_uart *rfu = container_of(port, struct rpi_fw_uart, port); + struct rpi_fw_uart_params msg; + unsigned long flags; + int rc; + + rpi_fw_uart_stop(port); + + memset(&msg, 0, sizeof(msg)); + msg.start = 1; + msg.gpio_rx = rfu->rx_gpio; + msg.gpio_tx = rfu->tx_gpio; + msg.data_bits = rfu->data_bits; + msg.stop_bits = rfu->stop_bits; + msg.baud = rfu->baud; + msg.fifosize = RPI_FW_UART_FIFO_SIZE; + msg.rx_buffer = (u32) rfu->rx_buffer_dma_addr; + msg.tx_buffer = (u32) rfu->tx_buffer_dma_addr; + + rfu->rx_poll_delay = ms_to_ktime(50); + + /* + * Reconfigures the firmware UART with the new settings. On the first + * call retrieve the addresses of the FIFO buffers. The buffers are + * allocated at startup and are not de-allocated. + * NB rpi_firmware_property can block + */ + rc = rpi_firmware_property(rfu->firmware, + RPI_FIRMWARE_SET_SW_UART, + &msg, sizeof(msg)); + if (rc) + goto fail; + + rc = rpi_firmware_property(rfu->firmware, + RPI_FIRMWARE_GET_SW_UART, + &msg, sizeof(msg)); + if (rc) + goto fail; + + dev_dbg(port->dev, "version %08x, reg addr %x\n", msg.version, + msg.fifo_reg_base); + + dev_info(port->dev, "started %d baud %u data %u stop %u rx %u tx %u flags %u fifosize %u\n", + msg.start, msg.baud, msg.data_bits, msg.stop_bits, + msg.gpio_rx, msg.gpio_tx, msg.flags, msg.fifosize); + + if (msg.fifosize != port->fifosize) { + dev_err(port->dev, "Expected fifo size %u actual %u", + port->fifosize, msg.fifosize); + rc = -EINVAL; + goto fail; + } + + if (!msg.start) { + dev_err(port->dev, "Firmware service not running\n"); + rc = -EINVAL; + } + + spin_lock_irqsave(&rfu->port.lock, flags); + rfu->rx_stop = 0; + hrtimer_start(&rfu->trigger_start_rx, + rfu->rx_poll_delay, HRTIMER_MODE_REL); + spin_unlock_irqrestore(&rfu->port.lock, flags); + return 0; +fail: + dev_err(port->dev, "Failed to configure rpi-fw uart. Firmware not configured?"); + return rc; +} + +static void rpi_fw_uart_free_buffers(struct uart_port *port) +{ + struct rpi_fw_uart *rfu = container_of(port, struct rpi_fw_uart, port); + + if (rfu->rx_buffer) + dma_free_coherent(port->dev, rfu->dma_buffer_size, + rfu->rx_buffer, GFP_ATOMIC); + + if (rfu->tx_buffer) + dma_free_coherent(port->dev, rfu->dma_buffer_size, + rfu->tx_buffer, GFP_ATOMIC); + + rfu->rx_buffer = NULL; + rfu->tx_buffer = NULL; + rfu->rx_buffer_dma_addr = 0; + rfu->tx_buffer_dma_addr = 0; +} + +static int rpi_fw_uart_alloc_buffers(struct uart_port *port) +{ + struct rpi_fw_uart *rfu = container_of(port, struct rpi_fw_uart, port); + + if (rfu->tx_buffer) + return 0; + + rfu->dma_buffer_size = PAGE_ALIGN(RPI_FW_UART_FIFO_SIZE); + + rfu->rx_buffer = dma_alloc_coherent(port->dev, rfu->dma_buffer_size, + &rfu->rx_buffer_dma_addr, GFP_ATOMIC); + + if (!rfu->rx_buffer) + goto alloc_fail; + + rfu->tx_buffer = dma_alloc_coherent(port->dev, rfu->dma_buffer_size, + &rfu->tx_buffer_dma_addr, GFP_ATOMIC); + + if (!rfu->tx_buffer) + goto alloc_fail; + + dev_dbg(port->dev, "alloc-buffers %p %x %p %x\n", + rfu->rx_buffer, (u32) rfu->rx_buffer_dma_addr, + rfu->tx_buffer, (u32) rfu->tx_buffer_dma_addr); + return 0; + +alloc_fail: + dev_err(port->dev, "%s uart buffer allocation failed\n", __func__); + rpi_fw_uart_free_buffers(port); + return -ENOMEM; +} + +static int rpi_fw_uart_startup(struct uart_port *port) +{ + int rc; + + rc = rpi_fw_uart_alloc_buffers(port); + if (rc) + dev_err(port->dev, "Failed to start\n"); + return rc; +} + +static void rpi_fw_uart_shutdown(struct uart_port *port) +{ + rpi_fw_uart_stop(port); + rpi_fw_uart_free_buffers(port); +} + +static void rpi_fw_uart_set_termios(struct uart_port *port, + struct ktermios *new, + const struct ktermios *old) +{ + struct rpi_fw_uart *rfu = + container_of(port, struct rpi_fw_uart, port); + rfu->baud = uart_get_baud_rate(port, new, old, 50, 115200); + rfu->stop_bits = (new->c_cflag & CSTOPB) ? 2 : 1; + + rpi_fw_uart_configure(port); +} + +static const struct uart_ops rpi_fw_uart_ops = { + .tx_empty = rpi_fw_uart_tx_empty, + .set_mctrl = rpi_fw_uart_set_mctrl, + .get_mctrl = rpi_fw_uart_get_mctrl, + .stop_rx = rpi_fw_uart_stop_rx, + .stop_tx = rpi_fw_uart_stop_tx, + .start_tx = rpi_fw_uart_start_tx, + .break_ctl = rpi_fw_uart_break_ctl, + .startup = rpi_fw_uart_startup, + .shutdown = rpi_fw_uart_shutdown, + .set_termios = rpi_fw_uart_set_termios, +}; + +static int rpi_fw_uart_get_gpio_offset(struct device *dev, const char *name) +{ + struct of_phandle_args of_args = { 0 }; + bool is_bcm28xx; + + /* This really shouldn't fail, given that we have a gpiod */ + if (of_parse_phandle_with_args(dev->of_node, name, "#gpio-cells", 0, &of_args)) + return dev_err_probe(dev, -EINVAL, "can't find gpio declaration\n"); + + is_bcm28xx = of_device_is_compatible(of_args.np, "brcm,bcm2835-gpio") || + of_device_is_compatible(of_args.np, "brcm,bcm2711-gpio"); + of_node_put(of_args.np); + if (!is_bcm28xx || of_args.args_count != 2) + return dev_err_probe(dev, -EINVAL, "not a BCM28xx gpio\n"); + + return of_args.args[0]; +} + +static int rpi_fw_uart_probe(struct platform_device *pdev) +{ + struct device_node *firmware_node; + struct device *dev = &pdev->dev; + struct rpi_firmware *firmware; + struct uart_port *port; + struct rpi_fw_uart *rfu; + struct rpi_fw_uart_params msg; + int version_major; + int err; + + dev_dbg(dev, "%s of_node %p\n", __func__, dev->of_node); + + /* + * We can be probed either through the an old-fashioned + * platform device registration or through a DT node that is a + * child of the firmware node. Handle both cases. + */ + if (dev->of_node) + firmware_node = of_parse_phandle(dev->of_node, "firmware", 0); + else + firmware_node = of_find_compatible_node(NULL, NULL, + "raspberrypi,bcm2835-firmware"); + if (!firmware_node) { + dev_err(dev, "Missing firmware node\n"); + return -ENOENT; + } + + firmware = devm_rpi_firmware_get(dev, firmware_node); + of_node_put(firmware_node); + if (!firmware) + return -EPROBE_DEFER; + + rfu = devm_kzalloc(dev, sizeof(*rfu), GFP_KERNEL); + if (!rfu) + return -ENOMEM; + + rfu->firmware = firmware; + + err = rpi_firmware_property(rfu->firmware, RPI_FIRMWARE_GET_SW_UART, + &msg, sizeof(msg)); + if (err) { + dev_err(dev, "VC firmware does not support rpi-fw-uart\n"); + return err; + } + + version_major = msg.version >> 16; + if (msg.version < RPI_FW_UART_MIN_VERSION) { + dev_err(dev, "rpi-fw-uart fw version %d is too old min version %d\n", + version_major, RPI_FW_UART_MIN_VERSION); + return -EINVAL; + } + + rfu->rx_gpiod = devm_gpiod_get(dev, "rx", GPIOD_IN); + if (IS_ERR(rfu->rx_gpiod)) + return PTR_ERR(rfu->rx_gpiod); + + rfu->tx_gpiod = devm_gpiod_get(dev, "tx", GPIOD_OUT_HIGH); + if (IS_ERR(rfu->tx_gpiod)) + return PTR_ERR(rfu->tx_gpiod); + + rfu->rx_gpio = rpi_fw_uart_get_gpio_offset(dev, "rx-gpios"); + if (rfu->rx_gpio < 0) + return rfu->rx_gpio; + rfu->tx_gpio = rpi_fw_uart_get_gpio_offset(dev, "tx-gpios"); + if (rfu->tx_gpio < 0) + return rfu->tx_gpio; + + rfu->base = devm_platform_ioremap_resource(pdev, 0); + if (IS_ERR(rfu->base)) + return PTR_ERR(rfu->base); + + /* setup the driver */ + rfu->driver.owner = THIS_MODULE; + rfu->driver.driver_name = "ttyRFU"; + rfu->driver.dev_name = "ttyRFU"; + rfu->driver.nr = 1; + rfu->data_bits = 8; + + /* RX is polled */ + hrtimer_init(&rfu->trigger_start_rx, CLOCK_MONOTONIC, HRTIMER_MODE_REL); + rfu->trigger_start_rx.function = rpi_fw_uart_trigger_rx; + + err = uart_register_driver(&rfu->driver); + if (err) { + dev_err(dev, "failed to register UART driver: %d\n", + err); + return err; + } + + /* setup the port */ + port = &rfu->port; + spin_lock_init(&port->lock); + port->dev = &pdev->dev; + port->type = PORT_RPI_FW; + port->ops = &rpi_fw_uart_ops; + port->fifosize = RPI_FW_UART_FIFO_SIZE; + port->iotype = UPIO_MEM; + port->flags = UPF_BOOT_AUTOCONF; + port->private_data = rfu; + + err = uart_add_one_port(&rfu->driver, port); + if (err) { + dev_err(dev, "failed to add UART port: %d\n", err); + goto unregister_uart; + } + platform_set_drvdata(pdev, rfu); + + dev_info(dev, "version %d.%d gpios tx %u rx %u\n", + msg.version >> 16, msg.version & 0xffff, + rfu->tx_gpio, rfu->rx_gpio); + return 0; + +unregister_uart: + uart_unregister_driver(&rfu->driver); + + return err; +} + +static int rpi_fw_uart_remove(struct platform_device *pdev) +{ + struct rpi_fw_uart *rfu = platform_get_drvdata(pdev); + + uart_remove_one_port(&rfu->driver, &rfu->port); + uart_unregister_driver(&rfu->driver); + + return 0; +} + +static const struct of_device_id rpi_fw_match[] = { + { .compatible = "raspberrypi,firmware-uart" }, + { } +}; +MODULE_DEVICE_TABLE(of, rpi_fw_match); + +static struct platform_driver rpi_fw_driver = { + .driver = { + .name = "rpi_fw-uart", + .of_match_table = rpi_fw_match, + }, + .probe = rpi_fw_uart_probe, + .remove = rpi_fw_uart_remove, +}; +module_platform_driver(rpi_fw_driver); + +MODULE_AUTHOR("Tim Gover "); +MODULE_LICENSE("GPL"); +MODULE_DESCRIPTION("Raspberry Pi Firmware Software UART driver"); From 339953fe96c5d2e73bb08fcfac79f2ce0aee5e22 Mon Sep 17 00:00:00 2001 From: Tim Gover Date: Fri, 1 Nov 2024 19:44:37 +0000 Subject: [PATCH 4/5] configs: Enable the RPi FW UART driver Enable the RPi firmware driver for Raspberry Pi4 and earlier models. Signed-off-by: Tim Gover --- arch/arm/configs/bcm2709_defconfig | 1 + arch/arm/configs/bcm2711_defconfig | 1 + arch/arm/configs/bcmrpi_defconfig | 1 + arch/arm64/configs/bcm2711_defconfig | 1 + arch/arm64/configs/bcmrpi3_defconfig | 1 + 5 files changed, 5 insertions(+) diff --git a/arch/arm/configs/bcm2709_defconfig b/arch/arm/configs/bcm2709_defconfig index c8402e98544813..963641976cfb8c 100644 --- a/arch/arm/configs/bcm2709_defconfig +++ b/arch/arm/configs/bcm2709_defconfig @@ -671,6 +671,7 @@ CONFIG_SERIAL_AMBA_PL011=y CONFIG_SERIAL_AMBA_PL011_CONSOLE=y CONFIG_SERIAL_SC16IS7XX=m CONFIG_SERIAL_SC16IS7XX_SPI=y +CONFIG_SERIAL_RPI_FW=m CONFIG_SERIAL_DEV_BUS=y CONFIG_TTY_PRINTK=y CONFIG_HW_RANDOM=y diff --git a/arch/arm/configs/bcm2711_defconfig b/arch/arm/configs/bcm2711_defconfig index e90b9b6e7cf24c..513b8b4b731692 100644 --- a/arch/arm/configs/bcm2711_defconfig +++ b/arch/arm/configs/bcm2711_defconfig @@ -689,6 +689,7 @@ CONFIG_SERIAL_AMBA_PL011=y CONFIG_SERIAL_AMBA_PL011_CONSOLE=y CONFIG_SERIAL_SC16IS7XX=m CONFIG_SERIAL_SC16IS7XX_SPI=y +CONFIG_SERIAL_RPI_FW=m CONFIG_SERIAL_DEV_BUS=y CONFIG_TTY_PRINTK=y CONFIG_HW_RANDOM=y diff --git a/arch/arm/configs/bcmrpi_defconfig b/arch/arm/configs/bcmrpi_defconfig index f1051be76fe95b..a88bad286cf7a6 100644 --- a/arch/arm/configs/bcmrpi_defconfig +++ b/arch/arm/configs/bcmrpi_defconfig @@ -666,6 +666,7 @@ CONFIG_SERIAL_AMBA_PL011=y CONFIG_SERIAL_AMBA_PL011_CONSOLE=y CONFIG_SERIAL_SC16IS7XX=m CONFIG_SERIAL_SC16IS7XX_SPI=y +CONFIG_SERIAL_RPI_FW=m CONFIG_SERIAL_DEV_BUS=y CONFIG_TTY_PRINTK=y CONFIG_HW_RANDOM=y diff --git a/arch/arm64/configs/bcm2711_defconfig b/arch/arm64/configs/bcm2711_defconfig index d099ebfe5a8c3f..7b6d2a0c1a2b83 100644 --- a/arch/arm64/configs/bcm2711_defconfig +++ b/arch/arm64/configs/bcm2711_defconfig @@ -712,6 +712,7 @@ CONFIG_SERIAL_AMBA_PL011=y CONFIG_SERIAL_AMBA_PL011_CONSOLE=y CONFIG_SERIAL_SC16IS7XX=m CONFIG_SERIAL_SC16IS7XX_SPI=y +CONFIG_SERIAL_RPI_FW=m CONFIG_SERIAL_DEV_BUS=y CONFIG_TTY_PRINTK=y CONFIG_HW_RANDOM=y diff --git a/arch/arm64/configs/bcmrpi3_defconfig b/arch/arm64/configs/bcmrpi3_defconfig index 1a22245321d823..951dcc6915c094 100644 --- a/arch/arm64/configs/bcmrpi3_defconfig +++ b/arch/arm64/configs/bcmrpi3_defconfig @@ -669,6 +669,7 @@ CONFIG_SERIAL_AMBA_PL011=y CONFIG_SERIAL_AMBA_PL011_CONSOLE=y CONFIG_SERIAL_SC16IS7XX=m CONFIG_SERIAL_SC16IS7XX_SPI=y +CONFIG_SERIAL_RPI_FW=m CONFIG_SERIAL_DEV_BUS=y CONFIG_TTY_PRINTK=y CONFIG_HW_RANDOM=y From 0f460142b08fa33cfc183600c28b105f9909a521 Mon Sep 17 00:00:00 2001 From: Tim Gover Date: Mon, 4 Nov 2024 13:44:10 +0000 Subject: [PATCH 5/5] dtoverlay: Add an overlay for the Raspberry Pi firmware UART Add a device-tree overlay to configure the GPIOs for the Raspberry Pi firmware UART. Example config.txt dtoverlay=rpi-fw-uart,txd0_pin=20,rxd0_pin=21 Signed-off-by: Phil Elwell Signed-off-by: Tim Gover --- arch/arm/boot/dts/overlays/Makefile | 1 + arch/arm/boot/dts/overlays/README | 12 ++++++ .../boot/dts/overlays/rpi-fw-uart-overlay.dts | 41 +++++++++++++++++++ 3 files changed, 54 insertions(+) create mode 100644 arch/arm/boot/dts/overlays/rpi-fw-uart-overlay.dts diff --git a/arch/arm/boot/dts/overlays/Makefile b/arch/arm/boot/dts/overlays/Makefile index b023a7e0741d67..367cbf437e1b0f 100644 --- a/arch/arm/boot/dts/overlays/Makefile +++ b/arch/arm/boot/dts/overlays/Makefile @@ -233,6 +233,7 @@ dtbo-$(CONFIG_ARCH_BCM2835) += \ rpi-dacpro.dtbo \ rpi-digiampplus.dtbo \ rpi-ft5406.dtbo \ + rpi-fw-uart.dtbo \ rpi-poe.dtbo \ rpi-poe-plus.dtbo \ rpi-sense.dtbo \ diff --git a/arch/arm/boot/dts/overlays/README b/arch/arm/boot/dts/overlays/README index 2da54f781e3b94..f3c0eb2fef05ff 100644 --- a/arch/arm/boot/dts/overlays/README +++ b/arch/arm/boot/dts/overlays/README @@ -4141,6 +4141,18 @@ Params: touchscreen-size-x Touchscreen X resolution (default 800) touchscreen-swapped-x-y Swap X and Y cordinates (default 0); +Name: rpi-fw-uart +Info: Configures the firmware software UART driver. + This driver requires exclusive usage of the second VPU core. The + following config.txt entries should be set when this driver is used. + dtparam=audio=off + isp_use_vpu0=1 +Load: dtoverlay=rpi-fw-uart,[=] +Params: txd0_pin GPIO pin for TXD0 (any free - default 20) + + rxd0_pin GPIO pin for RXD0 (any free - default 21) + + Name: rpi-poe Info: Raspberry Pi PoE HAT fan Load: dtoverlay=rpi-poe,[=] diff --git a/arch/arm/boot/dts/overlays/rpi-fw-uart-overlay.dts b/arch/arm/boot/dts/overlays/rpi-fw-uart-overlay.dts new file mode 100644 index 00000000000000..c17556e91105d8 --- /dev/null +++ b/arch/arm/boot/dts/overlays/rpi-fw-uart-overlay.dts @@ -0,0 +1,41 @@ +// SPDX-License-Identifier: GPL-2.0 +// Overlay for the Raspberry Pi Firmware UART driver +/dts-v1/; +/plugin/; + +/{ + compatible = "brcm,bcm2835"; + + fragment@0 { + target = <&gpio>; + __overlay__ { + rpi_fw_uart_pins: rpi_fw_uart_pins@4 { + brcm,pins = <20 21>; + brcm,function = <1 0>; /* output input */ + brcm,pull = <0 2>; /* none pull-up */ + }; + }; + }; + + fragment@1 { + target = <&soc>; + __overlay__ { + rpi_fw_uart: rpi_fw_uart@7e000000 { + compatible = "raspberrypi,firmware-uart"; + reg = <0x7e000000 0x100>; /* VideoCore MS sync regs */ + firmware = <&firmware>; + pinctrl-names = "default"; + pinctrl-0 = <&rpi_fw_uart_pins>; + tx-gpios = <&gpio 20 0>; + rx-gpios = <&gpio 21 0>; + }; + }; + }; + + __overrides__ { + txd0_pin = <&rpi_fw_uart>,"tx-gpios:4", + <&rpi_fw_uart_pins>, "brcm,pins:0"; + rxd0_pin = <&rpi_fw_uart>,"rx-gpios:4", + <&rpi_fw_uart_pins>, "brcm,pins:4"; + }; +};