Skip site navigation (1)Skip section navigation (2)
Date:      Wed, 2 Apr 2025 02:57:56 GMT
From:      Kyle Evans <kevans@FreeBSD.org>
To:        src-committers@FreeBSD.org, dev-commits-src-all@FreeBSD.org, dev-commits-src-main@FreeBSD.org
Subject:   git: ba2336d3044c - main - arm64: add a driver for the uart found on Apple Silicon machines
Message-ID:  <202504020257.5322vuj0078587@gitrepo.freebsd.org>

next in thread | raw e-mail | index | archive | help
The branch main has been updated by kevans:

URL: https://cgit.FreeBSD.org/src/commit/?id=ba2336d3044c681462224c12879ecc8f659be54a

commit ba2336d3044c681462224c12879ecc8f659be54a
Author:     Kyle Evans <kevans@FreeBSD.org>
AuthorDate: 2025-04-02 02:57:16 +0000
Commit:     Kyle Evans <kevans@FreeBSD.org>
CommitDate: 2025-04-02 02:57:17 +0000

    arm64: add a driver for the uart found on Apple Silicon machines
    
    This is a revival of the old exynos4210 driver, with some additional
    bits to configure the apple "s5l" uart (which is actually slightly
    different to operate).
    
    This hasn't been tested on anything that would hit the non-s5l path, so
    banish it off to the apple/ domain until someone cares to confirm that
    none of the other hardware is broken -- it may be that nobody does, but
    the complexity isn't too bad: mostly the driver1 construct added to the
    uart_bas that we use to avoid having a whole bunch of shims for uart
    driver methods and hardcoded references to the cfg structs.
    
    Reviewed by:    andrew
    Differential Revision:  https://reviews.freebsd.org/D48120
---
 sys/arm64/apple/exynos_uart.c | 568 ++++++++++++++++++++++++++++++++++++++++++
 sys/arm64/apple/exynos_uart.h | 136 ++++++++++
 sys/conf/files.arm64          |   1 +
 sys/dev/uart/uart.h           |   1 +
 4 files changed, 706 insertions(+)

diff --git a/sys/arm64/apple/exynos_uart.c b/sys/arm64/apple/exynos_uart.c
new file mode 100644
index 000000000000..2767c338b918
--- /dev/null
+++ b/sys/arm64/apple/exynos_uart.c
@@ -0,0 +1,568 @@
+/*
+ * SPDX-License-Identifier: BSD-2-Clause
+ *
+ * Copyright (c) 2003 Marcel Moolenaar
+ * Copyright (c) 2007-2009 Andrew Turner
+ * Copyright (c) 2013 Ruslan Bukin <br@bsdpad.com>
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR
+ * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES
+ * OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
+ * IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
+ * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+ * DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+ * THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
+ * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#include <sys/param.h>
+#include <sys/systm.h>
+#include <sys/bus.h>
+#include <sys/conf.h>
+#include <sys/cons.h>
+#include <sys/rman.h>
+#include <machine/bus.h>
+#include <machine/intr.h>
+
+#include <dev/uart/uart.h>
+#include <dev/uart/uart_cpu.h>
+#include <dev/uart/uart_cpu_fdt.h>
+#include <dev/uart/uart_bus.h>
+
+#include <arm64/apple/exynos_uart.h>
+
+#include "uart_if.h"
+
+struct exynos_uart_cfg;
+
+#define	DEF_CLK		100000000
+
+static int sscomspeed(long, long);
+static int exynos4210_uart_param(struct uart_bas *, int, int, int, int);
+
+/*
+ * Low-level UART interface.
+ */
+static int exynos4210_probe(struct uart_bas *bas);
+static void exynos4210_init_common(struct exynos_uart_cfg *cfg,
+    struct uart_bas *bas, int, int, int, int);
+static void exynos4210_init(struct uart_bas *bas, int, int, int, int);
+static void exynos4210_s5l_init(struct uart_bas *bas, int, int, int, int);
+static void exynos4210_term(struct uart_bas *bas);
+static void exynos4210_putc(struct uart_bas *bas, int);
+static int exynos4210_rxready(struct uart_bas *bas);
+static int exynos4210_getc(struct uart_bas *bas, struct mtx *mtx);
+
+extern SLIST_HEAD(uart_devinfo_list, uart_devinfo) uart_sysdevs;
+
+static struct uart_ops uart_exynos4210_ops;
+static struct uart_ops uart_s5l_ops;
+static kobj_method_t exynos4210_methods[];
+static kobj_method_t s5l_methods[];
+static struct ofw_compat_data compat_data[];
+
+enum exynos_uart_type {
+	EXUART_4210,
+	EXUART_S5L,
+};
+
+struct exynos_uart_cfg {
+	enum exynos_uart_type	cfg_type;
+	uint64_t		cfg_uart_full_mask;
+};
+
+struct exynos_uart_class {
+	struct uart_class base;
+	struct exynos_uart_cfg cfg;
+};
+
+static struct exynos_uart_class uart_ex4210_class = {
+	.base = {
+		"exynos4210 class",
+		exynos4210_methods,
+		1,
+		.uc_ops = &uart_exynos4210_ops,
+		.uc_range = 8,
+		.uc_rclk = 0,
+		.uc_rshift = 0
+	},
+	.cfg = {
+		.cfg_type = EXUART_4210,
+		.cfg_uart_full_mask = UFSTAT_TXFULL,
+	},
+};
+
+
+static struct exynos_uart_class uart_s5l_class = {
+	.base = {
+		"s5l class",
+		s5l_methods,
+		1,
+		.uc_ops = &uart_s5l_ops,
+		.uc_range = 8,
+		.uc_rclk = 0,
+		.uc_rshift = 0
+	},
+	.cfg = {
+		.cfg_type = EXUART_S5L,
+		.cfg_uart_full_mask = UFSTAT_S5L_TXFULL,
+	},
+};
+
+static int
+sscomspeed(long speed, long frequency)
+{
+	int x;
+
+	if (speed <= 0 || frequency <= 0)
+		return (-1);
+	x = (frequency / 16) / speed;
+	return (x-1);
+}
+
+static int
+exynos4210_uart_param(struct uart_bas *bas, int baudrate, int databits,
+    int stopbits, int parity)
+{
+	int brd, ulcon;
+
+	ulcon = 0;
+
+	switch(databits) {
+	case 5:
+		ulcon |= ULCON_LENGTH_5;
+		break;
+	case 6:
+		ulcon |= ULCON_LENGTH_6;
+		break;
+	case 7:
+		ulcon |= ULCON_LENGTH_7;
+		break;
+	case 8:
+		ulcon |= ULCON_LENGTH_8;
+		break;
+	default:
+		return (EINVAL);
+	}
+
+	switch (parity) {
+	case UART_PARITY_NONE:
+		ulcon |= ULCON_PARITY_NONE;
+		break;
+	case UART_PARITY_ODD:
+		ulcon |= ULCON_PARITY_ODD;
+		break;
+	case UART_PARITY_EVEN:
+		ulcon |= ULCON_PARITY_EVEN;
+		break;
+	case UART_PARITY_MARK:
+	case UART_PARITY_SPACE:
+	default:
+		return (EINVAL);
+	}
+
+	if (stopbits == 2)
+		ulcon |= ULCON_STOP;
+
+	uart_setreg(bas, SSCOM_ULCON, ulcon);
+
+	/* baudrate may be negative, in which case we just leave it alone. */
+	if (baudrate > 0) {
+		brd = sscomspeed(baudrate, bas->rclk);
+		uart_setreg(bas, SSCOM_UBRDIV, brd);
+	}
+
+	return (0);
+}
+
+static struct uart_ops uart_exynos4210_ops = {
+	.probe = exynos4210_probe,
+	.init = exynos4210_init,
+	.term = exynos4210_term,
+	.putc = exynos4210_putc,
+	.rxready = exynos4210_rxready,
+	.getc = exynos4210_getc,
+};
+
+static struct uart_ops uart_s5l_ops = {
+	.probe = exynos4210_probe,
+	.init = exynos4210_s5l_init,
+	.term = exynos4210_term,
+	.putc = exynos4210_putc,
+	.rxready = exynos4210_rxready,
+	.getc = exynos4210_getc,
+};
+
+static int
+exynos4210_probe(struct uart_bas *bas)
+{
+
+	return (0);
+}
+
+static void
+exynos4210_init_common(struct exynos_uart_cfg *cfg, struct uart_bas *bas,
+    int baudrate, int databits, int stopbits, int parity)
+{
+
+	if (bas->rclk == 0)
+		bas->rclk = DEF_CLK;
+
+	KASSERT(bas->rclk != 0, ("exynos4210_init: Invalid rclk"));
+
+	bas->driver1 = cfg;
+
+	/* Clear interrupts */
+	if (cfg->cfg_type == EXUART_S5L) {
+		uart_setreg(bas, SSCOM_UTRSTAT, 0);
+	} else {
+		uart_setreg(bas, SSCOM_UCON, 0);
+		uart_setreg(bas, SSCOM_UFCON,
+		    UFCON_TXTRIGGER_8 | UFCON_RXTRIGGER_8 |
+		    UFCON_TXFIFO_RESET | UFCON_RXFIFO_RESET |
+		    UFCON_FIFO_ENABLE);
+	}
+
+	exynos4210_uart_param(bas, baudrate, databits, stopbits, parity);
+
+	/* Enable UART. */
+	if (cfg->cfg_type == EXUART_S5L) {
+		uart_setreg(bas, SSCOM_UCON, uart_getreg(bas, SSCOM_UCON) |
+		    UCON_TOINT | UCON_S5L_RXTHRESH | UCON_S5L_RX_TIMEOUT |
+		    UCON_S5L_TXTHRESH);
+	} else {
+		uart_setreg(bas, SSCOM_UCON, uart_getreg(bas, SSCOM_UCON) |
+		    UCON_TXMODE_INT | UCON_RXMODE_INT | UCON_TOINT);
+		uart_setreg(bas, SSCOM_UMCON, UMCON_RTS);
+	}
+}
+
+static void
+exynos4210_init(struct uart_bas *bas, int baudrate, int databits, int stopbits,
+    int parity)
+{
+
+	return (exynos4210_init_common(&uart_ex4210_class.cfg, bas, baudrate,
+	    databits, stopbits, parity));
+}
+
+static void
+exynos4210_s5l_init(struct uart_bas *bas, int baudrate, int databits, int stopbits,
+    int parity)
+{
+
+	return (exynos4210_init_common(&uart_s5l_class.cfg, bas, baudrate,
+	    databits, stopbits, parity));
+}
+
+static void
+exynos4210_term(struct uart_bas *bas)
+{
+	/* XXX */
+}
+
+static void
+exynos4210_putc(struct uart_bas *bas, int c)
+{
+	struct exynos_uart_cfg *cfg;
+
+	cfg = bas->driver1;
+
+	while ((bus_space_read_4(bas->bst, bas->bsh, SSCOM_UFSTAT) &
+	    cfg->cfg_uart_full_mask) != 0)
+		continue;
+
+	uart_setreg(bas, SSCOM_UTXH, c);
+	uart_barrier(bas);
+}
+
+static int
+exynos4210_rxready_impl(struct uart_bas *bas, bool intr)
+{
+	struct exynos_uart_cfg *cfg;
+	int ufstat, utrstat;
+
+	cfg = bas->driver1;
+	if (!intr || cfg->cfg_type != EXUART_S5L) {
+		utrstat = bus_space_read_4(bas->bst, bas->bsh, SSCOM_UTRSTAT);
+
+		if ((utrstat & UTRSTAT_RXREADY) != 0)
+			return (1);
+		if (cfg->cfg_type != EXUART_S5L)
+			return (0);
+	}
+
+	ufstat = bus_space_read_4(bas->bst, bas->bsh, SSCOM_UFSTAT);
+
+	return ((ufstat & (UFSTAT_RXCOUNT | UFSTAT_RXFULL)) != 0);
+}
+
+static int
+exynos4210_rxready(struct uart_bas *bas)
+{
+
+	return (exynos4210_rxready_impl(bas, false));
+}
+
+static int
+exynos4210_getc(struct uart_bas *bas, struct mtx *mtx)
+{
+
+	while (!exynos4210_rxready(bas)) {
+		continue;
+	}
+
+	return (uart_getreg(bas, SSCOM_URXH));
+}
+
+static int exynos4210_bus_probe(struct uart_softc *sc);
+static int exynos4210_bus_attach(struct uart_softc *sc);
+static int exynos4210_bus_flush(struct uart_softc *, int);
+static int exynos4210_bus_getsig(struct uart_softc *);
+static int exynos4210_bus_ioctl(struct uart_softc *, int, intptr_t);
+static int exynos4210_bus_ipend(struct uart_softc *);
+static int s5l_bus_ipend(struct uart_softc *);
+static int exynos4210_bus_param(struct uart_softc *, int, int, int, int);
+static int exynos4210_bus_receive(struct uart_softc *);
+static int exynos4210_bus_setsig(struct uart_softc *, int);
+static int exynos4210_bus_transmit(struct uart_softc *);
+
+static kobj_method_t exynos4210_methods[] = {
+	KOBJMETHOD(uart_probe,		exynos4210_bus_probe),
+	KOBJMETHOD(uart_attach, 	exynos4210_bus_attach),
+	KOBJMETHOD(uart_flush,		exynos4210_bus_flush),
+	KOBJMETHOD(uart_getsig,		exynos4210_bus_getsig),
+	KOBJMETHOD(uart_ioctl,		exynos4210_bus_ioctl),
+	KOBJMETHOD(uart_ipend,		exynos4210_bus_ipend),
+	KOBJMETHOD(uart_param,		exynos4210_bus_param),
+	KOBJMETHOD(uart_receive,	exynos4210_bus_receive),
+	KOBJMETHOD(uart_setsig,		exynos4210_bus_setsig),
+	KOBJMETHOD(uart_transmit,	exynos4210_bus_transmit),
+	{0, 0 }
+};
+
+static kobj_method_t s5l_methods[] = {
+	KOBJMETHOD(uart_probe,		exynos4210_bus_probe),
+	KOBJMETHOD(uart_attach, 	exynos4210_bus_attach),
+	KOBJMETHOD(uart_flush,		exynos4210_bus_flush),
+	KOBJMETHOD(uart_getsig,		exynos4210_bus_getsig),
+	KOBJMETHOD(uart_ioctl,		exynos4210_bus_ioctl),
+	KOBJMETHOD(uart_ipend,		s5l_bus_ipend),
+	KOBJMETHOD(uart_param,		exynos4210_bus_param),
+	KOBJMETHOD(uart_receive,	exynos4210_bus_receive),
+	KOBJMETHOD(uart_setsig,		exynos4210_bus_setsig),
+	KOBJMETHOD(uart_transmit,	exynos4210_bus_transmit),
+	{0, 0 }
+};
+
+int
+exynos4210_bus_probe(struct uart_softc *sc)
+{
+
+	sc->sc_txfifosz = 16;
+	sc->sc_rxfifosz = 16;
+
+	return (0);
+}
+
+static int
+exynos4210_bus_attach(struct uart_softc *sc)
+{
+	struct exynos_uart_class *class;
+	struct exynos_uart_cfg *cfg;
+
+	sc->sc_hwiflow = 0;
+	sc->sc_hwoflow = 0;
+
+	class = (struct exynos_uart_class *)ofw_bus_search_compatible(sc->sc_dev,
+	    compat_data)->ocd_data;
+	MPASS(class != NULL);
+
+	cfg = &class->cfg;
+	MPASS(sc->sc_sysdev == NULL || cfg == sc->sc_sysdev->bas.driver1);
+	sc->sc_bas.driver1 = cfg;
+
+	return (0);
+}
+
+static int
+exynos4210_bus_transmit(struct uart_softc *sc)
+{
+	struct exynos_uart_cfg *cfg;
+	int i;
+	int reg;
+
+	cfg = sc->sc_bas.driver1;
+	uart_lock(sc->sc_hwmtx);
+
+	/* tx fifo has room, fire away. */
+	for (i = 0; i < sc->sc_txdatasz; i++) {
+		uart_setreg(&sc->sc_bas, SSCOM_UTXH, sc->sc_txbuf[i]);
+		uart_barrier(&sc->sc_bas);
+	}
+
+	if (cfg->cfg_type == EXUART_S5L) {
+		sc->sc_txbusy = 1;
+	} else {
+		/* unmask TX interrupt */
+		reg = bus_space_read_4(sc->sc_bas.bst, sc->sc_bas.bsh,
+		    SSCOM_UINTM);
+		reg &= ~(1 << 2);
+		bus_space_write_4(sc->sc_bas.bst, sc->sc_bas.bsh, SSCOM_UINTM,
+		    reg);
+	}
+
+	uart_unlock(sc->sc_hwmtx);
+
+	return (0);
+}
+
+static int
+exynos4210_bus_setsig(struct uart_softc *sc, int sig)
+{
+
+	return (0);
+}
+
+static int
+exynos4210_bus_receive(struct uart_softc *sc)
+{
+	struct uart_bas *bas;
+
+	bas = &sc->sc_bas;
+	uart_lock(sc->sc_hwmtx);
+
+	while (exynos4210_rxready_impl(bas, true)) {
+		if (uart_rx_full(sc)) {
+			sc->sc_rxbuf[sc->sc_rxput] = UART_STAT_OVERRUN;
+			break;
+		}
+
+		uart_rx_put(sc, uart_getreg(&sc->sc_bas, SSCOM_URXH));
+	}
+
+	uart_unlock(sc->sc_hwmtx);
+
+	return (0);
+}
+
+static int
+exynos4210_bus_param(struct uart_softc *sc, int baudrate, int databits,
+    int stopbits, int parity)
+{
+	int error;
+
+	if (sc->sc_bas.rclk == 0)
+		sc->sc_bas.rclk = DEF_CLK;
+
+	KASSERT(sc->sc_bas.rclk != 0, ("exynos4210_init: Invalid rclk"));
+
+	uart_lock(sc->sc_hwmtx);
+	error = exynos4210_uart_param(&sc->sc_bas, baudrate, databits, stopbits,
+	    parity);
+	uart_unlock(sc->sc_hwmtx);
+
+	return (error);
+}
+
+static int
+s5l_bus_ipend(struct uart_softc *sc)
+{
+	int ipend;
+	uint32_t uerstat, utrstat;
+
+	ipend = 0;
+	uart_lock(sc->sc_hwmtx);
+	utrstat = bus_space_read_4(sc->sc_bas.bst, sc->sc_bas.bsh,
+	    SSCOM_UTRSTAT);
+
+        if (utrstat & (UTRSTAT_S5L_RXTHRESH | UTRSTAT_S5L_RX_TIMEOUT))
+		ipend |= SER_INT_RXREADY;
+
+        if (utrstat & UTRSTAT_S5L_TXTHRESH)
+		ipend |= SER_INT_TXIDLE;
+
+	uerstat = bus_space_read_4(sc->sc_bas.bst, sc->sc_bas.bsh,
+	    SSCOM_UERSTAT);
+	if ((uerstat & UERSTAT_BREAK) != 0)
+		ipend |= SER_INT_BREAK;
+
+	bus_space_write_4(sc->sc_bas.bst, sc->sc_bas.bsh, SSCOM_UTRSTAT,
+	    utrstat);
+	uart_unlock(sc->sc_hwmtx);
+
+	return (ipend);
+}
+
+static int
+exynos4210_bus_ipend(struct uart_softc *sc)
+{
+	uint32_t ints;
+	int reg;
+	int ipend;
+
+	uart_lock(sc->sc_hwmtx);
+	ints = bus_space_read_4(sc->sc_bas.bst, sc->sc_bas.bsh, SSCOM_UINTP);
+	bus_space_write_4(sc->sc_bas.bst, sc->sc_bas.bsh, SSCOM_UINTP, ints);
+
+	ipend = 0;
+	if ((ints & UINTP_TXEMPTY) != 0) {
+		if (sc->sc_txbusy != 0)
+			ipend |= SER_INT_TXIDLE;
+
+		/* mask TX interrupt */
+		reg = bus_space_read_4(sc->sc_bas.bst, sc->sc_bas.bsh,
+		    SSCOM_UINTM);
+		reg |= UINTM_TXINTR;
+		bus_space_write_4(sc->sc_bas.bst, sc->sc_bas.bsh,
+		    SSCOM_UINTM, reg);
+	}
+
+	if ((ints & UINTP_RXREADY) != 0) {
+		ipend |= SER_INT_RXREADY;
+	}
+
+	uart_unlock(sc->sc_hwmtx);
+	return (ipend);
+}
+
+static int
+exynos4210_bus_flush(struct uart_softc *sc, int what)
+{
+
+	return (0);
+}
+
+static int
+exynos4210_bus_getsig(struct uart_softc *sc)
+{
+
+	return (0);
+}
+
+static int
+exynos4210_bus_ioctl(struct uart_softc *sc, int request, intptr_t data)
+{
+
+	return (EINVAL);
+}
+
+static struct ofw_compat_data compat_data[] = {
+	{"apple,s5l-uart",		(uintptr_t)&uart_s5l_class.base},
+	{"samsung,exynos4210-uart",	(uintptr_t)&uart_ex4210_class.base},
+	{NULL,			(uintptr_t)NULL},
+};
+UART_FDT_CLASS_AND_DEVICE(compat_data);
diff --git a/sys/arm64/apple/exynos_uart.h b/sys/arm64/apple/exynos_uart.h
new file mode 100644
index 000000000000..6c817252a69a
--- /dev/null
+++ b/sys/arm64/apple/exynos_uart.h
@@ -0,0 +1,136 @@
+/* $NetBSD: s3c2xx0reg.h,v 1.4 2004/02/12 03:47:29 bsh Exp $ */
+
+/*-
+ * SPDX-License-Identifier: BSD-3-Clause
+ *
+ * Copyright (c) 2002, 2003 Fujitsu Component Limited
+ * Copyright (c) 2002, 2003 Genetec Corporation
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ * 1. Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ * 3. Neither the name of The Fujitsu Component Limited nor the name of
+ *    Genetec corporation may not be used to endorse or promote products
+ *    derived from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY FUJITSU COMPONENT LIMITED AND GENETEC
+ * CORPORATION ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES,
+ * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
+ * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED.  IN NO EVENT SHALL FUJITSU COMPONENT LIMITED OR GENETEC
+ * CORPORATION BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+ * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
+ * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
+ * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+ * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
+ * OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
+ * SUCH DAMAGE.
+ */
+
+/* s3c2410-specific registers */
+#define	UMCON_AFC		(1 << 4)	/* auto flow control */
+#define	UMSTAT_DCTS		(1 << 2)	/* CTS change */
+#define	ULCON_IR		(1 << 6)
+#define	ULCON_PARITY_SHIFT	3
+
+/*
+ * Exynos-specific
+ *
+ * UFSTAT_TXFULL register differs between Exynos and others.
+ * Others have UFSTAT_TXFULL  (1 << 9)
+ */
+#define	UFSTAT_TXFULL		(1 << 24)
+#define	UFSTAT_S5L_TXFULL	(1 << 9)
+
+#define	SSCOM_UINTM		0x038
+#define	 UINTM_TXINTR		(1 << 2)
+#define	SSCOM_UINTP		0x030
+#define	 UINTP_RXREADY		(1 << 0)
+#define	 UINTP_TXEMPTY		(1 << 2)
+
+/* common for s3c2800 and s3c24x0 */
+#define	SSCOM_ULCON		0x00		/* UART line control */
+#define	 ULCON_PARITY_NONE	(0 << ULCON_PARITY_SHIFT)
+#define	 ULCON_PARITY_ODD	(4 << ULCON_PARITY_SHIFT)
+#define	 ULCON_PARITY_EVEN	(5 << ULCON_PARITY_SHIFT)
+#define	 ULCON_PARITY_ONE	(6 << ULCON_PARITY_SHIFT)
+#define	 ULCON_PARITY_ZERO	(7 << ULCON_PARITY_SHIFT)
+#define	 ULCON_STOP		(1 << 2)
+#define	 ULCON_LENGTH_5		0
+#define	 ULCON_LENGTH_6		1
+#define	 ULCON_LENGTH_7		2
+#define	 ULCON_LENGTH_8		3
+#define	SSCOM_UCON		0x04		/* UART control */
+#define	 UCON_TXINT_TYPE	(1 << 9)	/* Tx interrupt. 0=pulse,1=level */
+#define	 UCON_TXINT_TYPE_LEVEL	UCON_TXINT_TYPE
+#define	 UCON_TXINT_TYPE_PULSE	0
+#define	 UCON_RXINT_TYPE	(1 << 8)	/* Rx interrupt */
+#define	 UCON_RXINT_TYPE_LEVEL	UCON_RXINT_TYPE
+#define	 UCON_RXINT_TYPE_PULSE	0
+#define	 UCON_TOINT		(1 << 7)	/* Rx timeout interrupt */
+#define	 UCON_ERRINT		(1 << 6)	/* receive error interrupt */
+#define	 UCON_LOOP		(1 << 5)	/* loopback */
+#define	 UCON_SBREAK		(1 << 4)	/* send break */
+#define	 UCON_TXMODE_DISABLE	(0 << 2)
+#define	 UCON_TXMODE_INT	(1 << 2)
+#define	 UCON_TXMODE_DMA	(2 << 2)
+#define	 UCON_TXMODE_MASK	(3 << 2)
+#define	 UCON_RXMODE_DISABLE	(0 << 0)
+#define	 UCON_RXMODE_INT	(1 << 0)
+#define	 UCON_RXMODE_DMA	(2 << 0)
+#define	 UCON_RXMODE_MASK	(3 << 0)
+#define  UCON_S5L_RX_TIMEOUT	(0x1 << 9)
+#define  UCON_S5L_RXTHRESH	(0x1 << 12)
+#define  UCON_S5L_TXTHRESH	(0x1 << 13)
+#define	SSCOM_UFCON		0x08		/* FIFO control */
+#define	 UFCON_TXTRIGGER_0	(0 << 6)
+#define	 UFCON_TXTRIGGER_4	(1 << 6)
+#define	 UFCON_TXTRIGGER_8	(2 << 6)
+#define	 UFCON_TXTRIGGER_16	(3 << 6)
+#define	 UFCON_RXTRIGGER_4	(0 << 4)
+#define	 UFCON_RXTRIGGER_8	(1 << 4)
+#define	 UFCON_RXTRIGGER_12	(2 << 4)
+#define	 UFCON_RXTRIGGER_16	(3 << 4)
+#define	 UFCON_TXFIFO_RESET	(1 << 2)
+#define	 UFCON_RXFIFO_RESET	(1 << 1)
+#define	 UFCON_FIFO_ENABLE	(1 << 0)
+#define	SSCOM_UMCON		0x0c		/* MODEM control */
+#define	 UMCON_RTS		(1 << 0)	/* Request to send */
+#define	SSCOM_UTRSTAT		0x10		/* Status register */
+#define	 UTRSTAT_TXSHIFTER_EMPTY	( 1<< 2)
+#define	 UTRSTAT_TXEMPTY	(1 << 1)	/* TX fifo or buffer empty */
+#define	 UTRSTAT_RXREADY	(1 << 0)	/* RX fifo or buffer is not empty */
+#define	 UTRSTAT_S5L_RXTHRESH		(0x1 << 4)
+#define	 UTRSTAT_S5L_TXTHRESH		(0x1 << 5)
+#define	 UTRSTAT_S5L_RX_TIMEOUT		(0x1 << 9)
+#define	SSCOM_UERSTAT		0x14		/* Error status register */
+#define	 UERSTAT_BREAK		(1 << 3)	/* Break signal, not 2410 */
+#define	 UERSTAT_FRAME		(1 << 2)	/* Frame error */
+#define	 UERSTAT_PARITY		(1 << 1)	/* Parity error, not 2410 */
+#define	 UERSTAT_OVERRUN	(1 << 0)	/* Overrun */
+#define	 UERSTAT_ALL_ERRORS \
+	(UERSTAT_OVERRUN|UERSTAT_BREAK|UERSTAT_FRAME|UERSTAT_PARITY)
+#define	SSCOM_UFSTAT		0x18		/* Fifo status register */
+#define	 UFSTAT_RXFULL		(1 <<8)		/* Rx fifo full */
+#define	 UFSTAT_TXCOUNT_SHIFT	4		/* TX FIFO count */
+#define	 UFSTAT_TXCOUNT		(0x0f << UFSTAT_TXCOUNT_SHIFT)
+#define	 UFSTAT_RXCOUNT_SHIFT	0		/* RX FIFO count */
+#define	 UFSTAT_RXCOUNT		(0x0f << UFSTAT_RXCOUNT_SHIFT)
+#define	SSCOM_UMSTAT		0x1c		/* Modem status register */
+#define	 UMSTAT_CTS		(1 << 0)	/* Clear to send */
+#if _BYTE_ORDER == _LITTLE_ENDIAN
+#define	SSCOM_UTXH		0x20		/* Transmit data register */
+#define	SSCOM_URXH		0x24		/* Receive data register */
+#else
+#define	SSCOM_UTXH		0x23		/* Transmit data register */
+#define	SSCOM_URXH		0x27		/* Receive data register */
+#endif
+#define	SSCOM_UBRDIV		0x28		/* baud-reate divisor */
+#define	SSCOM_SIZE		0x2c
diff --git a/sys/conf/files.arm64 b/sys/conf/files.arm64
index 480f1ac78905..74387914043e 100644
--- a/sys/conf/files.arm64
+++ b/sys/conf/files.arm64
@@ -548,6 +548,7 @@ arm/annapurna/alpine/alpine_serdes.c		optional al_serdes fdt		\
 # Apple
 arm64/apple/apple_aic.c				optional soc_apple_t8103 fdt
 arm64/apple/apple_wdog.c			optional soc_apple_t8103 fdt
+arm64/apple/exynos_uart.c			optional soc_apple_t8103 fdt
 
 # Broadcom
 arm64/broadcom/brcmmdio/mdio_mux_iproc.c		optional soc_brcm_ns2 fdt
diff --git a/sys/dev/uart/uart.h b/sys/dev/uart/uart.h
index 9b80f0148dc2..b9401996e655 100644
--- a/sys/dev/uart/uart.h
+++ b/sys/dev/uart/uart.h
@@ -40,6 +40,7 @@
 struct uart_bas {
 	bus_space_tag_t bst;
 	bus_space_handle_t bsh;
+	void	*driver1;
 	u_int	chan;
 	u_int	rclk;
 	u_int	regshft;



Want to link to this message? Use this URL: <https://mail-archive.FreeBSD.org/cgi/mid.cgi?202504020257.5322vuj0078587>