ALT Linux kernel packages development
 help / color / mirror / Atom feed
From: Alexey Sheplyakov <asheplyakov@basealt.ru>
To: devel-kernel@lists.altlinux.org
Cc: "Роман Ставцев" <rst@basealt.ru>, "Игорь Чудов" <nir@basealt.ru>,
	"Евгений Синельников" <sin@basealt.ru>,
	"Дмитрий Терёхин" <jqt4@basealt.ru>
Subject: [d-kernel] [PATCH 11/32] net: stmmac: inital support of Baikal-T1/M SoCs GMAC
Date: Wed, 14 Dec 2022 17:18:58 +0400
Message-ID: <20221214131919.681481-11-asheplyakov@basealt.ru> (raw)
In-Reply-To: <20221214131919.681481-1-asheplyakov@basealt.ru>

The gigabit Ethernet controller available in Baikal-T1 and Baikal-M
SoCs is a Synopsys DesignWare MAC IP core, already supported by
the stmmac driver.

This patch implements some SoC specific operations (DMA reset and
speed fixup) necessary (but in general not sufficient) for
Baikal-T1/M variants.

Note that this driver does NOT cover all the IP blocks and platform
setup peculiarities. It's known to work on some Baikal-T1 boards
(including BFK3.1 reference board) and some Baikal-M based boards:
(TF307 revision D, LGP-16, AQBM1000), however it might or might not
work with other boards.

Changes since v2:

* Clearly explained the status of the driver (initial support),
  mentioned the boards it known to work with.
* Increased timeouts in baikal_dma_reset so they are enough for
  many PHYs, explained why such timeouts are necessary.

Changes since v1:

* The code compiles with -Werror

Signed-off-by: Alexey Sheplyakov <asheplyakov@basealt.ru>
Co-developed-by: Dmitry Dunaev <dmitry.dunaev@baikalelectronics.ru>
Co-developed-by: Vasiliy Vinogradov <v.vinogradov@aq.ru>
Tested-by: Alexey Sheplyakov <asheplyakov@basealt.ru>
X-feature-Baikal-M
---
 drivers/net/ethernet/stmicro/stmmac/Kconfig   |  11 +
 drivers/net/ethernet/stmicro/stmmac/Makefile  |   1 +
 .../ethernet/stmicro/stmmac/dwmac-baikal.c    | 215 ++++++++++++++++++
 .../ethernet/stmicro/stmmac/dwmac1000_core.c  |   1 +
 .../ethernet/stmicro/stmmac/dwmac1000_dma.c   |  46 ++--
 .../ethernet/stmicro/stmmac/dwmac1000_dma.h   |  26 +++
 .../net/ethernet/stmicro/stmmac/dwmac_lib.c   |   8 +
 7 files changed, 290 insertions(+), 18 deletions(-)
 create mode 100644 drivers/net/ethernet/stmicro/stmmac/dwmac-baikal.c
 create mode 100644 drivers/net/ethernet/stmicro/stmmac/dwmac1000_dma.h

diff --git a/drivers/net/ethernet/stmicro/stmmac/Kconfig b/drivers/net/ethernet/stmicro/stmmac/Kconfig
index 31ff35174034..569f000e1fcc 100644
--- a/drivers/net/ethernet/stmicro/stmmac/Kconfig
+++ b/drivers/net/ethernet/stmicro/stmmac/Kconfig
@@ -66,6 +66,17 @@ config DWMAC_ANARION
 
 	  This selects the Anarion SoC glue layer support for the stmmac driver.
 
+config DWMAC_BAIKAL
+	tristate "Baikal Electronics GMAC support"
+	default MIPS_BAIKAL_T1
+	depends on OF && (MIPS || ARM64 || COMPILE_TEST)
+	help
+	  Support for gigabit ethernet controller on Baikal Electronics SoCs.
+
+	  This selects the Baikal Electronics SoCs glue layer support for
+	  the stmmac driver. This driver is used for Baikal-T1 and Baikal-M
+	  SoCs gigabit ethernet controller.
+
 config DWMAC_INGENIC
 	tristate "Ingenic MAC support"
 	default MACH_INGENIC
diff --git a/drivers/net/ethernet/stmicro/stmmac/Makefile b/drivers/net/ethernet/stmicro/stmmac/Makefile
index d4e12e9ace4f..ad138062e199 100644
--- a/drivers/net/ethernet/stmicro/stmmac/Makefile
+++ b/drivers/net/ethernet/stmicro/stmmac/Makefile
@@ -14,6 +14,7 @@ stmmac-$(CONFIG_STMMAC_SELFTESTS) += stmmac_selftests.o
 # Ordering matters. Generic driver must be last.
 obj-$(CONFIG_STMMAC_PLATFORM)	+= stmmac-platform.o
 obj-$(CONFIG_DWMAC_ANARION)	+= dwmac-anarion.o
+obj-$(CONFIG_DWMAC_BAIKAL)	+= dwmac-baikal.o
 obj-$(CONFIG_DWMAC_INGENIC)	+= dwmac-ingenic.o
 obj-$(CONFIG_DWMAC_IPQ806X)	+= dwmac-ipq806x.o
 obj-$(CONFIG_DWMAC_LPC18XX)	+= dwmac-lpc18xx.o
diff --git a/drivers/net/ethernet/stmicro/stmmac/dwmac-baikal.c b/drivers/net/ethernet/stmicro/stmmac/dwmac-baikal.c
new file mode 100644
index 000000000000..9def4ea7fb3b
--- /dev/null
+++ b/drivers/net/ethernet/stmicro/stmmac/dwmac-baikal.c
@@ -0,0 +1,215 @@
+// SPDX-License-Identifier: GPL-2.0-or-later
+/*
+ * Baikal-T1/M SoCs DWMAC glue layer
+ *
+ * Copyright (C) 2015,2016,2021 Baikal Electronics JSC
+ * Copyright (C) 2020-2022 BaseALT Ltd
+ * Authors: Dmitry Dunaev <dmitry.dunaev@baikalelectronics.ru>
+ *          Alexey Sheplyakov <asheplyakov@basealt.ru>
+ */
+
+#include <linux/clk.h>
+#include <linux/iopoll.h>
+#include <linux/module.h>
+#include <linux/of.h>
+#include <linux/platform_device.h>
+
+#include "stmmac.h"
+#include "stmmac_platform.h"
+#include "common.h"
+#include "dwmac_dma.h"
+#include "dwmac1000_dma.h"
+
+#define MAC_GPIO	0x00e0	/* GPIO register */
+#define MAC_GPIO_GPO	BIT(8)	/* Output port */
+
+struct baikal_dwmac {
+	struct device	*dev;
+	struct clk	*tx2_clk;
+};
+
+static int baikal_dwmac_dma_reset(void __iomem *ioaddr)
+{
+	u32 value;
+
+	/* DMA SW reset */
+	value = readl(ioaddr + DMA_BUS_MODE);
+	value |= DMA_BUS_MODE_SFT_RESET;
+	writel(value, ioaddr + DMA_BUS_MODE);
+
+	/* Software DMA reset also resets MAC, so GP_OUT is set to zero.
+	 * Which resets PHY as a side effect (if GP_OUT is connected directly
+	 * to PHY reset).
+	 * TODO: read the PHY reset duration from the device tree.
+	 * Meanwhile use 100 milliseconds which seems to be enough for
+	 * most PHYs
+	 */
+	usleep_range(100000, 120000);
+
+	/* Clear PHY reset */
+	value = readl(ioaddr + MAC_GPIO);
+	value |= MAC_GPIO_GPO;
+	writel(value, ioaddr + MAC_GPIO);
+
+	/* Many PHYs need ~ 100 milliseconds to calm down after PHY reset
+	 * has been cleared. And check for DMA reset below might return
+	 * much earlier (i.e. in ~ 20 milliseconds). As a result reading
+	 * PHY registers (after this function returns) might return garbage.
+	 * Wait a bit to avoid the problem.
+	 * TODO: read PHY post-reset delay from the device tree.
+	 */
+	usleep_range(100000, 150000);
+
+	return readl_poll_timeout(ioaddr + DMA_BUS_MODE, value,
+				  !(value & DMA_BUS_MODE_SFT_RESET),
+				  10000, 1000000);
+}
+
+static const struct stmmac_dma_ops baikal_dwmac_dma_ops = {
+	.reset = baikal_dwmac_dma_reset,
+	.init = dwmac1000_dma_init,
+	.init_rx_chan = dwmac1000_dma_init_rx,
+	.init_tx_chan = dwmac1000_dma_init_tx,
+	.axi = dwmac1000_dma_axi,
+	.dump_regs = dwmac1000_dump_dma_regs,
+	.dma_rx_mode = dwmac1000_dma_operation_mode_rx,
+	.dma_tx_mode = dwmac1000_dma_operation_mode_tx,
+	.enable_dma_transmission = dwmac_enable_dma_transmission,
+	.enable_dma_irq = dwmac_enable_dma_irq,
+	.disable_dma_irq = dwmac_disable_dma_irq,
+	.start_tx = dwmac_dma_start_tx,
+	.stop_tx = dwmac_dma_stop_tx,
+	.start_rx = dwmac_dma_start_rx,
+	.stop_rx = dwmac_dma_stop_rx,
+	.dma_interrupt = dwmac_dma_interrupt,
+	.get_hw_feature = dwmac1000_get_hw_feature,
+	.rx_watchdog = dwmac1000_rx_watchdog
+};
+
+static struct mac_device_info *baikal_dwmac_setup(void *ppriv)
+{
+	struct mac_device_info *mac;
+	struct stmmac_priv *priv = ppriv;
+	int ret;
+	u32 value;
+
+	mac = devm_kzalloc(priv->device, sizeof(*mac), GFP_KERNEL);
+	if (!mac)
+		return NULL;
+
+	/* Clear PHY reset */
+	value = readl(priv->ioaddr + MAC_GPIO);
+	value |= MAC_GPIO_GPO;
+	writel(value, priv->ioaddr + MAC_GPIO);
+
+	mac->dma = &baikal_dwmac_dma_ops;
+	priv->hw = mac;
+	ret = dwmac1000_setup(priv);
+	if (ret) {
+		dev_err(priv->device, "dwmac1000_setup: error %d", ret);
+		return NULL;
+	}
+
+	return mac;
+}
+
+static void baikal_dwmac_fix_mac_speed(void *priv, unsigned int speed)
+{
+	struct baikal_dwmac *dwmac = priv;
+	unsigned long tx2_clk_freq;
+
+	switch (speed) {
+	case SPEED_1000:
+		tx2_clk_freq = 250000000;
+		break;
+	case SPEED_100:
+		tx2_clk_freq = 50000000;
+		break;
+	case SPEED_10:
+		tx2_clk_freq = 5000000;
+		break;
+	default:
+		dev_warn(dwmac->dev, "invalid speed: %u\n", speed);
+		return;
+	}
+	dev_dbg(dwmac->dev, "speed %u, setting TX2 clock frequency to %lu\n",
+		speed, tx2_clk_freq);
+	clk_set_rate(dwmac->tx2_clk, tx2_clk_freq);
+}
+
+static int dwmac_baikal_probe(struct platform_device *pdev)
+{
+	struct plat_stmmacenet_data *plat_dat;
+	struct stmmac_resources stmmac_res;
+	struct baikal_dwmac *dwmac;
+	int ret;
+
+	dwmac = devm_kzalloc(&pdev->dev, sizeof(*dwmac), GFP_KERNEL);
+	if (!dwmac)
+		return -ENOMEM;
+
+	ret = stmmac_get_platform_resources(pdev, &stmmac_res);
+	if (ret)
+		return ret;
+
+	ret = dma_set_mask_and_coherent(&pdev->dev, DMA_BIT_MASK(32));
+	if (ret) {
+		dev_err(&pdev->dev, "no suitable DMA available\n");
+		return ret;
+	}
+
+	plat_dat = stmmac_probe_config_dt(pdev, stmmac_res.mac);
+	if (IS_ERR(plat_dat)) {
+		dev_err(&pdev->dev, "dt configuration failed\n");
+		return PTR_ERR(plat_dat);
+	}
+
+	dwmac->dev = &pdev->dev;
+	dwmac->tx2_clk = devm_clk_get_optional(dwmac->dev, "tx2_clk");
+	if (IS_ERR(dwmac->tx2_clk)) {
+		ret = PTR_ERR(dwmac->tx2_clk);
+		dev_err(&pdev->dev, "couldn't get TX2 clock: %d\n", ret);
+		goto err_remove_config_dt;
+	}
+
+	if (dwmac->tx2_clk)
+		plat_dat->fix_mac_speed = baikal_dwmac_fix_mac_speed;
+	plat_dat->bsp_priv = dwmac;
+	plat_dat->has_gmac = 1;
+	plat_dat->enh_desc = 1;
+	plat_dat->tx_coe = 1;
+	plat_dat->rx_coe = 1;
+	plat_dat->clk_csr = 3;
+	plat_dat->setup = baikal_dwmac_setup;
+
+	ret = stmmac_dvr_probe(&pdev->dev, plat_dat, &stmmac_res);
+	if (ret)
+		goto err_remove_config_dt;
+
+	return 0;
+
+err_remove_config_dt:
+	stmmac_remove_config_dt(pdev, plat_dat);
+	return ret;
+}
+
+static const struct of_device_id dwmac_baikal_match[] = {
+	{ .compatible = "baikal,bm1000-gmac" },
+	{ .compatible = "baikal,dwmac" },
+	{ }
+};
+MODULE_DEVICE_TABLE(of, dwmac_baikal_match);
+
+static struct platform_driver dwmac_baikal_driver = {
+	.probe	= dwmac_baikal_probe,
+	.remove	= stmmac_pltfr_remove,
+	.driver	= {
+		.name = "baikal-dwmac",
+		.pm = &stmmac_pltfr_pm_ops,
+		.of_match_table = of_match_ptr(dwmac_baikal_match)
+	}
+};
+module_platform_driver(dwmac_baikal_driver);
+
+MODULE_DESCRIPTION("Baikal-T1/M DWMAC driver");
+MODULE_LICENSE("GPL");
diff --git a/drivers/net/ethernet/stmicro/stmmac/dwmac1000_core.c b/drivers/net/ethernet/stmicro/stmmac/dwmac1000_core.c
index 0e00dd83d027..d02c20eaba86 100644
--- a/drivers/net/ethernet/stmicro/stmmac/dwmac1000_core.c
+++ b/drivers/net/ethernet/stmicro/stmmac/dwmac1000_core.c
@@ -554,3 +554,4 @@ int dwmac1000_setup(struct stmmac_priv *priv)
 
 	return 0;
 }
+EXPORT_SYMBOL_GPL(dwmac1000_setup);
diff --git a/drivers/net/ethernet/stmicro/stmmac/dwmac1000_dma.c b/drivers/net/ethernet/stmicro/stmmac/dwmac1000_dma.c
index f5581db0ba9b..1782a65cc9af 100644
--- a/drivers/net/ethernet/stmicro/stmmac/dwmac1000_dma.c
+++ b/drivers/net/ethernet/stmicro/stmmac/dwmac1000_dma.c
@@ -15,8 +15,9 @@
 #include <asm/io.h>
 #include "dwmac1000.h"
 #include "dwmac_dma.h"
+#include "dwmac1000_dma.h"
 
-static void dwmac1000_dma_axi(void __iomem *ioaddr, struct stmmac_axi *axi)
+void dwmac1000_dma_axi(void __iomem *ioaddr, struct stmmac_axi *axi)
 {
 	u32 value = readl(ioaddr + DMA_AXI_BUS_MODE);
 	int i;
@@ -69,9 +70,10 @@ static void dwmac1000_dma_axi(void __iomem *ioaddr, struct stmmac_axi *axi)
 
 	writel(value, ioaddr + DMA_AXI_BUS_MODE);
 }
+EXPORT_SYMBOL_GPL(dwmac1000_dma_axi);
 
-static void dwmac1000_dma_init(void __iomem *ioaddr,
-			       struct stmmac_dma_cfg *dma_cfg, int atds)
+void dwmac1000_dma_init(void __iomem *ioaddr,
+			struct stmmac_dma_cfg *dma_cfg, int atds)
 {
 	u32 value = readl(ioaddr + DMA_BUS_MODE);
 	int txpbl = dma_cfg->txpbl ?: dma_cfg->pbl;
@@ -109,22 +111,25 @@ static void dwmac1000_dma_init(void __iomem *ioaddr,
 	/* Mask interrupts by writing to CSR7 */
 	writel(DMA_INTR_DEFAULT_MASK, ioaddr + DMA_INTR_ENA);
 }
+EXPORT_SYMBOL_GPL(dwmac1000_dma_init);
 
-static void dwmac1000_dma_init_rx(void __iomem *ioaddr,
-				  struct stmmac_dma_cfg *dma_cfg,
-				  dma_addr_t dma_rx_phy, u32 chan)
+void dwmac1000_dma_init_rx(void __iomem *ioaddr,
+			   struct stmmac_dma_cfg *dma_cfg,
+			   dma_addr_t dma_rx_phy, u32 chan)
 {
 	/* RX descriptor base address list must be written into DMA CSR3 */
 	writel(lower_32_bits(dma_rx_phy), ioaddr + DMA_RCV_BASE_ADDR);
 }
+EXPORT_SYMBOL_GPL(dwmac1000_dma_init_rx);
 
-static void dwmac1000_dma_init_tx(void __iomem *ioaddr,
-				  struct stmmac_dma_cfg *dma_cfg,
-				  dma_addr_t dma_tx_phy, u32 chan)
+void dwmac1000_dma_init_tx(void __iomem *ioaddr,
+			   struct stmmac_dma_cfg *dma_cfg,
+			   dma_addr_t dma_tx_phy, u32 chan)
 {
 	/* TX descriptor base address list must be written into DMA CSR4 */
 	writel(lower_32_bits(dma_tx_phy), ioaddr + DMA_TX_BASE_ADDR);
 }
+EXPORT_SYMBOL_GPL(dwmac1000_dma_init_tx);
 
 static u32 dwmac1000_configure_fc(u32 csr6, int rxfifosz)
 {
@@ -147,8 +152,8 @@ static u32 dwmac1000_configure_fc(u32 csr6, int rxfifosz)
 	return csr6;
 }
 
-static void dwmac1000_dma_operation_mode_rx(void __iomem *ioaddr, int mode,
-					    u32 channel, int fifosz, u8 qmode)
+void dwmac1000_dma_operation_mode_rx(void __iomem *ioaddr, int mode,
+				     u32 channel, int fifosz, u8 qmode)
 {
 	u32 csr6 = readl(ioaddr + DMA_CONTROL);
 
@@ -174,9 +179,10 @@ static void dwmac1000_dma_operation_mode_rx(void __iomem *ioaddr, int mode,
 
 	writel(csr6, ioaddr + DMA_CONTROL);
 }
+EXPORT_SYMBOL_GPL(dwmac1000_dma_operation_mode_rx);
 
-static void dwmac1000_dma_operation_mode_tx(void __iomem *ioaddr, int mode,
-					    u32 channel, int fifosz, u8 qmode)
+void dwmac1000_dma_operation_mode_tx(void __iomem *ioaddr, int mode,
+				     u32 channel, int fifosz, u8 qmode)
 {
 	u32 csr6 = readl(ioaddr + DMA_CONTROL);
 
@@ -207,8 +213,9 @@ static void dwmac1000_dma_operation_mode_tx(void __iomem *ioaddr, int mode,
 
 	writel(csr6, ioaddr + DMA_CONTROL);
 }
+EXPORT_SYMBOL_GPL(dwmac1000_dma_operation_mode_tx);
 
-static void dwmac1000_dump_dma_regs(void __iomem *ioaddr, u32 *reg_space)
+void dwmac1000_dump_dma_regs(void __iomem *ioaddr, u32 *reg_space)
 {
 	int i;
 
@@ -217,9 +224,10 @@ static void dwmac1000_dump_dma_regs(void __iomem *ioaddr, u32 *reg_space)
 			reg_space[DMA_BUS_MODE / 4 + i] =
 				readl(ioaddr + DMA_BUS_MODE + i * 4);
 }
+EXPORT_SYMBOL_GPL(dwmac1000_dump_dma_regs);
 
-static int dwmac1000_get_hw_feature(void __iomem *ioaddr,
-				    struct dma_features *dma_cap)
+int dwmac1000_get_hw_feature(void __iomem *ioaddr,
+			     struct dma_features *dma_cap)
 {
 	u32 hw_cap = readl(ioaddr + DMA_HW_FEATURE);
 
@@ -262,12 +270,14 @@ static int dwmac1000_get_hw_feature(void __iomem *ioaddr,
 
 	return 0;
 }
+EXPORT_SYMBOL_GPL(dwmac1000_get_hw_feature);
 
-static void dwmac1000_rx_watchdog(void __iomem *ioaddr, u32 riwt,
-				  u32 queue)
+void dwmac1000_rx_watchdog(void __iomem *ioaddr, u32 riwt,
+			   u32 queue)
 {
 	writel(riwt, ioaddr + DMA_RX_WATCHDOG);
 }
+EXPORT_SYMBOL_GPL(dwmac1000_rx_watchdog);
 
 const struct stmmac_dma_ops dwmac1000_dma_ops = {
 	.reset = dwmac_dma_reset,
diff --git a/drivers/net/ethernet/stmicro/stmmac/dwmac1000_dma.h b/drivers/net/ethernet/stmicro/stmmac/dwmac1000_dma.h
new file mode 100644
index 000000000000..b254a0734447
--- /dev/null
+++ b/drivers/net/ethernet/stmicro/stmmac/dwmac1000_dma.h
@@ -0,0 +1,26 @@
+/* SPDX-License-Identifier: GPL-2.0-only */
+
+#ifndef __DWMAC1000_DMA_H__
+#define __DWMAC1000_DMA_H__
+#include "dwmac1000.h"
+
+void dwmac1000_dma_axi(void __iomem *ioaddr, struct stmmac_axi *axi);
+void dwmac1000_dma_init(void __iomem *ioaddr,
+			struct stmmac_dma_cfg *dma_cfg, int atds);
+void dwmac1000_dma_init_rx(void __iomem *ioaddr,
+			   struct stmmac_dma_cfg *dma_cfg,
+			   dma_addr_t dma_rx_phy, u32 chan);
+void dwmac1000_dma_init_tx(void __iomem *ioaddr,
+			   struct stmmac_dma_cfg *dma_cfg,
+			   dma_addr_t dma_tx_phy, u32 chan);
+void dwmac1000_dma_operation_mode_rx(void __iomem *ioaddr, int mode,
+				     u32 channel, int fifosz, u8 qmode);
+void dwmac1000_dma_operation_mode_tx(void __iomem *ioaddr, int mode,
+				     u32 channel, int fifosz, u8 qmode);
+void dwmac1000_dump_dma_regs(void __iomem *ioaddr, u32 *reg_space);
+
+int  dwmac1000_get_hw_feature(void __iomem *ioaddr,
+			      struct dma_features *dma_cap);
+
+void dwmac1000_rx_watchdog(void __iomem *ioaddr, u32 riwt, u32 number_chan);
+#endif /* __DWMAC1000_DMA_H__ */
diff --git a/drivers/net/ethernet/stmicro/stmmac/dwmac_lib.c b/drivers/net/ethernet/stmicro/stmmac/dwmac_lib.c
index 9b6138b11776..d54825484f54 100644
--- a/drivers/net/ethernet/stmicro/stmmac/dwmac_lib.c
+++ b/drivers/net/ethernet/stmicro/stmmac/dwmac_lib.c
@@ -31,6 +31,7 @@ void dwmac_enable_dma_transmission(void __iomem *ioaddr)
 {
 	writel(1, ioaddr + DMA_XMT_POLL_DEMAND);
 }
+EXPORT_SYMBOL_GPL(dwmac_enable_dma_transmission);
 
 void dwmac_enable_dma_irq(void __iomem *ioaddr, u32 chan, bool rx, bool tx)
 {
@@ -43,6 +44,7 @@ void dwmac_enable_dma_irq(void __iomem *ioaddr, u32 chan, bool rx, bool tx)
 
 	writel(value, ioaddr + DMA_INTR_ENA);
 }
+EXPORT_SYMBOL_GPL(dwmac_enable_dma_irq);
 
 void dwmac_disable_dma_irq(void __iomem *ioaddr, u32 chan, bool rx, bool tx)
 {
@@ -55,6 +57,7 @@ void dwmac_disable_dma_irq(void __iomem *ioaddr, u32 chan, bool rx, bool tx)
 
 	writel(value, ioaddr + DMA_INTR_ENA);
 }
+EXPORT_SYMBOL_GPL(dwmac_disable_dma_irq);
 
 void dwmac_dma_start_tx(void __iomem *ioaddr, u32 chan)
 {
@@ -62,6 +65,7 @@ void dwmac_dma_start_tx(void __iomem *ioaddr, u32 chan)
 	value |= DMA_CONTROL_ST;
 	writel(value, ioaddr + DMA_CONTROL);
 }
+EXPORT_SYMBOL_GPL(dwmac_dma_start_tx);
 
 void dwmac_dma_stop_tx(void __iomem *ioaddr, u32 chan)
 {
@@ -69,6 +73,7 @@ void dwmac_dma_stop_tx(void __iomem *ioaddr, u32 chan)
 	value &= ~DMA_CONTROL_ST;
 	writel(value, ioaddr + DMA_CONTROL);
 }
+EXPORT_SYMBOL_GPL(dwmac_dma_stop_tx);
 
 void dwmac_dma_start_rx(void __iomem *ioaddr, u32 chan)
 {
@@ -76,6 +81,7 @@ void dwmac_dma_start_rx(void __iomem *ioaddr, u32 chan)
 	value |= DMA_CONTROL_SR;
 	writel(value, ioaddr + DMA_CONTROL);
 }
+EXPORT_SYMBOL_GPL(dwmac_dma_start_rx);
 
 void dwmac_dma_stop_rx(void __iomem *ioaddr, u32 chan)
 {
@@ -83,6 +89,7 @@ void dwmac_dma_stop_rx(void __iomem *ioaddr, u32 chan)
 	value &= ~DMA_CONTROL_SR;
 	writel(value, ioaddr + DMA_CONTROL);
 }
+EXPORT_SYMBOL_GPL(dwmac_dma_stop_rx);
 
 #ifdef DWMAC_DMA_DEBUG
 static void show_tx_process_state(unsigned int status)
@@ -230,6 +237,7 @@ int dwmac_dma_interrupt(void __iomem *ioaddr,
 
 	return ret;
 }
+EXPORT_SYMBOL_GPL(dwmac_dma_interrupt);
 
 void dwmac_dma_flush_tx_fifo(void __iomem *ioaddr)
 {
-- 
2.33.5



  parent reply	other threads:[~2022-12-14 13:18 UTC|newest]

Thread overview: 35+ messages / expand[flat|nested]  mbox.gz  Atom feed  top
2022-12-14 13:18 [d-kernel] [PATCH 01/32] clk: added Baikal-M clock management unit driver Alexey Sheplyakov
2022-12-14 13:18 ` [d-kernel] [PATCH 02/32] cpufreq-dt: don't load on Baikal-M SoC Alexey Sheplyakov
2022-12-14 13:18 ` [d-kernel] [PATCH 03/32] serial: 8250_dw: verify clock rate in dw8250_set_termios Alexey Sheplyakov
2022-12-14 13:18 ` [d-kernel] [PATCH 04/32] usb: dwc3: of-simple: added compatible string for Baikal-M SoC Alexey Sheplyakov
2022-12-14 13:18 ` [d-kernel] [PATCH 05/32] dw-pcie: refuse to load on Baikal-M with recent firmware Alexey Sheplyakov
2022-12-14 13:18 ` [d-kernel] [PATCH 06/32] arm64: Enable armv8 based Baikal-M SoC support Alexey Sheplyakov
2022-12-14 13:18 ` [d-kernel] [PATCH 07/32] efi-rtc: avoid calling efi.get_time on Baikal-M SoC Alexey Sheplyakov
2022-12-14 13:18 ` [d-kernel] [PATCH 08/32] arm64-stub: fixed secondary cores boot " Alexey Sheplyakov
2022-12-14 13:18 ` [d-kernel] [PATCH 09/32] pm: disable all sleep states on Baikal-M based boards Alexey Sheplyakov
2022-12-14 13:18 ` [d-kernel] [PATCH 10/32] net: fwnode_get_phy_id: consider all compatible strings Alexey Sheplyakov
2022-12-14 13:18 ` Alexey Sheplyakov [this message]
2022-12-14 13:18 ` [d-kernel] [PATCH 12/32] dt-bindings: dwmac: Add bindings for Baikal-T1/M SoCs Alexey Sheplyakov
2022-12-14 13:19 ` [d-kernel] [PATCH 13/32] net: dwmac-baikal: added compatible strings Alexey Sheplyakov
2022-12-14 13:19 ` [d-kernel] [PATCH 14/32] Added TF307/TF306 board management controller driver Alexey Sheplyakov
2022-12-14 13:19 ` [d-kernel] [PATCH 15/32] hwmon: bt1-pvt: access registers via pvt_{readl, writel} helpers Alexey Sheplyakov
2022-12-14 13:19 ` [d-kernel] [PATCH 16/32] hwmon: bt1-pvt: define pvt_readl/pvt_writel for Baikal-M SoC Alexey Sheplyakov
2022-12-14 13:19 ` [d-kernel] [PATCH 17/32] hwmon: bt1-pvt: adjusted probing " Alexey Sheplyakov
2022-12-14 13:19 ` [d-kernel] [PATCH 18/32] hwmon: bt1-pvt: added compatible baikal, pvt Alexey Sheplyakov
2022-12-14 13:19 ` [d-kernel] [PATCH 19/32] drm: new bridge driver - stdp4028 Alexey Sheplyakov
2022-12-14 13:19 ` [d-kernel] [PATCH 20/32] drm: added Baikal-M SoC video display unit driver Alexey Sheplyakov
2022-12-14 13:19 ` [d-kernel] [PATCH 21/32] drm/bridge: dw-hdmi: support ahb audio hw revision 0x2a Alexey Sheplyakov
2022-12-14 13:19 ` [d-kernel] [PATCH 22/32] dt-bindings: dw-hdmi: added ahb-audio-regshift Alexey Sheplyakov
2022-12-14 13:19 ` [d-kernel] [PATCH 23/32] drm/bridge: dw-hdmi: force ahb audio register offset for Baikal-M Alexey Sheplyakov
2022-12-14 13:19 ` [d-kernel] [PATCH 24/32] drm/panfrost: forcibly set dma-coherent on Baikal-M Alexey Sheplyakov
2022-12-14 13:19 ` [d-kernel] [PATCH 25/32] drm/panfrost: disable devfreq " Alexey Sheplyakov
2022-12-14 13:19 ` [d-kernel] [PATCH 26/32] ALSA: hda: Baikal-M support Alexey Sheplyakov
2022-12-14 13:19 ` [d-kernel] [PATCH 27/32] PCI: pcie-baikal: driver for Baikal-M with new firmware Alexey Sheplyakov
2022-12-14 13:19 ` [d-kernel] [PATCH 28/32] (BROKEN) dwc-i2s: support Baikal-M SoC Alexey Sheplyakov
2022-12-14 13:19 ` [d-kernel] [PATCH 29/32] input: added TF307 serio PS/2 emulator driver Alexey Sheplyakov
2022-12-14 13:19 ` [d-kernel] [PATCH 30/32] input: new driver - serdev-serio Alexey Sheplyakov
2022-12-14 13:19 ` [d-kernel] [PATCH 31/32] phy: realtek: leds configuration for RTL8211f Alexey Sheplyakov
2022-12-14 15:06 ` [d-kernel] [PATCH 01/32] clk: added Baikal-M clock management unit driver Vitaly Chikunov
2022-12-16  9:54   ` Alexey Sheplyakov
2022-12-16 12:34     ` Vitaly Chikunov
2022-12-16 12:40       ` Vitaly Chikunov

Reply instructions:

You may reply publicly to this message via plain-text email
using any one of the following methods:

* Save the following mbox file, import it into your mail client,
  and reply-to-all from there: mbox

  Avoid top-posting and favor interleaved quoting:
  https://en.wikipedia.org/wiki/Posting_style#Interleaved_style

* Reply using the --to, --cc, and --in-reply-to
  switches of git-send-email(1):

  git send-email \
    --in-reply-to=20221214131919.681481-11-asheplyakov@basealt.ru \
    --to=asheplyakov@basealt.ru \
    --cc=devel-kernel@lists.altlinux.org \
    --cc=jqt4@basealt.ru \
    --cc=nir@basealt.ru \
    --cc=rst@basealt.ru \
    --cc=sin@basealt.ru \
    /path/to/YOUR_REPLY

  https://kernel.org/pub/software/scm/git/docs/git-send-email.html

* If your mail client supports setting the In-Reply-To header
  via mailto: links, try the mailto: link

ALT Linux kernel packages development

This inbox may be cloned and mirrored by anyone:

	git clone --mirror http://lore.altlinux.org/devel-kernel/0 devel-kernel/git/0.git

	# If you have public-inbox 1.1+ installed, you may
	# initialize and index your mirror using the following commands:
	public-inbox-init -V2 devel-kernel devel-kernel/ http://lore.altlinux.org/devel-kernel \
		devel-kernel@altlinux.org devel-kernel@altlinux.ru devel-kernel@altlinux.com
	public-inbox-index devel-kernel

Example config snippet for mirrors.
Newsgroup available over NNTP:
	nntp://lore.altlinux.org/org.altlinux.lists.devel-kernel


AGPL code for this site: git clone https://public-inbox.org/public-inbox.git