linux-arm-kernel.lists.infradead.org archive mirror
 help / color / mirror / Atom feed
* [PATCH net-next v3 0/3] net: stmmac: Add PCI driver support for BCM8958x
@ 2024-08-02  3:18 jitendra.vegiraju
  2024-08-02  3:18 ` [PATCH net-next v3 1/3] net: stmmac: Add basic dwxgmac4 support to stmmac core jitendra.vegiraju
                   ` (3 more replies)
  0 siblings, 4 replies; 30+ messages in thread
From: jitendra.vegiraju @ 2024-08-02  3:18 UTC (permalink / raw)
  To: netdev
  Cc: alexandre.torgue, joabreu, davem, edumazet, kuba, pabeni,
	mcoquelin.stm32, jitendra.vegiraju, bcm-kernel-feedback-list,
	richardcochran, ast, daniel, hawk, john.fastabend, linux-kernel,
	linux-stm32, linux-arm-kernel, bpf, andrew, linux, horms,
	florian.fainelli

From: Jitendra Vegiraju <jitendra.vegiraju@broadcom.com>

This patchset adds basic PCI ethernet device driver support for Broadcom
BCM8958x Automotive Ethernet switch SoC devices.

This SoC device has PCIe ethernet MAC attached to an integrated ethernet
switch using XGMII interface. The PCIe ethernet controller is presented to
the Linux host as PCI network device.

The following block diagram gives an overview of the application.
             +=================================+
             |       Host CPU/Linux            |
             +=================================+
                        || PCIe
                        ||
        +==========================================+
        |           +--------------+               |
        |           | PCIE Endpoint|               |
        |           | Ethernet     |               |
        |           | Controller   |               |
        |           |   DMA        |               |
        |           +--------------+               |
        |           |   MAC        |   BCM8958X    |
        |           +--------------+   SoC         |
        |               || XGMII                   |
        |               ||                         |
        |           +--------------+               |
        |           | Ethernet     |               |
        |           | switch       |               |
        |           +--------------+               |
        |             || || || ||                  |
        +==========================================+
                      || || || || More external interfaces

The MAC block on BCM8958x is based on Synopsis XGMAC 4.00a core. This
driver uses common dwxgmac2 code where applicable.
Driver functionality specific to this MAC is implemented in dwxgmac4.c.
Management of integrated ethernet switch on this SoC is not handled by
the PCIe interface.
This SoC device has PCIe ethernet MAC directly attached to an integrated
ethernet switch using XGMII interface.

v2->v3:
   Addressed v2 comments from Andrew, Jakub, Russel and Simon.
   Based on suggestion by Russel and Andrew, added software node to create
   phylink in fixed-link mode.
   Moved dwxgmac4 specific functions to new files dwxgmac4.c and dwxgmac4.h
   in stmmac core module.
   Reorganized the code to use the existing glue logic support for xgmac in
   hwif.c and override ops functions for dwxgmac4 specific functions.
   The patch is split into three parts.
     Patch#1 Adds dma_ops for dwxgmac4 in stmmac core
     Patch#2 Hooks in the hardware interface handling for dwxgmac4
     Patch#3 Adds PCI driver for BCM8958x device

v1->v2:
   Minor fixes to address coding style issues.
   Sent v2 too soon by mistake, without waiting for review comments.
   Received feedback on this version.
   https://lore.kernel.org/netdev/20240511015924.41457-1-jitendra.vegiraju@broadcom.com/

v1:  
   https://lore.kernel.org/netdev/20240510000331.154486-1-jitendra.vegiraju@broadcom.com/

Jitendra Vegiraju (3):
  Add basic dwxgmac4 support to stmmac core
  Integrate dwxgmac4 into stmmac hwif handling
  Add PCI driver support for BCM8958x

 MAINTAINERS                                   |   8 +
 drivers/net/ethernet/stmicro/stmmac/Kconfig   |  11 +
 drivers/net/ethernet/stmicro/stmmac/Makefile  |   3 +-
 drivers/net/ethernet/stmicro/stmmac/common.h  |   4 +
 .../net/ethernet/stmicro/stmmac/dwmac-brcm.c  | 517 ++++++++++++++++++
 .../ethernet/stmicro/stmmac/dwxgmac2_dma.c    |  31 ++
 .../net/ethernet/stmicro/stmmac/dwxgmac4.c    | 142 +++++
 .../net/ethernet/stmicro/stmmac/dwxgmac4.h    |  84 +++
 drivers/net/ethernet/stmicro/stmmac/hwif.c    |  26 +-
 drivers/net/ethernet/stmicro/stmmac/hwif.h    |   1 +
 10 files changed, 825 insertions(+), 2 deletions(-)
 create mode 100644 drivers/net/ethernet/stmicro/stmmac/dwmac-brcm.c
 create mode 100644 drivers/net/ethernet/stmicro/stmmac/dwxgmac4.c
 create mode 100644 drivers/net/ethernet/stmicro/stmmac/dwxgmac4.h

-- 
2.34.1



^ permalink raw reply	[flat|nested] 30+ messages in thread

* [PATCH net-next v3 1/3] net: stmmac: Add basic dwxgmac4 support to stmmac core
  2024-08-02  3:18 [PATCH net-next v3 0/3] net: stmmac: Add PCI driver support for BCM8958x jitendra.vegiraju
@ 2024-08-02  3:18 ` jitendra.vegiraju
  2024-08-02  8:21   ` Russell King (Oracle)
                     ` (2 more replies)
  2024-08-02  3:18 ` [PATCH net-next v3 2/3] net: stmmac: Integrate dwxgmac4 into stmmac hwif handling jitendra.vegiraju
                   ` (2 subsequent siblings)
  3 siblings, 3 replies; 30+ messages in thread
From: jitendra.vegiraju @ 2024-08-02  3:18 UTC (permalink / raw)
  To: netdev
  Cc: alexandre.torgue, joabreu, davem, edumazet, kuba, pabeni,
	mcoquelin.stm32, jitendra.vegiraju, bcm-kernel-feedback-list,
	richardcochran, ast, daniel, hawk, john.fastabend, linux-kernel,
	linux-stm32, linux-arm-kernel, bpf, andrew, linux, horms,
	florian.fainelli

From: Jitendra Vegiraju <jitendra.vegiraju@broadcom.com>

Adds support for DWC_xgmac version 4.00a in stmmac core module.
This version adds enhancements to DMA architecture for virtualization
scalability. This is realized by decoupling physical DMA channels (PDMA)
from Virtual DMA channels (VDMA). The  VDMAs are software abastractions
that map to PDMAs for frame transmission and reception.

The virtualization enhancements are currently not being used and hence
a fixed mapping of VDMA to PDMA is configured in the init functions.
Because of the new init functions, a new instance of struct stmmac_dma_ops
dwxgmac400_dma_ops is added.
Most of the other dma operation functions in existing dwxgamc2_dma.c file
can be reused.

Signed-off-by: Jitendra Vegiraju <jitendra.vegiraju@broadcom.com>
---
 drivers/net/ethernet/stmicro/stmmac/Makefile  |   2 +-
 .../ethernet/stmicro/stmmac/dwxgmac2_dma.c    |  31 ++++
 .../net/ethernet/stmicro/stmmac/dwxgmac4.c    | 142 ++++++++++++++++++
 .../net/ethernet/stmicro/stmmac/dwxgmac4.h    |  84 +++++++++++
 4 files changed, 258 insertions(+), 1 deletion(-)
 create mode 100644 drivers/net/ethernet/stmicro/stmmac/dwxgmac4.c
 create mode 100644 drivers/net/ethernet/stmicro/stmmac/dwxgmac4.h

diff --git a/drivers/net/ethernet/stmicro/stmmac/Makefile b/drivers/net/ethernet/stmicro/stmmac/Makefile
index c2f0e91f6bf8..2f637612513d 100644
--- a/drivers/net/ethernet/stmicro/stmmac/Makefile
+++ b/drivers/net/ethernet/stmicro/stmmac/Makefile
@@ -6,7 +6,7 @@ stmmac-objs:= stmmac_main.o stmmac_ethtool.o stmmac_mdio.o ring_mode.o	\
 	      mmc_core.o stmmac_hwtstamp.o stmmac_ptp.o dwmac4_descs.o	\
 	      dwmac4_dma.o dwmac4_lib.o dwmac4_core.o dwmac5.o hwif.o \
 	      stmmac_tc.o dwxgmac2_core.o dwxgmac2_dma.o dwxgmac2_descs.o \
-	      stmmac_xdp.o stmmac_est.o \
+	      stmmac_xdp.o stmmac_est.o dwxgmac4.o \
 	      $(stmmac-y)
 
 stmmac-$(CONFIG_STMMAC_SELFTESTS) += stmmac_selftests.o
diff --git a/drivers/net/ethernet/stmicro/stmmac/dwxgmac2_dma.c b/drivers/net/ethernet/stmicro/stmmac/dwxgmac2_dma.c
index dd2ab6185c40..c15f5247aaa8 100644
--- a/drivers/net/ethernet/stmicro/stmmac/dwxgmac2_dma.c
+++ b/drivers/net/ethernet/stmicro/stmmac/dwxgmac2_dma.c
@@ -7,6 +7,7 @@
 #include <linux/iopoll.h>
 #include "stmmac.h"
 #include "dwxgmac2.h"
+#include "dwxgmac4.h"
 
 static int dwxgmac2_dma_reset(void __iomem *ioaddr)
 {
@@ -641,3 +642,33 @@ const struct stmmac_dma_ops dwxgmac210_dma_ops = {
 	.enable_sph = dwxgmac2_enable_sph,
 	.enable_tbs = dwxgmac2_enable_tbs,
 };
+
+const struct stmmac_dma_ops dwxgmac400_dma_ops = {
+	.reset = dwxgmac2_dma_reset,
+	.init = dwxgmac4_dma_init,
+	.init_chan = dwxgmac2_dma_init_chan,
+	.init_rx_chan = dwxgmac4_dma_init_rx_chan,
+	.init_tx_chan = dwxgmac4_dma_init_tx_chan,
+	.axi = dwxgmac2_dma_axi,
+	.dump_regs = dwxgmac2_dma_dump_regs,
+	.dma_rx_mode = dwxgmac2_dma_rx_mode,
+	.dma_tx_mode = dwxgmac2_dma_tx_mode,
+	.enable_dma_irq = dwxgmac2_enable_dma_irq,
+	.disable_dma_irq = dwxgmac2_disable_dma_irq,
+	.start_tx = dwxgmac2_dma_start_tx,
+	.stop_tx = dwxgmac2_dma_stop_tx,
+	.start_rx = dwxgmac2_dma_start_rx,
+	.stop_rx = dwxgmac2_dma_stop_rx,
+	.dma_interrupt = dwxgmac2_dma_interrupt,
+	.get_hw_feature = dwxgmac2_get_hw_feature,
+	.rx_watchdog = dwxgmac2_rx_watchdog,
+	.set_rx_ring_len = dwxgmac2_set_rx_ring_len,
+	.set_tx_ring_len = dwxgmac2_set_tx_ring_len,
+	.set_rx_tail_ptr = dwxgmac2_set_rx_tail_ptr,
+	.set_tx_tail_ptr = dwxgmac2_set_tx_tail_ptr,
+	.enable_tso = dwxgmac2_enable_tso,
+	.qmode = dwxgmac2_qmode,
+	.set_bfsize = dwxgmac2_set_bfsize,
+	.enable_sph = dwxgmac2_enable_sph,
+	.enable_tbs = dwxgmac2_enable_tbs,
+};
diff --git a/drivers/net/ethernet/stmicro/stmmac/dwxgmac4.c b/drivers/net/ethernet/stmicro/stmmac/dwxgmac4.c
new file mode 100644
index 000000000000..9c8748122dc6
--- /dev/null
+++ b/drivers/net/ethernet/stmicro/stmmac/dwxgmac4.c
@@ -0,0 +1,142 @@
+// SPDX-License-Identifier: GPL-2.0-only
+/*
+ * Copyright (c) 2024 Broadcom Corporation
+ */
+#include "dwxgmac2.h"
+#include "dwxgmac4.h"
+
+static int rd_dma_ch_ind(void __iomem *ioaddr, u8 mode, u32 channel)
+{
+	u32 reg_val = 0;
+	u32 val = 0;
+
+	reg_val |= mode << XGMAC4_MSEL_SHIFT & XGMAC4_MODE_SELECT;
+	reg_val |= channel << XGMAC4_AOFF_SHIFT & XGMAC4_ADDR_OFFSET;
+	reg_val |= XGMAC4_CMD_TYPE | XGMAC4_OB;
+	writel(reg_val, ioaddr + XGMAC4_DMA_CH_IND_CONTROL);
+	val = readl(ioaddr + XGMAC4_DMA_CH_IND_DATA);
+	return val;
+}
+
+static void wr_dma_ch_ind(void __iomem *ioaddr, u8 mode, u32 channel, u32 val)
+{
+	u32 reg_val = 0;
+
+	writel(val, ioaddr + XGMAC4_DMA_CH_IND_DATA);
+	reg_val |= mode << XGMAC4_MSEL_SHIFT & XGMAC4_MODE_SELECT;
+	reg_val |= channel << XGMAC4_AOFF_SHIFT & XGMAC4_ADDR_OFFSET;
+	reg_val |= XGMAC_OB;
+	writel(reg_val, ioaddr + XGMAC4_DMA_CH_IND_CONTROL);
+}
+
+static void xgmac4_tp2tc_map(void __iomem *ioaddr, u8 pdma_ch, u32 tc_num)
+{
+	u32 val = 0;
+
+	val = rd_dma_ch_ind(ioaddr, MODE_TXEXTCFG, pdma_ch);
+	val &= ~XGMAC4_TP2TCMP;
+	val |= tc_num << XGMAC4_TP2TCMP_SHIFT & XGMAC4_TP2TCMP;
+	wr_dma_ch_ind(ioaddr, MODE_TXEXTCFG, pdma_ch, val);
+}
+
+static void xgmac4_rp2tc_map(void __iomem *ioaddr, u8 pdma_ch, u32 tc_num)
+{
+	u32 val = 0;
+
+	val = rd_dma_ch_ind(ioaddr, MODE_RXEXTCFG, pdma_ch);
+	val &= ~XGMAC4_RP2TCMP;
+	val |= tc_num << XGMAC4_RP2TCMP_SHIFT & XGMAC4_RP2TCMP;
+	wr_dma_ch_ind(ioaddr, MODE_RXEXTCFG, pdma_ch, val);
+}
+
+void dwxgmac4_dma_init(void __iomem *ioaddr,
+		       struct stmmac_dma_cfg *dma_cfg, int atds)
+{
+	u32 value;
+	u32 i;
+
+	value = readl(ioaddr + XGMAC_DMA_SYSBUS_MODE);
+
+	if (dma_cfg->aal)
+		value |= XGMAC_AAL;
+
+	if (dma_cfg->eame)
+		value |= XGMAC_EAME;
+
+	writel(value, ioaddr + XGMAC_DMA_SYSBUS_MODE);
+
+	for (i = 0; i < VDMA_TOTAL_CH_COUNT; i++) {
+		value = rd_dma_ch_ind(ioaddr, MODE_TXDESCCTRL, i);
+		value &= ~XGMAC4_TXDCSZ;
+		value |= 0x3;
+		value &= ~XGMAC4_TDPS;
+		value |= (3 << XGMAC4_TDPS_SHIFT) & XGMAC4_TDPS;
+		wr_dma_ch_ind(ioaddr, MODE_TXDESCCTRL, i, value);
+
+		value = rd_dma_ch_ind(ioaddr, MODE_RXDESCCTRL, i);
+		value &= ~XGMAC4_RXDCSZ;
+		value |= 0x3;
+		value &= ~XGMAC4_RDPS;
+		value |= (3 << XGMAC4_RDPS_SHIFT) & XGMAC4_RDPS;
+		wr_dma_ch_ind(ioaddr, MODE_RXDESCCTRL, i, value);
+	}
+
+	for (i = 0; i < PDMA_TX_CH_COUNT; i++) {
+		value = rd_dma_ch_ind(ioaddr, MODE_TXEXTCFG, i);
+		value &= ~(XGMAC4_TXPBL | XGMAC4_TPBLX8_MODE);
+		if (dma_cfg->pblx8)
+			value |= XGMAC4_TPBLX8_MODE;
+		value |= (dma_cfg->pbl << XGMAC4_TXPBL_SHIFT) & XGMAC4_TXPBL;
+		wr_dma_ch_ind(ioaddr, MODE_TXEXTCFG, i, value);
+		xgmac4_tp2tc_map(ioaddr, i, i);
+	}
+
+	for (i = 0; i < PDMA_RX_CH_COUNT; i++) {
+		value = rd_dma_ch_ind(ioaddr, MODE_RXEXTCFG, i);
+		value &= ~(XGMAC4_RXPBL | XGMAC4_RPBLX8_MODE);
+		if (dma_cfg->pblx8)
+			value |= XGMAC4_RPBLX8_MODE;
+		value |= (dma_cfg->pbl << XGMAC4_RXPBL_SHIFT) & XGMAC4_RXPBL;
+		wr_dma_ch_ind(ioaddr, MODE_RXEXTCFG, i, value);
+		if (i < PDMA_MAX_TC_COUNT)
+			xgmac4_rp2tc_map(ioaddr, i, i);
+		else
+			xgmac4_rp2tc_map(ioaddr, i, PDMA_MAX_TC_COUNT - 1);
+	}
+}
+
+void dwxgmac4_dma_init_tx_chan(struct stmmac_priv *priv,
+			       void __iomem *ioaddr,
+			       struct stmmac_dma_cfg *dma_cfg,
+			       dma_addr_t dma_addr, u32 chan)
+{
+	u32 value;
+
+	value = readl(ioaddr + XGMAC_DMA_CH_TX_CONTROL(chan));
+	value &= ~XGMAC4_TVDMA2TCMP;
+	value |= (chan << XGMAC4_TVDMA2TCMP_SHIFT) & XGMAC4_TVDMA2TCMP;
+	writel(value, ioaddr + XGMAC_DMA_CH_TX_CONTROL(chan));
+
+	writel(upper_32_bits(dma_addr),
+	       ioaddr + XGMAC_DMA_CH_TxDESC_HADDR(chan));
+	writel(lower_32_bits(dma_addr),
+	       ioaddr + XGMAC_DMA_CH_TxDESC_LADDR(chan));
+}
+
+void dwxgmac4_dma_init_rx_chan(struct stmmac_priv *priv,
+			       void __iomem *ioaddr,
+			       struct stmmac_dma_cfg *dma_cfg,
+			       dma_addr_t dma_addr, u32 chan)
+{
+	u32 value;
+
+	value = readl(ioaddr + XGMAC_DMA_CH_RX_CONTROL(chan));
+	value &= ~XGMAC4_RVDMA2TCMP;
+	value |= (chan << XGMAC4_RVDMA2TCMP_SHIFT) & XGMAC4_RVDMA2TCMP;
+	writel(value, ioaddr + XGMAC_DMA_CH_RX_CONTROL(chan));
+
+	writel(upper_32_bits(dma_addr),
+	       ioaddr + XGMAC_DMA_CH_RxDESC_HADDR(chan));
+	writel(lower_32_bits(dma_addr),
+	       ioaddr + XGMAC_DMA_CH_RxDESC_LADDR(chan));
+}
diff --git a/drivers/net/ethernet/stmicro/stmmac/dwxgmac4.h b/drivers/net/ethernet/stmicro/stmmac/dwxgmac4.h
new file mode 100644
index 000000000000..0ce1856b0b34
--- /dev/null
+++ b/drivers/net/ethernet/stmicro/stmmac/dwxgmac4.h
@@ -0,0 +1,84 @@
+/* SPDX-License-Identifier: GPL-2.0-only */
+/* Copyright (c) 2024 Broadcom Corporation
+ * XGMAC4 definitions.
+ */
+#ifndef __STMMAC_DWXGMAC4_H__
+#define __STMMAC_DWXGMAC4_H__
+
+/* DMA Indirect Registers*/
+#define XGMAC4_DMA_CH_IND_CONTROL	0X00003080
+#define XGMAC4_MODE_SELECT		GENMASK(27, 24)
+#define XGMAC4_MSEL_SHIFT		24
+enum dma_ch_ind_modes {
+	MODE_TXEXTCFG	 = 0x0,	  /* Tx Extended Config */
+	MODE_RXEXTCFG	 = 0x1,	  /* Rx Extended Config */
+	MODE_TXDBGSTS	 = 0x2,	  /* Tx Debug Status */
+	MODE_RXDBGSTS	 = 0x3,	  /* Rx Debug Status */
+	MODE_TXDESCCTRL	 = 0x4,	  /* Tx Descriptor control */
+	MODE_RXDESCCTRL	 = 0x5,	  /* Rx Descriptor control */
+};
+
+#define XGMAC4_ADDR_OFFSET		GENMASK(14, 8)
+#define XGMAC4_AOFF_SHIFT		8
+#define XGMAC4_AUTO_INCR		GENMASK(5, 4)
+#define XGMAC4_AUTO_SHIFT		4
+#define XGMAC4_CMD_TYPE			BIT(1)
+#define XGMAC4_OB			BIT(0)
+#define XGMAC4_DMA_CH_IND_DATA		0X00003084
+
+/* TX Config definitions */
+#define XGMAC4_TXPBL			GENMASK(29, 24)
+#define XGMAC4_TXPBL_SHIFT		24
+#define XGMAC4_TPBLX8_MODE		BIT(19)
+#define XGMAC4_TP2TCMP			GENMASK(18, 16)
+#define XGMAC4_TP2TCMP_SHIFT		16
+#define XGMAC4_ORRQ			GENMASK(13, 8)
+/* RX Config definitions */
+#define XGMAC4_RXPBL			GENMASK(29, 24)
+#define XGMAC4_RXPBL_SHIFT		24
+#define XGMAC4_RPBLX8_MODE		BIT(19)
+#define XGMAC4_RP2TCMP			GENMASK(18, 16)
+#define XGMAC4_RP2TCMP_SHIFT		16
+#define XGMAC4_OWRQ			GENMASK(13, 8)
+/* Tx Descriptor control */
+#define XGMAC4_TXDCSZ			GENMASK(2, 0)
+#define XGMAC4_TDPS			GENMASK(5, 3)
+#define XGMAC4_TDPS_SHIFT		3
+/* Rx Descriptor control */
+#define XGMAC4_RXDCSZ			GENMASK(2, 0)
+#define XGMAC4_RDPS			GENMASK(5, 3)
+#define XGMAC4_RDPS_SHIFT		3
+
+/* DWCXG_DMA_CH(#i) Registers*/
+#define XGMAC4_DSL			GENMASK(20, 18)
+#define XGMAC4_MSS			GENMASK(13, 0)
+#define XGMAC4_TFSEL			GENMASK(30, 29)
+#define XGMAC4_TQOS			GENMASK(27, 24)
+#define XGMAC4_IPBL			BIT(15)
+#define XGMAC4_TVDMA2TCMP		GENMASK(6, 4)
+#define XGMAC4_TVDMA2TCMP_SHIFT		4
+#define XGMAC4_RPF			BIT(31)
+#define XGMAC4_RVDMA2TCMP		GENMASK(30, 28)
+#define XGMAC4_RVDMA2TCMP_SHIFT		28
+#define XGMAC4_RQOS			GENMASK(27, 24)
+
+/* PDMA Channel count */
+#define PDMA_TX_CH_COUNT		8
+#define PDMA_RX_CH_COUNT		10
+#define PDMA_MAX_TC_COUNT		8
+
+/* VDMA channel count */
+#define VDMA_TOTAL_CH_COUNT		32
+
+void dwxgmac4_dma_init(void __iomem *ioaddr,
+		       struct stmmac_dma_cfg *dma_cfg, int atds);
+
+void dwxgmac4_dma_init_tx_chan(struct stmmac_priv *priv,
+			       void __iomem *ioaddr,
+			       struct stmmac_dma_cfg *dma_cfg,
+			       dma_addr_t dma_addr, u32 chan);
+void dwxgmac4_dma_init_rx_chan(struct stmmac_priv *priv,
+			       void __iomem *ioaddr,
+			       struct stmmac_dma_cfg *dma_cfg,
+			       dma_addr_t dma_addr, u32 chan);
+#endif /* __STMMAC_DWXGMAC4_H__ */
-- 
2.34.1



^ permalink raw reply related	[flat|nested] 30+ messages in thread

* [PATCH net-next v3 2/3] net: stmmac: Integrate dwxgmac4 into stmmac hwif handling
  2024-08-02  3:18 [PATCH net-next v3 0/3] net: stmmac: Add PCI driver support for BCM8958x jitendra.vegiraju
  2024-08-02  3:18 ` [PATCH net-next v3 1/3] net: stmmac: Add basic dwxgmac4 support to stmmac core jitendra.vegiraju
@ 2024-08-02  3:18 ` jitendra.vegiraju
  2024-08-02  8:23   ` Russell King (Oracle)
                     ` (2 more replies)
  2024-08-02  3:18 ` [PATCH net-next v3 3/3] net: stmmac: Add PCI driver support for BCM8958x jitendra.vegiraju
  2024-08-02 10:02 ` [PATCH net-next v3 0/3] " Serge Semin
  3 siblings, 3 replies; 30+ messages in thread
From: jitendra.vegiraju @ 2024-08-02  3:18 UTC (permalink / raw)
  To: netdev
  Cc: alexandre.torgue, joabreu, davem, edumazet, kuba, pabeni,
	mcoquelin.stm32, jitendra.vegiraju, bcm-kernel-feedback-list,
	richardcochran, ast, daniel, hawk, john.fastabend, linux-kernel,
	linux-stm32, linux-arm-kernel, bpf, andrew, linux, horms,
	florian.fainelli

From: Jitendra Vegiraju <jitendra.vegiraju@broadcom.com>

Integrate dwxgmac4 support into stmmac hardware interface handling.
A dwxgmac4 is an xgmac device and hence it inherits properties from
existing stmmac_hw table entry.
The quirks handling facility is used to update dma_ops field to
point to dwxgmac400_dma_ops when the user version field matches.

Signed-off-by: Jitendra Vegiraju <jitendra.vegiraju@broadcom.com>
---
 drivers/net/ethernet/stmicro/stmmac/common.h |  4 +++
 drivers/net/ethernet/stmicro/stmmac/hwif.c   | 26 +++++++++++++++++++-
 drivers/net/ethernet/stmicro/stmmac/hwif.h   |  1 +
 3 files changed, 30 insertions(+), 1 deletion(-)

diff --git a/drivers/net/ethernet/stmicro/stmmac/common.h b/drivers/net/ethernet/stmicro/stmmac/common.h
index cd36ff4da68c..9bf278e11704 100644
--- a/drivers/net/ethernet/stmicro/stmmac/common.h
+++ b/drivers/net/ethernet/stmicro/stmmac/common.h
@@ -37,11 +37,15 @@
 #define DWXGMAC_CORE_2_10	0x21
 #define DWXGMAC_CORE_2_20	0x22
 #define DWXLGMAC_CORE_2_00	0x20
+#define DWXGMAC_CORE_4_00	0x40
 
 /* Device ID */
 #define DWXGMAC_ID		0x76
 #define DWXLGMAC_ID		0x27
 
+/* User Version */
+#define DWXGMAC_USER_VER_X22	0x22
+
 #define STMMAC_CHAN0	0	/* Always supported and default for all chips */
 
 /* TX and RX Descriptor Length, these need to be power of two.
diff --git a/drivers/net/ethernet/stmicro/stmmac/hwif.c b/drivers/net/ethernet/stmicro/stmmac/hwif.c
index 29367105df54..713cb5aa2c3e 100644
--- a/drivers/net/ethernet/stmicro/stmmac/hwif.c
+++ b/drivers/net/ethernet/stmicro/stmmac/hwif.c
@@ -36,6 +36,18 @@ static u32 stmmac_get_dev_id(struct stmmac_priv *priv, u32 id_reg)
 	return (reg & GENMASK(15, 8)) >> 8;
 }
 
+static u32 stmmac_get_user_version(struct stmmac_priv *priv, u32 id_reg)
+{
+	u32 reg = readl(priv->ioaddr + id_reg);
+
+	if (!reg) {
+		dev_info(priv->device, "User Version not available\n");
+		return 0x0;
+	}
+
+	return (reg & GENMASK(23, 16)) >> 16;
+}
+
 static void stmmac_dwmac_mode_quirk(struct stmmac_priv *priv)
 {
 	struct mac_device_info *mac = priv->hw;
@@ -82,6 +94,18 @@ static int stmmac_dwmac4_quirks(struct stmmac_priv *priv)
 	return 0;
 }
 
+static int stmmac_dwxgmac_quirks(struct stmmac_priv *priv)
+{
+	struct mac_device_info *mac = priv->hw;
+	u32 user_ver;
+
+	user_ver = stmmac_get_user_version(priv, GMAC4_VERSION);
+	if (priv->synopsys_id == DWXGMAC_CORE_4_00 &&
+	    user_ver == DWXGMAC_USER_VER_X22)
+		mac->dma = &dwxgmac400_dma_ops;
+	return 0;
+}
+
 static int stmmac_dwxlgmac_quirks(struct stmmac_priv *priv)
 {
 	priv->hw->xlgmac = true;
@@ -256,7 +280,7 @@ static const struct stmmac_hwif_entry {
 		.mmc = &dwxgmac_mmc_ops,
 		.est = &dwmac510_est_ops,
 		.setup = dwxgmac2_setup,
-		.quirks = NULL,
+		.quirks = stmmac_dwxgmac_quirks,
 	}, {
 		.gmac = false,
 		.gmac4 = false,
diff --git a/drivers/net/ethernet/stmicro/stmmac/hwif.h b/drivers/net/ethernet/stmicro/stmmac/hwif.h
index e53c32362774..6213c496385c 100644
--- a/drivers/net/ethernet/stmicro/stmmac/hwif.h
+++ b/drivers/net/ethernet/stmicro/stmmac/hwif.h
@@ -683,6 +683,7 @@ extern const struct stmmac_desc_ops dwxgmac210_desc_ops;
 extern const struct stmmac_mmc_ops dwmac_mmc_ops;
 extern const struct stmmac_mmc_ops dwxgmac_mmc_ops;
 extern const struct stmmac_est_ops dwmac510_est_ops;
+extern const struct stmmac_dma_ops dwxgmac400_dma_ops;
 
 #define GMAC_VERSION		0x00000020	/* GMAC CORE Version */
 #define GMAC4_VERSION		0x00000110	/* GMAC4+ CORE Version */
-- 
2.34.1



^ permalink raw reply related	[flat|nested] 30+ messages in thread

* [PATCH net-next v3 3/3] net: stmmac: Add PCI driver support for BCM8958x
  2024-08-02  3:18 [PATCH net-next v3 0/3] net: stmmac: Add PCI driver support for BCM8958x jitendra.vegiraju
  2024-08-02  3:18 ` [PATCH net-next v3 1/3] net: stmmac: Add basic dwxgmac4 support to stmmac core jitendra.vegiraju
  2024-08-02  3:18 ` [PATCH net-next v3 2/3] net: stmmac: Integrate dwxgmac4 into stmmac hwif handling jitendra.vegiraju
@ 2024-08-02  3:18 ` jitendra.vegiraju
  2024-08-02 23:08   ` Andrew Lunn
  2024-08-02 10:02 ` [PATCH net-next v3 0/3] " Serge Semin
  3 siblings, 1 reply; 30+ messages in thread
From: jitendra.vegiraju @ 2024-08-02  3:18 UTC (permalink / raw)
  To: netdev
  Cc: alexandre.torgue, joabreu, davem, edumazet, kuba, pabeni,
	mcoquelin.stm32, jitendra.vegiraju, bcm-kernel-feedback-list,
	richardcochran, ast, daniel, hawk, john.fastabend, linux-kernel,
	linux-stm32, linux-arm-kernel, bpf, andrew, linux, horms,
	florian.fainelli

From: Jitendra Vegiraju <jitendra.vegiraju@broadcom.com>

Add PCI ethernet driver support for Broadcom BCM8958x SoC devices used
in automotive applications.

This SoC device has PCIe ethernet MAC attached to an integrated ethernet
switch using XGMII interface. The PCIe ethernet controller is presented to
the Linux host as PCI network device.

The following block diagram gives an overview of the application.
             +=================================+
             |       Host CPU/Linux            |
             +=================================+
                        || PCIe
                        ||
        +==========================================+
        |           +--------------+               |
        |           | PCIE Endpoint|               |
        |           | Ethernet     |               |
        |           | Controller   |               |
        |           |   DMA        |               |
        |           +--------------+               |
        |           |   MAC        |   BCM8958X    |
        |           +--------------+   SoC         |
        |               || XGMII                   |
        |               ||                         |
        |           +--------------+               |
        |           | Ethernet     |               |
        |           | switch       |               |
        |           +--------------+               |
        |             || || || ||                  |
        +==========================================+
                      || || || || More external interfaces

The MAC block on BCM8958x is based on Synopsis XGMAC 4.00a core. This
driver uses common dwxgmac2 code where applicable.
Driver functionality specific to this MAC is implemented in dwxgmac4.c.

Management of integrated ethernet switch on this SoC is not handled by
the PCIe interface.

This SoC device has PCIe ethernet MAC directly attached to an integrated
ethernet switch using XGMII interface. Since device tree support is not
available on this platform, a software node is created to enable
fixed-link support using phylink driver.

Signed-off-by: Jitendra Vegiraju <jitendra.vegiraju@broadcom.com>
---
 MAINTAINERS                                   |   8 +
 drivers/net/ethernet/stmicro/stmmac/Kconfig   |  11 +
 drivers/net/ethernet/stmicro/stmmac/Makefile  |   1 +
 .../net/ethernet/stmicro/stmmac/dwmac-brcm.c  | 517 ++++++++++++++++++
 4 files changed, 537 insertions(+)
 create mode 100644 drivers/net/ethernet/stmicro/stmmac/dwmac-brcm.c

diff --git a/MAINTAINERS b/MAINTAINERS
index 8766f3e5e87e..cce3d2e9eb22 100644
--- a/MAINTAINERS
+++ b/MAINTAINERS
@@ -4350,6 +4350,14 @@ N:	brcmstb
 N:	bcm7038
 N:	bcm7120
 
+BROADCOM BCM8958X ETHERNET DRIVER
+M:	Jitendra Vegiraju <jitendra.vegiraju@broadcom.com>
+R:	Broadcom internal kernel review list <bcm-kernel-feedback-list@broadcom.com>
+L:	netdev@vger.kernel.org
+S:	Maintained
+F:	drivers/net/ethernet/stmicro/stmmac/dwmac-brcm.c
+F:	drivers/net/ethernet/stmicro/stmmac/dwxgmac4.*
+
 BROADCOM BCMBCA ARM ARCHITECTURE
 M:	William Zhang <william.zhang@broadcom.com>
 M:	Anand Gore <anand.gore@broadcom.com>
diff --git a/drivers/net/ethernet/stmicro/stmmac/Kconfig b/drivers/net/ethernet/stmicro/stmmac/Kconfig
index 05cc07b8f48c..47c9db123b03 100644
--- a/drivers/net/ethernet/stmicro/stmmac/Kconfig
+++ b/drivers/net/ethernet/stmicro/stmmac/Kconfig
@@ -298,6 +298,17 @@ config DWMAC_LOONGSON
 	  This selects the LOONGSON PCI bus support for the stmmac driver,
 	  Support for ethernet controller on Loongson-2K1000 SoC and LS7A1000 bridge.
 
+config DWMAC_BRCM
+	tristate "Broadcom XGMAC support"
+	depends on STMMAC_ETH && PCI
+	depends on COMMON_CLK
+	help
+	  Support for ethernet controllers on Broadcom BCM8958x SoCs.
+
+	  This selects Broadcom XGMAC specific PCI bus support for the
+	  stmmac driver. This driver provides the glue layer on top of the
+	  stmmac driver required for the Broadcom BCM8958x SoC devices.
+
 config STMMAC_PCI
 	tristate "STMMAC PCI bus support"
 	depends on STMMAC_ETH && PCI
diff --git a/drivers/net/ethernet/stmicro/stmmac/Makefile b/drivers/net/ethernet/stmicro/stmmac/Makefile
index 2f637612513d..90c135ea25eb 100644
--- a/drivers/net/ethernet/stmicro/stmmac/Makefile
+++ b/drivers/net/ethernet/stmicro/stmmac/Makefile
@@ -41,4 +41,5 @@ dwmac-altr-socfpga-objs := dwmac-socfpga.o
 obj-$(CONFIG_STMMAC_PCI)	+= stmmac-pci.o
 obj-$(CONFIG_DWMAC_INTEL)	+= dwmac-intel.o
 obj-$(CONFIG_DWMAC_LOONGSON)	+= dwmac-loongson.o
+obj-$(CONFIG_DWMAC_BRCM)	+= dwmac-brcm.o
 stmmac-pci-objs:= stmmac_pci.o
diff --git a/drivers/net/ethernet/stmicro/stmmac/dwmac-brcm.c b/drivers/net/ethernet/stmicro/stmmac/dwmac-brcm.c
new file mode 100644
index 000000000000..a7b0031506b8
--- /dev/null
+++ b/drivers/net/ethernet/stmicro/stmmac/dwmac-brcm.c
@@ -0,0 +1,517 @@
+// SPDX-License-Identifier: GPL-2.0-only
+/* Copyright (c) 2024 Broadcom Corporation
+ *
+ * PCI driver for ethernet interface of BCM8958X automotive switch chip.
+ *
+ * High level block diagram of the device.
+ *              +=================================+
+ *              |       Host CPU/Linux            |
+ *              +=================================+
+ *                         || PCIe
+ *                         ||
+ *         +==========================================+
+ *         |           +--------------+               |
+ *         |           | PCIE Endpoint|               |
+ *         |           | Ethernet     |               |
+ *         |           | Controller   |               |
+ *         |           |   DMA        |               |
+ *         |           +--------------+               |
+ *         |           |   MAC        |   BCM8958X    |
+ *         |           +--------------+   SoC         |
+ *         |               || XGMII                   |
+ *         |               ||                         |
+ *         |           +--------------+               |
+ *         |           | Ethernet     |               |
+ *         |           | switch       |               |
+ *         |           +--------------+               |
+ *         |             || || || ||                  |
+ *         +==========================================+
+ *                       || || || || More external interfaces
+ *
+ * This SoC device has PCIe ethernet MAC directly attached to an integrated
+ * ethernet switch using XGMII interface. Since devicetree support is not
+ * available on this platform, a software node is created to enable
+ * fixed-link support using phylink driver.
+ */
+
+#include <linux/clk-provider.h>
+#include <linux/dmi.h>
+#include <linux/pci.h>
+#include <linux/phy.h>
+
+#include "stmmac.h"
+#include "dwxgmac2.h"
+
+#define PCI_DEVICE_ID_BROADCOM_BCM8958X		0xa00d
+#define BRCM_MAX_MTU				1500
+#define READ_POLL_DELAY_US			100
+#define READ_POLL_TIMEOUT_US			10000
+#define DWMAC_125MHZ				125000000
+#define DWMAC_250MHZ				250000000
+#define BRCM_XGMAC_NUM_VLAN_FILTERS		32
+
+/* TX and RX Queue counts */
+#define BRCM_TX_Q_COUNT				4
+#define BRCM_RX_Q_COUNT				4
+
+#define BRCM_XGMAC_DMA_TX_SIZE			1024
+#define BRCM_XGMAC_DMA_RX_SIZE			1024
+#define BRCM_XGMAC_BAR0_MASK			BIT(0)
+
+#define BRCM_XGMAC_IOMEM_MISC_REG_OFFSET	0x0
+#define BRCM_XGMAC_IOMEM_MBOX_REG_OFFSET	0x1000
+#define BRCM_XGMAC_IOMEM_CFG_REG_OFFSET		0x3000
+
+#define XGMAC_MMC_CTRL_RCHM_DISABLE		BIT(31)
+#define XGMAC_PCIE_CFG_MSIX_ADDR_MATCH_LOW	0x940
+#define XGMAC_PCIE_CFG_MSIX_ADDR_MATCH_LO_VALUE	0x00000001
+#define XGMAC_PCIE_CFG_MSIX_ADDR_MATCH_HIGH	0x944
+#define XGMAC_PCIE_CFG_MSIX_ADDR_MATCH_HI_VALUE	0x88000000
+
+#define XGMAC_PCIE_MISC_MII_CTRL			0x4
+#define XGMAC_PCIE_MISC_MII_CTRL_VALUE			0x7
+#define XGMAC_PCIE_MISC_PCIESS_CTRL			0x8
+#define XGMAC_PCIE_MISC_PCIESS_CTRL_VALUE		0x200
+#define XGMAC_PCIE_MISC_MSIX_ADDR_MATCH_LO		0x90
+#define XGMAC_PCIE_MISC_MSIX_ADDR_MATCH_LO_VALUE	0x00000001
+#define XGMAC_PCIE_MISC_MSIX_ADDR_MATCH_HI		0x94
+#define XGMAC_PCIE_MISC_MSIX_ADDR_MATCH_HI_VALUE	0x88000000
+#define XGMAC_PCIE_MISC_MSIX_VECTOR_MAP_EP2HOST0	0x700
+#define XGMAC_PCIE_MISC_MSIX_VECTOR_MAP_EP2HOST0_VALUE	1
+#define XGMAC_PCIE_MISC_MSIX_VECTOR_MAP_EP2HOST1	0x704
+#define XGMAC_PCIE_MISC_MSIX_VECTOR_MAP_EP2HOST1_VALUE	1
+#define XGMAC_PCIE_MISC_MSIX_VECTOR_MAP_EP2HOST_DBELL	0x728
+#define XGMAC_PCIE_MISC_MSIX_VECTOR_MAP_EP2HOST_DBELL_VALUE	1
+#define XGMAC_PCIE_MISC_MSIX_VECTOR_MAP_SBD_ALL		0x740
+#define XGMAC_PCIE_MISC_MSIX_VECTOR_MAP_SBD_ALL_VALUE	0
+
+#define XGMAC_PCIE_MISC_FUNC_RESOURCES_PF0	0x804
+
+/* MSIX Vector map register starting offsets */
+#define XGMAC_PCIE_MISC_MSIX_VECTOR_MAP_RX0_PF0	0x840
+#define XGMAC_PCIE_MISC_MSIX_VECTOR_MAP_TX0_PF0	0x890
+#define BRCM_MAX_DMA_CHANNEL_PAIRS		4
+
+#define BRCM_XGMAC_MSI_MAC_VECTOR		0
+#define BRCM_XGMAC_MSI_RX_VECTOR_START		9
+#define BRCM_XGMAC_MSI_TX_VECTOR_START		10
+
+static const struct software_node phy_handle_node = {
+	.name = "bcm8958x-fixed-link",
+};
+
+static const struct property_entry fixed_link_properties[] = {
+	PROPERTY_ENTRY_U32("speed", 10000),
+	PROPERTY_ENTRY_BOOL("full-duplex"),
+	PROPERTY_ENTRY_BOOL("pause"),
+	{ }
+};
+
+static const struct software_node fixed_link_node = {
+	.name = "fixed-link",
+	.parent = &phy_handle_node,
+	.properties = fixed_link_properties,
+};
+
+static const struct software_node *fixed_link_node_group[] = {
+	&phy_handle_node,
+	&fixed_link_node,
+	NULL
+};
+
+static int num_instances;
+
+struct brcm_priv_data {
+	void __iomem *mbox_regs;    /* MBOX  Registers*/
+	void __iomem *misc_regs;    /* MISC  Registers*/
+	void __iomem *xgmac_regs;   /* XGMAC Registers*/
+};
+
+struct dwxgmac_brcm_pci_info {
+	int (*setup)(struct pci_dev *pdev, struct plat_stmmacenet_data *plat);
+};
+
+static void misc_iowrite(struct brcm_priv_data *brcm_priv,
+			 u32 reg, u32 val)
+{
+	iowrite32(val, brcm_priv->misc_regs + reg);
+}
+
+static struct mac_device_info *dwxgmac_brcm_setup(void *ppriv)
+{
+	struct stmmac_priv *priv = ppriv;
+	struct mac_device_info *mac;
+
+	mac = devm_kzalloc(priv->device, sizeof(*mac), GFP_KERNEL);
+	if (!mac)
+		return NULL;
+
+	priv->synopsys_id = DWXGMAC_CORE_4_00;
+	priv->dma_conf.dma_tx_size = BRCM_XGMAC_DMA_TX_SIZE;
+	priv->dma_conf.dma_rx_size = BRCM_XGMAC_DMA_RX_SIZE;
+	priv->plat->rss_en = 1;
+	mac->pcsr = priv->ioaddr;
+	priv->dev->priv_flags |= IFF_UNICAST_FLT;
+	mac->multicast_filter_bins = priv->plat->multicast_filter_bins;
+	mac->unicast_filter_entries = priv->plat->unicast_filter_entries;
+	mac->mcast_bits_log2 = 0;
+
+	if (mac->multicast_filter_bins)
+		mac->mcast_bits_log2 = ilog2(mac->multicast_filter_bins);
+
+	mac->link.duplex = DUPLEX_FULL;
+	mac->link.caps = (MAC_ASYM_PAUSE | MAC_SYM_PAUSE | MAC_10000FD);
+	mac->link.xgmii.speed10000 = XGMAC_CONFIG_SS_10000;
+	mac->link.speed_mask = XGMAC_CONFIG_SS_MASK;
+
+	return mac;
+}
+
+static void dwxgmac_brcm_common_default_data(struct plat_stmmacenet_data *plat)
+{
+	int i;
+
+	plat->has_xgmac = 1;
+	plat->force_sf_dma_mode = 1;
+	plat->mac_port_sel_speed = SPEED_10000;
+	plat->clk_ptp_rate = DWMAC_125MHZ;
+	plat->clk_ref_rate = DWMAC_250MHZ;
+	plat->setup = dwxgmac_brcm_setup;
+	plat->tx_coe = 1;
+	plat->rx_coe = 1;
+	plat->max_speed = SPEED_10000;
+
+	/* Set default value for multicast hash bins */
+	plat->multicast_filter_bins = HASH_TABLE_SIZE;
+
+	/* Set default value for unicast filter entries */
+	plat->unicast_filter_entries = 1;
+
+	/* Set the maxmtu to device's default */
+	plat->maxmtu = BRCM_MAX_MTU;
+
+	/* Set default number of RX and TX queues to use */
+	plat->tx_queues_to_use = BRCM_TX_Q_COUNT;
+	plat->rx_queues_to_use = BRCM_RX_Q_COUNT;
+
+	plat->tx_sched_algorithm = MTL_TX_ALGORITHM_SP;
+	for (i = 0; i < plat->tx_queues_to_use; i++) {
+		plat->tx_queues_cfg[i].use_prio = false;
+		plat->tx_queues_cfg[i].prio = 0;
+		plat->tx_queues_cfg[i].mode_to_use = MTL_QUEUE_AVB;
+	}
+
+	plat->rx_sched_algorithm = MTL_RX_ALGORITHM_SP;
+	for (i = 0; i < plat->rx_queues_to_use; i++) {
+		plat->rx_queues_cfg[i].use_prio = false;
+		plat->rx_queues_cfg[i].mode_to_use = MTL_QUEUE_AVB;
+		plat->rx_queues_cfg[i].pkt_route = 0x0;
+		plat->rx_queues_cfg[i].chan = i;
+	}
+}
+
+static int dwxgmac_brcm_default_data(struct pci_dev *pdev,
+				     struct plat_stmmacenet_data *plat)
+{
+	/* Set common default data first */
+	dwxgmac_brcm_common_default_data(plat);
+
+	plat->bus_id = 0;
+	plat->phy_addr = 0;
+	plat->phy_interface = PHY_INTERFACE_MODE_USXGMII;
+
+	plat->dma_cfg->pbl = 32;
+	plat->dma_cfg->pblx8 = 0;
+	plat->dma_cfg->aal = 0;
+	plat->dma_cfg->eame = 1;
+
+	plat->axi->axi_wr_osr_lmt = 31;
+	plat->axi->axi_rd_osr_lmt = 31;
+	plat->axi->axi_fb = 0;
+	plat->axi->axi_blen[0] = 4;
+	plat->axi->axi_blen[1] = 8;
+	plat->axi->axi_blen[2] = 16;
+	plat->axi->axi_blen[3] = 32;
+	plat->axi->axi_blen[4] = 64;
+	plat->axi->axi_blen[5] = 128;
+	plat->axi->axi_blen[6] = 256;
+
+	plat->msi_mac_vec = BRCM_XGMAC_MSI_MAC_VECTOR;
+	plat->msi_rx_base_vec = BRCM_XGMAC_MSI_RX_VECTOR_START;
+	plat->msi_tx_base_vec = BRCM_XGMAC_MSI_TX_VECTOR_START;
+
+	return 0;
+}
+
+static struct dwxgmac_brcm_pci_info dwxgmac_brcm_pci_info = {
+	.setup = dwxgmac_brcm_default_data,
+};
+
+static int brcm_config_multi_msi(struct pci_dev *pdev,
+				 struct plat_stmmacenet_data *plat,
+				 struct stmmac_resources *res)
+{
+	int ret;
+	int i;
+
+	if (plat->msi_rx_base_vec >= STMMAC_MSI_VEC_MAX ||
+	    plat->msi_tx_base_vec >= STMMAC_MSI_VEC_MAX) {
+		dev_err(&pdev->dev, "%s: Invalid RX & TX vector defined\n",
+			__func__);
+		return -EINVAL;
+	}
+
+	ret = pci_alloc_irq_vectors(pdev, 2, STMMAC_MSI_VEC_MAX,
+				    PCI_IRQ_MSI | PCI_IRQ_MSIX);
+	if (ret < 0) {
+		dev_err(&pdev->dev, "%s: multi MSI enablement failed\n",
+			__func__);
+		return ret;
+	}
+
+	/* For RX MSI */
+	for (i = 0; i < plat->rx_queues_to_use; i++)
+		res->rx_irq[i] = pci_irq_vector(pdev,
+						plat->msi_rx_base_vec + i * 2);
+
+	/* For TX MSI */
+	for (i = 0; i < plat->tx_queues_to_use; i++)
+		res->tx_irq[i] = pci_irq_vector(pdev,
+						plat->msi_tx_base_vec + i * 2);
+
+	if (plat->msi_mac_vec < STMMAC_MSI_VEC_MAX)
+		res->irq = pci_irq_vector(pdev, plat->msi_mac_vec);
+
+	plat->flags |= STMMAC_FLAG_MULTI_MSI_EN;
+	plat->flags |= STMMAC_FLAG_TSO_EN;
+
+	return 0;
+}
+
+static int dwxgmac_brcm_pci_probe(struct pci_dev *pdev,
+				  const struct pci_device_id *id)
+{
+	struct dwxgmac_brcm_pci_info *info =
+		(struct dwxgmac_brcm_pci_info *)id->driver_data;
+	struct plat_stmmacenet_data *plat;
+	struct brcm_priv_data *brcm_priv;
+	struct stmmac_resources res;
+	int rx_offset;
+	int tx_offset;
+	int vector;
+	int ret;
+
+	brcm_priv = devm_kzalloc(&pdev->dev, sizeof(*brcm_priv), GFP_KERNEL);
+	if (!brcm_priv)
+		return -ENOMEM;
+
+	plat = devm_kzalloc(&pdev->dev, sizeof(*plat), GFP_KERNEL);
+	if (!plat)
+		return -ENOMEM;
+
+	plat->dma_cfg = devm_kzalloc(&pdev->dev, sizeof(*plat->dma_cfg),
+				     GFP_KERNEL);
+	if (!plat->dma_cfg)
+		return -ENOMEM;
+
+	plat->axi = devm_kzalloc(&pdev->dev, sizeof(*plat->axi), GFP_KERNEL);
+	if (!plat->axi)
+		return -ENOMEM;
+
+	/* This device is directly attached to the switch chip internal to the
+	 * SoC using XGMII interface. Since no MDIO is present, register
+	 * fixed-link software_node to create phylink.
+	 */
+	if (num_instances == 0) {
+		ret = software_node_register_node_group(fixed_link_node_group);
+		if (ret) {
+			dev_err(&pdev->dev,
+				"%s: failed to register software node\n",
+				__func__);
+			return ret;
+		}
+	}
+	num_instances++;
+	plat->port_node = software_node_fwnode(&phy_handle_node);
+
+	/* Disable D3COLD as our device does not support it */
+	pci_d3cold_disable(pdev);
+
+	/* Enable PCI device */
+	ret = pcim_enable_device(pdev);
+	if (ret) {
+		dev_err(&pdev->dev, "%s: ERROR: failed to enable device\n",
+			__func__);
+		return ret;
+	}
+
+	/* Get the base address of device */
+	ret = pcim_iomap_regions(pdev, BRCM_XGMAC_BAR0_MASK, pci_name(pdev));
+	if (ret)
+		goto err_disable_device;
+	pci_set_master(pdev);
+
+	memset(&res, 0, sizeof(res));
+	res.addr = pcim_iomap_table(pdev)[0];
+	/* MISC Regs */
+	brcm_priv->misc_regs = res.addr + BRCM_XGMAC_IOMEM_MISC_REG_OFFSET;
+	/* MBOX Regs */
+	brcm_priv->mbox_regs = res.addr + BRCM_XGMAC_IOMEM_MBOX_REG_OFFSET;
+	/* XGMAC config Regs */
+	res.addr += BRCM_XGMAC_IOMEM_CFG_REG_OFFSET;
+	brcm_priv->xgmac_regs = res.addr;
+
+	plat->bsp_priv = brcm_priv;
+
+	/* Initialize all MSI vectors to invalid so that it can be set
+	 * according to platform data settings below.
+	 * Note: MSI vector takes value from 0 up to 31 (STMMAC_MSI_VEC_MAX)
+	 */
+	plat->msi_mac_vec = STMMAC_MSI_VEC_MAX;
+	plat->msi_wol_vec = STMMAC_MSI_VEC_MAX;
+	plat->msi_lpi_vec = STMMAC_MSI_VEC_MAX;
+	plat->msi_sfty_ce_vec = STMMAC_MSI_VEC_MAX;
+	plat->msi_sfty_ue_vec = STMMAC_MSI_VEC_MAX;
+	plat->msi_rx_base_vec = STMMAC_MSI_VEC_MAX;
+	plat->msi_tx_base_vec = STMMAC_MSI_VEC_MAX;
+
+	ret = info->setup(pdev, plat);
+	if (ret)
+		goto err_disable_device;
+
+	pci_write_config_dword(pdev, XGMAC_PCIE_CFG_MSIX_ADDR_MATCH_LOW,
+			       XGMAC_PCIE_CFG_MSIX_ADDR_MATCH_LO_VALUE);
+	pci_write_config_dword(pdev, XGMAC_PCIE_CFG_MSIX_ADDR_MATCH_HIGH,
+			       XGMAC_PCIE_CFG_MSIX_ADDR_MATCH_HI_VALUE);
+
+	misc_iowrite(brcm_priv, XGMAC_PCIE_MISC_MSIX_ADDR_MATCH_LO,
+		     XGMAC_PCIE_MISC_MSIX_ADDR_MATCH_LO_VALUE);
+	misc_iowrite(brcm_priv, XGMAC_PCIE_MISC_MSIX_ADDR_MATCH_HI,
+		     XGMAC_PCIE_MISC_MSIX_ADDR_MATCH_HI_VALUE);
+
+	/* SBD Interrupt */
+	misc_iowrite(brcm_priv, XGMAC_PCIE_MISC_MSIX_VECTOR_MAP_SBD_ALL,
+		     XGMAC_PCIE_MISC_MSIX_VECTOR_MAP_SBD_ALL_VALUE);
+	/* EP_DOORBELL Interrupt */
+	misc_iowrite(brcm_priv, XGMAC_PCIE_MISC_MSIX_VECTOR_MAP_EP2HOST_DBELL,
+		     XGMAC_PCIE_MISC_MSIX_VECTOR_MAP_EP2HOST_DBELL_VALUE);
+	/* EP_H0 Interrupt */
+	misc_iowrite(brcm_priv, XGMAC_PCIE_MISC_MSIX_VECTOR_MAP_EP2HOST0,
+		     XGMAC_PCIE_MISC_MSIX_VECTOR_MAP_EP2HOST0_VALUE);
+	/* EP_H1 Interrupt */
+	misc_iowrite(brcm_priv, XGMAC_PCIE_MISC_MSIX_VECTOR_MAP_EP2HOST1,
+		     XGMAC_PCIE_MISC_MSIX_VECTOR_MAP_EP2HOST1_VALUE);
+
+	rx_offset = XGMAC_PCIE_MISC_MSIX_VECTOR_MAP_RX0_PF0;
+	tx_offset = XGMAC_PCIE_MISC_MSIX_VECTOR_MAP_TX0_PF0;
+	vector = BRCM_XGMAC_MSI_RX_VECTOR_START;
+	for (int i = 0; i < BRCM_MAX_DMA_CHANNEL_PAIRS; i++) {
+		/* RX Interrupt */
+		misc_iowrite(brcm_priv, rx_offset, vector++);
+		/* TX Interrupt */
+		misc_iowrite(brcm_priv, tx_offset, vector++);
+		rx_offset += 4;
+		tx_offset += 4;
+	}
+
+	/* Enable Switch Link */
+	misc_iowrite(brcm_priv, XGMAC_PCIE_MISC_MII_CTRL,
+		     XGMAC_PCIE_MISC_MII_CTRL_VALUE);
+	/* Enable MSI-X */
+	misc_iowrite(brcm_priv, XGMAC_PCIE_MISC_PCIESS_CTRL,
+		     XGMAC_PCIE_MISC_PCIESS_CTRL_VALUE);
+
+	ret = brcm_config_multi_msi(pdev, plat, &res);
+	if (ret) {
+		dev_err(&pdev->dev,
+			"%s: ERROR: failed to enable IRQ\n", __func__);
+		goto err_disable_msi;
+	}
+
+	ret = stmmac_dvr_probe(&pdev->dev, plat, &res);
+	if (ret)
+		goto err_disable_msi;
+
+	return ret;
+
+err_disable_msi:
+	pci_free_irq_vectors(pdev);
+err_disable_device:
+	pci_disable_device(pdev);
+
+	return ret;
+}
+
+static void dwxgmac_brcm_pci_remove(struct pci_dev *pdev)
+{
+	stmmac_dvr_remove(&pdev->dev);
+	pci_free_irq_vectors(pdev);
+	pcim_iounmap_regions(pdev, BRCM_XGMAC_BAR0_MASK);
+	pci_clear_master(pdev);
+
+	if (num_instances == 1)
+		software_node_unregister_node_group(fixed_link_node_group);
+	num_instances--;
+}
+
+static int __maybe_unused dwxgmac_brcm_pci_suspend(struct device *dev)
+{
+	struct pci_dev *pdev = to_pci_dev(dev);
+	int ret;
+
+	ret = stmmac_suspend(dev);
+	if (ret)
+		return ret;
+
+	ret = pci_save_state(pdev);
+	if (ret)
+		return ret;
+
+	pci_disable_device(pdev);
+	pci_wake_from_d3(pdev, true);
+
+	return 0;
+}
+
+static int __maybe_unused dwxgmac_brcm_pci_resume(struct device *dev)
+{
+	struct pci_dev *pdev = to_pci_dev(dev);
+	int ret;
+
+	pci_restore_state(pdev);
+	pci_set_power_state(pdev, PCI_D0);
+
+	ret = pci_enable_device(pdev);
+	if (ret)
+		return ret;
+
+	pci_set_master(pdev);
+
+	return stmmac_resume(dev);
+}
+
+static SIMPLE_DEV_PM_OPS(dwxgmac_brcm_pm_ops,
+			 dwxgmac_brcm_pci_suspend,
+			 dwxgmac_brcm_pci_resume);
+
+static const struct pci_device_id dwxgmac_brcm_id_table[] = {
+	{ PCI_DEVICE_DATA(BROADCOM, BCM8958X, &dwxgmac_brcm_pci_info) },
+	{}
+};
+
+MODULE_DEVICE_TABLE(pci, dwxgmac_brcm_id_table);
+
+static struct pci_driver dwxgmac_brcm_pci_driver = {
+	.name = "brcm-bcm8958x",
+	.id_table = dwxgmac_brcm_id_table,
+	.probe	= dwxgmac_brcm_pci_probe,
+	.remove = dwxgmac_brcm_pci_remove,
+	.driver = {
+		.pm = &dwxgmac_brcm_pm_ops,
+	},
+};
+
+module_pci_driver(dwxgmac_brcm_pci_driver);
+
+MODULE_DESCRIPTION("Broadcom 10G Automotive Ethernet PCIe driver");
+MODULE_LICENSE("GPL");
-- 
2.34.1



^ permalink raw reply related	[flat|nested] 30+ messages in thread

* Re: [PATCH net-next v3 1/3] net: stmmac: Add basic dwxgmac4 support to stmmac core
  2024-08-02  3:18 ` [PATCH net-next v3 1/3] net: stmmac: Add basic dwxgmac4 support to stmmac core jitendra.vegiraju
@ 2024-08-02  8:21   ` Russell King (Oracle)
  2024-08-02 21:43     ` Jitendra Vegiraju
  2024-08-02 14:38   ` Simon Horman
  2024-08-06 21:56   ` Serge Semin
  2 siblings, 1 reply; 30+ messages in thread
From: Russell King (Oracle) @ 2024-08-02  8:21 UTC (permalink / raw)
  To: jitendra.vegiraju
  Cc: netdev, alexandre.torgue, joabreu, davem, edumazet, kuba, pabeni,
	mcoquelin.stm32, bcm-kernel-feedback-list, richardcochran, ast,
	daniel, hawk, john.fastabend, linux-kernel, linux-stm32,
	linux-arm-kernel, bpf, andrew, horms, florian.fainelli

On Thu, Aug 01, 2024 at 08:18:20PM -0700, jitendra.vegiraju@broadcom.com wrote:
> +static int rd_dma_ch_ind(void __iomem *ioaddr, u8 mode, u32 channel)
> +{
> +	u32 reg_val = 0;
> +	u32 val = 0;

val is unnecessary.

> +
> +	reg_val |= mode << XGMAC4_MSEL_SHIFT & XGMAC4_MODE_SELECT;

Consider using:

	reg_val |= FIELD_PREP(XGMAC4_MODE_SELECT, mode);

and similarly everywhere else you use a shift and mask. With this, you
can remove _all_ _SHIFT definitions in your header file.

> +	reg_val |= channel << XGMAC4_AOFF_SHIFT & XGMAC4_ADDR_OFFSET;
> +	reg_val |= XGMAC4_CMD_TYPE | XGMAC4_OB;
> +	writel(reg_val, ioaddr + XGMAC4_DMA_CH_IND_CONTROL);
> +	val = readl(ioaddr + XGMAC4_DMA_CH_IND_DATA);
> +	return val;

	return readl(ioaddr + XGMAC4_DMA_CH_IND_DATA);

...

> +void dwxgmac4_dma_init(void __iomem *ioaddr,
> +		       struct stmmac_dma_cfg *dma_cfg, int atds)
> +{
> +	u32 value;
> +	u32 i;
> +
> +	value = readl(ioaddr + XGMAC_DMA_SYSBUS_MODE);
> +
> +	if (dma_cfg->aal)
> +		value |= XGMAC_AAL;
> +
> +	if (dma_cfg->eame)
> +		value |= XGMAC_EAME;

What if dma_cfg doesn't have these bits set? Is it possible they will be
set in the register?

Thanks.

-- 
RMK's Patch system: https://www.armlinux.org.uk/developer/patches/
FTTP is here! 80Mbps down 10Mbps up. Decent connectivity at last!


^ permalink raw reply	[flat|nested] 30+ messages in thread

* Re: [PATCH net-next v3 2/3] net: stmmac: Integrate dwxgmac4 into stmmac hwif handling
  2024-08-02  3:18 ` [PATCH net-next v3 2/3] net: stmmac: Integrate dwxgmac4 into stmmac hwif handling jitendra.vegiraju
@ 2024-08-02  8:23   ` Russell King (Oracle)
  2024-08-02 21:49     ` Jitendra Vegiraju
  2024-08-02 22:59   ` Andrew Lunn
  2024-08-06 22:14   ` Serge Semin
  2 siblings, 1 reply; 30+ messages in thread
From: Russell King (Oracle) @ 2024-08-02  8:23 UTC (permalink / raw)
  To: jitendra.vegiraju
  Cc: netdev, alexandre.torgue, joabreu, davem, edumazet, kuba, pabeni,
	mcoquelin.stm32, bcm-kernel-feedback-list, richardcochran, ast,
	daniel, hawk, john.fastabend, linux-kernel, linux-stm32,
	linux-arm-kernel, bpf, andrew, horms, florian.fainelli

On Thu, Aug 01, 2024 at 08:18:21PM -0700, jitendra.vegiraju@broadcom.com wrote:
> +static u32 stmmac_get_user_version(struct stmmac_priv *priv, u32 id_reg)
> +{
> +	u32 reg = readl(priv->ioaddr + id_reg);
> +
> +	if (!reg) {
> +		dev_info(priv->device, "User Version not available\n");
> +		return 0x0;
> +	}
> +
> +	return (reg & GENMASK(23, 16)) >> 16;

	return FIELD_GET(GENMASK(23, 16), reg);

For even more bonus points, use a #define for the field mask.

Thanks.

-- 
RMK's Patch system: https://www.armlinux.org.uk/developer/patches/
FTTP is here! 80Mbps down 10Mbps up. Decent connectivity at last!


^ permalink raw reply	[flat|nested] 30+ messages in thread

* Re: [PATCH net-next v3 0/3] net: stmmac: Add PCI driver support for BCM8958x
  2024-08-02  3:18 [PATCH net-next v3 0/3] net: stmmac: Add PCI driver support for BCM8958x jitendra.vegiraju
                   ` (2 preceding siblings ...)
  2024-08-02  3:18 ` [PATCH net-next v3 3/3] net: stmmac: Add PCI driver support for BCM8958x jitendra.vegiraju
@ 2024-08-02 10:02 ` Serge Semin
  2024-08-02 22:06   ` Jitendra Vegiraju
  3 siblings, 1 reply; 30+ messages in thread
From: Serge Semin @ 2024-08-02 10:02 UTC (permalink / raw)
  To: jitendra.vegiraju
  Cc: netdev, alexandre.torgue, joabreu, davem, edumazet, kuba, pabeni,
	mcoquelin.stm32, bcm-kernel-feedback-list, richardcochran, ast,
	daniel, hawk, john.fastabend, linux-kernel, linux-stm32,
	linux-arm-kernel, bpf, andrew, linux, horms, florian.fainelli

Hi Jitendra

On Thu, Aug 01, 2024 at 08:18:19PM -0700, jitendra.vegiraju@broadcom.com wrote:
> From: Jitendra Vegiraju <jitendra.vegiraju@broadcom.com>
> 
> This patchset adds basic PCI ethernet device driver support for Broadcom
> BCM8958x Automotive Ethernet switch SoC devices.
> 
> This SoC device has PCIe ethernet MAC attached to an integrated ethernet
> switch using XGMII interface. The PCIe ethernet controller is presented to
> the Linux host as PCI network device.
> 
> The following block diagram gives an overview of the application.
>              +=================================+
>              |       Host CPU/Linux            |
>              +=================================+
>                         || PCIe
>                         ||
>         +==========================================+
>         |           +--------------+               |
>         |           | PCIE Endpoint|               |
>         |           | Ethernet     |               |
>         |           | Controller   |               |
>         |           |   DMA        |               |
>         |           +--------------+               |
>         |           |   MAC        |   BCM8958X    |
>         |           +--------------+   SoC         |
>         |               || XGMII                   |
>         |               ||                         |
>         |           +--------------+               |
>         |           | Ethernet     |               |
>         |           | switch       |               |
>         |           +--------------+               |
>         |             || || || ||                  |
>         +==========================================+
>                       || || || || More external interfaces
> 
> The MAC block on BCM8958x is based on Synopsis XGMAC 4.00a core. This
> driver uses common dwxgmac2 code where applicable.

Thanks for submitting the series.

I am curious how come Broadcom got to use an IP-core which hasn't
been even announced by Synopsys. AFAICS the most modern DW XGMAC
IP-core is of v3.xxa version:

https://www.synopsys.com/dw/ipdir.php?ds=dwc_ether_xgmac

Are you sure that your device isn't equipped with some another DW MAC
IP-core, like DW 25G Ethernet MAC? (which BTW is equipped with a new
Hyper DMA engine with a capability to have up to 128/256 channels with
likely indirect addressing.) Do I miss something?

* I'll join the patch set review after the weekend, sometime on the
next week.

-Serge(y)

> Driver functionality specific to this MAC is implemented in dwxgmac4.c.
> Management of integrated ethernet switch on this SoC is not handled by
> the PCIe interface.
> This SoC device has PCIe ethernet MAC directly attached to an integrated
> ethernet switch using XGMII interface.
> 
> v2->v3:
>    Addressed v2 comments from Andrew, Jakub, Russel and Simon.
>    Based on suggestion by Russel and Andrew, added software node to create
>    phylink in fixed-link mode.
>    Moved dwxgmac4 specific functions to new files dwxgmac4.c and dwxgmac4.h
>    in stmmac core module.
>    Reorganized the code to use the existing glue logic support for xgmac in
>    hwif.c and override ops functions for dwxgmac4 specific functions.
>    The patch is split into three parts.
>      Patch#1 Adds dma_ops for dwxgmac4 in stmmac core
>      Patch#2 Hooks in the hardware interface handling for dwxgmac4
>      Patch#3 Adds PCI driver for BCM8958x device
> 
> v1->v2:
>    Minor fixes to address coding style issues.
>    Sent v2 too soon by mistake, without waiting for review comments.
>    Received feedback on this version.
>    https://lore.kernel.org/netdev/20240511015924.41457-1-jitendra.vegiraju@broadcom.com/
> 
> v1:  
>    https://lore.kernel.org/netdev/20240510000331.154486-1-jitendra.vegiraju@broadcom.com/
> 
> Jitendra Vegiraju (3):
>   Add basic dwxgmac4 support to stmmac core
>   Integrate dwxgmac4 into stmmac hwif handling
>   Add PCI driver support for BCM8958x
> 
>  MAINTAINERS                                   |   8 +
>  drivers/net/ethernet/stmicro/stmmac/Kconfig   |  11 +
>  drivers/net/ethernet/stmicro/stmmac/Makefile  |   3 +-
>  drivers/net/ethernet/stmicro/stmmac/common.h  |   4 +
>  .../net/ethernet/stmicro/stmmac/dwmac-brcm.c  | 517 ++++++++++++++++++
>  .../ethernet/stmicro/stmmac/dwxgmac2_dma.c    |  31 ++
>  .../net/ethernet/stmicro/stmmac/dwxgmac4.c    | 142 +++++
>  .../net/ethernet/stmicro/stmmac/dwxgmac4.h    |  84 +++
>  drivers/net/ethernet/stmicro/stmmac/hwif.c    |  26 +-
>  drivers/net/ethernet/stmicro/stmmac/hwif.h    |   1 +
>  10 files changed, 825 insertions(+), 2 deletions(-)
>  create mode 100644 drivers/net/ethernet/stmicro/stmmac/dwmac-brcm.c
>  create mode 100644 drivers/net/ethernet/stmicro/stmmac/dwxgmac4.c
>  create mode 100644 drivers/net/ethernet/stmicro/stmmac/dwxgmac4.h
> 
> -- 
> 2.34.1
> 
> 


^ permalink raw reply	[flat|nested] 30+ messages in thread

* Re: [PATCH net-next v3 1/3] net: stmmac: Add basic dwxgmac4 support to stmmac core
  2024-08-02  3:18 ` [PATCH net-next v3 1/3] net: stmmac: Add basic dwxgmac4 support to stmmac core jitendra.vegiraju
  2024-08-02  8:21   ` Russell King (Oracle)
@ 2024-08-02 14:38   ` Simon Horman
  2024-08-02 21:45     ` Jitendra Vegiraju
  2024-08-06 21:56   ` Serge Semin
  2 siblings, 1 reply; 30+ messages in thread
From: Simon Horman @ 2024-08-02 14:38 UTC (permalink / raw)
  To: jitendra.vegiraju
  Cc: netdev, alexandre.torgue, joabreu, davem, edumazet, kuba, pabeni,
	mcoquelin.stm32, bcm-kernel-feedback-list, richardcochran, ast,
	daniel, hawk, john.fastabend, linux-kernel, linux-stm32,
	linux-arm-kernel, bpf, andrew, linux, florian.fainelli

On Thu, Aug 01, 2024 at 08:18:20PM -0700, jitendra.vegiraju@broadcom.com wrote:
> From: Jitendra Vegiraju <jitendra.vegiraju@broadcom.com>
> 
> Adds support for DWC_xgmac version 4.00a in stmmac core module.
> This version adds enhancements to DMA architecture for virtualization
> scalability. This is realized by decoupling physical DMA channels (PDMA)
> from Virtual DMA channels (VDMA). The  VDMAs are software abastractions
> that map to PDMAs for frame transmission and reception.
> 
> The virtualization enhancements are currently not being used and hence
> a fixed mapping of VDMA to PDMA is configured in the init functions.
> Because of the new init functions, a new instance of struct stmmac_dma_ops
> dwxgmac400_dma_ops is added.
> Most of the other dma operation functions in existing dwxgamc2_dma.c file
> can be reused.
> 
> Signed-off-by: Jitendra Vegiraju <jitendra.vegiraju@broadcom.com>

...

>  stmmac-$(CONFIG_STMMAC_SELFTESTS) += stmmac_selftests.o
> diff --git a/drivers/net/ethernet/stmicro/stmmac/dwxgmac2_dma.c b/drivers/net/ethernet/stmicro/stmmac/dwxgmac2_dma.c

...

> @@ -641,3 +642,33 @@ const struct stmmac_dma_ops dwxgmac210_dma_ops = {
>  	.enable_sph = dwxgmac2_enable_sph,
>  	.enable_tbs = dwxgmac2_enable_tbs,
>  };
> +
> +const struct stmmac_dma_ops dwxgmac400_dma_ops = {
> +	.reset = dwxgmac2_dma_reset,
> +	.init = dwxgmac4_dma_init,
> +	.init_chan = dwxgmac2_dma_init_chan,
> +	.init_rx_chan = dwxgmac4_dma_init_rx_chan,
> +	.init_tx_chan = dwxgmac4_dma_init_tx_chan,
> +	.axi = dwxgmac2_dma_axi,
> +	.dump_regs = dwxgmac2_dma_dump_regs,
> +	.dma_rx_mode = dwxgmac2_dma_rx_mode,
> +	.dma_tx_mode = dwxgmac2_dma_tx_mode,
> +	.enable_dma_irq = dwxgmac2_enable_dma_irq,
> +	.disable_dma_irq = dwxgmac2_disable_dma_irq,
> +	.start_tx = dwxgmac2_dma_start_tx,
> +	.stop_tx = dwxgmac2_dma_stop_tx,
> +	.start_rx = dwxgmac2_dma_start_rx,
> +	.stop_rx = dwxgmac2_dma_stop_rx,
> +	.dma_interrupt = dwxgmac2_dma_interrupt,
> +	.get_hw_feature = dwxgmac2_get_hw_feature,
> +	.rx_watchdog = dwxgmac2_rx_watchdog,
> +	.set_rx_ring_len = dwxgmac2_set_rx_ring_len,
> +	.set_tx_ring_len = dwxgmac2_set_tx_ring_len,
> +	.set_rx_tail_ptr = dwxgmac2_set_rx_tail_ptr,
> +	.set_tx_tail_ptr = dwxgmac2_set_tx_tail_ptr,
> +	.enable_tso = dwxgmac2_enable_tso,
> +	.qmode = dwxgmac2_qmode,
> +	.set_bfsize = dwxgmac2_set_bfsize,
> +	.enable_sph = dwxgmac2_enable_sph,
> +	.enable_tbs = dwxgmac2_enable_tbs,
> +};

Please add dwxgmac400_dma_ops to hwif.h in this patch rather than a
subsequent one to avoid Sparse suggesting the symbol should be static.

...


^ permalink raw reply	[flat|nested] 30+ messages in thread

* Re: [PATCH net-next v3 1/3] net: stmmac: Add basic dwxgmac4 support to stmmac core
  2024-08-02  8:21   ` Russell King (Oracle)
@ 2024-08-02 21:43     ` Jitendra Vegiraju
  0 siblings, 0 replies; 30+ messages in thread
From: Jitendra Vegiraju @ 2024-08-02 21:43 UTC (permalink / raw)
  To: Russell King (Oracle)
  Cc: netdev, alexandre.torgue, joabreu, davem, edumazet, kuba, pabeni,
	mcoquelin.stm32, bcm-kernel-feedback-list, richardcochran, ast,
	daniel, hawk, john.fastabend, linux-kernel, linux-stm32,
	linux-arm-kernel, bpf, andrew, horms, florian.fainelli

Sorry for reposting, resending the reply since I missed reply to all.

On Fri, Aug 2, 2024 at 1:21 AM Russell King (Oracle)
<linux@armlinux.org.uk> wrote:
>
> On Thu, Aug 01, 2024 at 08:18:20PM -0700, jitendra.vegiraju@broadcom.com wrote:
> > +static int rd_dma_ch_ind(void __iomem *ioaddr, u8 mode, u32 channel)
> > +{
> > +     u32 reg_val = 0;
> > +     u32 val = 0;
>
> val is unnecessary.
True, I will fix it.
>
> > +
> > +     reg_val |= mode << XGMAC4_MSEL_SHIFT & XGMAC4_MODE_SELECT;
>
> Consider using:
>
>         reg_val |= FIELD_PREP(XGMAC4_MODE_SELECT, mode);
>
Thanks, I will make the changes.

> and similarly everywhere else you use a shift and mask. With this, you
> can remove _all_ _SHIFT definitions in your header file.
>
> > +     reg_val |= channel << XGMAC4_AOFF_SHIFT & XGMAC4_ADDR_OFFSET;
> > +     reg_val |= XGMAC4_CMD_TYPE | XGMAC4_OB;
> > +     writel(reg_val, ioaddr + XGMAC4_DMA_CH_IND_CONTROL);
> > +     val = readl(ioaddr + XGMAC4_DMA_CH_IND_DATA);
> > +     return val;
>
>         return readl(ioaddr + XGMAC4_DMA_CH_IND_DATA);
>
> ...
>
> > +void dwxgmac4_dma_init(void __iomem *ioaddr,
> > +                    struct stmmac_dma_cfg *dma_cfg, int atds)
> > +{
> > +     u32 value;
> > +     u32 i;
> > +
> > +     value = readl(ioaddr + XGMAC_DMA_SYSBUS_MODE);
> > +
> > +     if (dma_cfg->aal)
> > +             value |= XGMAC_AAL;
> > +
> > +     if (dma_cfg->eame)
> > +             value |= XGMAC_EAME;
>
> What if dma_cfg doesn't have these bits set? Is it possible they will be
> set in the register?
The reset default for these bits is zero.
>
> Thanks.
>
> --
> RMK's Patch system: https://www.armlinux.org.uk/developer/patches/
> FTTP is here! 80Mbps down 10Mbps up. Decent connectivity at last!


^ permalink raw reply	[flat|nested] 30+ messages in thread

* Re: [PATCH net-next v3 1/3] net: stmmac: Add basic dwxgmac4 support to stmmac core
  2024-08-02 14:38   ` Simon Horman
@ 2024-08-02 21:45     ` Jitendra Vegiraju
  0 siblings, 0 replies; 30+ messages in thread
From: Jitendra Vegiraju @ 2024-08-02 21:45 UTC (permalink / raw)
  To: Simon Horman
  Cc: netdev, alexandre.torgue, joabreu, davem, edumazet, kuba, pabeni,
	mcoquelin.stm32, bcm-kernel-feedback-list, richardcochran, ast,
	daniel, hawk, john.fastabend, linux-kernel, linux-stm32,
	linux-arm-kernel, bpf, andrew, linux, florian.fainelli

On Fri, Aug 2, 2024 at 7:38 AM Simon Horman <horms@kernel.org> wrote:
>
> On Thu, Aug 01, 2024 at 08:18:20PM -0700, jitendra.vegiraju@broadcom.com wrote:
> > From: Jitendra Vegiraju <jitendra.vegiraju@broadcom.com>
> >
> > Adds support for DWC_xgmac version 4.00a in stmmac core module.
> > This version adds enhancements to DMA architecture for virtualization
> > scalability. This is realized by decoupling physical DMA channels (PDMA)
> > from Virtual DMA channels (VDMA). The  VDMAs are software abastractions
> > that map to PDMAs for frame transmission and reception.
> >
> > The virtualization enhancements are currently not being used and hence
> > a fixed mapping of VDMA to PDMA is configured in the init functions.
> > Because of the new init functions, a new instance of struct stmmac_dma_ops
> > dwxgmac400_dma_ops is added.
> > Most of the other dma operation functions in existing dwxgamc2_dma.c file
> > can be reused.
> >
> > Signed-off-by: Jitendra Vegiraju <jitendra.vegiraju@broadcom.com>
>
> ...
>
> >  stmmac-$(CONFIG_STMMAC_SELFTESTS) += stmmac_selftests.o
> > diff --git a/drivers/net/ethernet/stmicro/stmmac/dwxgmac2_dma.c b/drivers/net/ethernet/stmicro/stmmac/dwxgmac2_dma.c
>
> ...
>
> > @@ -641,3 +642,33 @@ const struct stmmac_dma_ops dwxgmac210_dma_ops = {
> >       .enable_sph = dwxgmac2_enable_sph,
> >       .enable_tbs = dwxgmac2_enable_tbs,
> >  };
> > +
> > +const struct stmmac_dma_ops dwxgmac400_dma_ops = {
> > +     .reset = dwxgmac2_dma_reset,
> > +     .init = dwxgmac4_dma_init,
> > +     .init_chan = dwxgmac2_dma_init_chan,
> > +     .init_rx_chan = dwxgmac4_dma_init_rx_chan,
> > +     .init_tx_chan = dwxgmac4_dma_init_tx_chan,
> > +     .axi = dwxgmac2_dma_axi,
> > +     .dump_regs = dwxgmac2_dma_dump_regs,
> > +     .dma_rx_mode = dwxgmac2_dma_rx_mode,
> > +     .dma_tx_mode = dwxgmac2_dma_tx_mode,
> > +     .enable_dma_irq = dwxgmac2_enable_dma_irq,
> > +     .disable_dma_irq = dwxgmac2_disable_dma_irq,
> > +     .start_tx = dwxgmac2_dma_start_tx,
> > +     .stop_tx = dwxgmac2_dma_stop_tx,
> > +     .start_rx = dwxgmac2_dma_start_rx,
> > +     .stop_rx = dwxgmac2_dma_stop_rx,
> > +     .dma_interrupt = dwxgmac2_dma_interrupt,
> > +     .get_hw_feature = dwxgmac2_get_hw_feature,
> > +     .rx_watchdog = dwxgmac2_rx_watchdog,
> > +     .set_rx_ring_len = dwxgmac2_set_rx_ring_len,
> > +     .set_tx_ring_len = dwxgmac2_set_tx_ring_len,
> > +     .set_rx_tail_ptr = dwxgmac2_set_rx_tail_ptr,
> > +     .set_tx_tail_ptr = dwxgmac2_set_tx_tail_ptr,
> > +     .enable_tso = dwxgmac2_enable_tso,
> > +     .qmode = dwxgmac2_qmode,
> > +     .set_bfsize = dwxgmac2_set_bfsize,
> > +     .enable_sph = dwxgmac2_enable_sph,
> > +     .enable_tbs = dwxgmac2_enable_tbs,
> > +};
>
> Please add dwxgmac400_dma_ops to hwif.h in this patch rather than a
> subsequent one to avoid Sparse suggesting the symbol should be static.
Thanks, I will make the change in the next patch revision.
>
> ...


^ permalink raw reply	[flat|nested] 30+ messages in thread

* Re: [PATCH net-next v3 2/3] net: stmmac: Integrate dwxgmac4 into stmmac hwif handling
  2024-08-02  8:23   ` Russell King (Oracle)
@ 2024-08-02 21:49     ` Jitendra Vegiraju
  0 siblings, 0 replies; 30+ messages in thread
From: Jitendra Vegiraju @ 2024-08-02 21:49 UTC (permalink / raw)
  To: Russell King (Oracle)
  Cc: netdev, alexandre.torgue, joabreu, davem, edumazet, kuba, pabeni,
	mcoquelin.stm32, bcm-kernel-feedback-list, richardcochran, ast,
	daniel, hawk, john.fastabend, linux-kernel, linux-stm32,
	linux-arm-kernel, bpf, andrew, horms, florian.fainelli

On Fri, Aug 2, 2024 at 1:23 AM Russell King (Oracle)
<linux@armlinux.org.uk> wrote:
>
> On Thu, Aug 01, 2024 at 08:18:21PM -0700, jitendra.vegiraju@broadcom.com wrote:
> > +static u32 stmmac_get_user_version(struct stmmac_priv *priv, u32 id_reg)
> > +{
> > +     u32 reg = readl(priv->ioaddr + id_reg);
> > +
> > +     if (!reg) {
> > +             dev_info(priv->device, "User Version not available\n");
> > +             return 0x0;
> > +     }
> > +
> > +     return (reg & GENMASK(23, 16)) >> 16;
>
>         return FIELD_GET(GENMASK(23, 16), reg);
>
> For even more bonus points, use a #define for the field mask.
Thanks, I will make the change.
>
> Thanks.
>
> --
> RMK's Patch system: https://www.armlinux.org.uk/developer/patches/
> FTTP is here! 80Mbps down 10Mbps up. Decent connectivity at last!


^ permalink raw reply	[flat|nested] 30+ messages in thread

* Re: [PATCH net-next v3 0/3] net: stmmac: Add PCI driver support for BCM8958x
  2024-08-02 10:02 ` [PATCH net-next v3 0/3] " Serge Semin
@ 2024-08-02 22:06   ` Jitendra Vegiraju
  2024-08-05 22:43     ` Serge Semin
  0 siblings, 1 reply; 30+ messages in thread
From: Jitendra Vegiraju @ 2024-08-02 22:06 UTC (permalink / raw)
  To: Serge Semin
  Cc: netdev, alexandre.torgue, joabreu, davem, edumazet, kuba, pabeni,
	mcoquelin.stm32, bcm-kernel-feedback-list, richardcochran, ast,
	daniel, hawk, john.fastabend, linux-kernel, linux-stm32,
	linux-arm-kernel, bpf, andrew, linux, horms, florian.fainelli

On Fri, Aug 2, 2024 at 3:02 AM Serge Semin <fancer.lancer@gmail.com> wrote:
>
> Hi Jitendra
>
> On Thu, Aug 01, 2024 at 08:18:19PM -0700, jitendra.vegiraju@broadcom.com wrote:
> > From: Jitendra Vegiraju <jitendra.vegiraju@broadcom.com>
> >
> > This patchset adds basic PCI ethernet device driver support for Broadcom
> > BCM8958x Automotive Ethernet switch SoC devices.
> >
> > This SoC device has PCIe ethernet MAC attached to an integrated ethernet
> > switch using XGMII interface. The PCIe ethernet controller is presented to
> > the Linux host as PCI network device.
> >
> > The following block diagram gives an overview of the application.
> >              +=================================+
> >              |       Host CPU/Linux            |
> >              +=================================+
> >                         || PCIe
> >                         ||
> >         +==========================================+
> >         |           +--------------+               |
> >         |           | PCIE Endpoint|               |
> >         |           | Ethernet     |               |
> >         |           | Controller   |               |
> >         |           |   DMA        |               |
> >         |           +--------------+               |
> >         |           |   MAC        |   BCM8958X    |
> >         |           +--------------+   SoC         |
> >         |               || XGMII                   |
> >         |               ||                         |
> >         |           +--------------+               |
> >         |           | Ethernet     |               |
> >         |           | switch       |               |
> >         |           +--------------+               |
> >         |             || || || ||                  |
> >         +==========================================+
> >                       || || || || More external interfaces
> >
> > The MAC block on BCM8958x is based on Synopsis XGMAC 4.00a core. This
> > driver uses common dwxgmac2 code where applicable.
>
> Thanks for submitting the series.
>
> I am curious how come Broadcom got to use an IP-core which hasn't
> been even announced by Synopsys. AFAICS the most modern DW XGMAC
> IP-core is of v3.xxa version:
>
> https://www.synopsys.com/dw/ipdir.php?ds=dwc_ether_xgmac
>
I am not sure why the 4.00a IP-code is not announced for general
availability yet.
The Synopsis documentation for this IP mentions 3.xx IP as reference
for this design and lists
new features for 4.00a.

> Are you sure that your device isn't equipped with some another DW MAC
> IP-core, like DW 25G Ethernet MAC? (which BTW is equipped with a new
> Hyper DMA engine with a capability to have up to 128/256 channels with
> likely indirect addressing.) Do I miss something?
>
Yes, I briefly mentioned the new DMA architecture in the commit log
for patch 1/3.
You are correct, the name for the new DMA engine is Hyper DMA. It
probably started with some 3.xx IP-Core.
This DW-MAC is capable of 25G, but this SOC is not using 25G support.

> * I'll join the patch set review after the weekend, sometime on the
> next week.
>
> -Serge(y)
>
> > Driver functionality specific to this MAC is implemented in dwxgmac4.c.
> > Management of integrated ethernet switch on this SoC is not handled by
> > the PCIe interface.
> > This SoC device has PCIe ethernet MAC directly attached to an integrated
> > ethernet switch using XGMII interface.
> >
> > v2->v3:
> >    Addressed v2 comments from Andrew, Jakub, Russel and Simon.
> >    Based on suggestion by Russel and Andrew, added software node to create
> >    phylink in fixed-link mode.
> >    Moved dwxgmac4 specific functions to new files dwxgmac4.c and dwxgmac4.h
> >    in stmmac core module.
> >    Reorganized the code to use the existing glue logic support for xgmac in
> >    hwif.c and override ops functions for dwxgmac4 specific functions.
> >    The patch is split into three parts.
> >      Patch#1 Adds dma_ops for dwxgmac4 in stmmac core
> >      Patch#2 Hooks in the hardware interface handling for dwxgmac4
> >      Patch#3 Adds PCI driver for BCM8958x device
> >
> > v1->v2:
> >    Minor fixes to address coding style issues.
> >    Sent v2 too soon by mistake, without waiting for review comments.
> >    Received feedback on this version.
> >    https://lore.kernel.org/netdev/20240511015924.41457-1-jitendra.vegiraju@broadcom.com/
> >
> > v1:
> >    https://lore.kernel.org/netdev/20240510000331.154486-1-jitendra.vegiraju@broadcom.com/
> >
> > Jitendra Vegiraju (3):
> >   Add basic dwxgmac4 support to stmmac core
> >   Integrate dwxgmac4 into stmmac hwif handling
> >   Add PCI driver support for BCM8958x
> >
> >  MAINTAINERS                                   |   8 +
> >  drivers/net/ethernet/stmicro/stmmac/Kconfig   |  11 +
> >  drivers/net/ethernet/stmicro/stmmac/Makefile  |   3 +-
> >  drivers/net/ethernet/stmicro/stmmac/common.h  |   4 +
> >  .../net/ethernet/stmicro/stmmac/dwmac-brcm.c  | 517 ++++++++++++++++++
> >  .../ethernet/stmicro/stmmac/dwxgmac2_dma.c    |  31 ++
> >  .../net/ethernet/stmicro/stmmac/dwxgmac4.c    | 142 +++++
> >  .../net/ethernet/stmicro/stmmac/dwxgmac4.h    |  84 +++
> >  drivers/net/ethernet/stmicro/stmmac/hwif.c    |  26 +-
> >  drivers/net/ethernet/stmicro/stmmac/hwif.h    |   1 +
> >  10 files changed, 825 insertions(+), 2 deletions(-)
> >  create mode 100644 drivers/net/ethernet/stmicro/stmmac/dwmac-brcm.c
> >  create mode 100644 drivers/net/ethernet/stmicro/stmmac/dwxgmac4.c
> >  create mode 100644 drivers/net/ethernet/stmicro/stmmac/dwxgmac4.h
> >
> > --
> > 2.34.1
> >
> >


^ permalink raw reply	[flat|nested] 30+ messages in thread

* Re: [PATCH net-next v3 2/3] net: stmmac: Integrate dwxgmac4 into stmmac hwif handling
  2024-08-02  3:18 ` [PATCH net-next v3 2/3] net: stmmac: Integrate dwxgmac4 into stmmac hwif handling jitendra.vegiraju
  2024-08-02  8:23   ` Russell King (Oracle)
@ 2024-08-02 22:59   ` Andrew Lunn
  2024-08-06  0:36     ` Jitendra Vegiraju
  2024-08-06 22:14   ` Serge Semin
  2 siblings, 1 reply; 30+ messages in thread
From: Andrew Lunn @ 2024-08-02 22:59 UTC (permalink / raw)
  To: jitendra.vegiraju
  Cc: netdev, alexandre.torgue, joabreu, davem, edumazet, kuba, pabeni,
	mcoquelin.stm32, bcm-kernel-feedback-list, richardcochran, ast,
	daniel, hawk, john.fastabend, linux-kernel, linux-stm32,
	linux-arm-kernel, bpf, linux, horms, florian.fainelli

> +	user_ver = stmmac_get_user_version(priv, GMAC4_VERSION);
> +	if (priv->synopsys_id == DWXGMAC_CORE_4_00 &&
> +	    user_ver == DWXGMAC_USER_VER_X22)
> +		mac->dma = &dwxgmac400_dma_ops;

I know nothing about this hardware....

Does priv->synopsys_id == DWXGMAC_CORE_4_0 not imply
dwxgmac400_dma_ops?

Could a user synthesise DWXGMAC_CORE_4_00 without using
dwxgmac400_dma_ops? Could dwxgmac500_dma_ops or dwxgmac100_dma_ops be
used?

	Andrew


^ permalink raw reply	[flat|nested] 30+ messages in thread

* Re: [PATCH net-next v3 3/3] net: stmmac: Add PCI driver support for BCM8958x
  2024-08-02  3:18 ` [PATCH net-next v3 3/3] net: stmmac: Add PCI driver support for BCM8958x jitendra.vegiraju
@ 2024-08-02 23:08   ` Andrew Lunn
  2024-08-06  0:56     ` Jitendra Vegiraju
  0 siblings, 1 reply; 30+ messages in thread
From: Andrew Lunn @ 2024-08-02 23:08 UTC (permalink / raw)
  To: jitendra.vegiraju
  Cc: netdev, alexandre.torgue, joabreu, davem, edumazet, kuba, pabeni,
	mcoquelin.stm32, bcm-kernel-feedback-list, richardcochran, ast,
	daniel, hawk, john.fastabend, linux-kernel, linux-stm32,
	linux-arm-kernel, bpf, linux, horms, florian.fainelli

> Management of integrated ethernet switch on this SoC is not handled by
> the PCIe interface.

MDIO? SPI? I2C?

> +#define XGMAC_PCIE_MISC_MII_CTRL			0x4
> +#define XGMAC_PCIE_MISC_MII_CTRL_VALUE			0x7

Could you replace these magic values with actual definitions. What
does 7 mean?

> +#define XGMAC_PCIE_MISC_PCIESS_CTRL			0x8
> +#define XGMAC_PCIE_MISC_PCIESS_CTRL_VALUE		0x200

> +static int num_instances;

> +	/* This device is directly attached to the switch chip internal to the
> +	 * SoC using XGMII interface. Since no MDIO is present, register
> +	 * fixed-link software_node to create phylink.
> +	 */
> +	if (num_instances == 0) {
> +		ret = software_node_register_node_group(fixed_link_node_group);
> +		if (ret) {
> +			dev_err(&pdev->dev,
> +				"%s: failed to register software node\n",
> +				__func__);
> +			return ret;
> +		}
> +	}
> +	num_instances++;

So all the instances of the MAC share one fixed link? That is pretty
unusual. In DT, each would have its own. Have you reviewed the
implications of this?

	Andrew


^ permalink raw reply	[flat|nested] 30+ messages in thread

* Re: [PATCH net-next v3 0/3] net: stmmac: Add PCI driver support for BCM8958x
  2024-08-02 22:06   ` Jitendra Vegiraju
@ 2024-08-05 22:43     ` Serge Semin
  2024-08-08 23:03       ` Jitendra Vegiraju
  0 siblings, 1 reply; 30+ messages in thread
From: Serge Semin @ 2024-08-05 22:43 UTC (permalink / raw)
  To: Jitendra Vegiraju
  Cc: netdev, alexandre.torgue, joabreu, davem, edumazet, kuba, pabeni,
	mcoquelin.stm32, bcm-kernel-feedback-list, richardcochran, ast,
	daniel, hawk, john.fastabend, linux-kernel, linux-stm32,
	linux-arm-kernel, bpf, andrew, linux, horms, florian.fainelli

On Fri, Aug 02, 2024 at 03:06:05PM -0700, Jitendra Vegiraju wrote:
> On Fri, Aug 2, 2024 at 3:02 AM Serge Semin <fancer.lancer@gmail.com> wrote:
> >
> > Hi Jitendra
> >
> > On Thu, Aug 01, 2024 at 08:18:19PM -0700, jitendra.vegiraju@broadcom.com wrote:
> > > From: Jitendra Vegiraju <jitendra.vegiraju@broadcom.com>
> > >
> > > This patchset adds basic PCI ethernet device driver support for Broadcom
> > > BCM8958x Automotive Ethernet switch SoC devices.
> > >
> > > This SoC device has PCIe ethernet MAC attached to an integrated ethernet
> > > switch using XGMII interface. The PCIe ethernet controller is presented to
> > > the Linux host as PCI network device.
> > >
> > > The following block diagram gives an overview of the application.
> > >              +=================================+
> > >              |       Host CPU/Linux            |
> > >              +=================================+
> > >                         || PCIe
> > >                         ||
> > >         +==========================================+
> > >         |           +--------------+               |
> > >         |           | PCIE Endpoint|               |
> > >         |           | Ethernet     |               |
> > >         |           | Controller   |               |
> > >         |           |   DMA        |               |
> > >         |           +--------------+               |
> > >         |           |   MAC        |   BCM8958X    |
> > >         |           +--------------+   SoC         |
> > >         |               || XGMII                   |
> > >         |               ||                         |
> > >         |           +--------------+               |
> > >         |           | Ethernet     |               |
> > >         |           | switch       |               |
> > >         |           +--------------+               |
> > >         |             || || || ||                  |
> > >         +==========================================+
> > >                       || || || || More external interfaces
> > >
> > > The MAC block on BCM8958x is based on Synopsis XGMAC 4.00a core. This
> > > driver uses common dwxgmac2 code where applicable.
> >
> > Thanks for submitting the series.
> >
> > I am curious how come Broadcom got to use an IP-core which hasn't
> > been even announced by Synopsys. AFAICS the most modern DW XGMAC
> > IP-core is of v3.xxa version:
> >
> > https://www.synopsys.com/dw/ipdir.php?ds=dwc_ether_xgmac
> >

> I am not sure why the 4.00a IP-code is not announced for general
> availability yet.
> The Synopsis documentation for this IP mentions 3.xx IP as reference
> for this design and lists
> new features for 4.00a.
> 
> > Are you sure that your device isn't equipped with some another DW MAC
> > IP-core, like DW 25G Ethernet MAC? (which BTW is equipped with a new
> > Hyper DMA engine with a capability to have up to 128/256 channels with
> > likely indirect addressing.) Do I miss something?
> >
> Yes, I briefly mentioned the new DMA architecture in the commit log
> for patch 1/3.
> You are correct, the name for the new DMA engine is Hyper DMA. It
> probably started with some 3.xx IP-Core.
> This DW-MAC is capable of 25G, but this SOC is not using 25G support.

Then what you have is likely the DW 25GMAC since just DW XGMAC hasn't
been announced to have neither 25G speed nor the Hyper-DMA with the
virtualization channels capabilities. Meanwhile the former IP-core
does have these features:
https://www.synopsys.com/dw/ipdir.php?ds=dwc_25g_ethernet_mac_ip

Alas I don't have the DW 25GMAC IP-core databook to say for sure, but
that's the only explanation of why you have the 0x40 Synopsys ID and
the IP-core version of v4.00a, and the 25G capability of the MAC.

Seeing Synopsys tends to re-use the CSRs mapping even across the major
IP-core releases it isn't that surprising that the DW XGMAC 3.xx
IP-core was referenced in the doc. (See the driver, DW XLGMAC is
almost fully compatible with the DW XGMAC CSRs mapping.)

Moreover the most DMA-capable device currently supported by the
STMMAC-driver is DW XGMAC/XLGMAC and it can't have more than 16
DMA-channels. That allows to directly map all the channels CSRs to the
system memory. But your case is different. The DW 25GMAC IP-core is
announced to support virtualization up to 128/256 channels, for which
the direct CSRs mapping could require 16-times more memory. That's
likely why the indirect addressing was implemented to access the
settings of all the possible channels. That's also implicitly proofs
that you have the DW 25GMAC IP-core.

-Serge(y)

> 
> > * I'll join the patch set review after the weekend, sometime on the
> > next week.
> >
> > -Serge(y)
> >
> > > Driver functionality specific to this MAC is implemented in dwxgmac4.c.
> > > Management of integrated ethernet switch on this SoC is not handled by
> > > the PCIe interface.
> > > This SoC device has PCIe ethernet MAC directly attached to an integrated
> > > ethernet switch using XGMII interface.
> > >
> > > v2->v3:
> > >    Addressed v2 comments from Andrew, Jakub, Russel and Simon.
> > >    Based on suggestion by Russel and Andrew, added software node to create
> > >    phylink in fixed-link mode.
> > >    Moved dwxgmac4 specific functions to new files dwxgmac4.c and dwxgmac4.h
> > >    in stmmac core module.
> > >    Reorganized the code to use the existing glue logic support for xgmac in
> > >    hwif.c and override ops functions for dwxgmac4 specific functions.
> > >    The patch is split into three parts.
> > >      Patch#1 Adds dma_ops for dwxgmac4 in stmmac core
> > >      Patch#2 Hooks in the hardware interface handling for dwxgmac4
> > >      Patch#3 Adds PCI driver for BCM8958x device
> > >
> > > v1->v2:
> > >    Minor fixes to address coding style issues.
> > >    Sent v2 too soon by mistake, without waiting for review comments.
> > >    Received feedback on this version.
> > >    https://lore.kernel.org/netdev/20240511015924.41457-1-jitendra.vegiraju@broadcom.com/
> > >
> > > v1:
> > >    https://lore.kernel.org/netdev/20240510000331.154486-1-jitendra.vegiraju@broadcom.com/
> > >
> > > Jitendra Vegiraju (3):
> > >   Add basic dwxgmac4 support to stmmac core
> > >   Integrate dwxgmac4 into stmmac hwif handling
> > >   Add PCI driver support for BCM8958x
> > >
> > >  MAINTAINERS                                   |   8 +
> > >  drivers/net/ethernet/stmicro/stmmac/Kconfig   |  11 +
> > >  drivers/net/ethernet/stmicro/stmmac/Makefile  |   3 +-
> > >  drivers/net/ethernet/stmicro/stmmac/common.h  |   4 +
> > >  .../net/ethernet/stmicro/stmmac/dwmac-brcm.c  | 517 ++++++++++++++++++
> > >  .../ethernet/stmicro/stmmac/dwxgmac2_dma.c    |  31 ++
> > >  .../net/ethernet/stmicro/stmmac/dwxgmac4.c    | 142 +++++
> > >  .../net/ethernet/stmicro/stmmac/dwxgmac4.h    |  84 +++
> > >  drivers/net/ethernet/stmicro/stmmac/hwif.c    |  26 +-
> > >  drivers/net/ethernet/stmicro/stmmac/hwif.h    |   1 +
> > >  10 files changed, 825 insertions(+), 2 deletions(-)
> > >  create mode 100644 drivers/net/ethernet/stmicro/stmmac/dwmac-brcm.c
> > >  create mode 100644 drivers/net/ethernet/stmicro/stmmac/dwxgmac4.c
> > >  create mode 100644 drivers/net/ethernet/stmicro/stmmac/dwxgmac4.h
> > >
> > > --
> > > 2.34.1
> > >
> > >


^ permalink raw reply	[flat|nested] 30+ messages in thread

* Re: [PATCH net-next v3 2/3] net: stmmac: Integrate dwxgmac4 into stmmac hwif handling
  2024-08-02 22:59   ` Andrew Lunn
@ 2024-08-06  0:36     ` Jitendra Vegiraju
  2024-08-06 23:13       ` Andrew Lunn
  0 siblings, 1 reply; 30+ messages in thread
From: Jitendra Vegiraju @ 2024-08-06  0:36 UTC (permalink / raw)
  To: Andrew Lunn
  Cc: netdev, alexandre.torgue, joabreu, davem, edumazet, kuba, pabeni,
	mcoquelin.stm32, bcm-kernel-feedback-list, richardcochran, ast,
	daniel, hawk, john.fastabend, linux-kernel, linux-stm32,
	linux-arm-kernel, bpf, linux, horms, florian.fainelli

Hi Andrew,
On Fri, Aug 2, 2024 at 3:59 PM Andrew Lunn <andrew@lunn.ch> wrote:
>
> > +     user_ver = stmmac_get_user_version(priv, GMAC4_VERSION);
> > +     if (priv->synopsys_id == DWXGMAC_CORE_4_00 &&
> > +         user_ver == DWXGMAC_USER_VER_X22)
> > +             mac->dma = &dwxgmac400_dma_ops;
>
> I know nothing about this hardware....
>
> Does priv->synopsys_id == DWXGMAC_CORE_4_0 not imply
> dwxgmac400_dma_ops?
>
> Could a user synthesise DWXGMAC_CORE_4_00 without using
> dwxgmac400_dma_ops? Could dwxgmac500_dma_ops or dwxgmac100_dma_ops be
> used?
Yes, the user can choose between Enhanced DMA , Hyper DMA , Normal DMA.
This SoC support has chosen Hyper DMA for future expandability.

>
>         Andrew


^ permalink raw reply	[flat|nested] 30+ messages in thread

* Re: [PATCH net-next v3 3/3] net: stmmac: Add PCI driver support for BCM8958x
  2024-08-02 23:08   ` Andrew Lunn
@ 2024-08-06  0:56     ` Jitendra Vegiraju
  2024-08-06 23:15       ` Andrew Lunn
  0 siblings, 1 reply; 30+ messages in thread
From: Jitendra Vegiraju @ 2024-08-06  0:56 UTC (permalink / raw)
  To: Andrew Lunn
  Cc: netdev, alexandre.torgue, joabreu, davem, edumazet, kuba, pabeni,
	mcoquelin.stm32, bcm-kernel-feedback-list, richardcochran, ast,
	daniel, hawk, john.fastabend, linux-kernel, linux-stm32,
	linux-arm-kernel, bpf, linux, horms, florian.fainelli

On Fri, Aug 2, 2024 at 4:08 PM Andrew Lunn <andrew@lunn.ch> wrote:
>
> > Management of integrated ethernet switch on this SoC is not handled by
> > the PCIe interface.
>
> MDIO? SPI? I2C?
>
The device uses SPI interface. The switch has internal ARM M7 for
controller firmware.

> > +#define XGMAC_PCIE_MISC_MII_CTRL                     0x4
> > +#define XGMAC_PCIE_MISC_MII_CTRL_VALUE                       0x7
>
> Could you replace these magic values with actual definitions. What
> does 7 mean?
>
Thanks, I will fix the macros.

> > +#define XGMAC_PCIE_MISC_PCIESS_CTRL                  0x8
> > +#define XGMAC_PCIE_MISC_PCIESS_CTRL_VALUE            0x200
>
> > +static int num_instances;
>
> > +     /* This device is directly attached to the switch chip internal to the
> > +      * SoC using XGMII interface. Since no MDIO is present, register
> > +      * fixed-link software_node to create phylink.
> > +      */
> > +     if (num_instances == 0) {
> > +             ret = software_node_register_node_group(fixed_link_node_group);
> > +             if (ret) {
> > +                     dev_err(&pdev->dev,
> > +                             "%s: failed to register software node\n",
> > +                             __func__);
> > +                     return ret;
> > +             }
> > +     }
> > +     num_instances++;
>
> So all the instances of the MAC share one fixed link? That is pretty
> unusual. In DT, each would have its own. Have you reviewed the
> implications of this?
>
Our thinking was that since the software node is only used for static
node data to populate phylink config, a per device node is not
required.
We tested with multiple devices and repeated PCI remove/rescan operations.
However, It does make sense to be consistent with the DT usage model.
We will add the per device node entry in the next patch update.
>         Andrew


^ permalink raw reply	[flat|nested] 30+ messages in thread

* Re: [PATCH net-next v3 1/3] net: stmmac: Add basic dwxgmac4 support to stmmac core
  2024-08-02  3:18 ` [PATCH net-next v3 1/3] net: stmmac: Add basic dwxgmac4 support to stmmac core jitendra.vegiraju
  2024-08-02  8:21   ` Russell King (Oracle)
  2024-08-02 14:38   ` Simon Horman
@ 2024-08-06 21:56   ` Serge Semin
  2024-08-09  0:41     ` Jitendra Vegiraju
  2 siblings, 1 reply; 30+ messages in thread
From: Serge Semin @ 2024-08-06 21:56 UTC (permalink / raw)
  To: jitendra.vegiraju
  Cc: netdev, alexandre.torgue, joabreu, davem, edumazet, kuba, pabeni,
	mcoquelin.stm32, bcm-kernel-feedback-list, richardcochran, ast,
	daniel, hawk, john.fastabend, linux-kernel, linux-stm32,
	linux-arm-kernel, bpf, andrew, linux, horms, florian.fainelli

On Thu, Aug 01, 2024 at 08:18:20PM -0700, jitendra.vegiraju@broadcom.com wrote:
> From: Jitendra Vegiraju <jitendra.vegiraju@broadcom.com>
> 
> Adds support for DWC_xgmac version 4.00a in stmmac core module.
> This version adds enhancements to DMA architecture for virtualization
> scalability. This is realized by decoupling physical DMA channels (PDMA)
> from Virtual DMA channels (VDMA). The  VDMAs are software abastractions
> that map to PDMAs for frame transmission and reception.
> 
> The virtualization enhancements are currently not being used and hence
> a fixed mapping of VDMA to PDMA is configured in the init functions.
> Because of the new init functions, a new instance of struct stmmac_dma_ops
> dwxgmac400_dma_ops is added.
> Most of the other dma operation functions in existing dwxgamc2_dma.c file
> can be reused.

As we figured out (didn't we?) that it's actually the DW 25GMAC, then
it should be taken into account across the entire series.

> 
> Signed-off-by: Jitendra Vegiraju <jitendra.vegiraju@broadcom.com>
> ---
>  drivers/net/ethernet/stmicro/stmmac/Makefile  |   2 +-
>  .../ethernet/stmicro/stmmac/dwxgmac2_dma.c    |  31 ++++
>  .../net/ethernet/stmicro/stmmac/dwxgmac4.c    | 142 ++++++++++++++++++
>  .../net/ethernet/stmicro/stmmac/dwxgmac4.h    |  84 +++++++++++
>  4 files changed, 258 insertions(+), 1 deletion(-)
>  create mode 100644 drivers/net/ethernet/stmicro/stmmac/dwxgmac4.c
>  create mode 100644 drivers/net/ethernet/stmicro/stmmac/dwxgmac4.h
> 
> diff --git a/drivers/net/ethernet/stmicro/stmmac/Makefile b/drivers/net/ethernet/stmicro/stmmac/Makefile
> index c2f0e91f6bf8..2f637612513d 100644
> --- a/drivers/net/ethernet/stmicro/stmmac/Makefile
> +++ b/drivers/net/ethernet/stmicro/stmmac/Makefile
> @@ -6,7 +6,7 @@ stmmac-objs:= stmmac_main.o stmmac_ethtool.o stmmac_mdio.o ring_mode.o	\
>  	      mmc_core.o stmmac_hwtstamp.o stmmac_ptp.o dwmac4_descs.o	\
>  	      dwmac4_dma.o dwmac4_lib.o dwmac4_core.o dwmac5.o hwif.o \
>  	      stmmac_tc.o dwxgmac2_core.o dwxgmac2_dma.o dwxgmac2_descs.o \
> -	      stmmac_xdp.o stmmac_est.o \

> +	      stmmac_xdp.o stmmac_est.o dwxgmac4.o \

dw25gmac.o?

>  	      $(stmmac-y)
>  
>  stmmac-$(CONFIG_STMMAC_SELFTESTS) += stmmac_selftests.o
> diff --git a/drivers/net/ethernet/stmicro/stmmac/dwxgmac2_dma.c b/drivers/net/ethernet/stmicro/stmmac/dwxgmac2_dma.c
> index dd2ab6185c40..c15f5247aaa8 100644
> --- a/drivers/net/ethernet/stmicro/stmmac/dwxgmac2_dma.c
> +++ b/drivers/net/ethernet/stmicro/stmmac/dwxgmac2_dma.c
> @@ -7,6 +7,7 @@
>  #include <linux/iopoll.h>
>  #include "stmmac.h"
>  #include "dwxgmac2.h"

> +#include "dwxgmac4.h"

"dw25gmac.h"?

>  
>  static int dwxgmac2_dma_reset(void __iomem *ioaddr)
>  {
> @@ -641,3 +642,33 @@ const struct stmmac_dma_ops dwxgmac210_dma_ops = {
>  	.enable_sph = dwxgmac2_enable_sph,
>  	.enable_tbs = dwxgmac2_enable_tbs,
>  };
> +

> +const struct stmmac_dma_ops dwxgmac400_dma_ops = {

dw25gmac_dma_ops?

> +	.reset = dwxgmac2_dma_reset,

> +	.init = dwxgmac4_dma_init,
> +	.init_chan = dwxgmac2_dma_init_chan,
> +	.init_rx_chan = dwxgmac4_dma_init_rx_chan,
> +	.init_tx_chan = dwxgmac4_dma_init_tx_chan,

dw25gmac_dma_init, dw25gmac_dma_init_rx_chan, dw25gmac_dma_init_tx_chan?

> +	.axi = dwxgmac2_dma_axi,
> +	.dump_regs = dwxgmac2_dma_dump_regs,
> +	.dma_rx_mode = dwxgmac2_dma_rx_mode,
> +	.dma_tx_mode = dwxgmac2_dma_tx_mode,
> +	.enable_dma_irq = dwxgmac2_enable_dma_irq,
> +	.disable_dma_irq = dwxgmac2_disable_dma_irq,
> +	.start_tx = dwxgmac2_dma_start_tx,
> +	.stop_tx = dwxgmac2_dma_stop_tx,
> +	.start_rx = dwxgmac2_dma_start_rx,
> +	.stop_rx = dwxgmac2_dma_stop_rx,
> +	.dma_interrupt = dwxgmac2_dma_interrupt,
> +	.get_hw_feature = dwxgmac2_get_hw_feature,
> +	.rx_watchdog = dwxgmac2_rx_watchdog,
> +	.set_rx_ring_len = dwxgmac2_set_rx_ring_len,
> +	.set_tx_ring_len = dwxgmac2_set_tx_ring_len,
> +	.set_rx_tail_ptr = dwxgmac2_set_rx_tail_ptr,
> +	.set_tx_tail_ptr = dwxgmac2_set_tx_tail_ptr,
> +	.enable_tso = dwxgmac2_enable_tso,
> +	.qmode = dwxgmac2_qmode,
> +	.set_bfsize = dwxgmac2_set_bfsize,
> +	.enable_sph = dwxgmac2_enable_sph,
> +	.enable_tbs = dwxgmac2_enable_tbs,
> +};

> diff --git a/drivers/net/ethernet/stmicro/stmmac/dwxgmac4.c b/drivers/net/ethernet/stmicro/stmmac/dwxgmac4.c
> new file mode 100644
> index 000000000000..9c8748122dc6
> --- /dev/null
> +++ b/drivers/net/ethernet/stmicro/stmmac/dwxgmac4.c

dw25gmac.c?

> @@ -0,0 +1,142 @@
> +// SPDX-License-Identifier: GPL-2.0-only
> +/*
> + * Copyright (c) 2024 Broadcom Corporation
> + */
> +#include "dwxgmac2.h"

> +#include "dwxgmac4.h"

dw25gmac.h?

> +
> +static int rd_dma_ch_ind(void __iomem *ioaddr, u8 mode, u32 channel)
> +{
> +	u32 reg_val = 0;
> +	u32 val = 0;
> +
> +	reg_val |= mode << XGMAC4_MSEL_SHIFT & XGMAC4_MODE_SELECT;
> +	reg_val |= channel << XGMAC4_AOFF_SHIFT & XGMAC4_ADDR_OFFSET;
> +	reg_val |= XGMAC4_CMD_TYPE | XGMAC4_OB;
> +	writel(reg_val, ioaddr + XGMAC4_DMA_CH_IND_CONTROL);
> +	val = readl(ioaddr + XGMAC4_DMA_CH_IND_DATA);
> +	return val;
> +}
> +
> +static void wr_dma_ch_ind(void __iomem *ioaddr, u8 mode, u32 channel, u32 val)
> +{
> +	u32 reg_val = 0;
> +
> +	writel(val, ioaddr + XGMAC4_DMA_CH_IND_DATA);
> +	reg_val |= mode << XGMAC4_MSEL_SHIFT & XGMAC4_MODE_SELECT;
> +	reg_val |= channel << XGMAC4_AOFF_SHIFT & XGMAC4_ADDR_OFFSET;
> +	reg_val |= XGMAC_OB;
> +	writel(reg_val, ioaddr + XGMAC4_DMA_CH_IND_CONTROL);
> +}
> +

> +static void xgmac4_tp2tc_map(void __iomem *ioaddr, u8 pdma_ch, u32 tc_num)
> +{
> +	u32 val = 0;
> +
> +	val = rd_dma_ch_ind(ioaddr, MODE_TXEXTCFG, pdma_ch);
> +	val &= ~XGMAC4_TP2TCMP;
> +	val |= tc_num << XGMAC4_TP2TCMP_SHIFT & XGMAC4_TP2TCMP;
> +	wr_dma_ch_ind(ioaddr, MODE_TXEXTCFG, pdma_ch, val);
> +}
> +
> +static void xgmac4_rp2tc_map(void __iomem *ioaddr, u8 pdma_ch, u32 tc_num)
> +{
> +	u32 val = 0;
> +
> +	val = rd_dma_ch_ind(ioaddr, MODE_RXEXTCFG, pdma_ch);
> +	val &= ~XGMAC4_RP2TCMP;
> +	val |= tc_num << XGMAC4_RP2TCMP_SHIFT & XGMAC4_RP2TCMP;
> +	wr_dma_ch_ind(ioaddr, MODE_RXEXTCFG, pdma_ch, val);
> +}

What does "tc" stand for? Traffic control? If it's a kind of queue
then what about implementing the stmmac_ops::map_mtl_to_dma interface
method?

> +
> +void dwxgmac4_dma_init(void __iomem *ioaddr,
> +		       struct stmmac_dma_cfg *dma_cfg, int atds)
> +{
> +	u32 value;
> +	u32 i;
> +
> +	value = readl(ioaddr + XGMAC_DMA_SYSBUS_MODE);
> +
> +	if (dma_cfg->aal)
> +		value |= XGMAC_AAL;
> +
> +	if (dma_cfg->eame)
> +		value |= XGMAC_EAME;
> +
> +	writel(value, ioaddr + XGMAC_DMA_SYSBUS_MODE);
> +
> +	for (i = 0; i < VDMA_TOTAL_CH_COUNT; i++) {

> +		value = rd_dma_ch_ind(ioaddr, MODE_TXDESCCTRL, i);
> +		value &= ~XGMAC4_TXDCSZ;
> +		value |= 0x3;
> +		value &= ~XGMAC4_TDPS;
> +		value |= (3 << XGMAC4_TDPS_SHIFT) & XGMAC4_TDPS;
> +		wr_dma_ch_ind(ioaddr, MODE_TXDESCCTRL, i, value);
> +
> +		value = rd_dma_ch_ind(ioaddr, MODE_RXDESCCTRL, i);
> +		value &= ~XGMAC4_RXDCSZ;
> +		value |= 0x3;
> +		value &= ~XGMAC4_RDPS;
> +		value |= (3 << XGMAC4_RDPS_SHIFT) & XGMAC4_RDPS;
> +		wr_dma_ch_ind(ioaddr, MODE_RXDESCCTRL, i, value);

I know that the TDPS/RDPS means Tx/Rx Descriptor Pre-fetch threshold
Size. What does the TXDCSZ/RXDCSZ config mean?

Most importantly why are these parameters hardcoded to 3? It
doesn't seem right.

> +	}
> +

> +	for (i = 0; i < PDMA_TX_CH_COUNT; i++) {
> +		value = rd_dma_ch_ind(ioaddr, MODE_TXEXTCFG, i);
> +		value &= ~(XGMAC4_TXPBL | XGMAC4_TPBLX8_MODE);
> +		if (dma_cfg->pblx8)
> +			value |= XGMAC4_TPBLX8_MODE;
> +		value |= (dma_cfg->pbl << XGMAC4_TXPBL_SHIFT) & XGMAC4_TXPBL;
> +		wr_dma_ch_ind(ioaddr, MODE_TXEXTCFG, i, value);
> +		xgmac4_tp2tc_map(ioaddr, i, i);
> +	}
> +
> +	for (i = 0; i < PDMA_RX_CH_COUNT; i++) {
> +		value = rd_dma_ch_ind(ioaddr, MODE_RXEXTCFG, i);
> +		value &= ~(XGMAC4_RXPBL | XGMAC4_RPBLX8_MODE);
> +		if (dma_cfg->pblx8)
> +			value |= XGMAC4_RPBLX8_MODE;
> +		value |= (dma_cfg->pbl << XGMAC4_RXPBL_SHIFT) & XGMAC4_RXPBL;
> +		wr_dma_ch_ind(ioaddr, MODE_RXEXTCFG, i, value);
> +		if (i < PDMA_MAX_TC_COUNT)
> +			xgmac4_rp2tc_map(ioaddr, i, i);
> +		else
> +			xgmac4_rp2tc_map(ioaddr, i, PDMA_MAX_TC_COUNT - 1);
> +	}

Shouldn't these initialization be done on the per-channel basis only
for only activated queues
plat_stmmacenet_data::{rx_queues_to_use,tx_queues_to_use} (the STMMAC
driver one-on-one maps queues and DMA-channels if no custom mapping
was specified)?

> +}
> +
> +void dwxgmac4_dma_init_tx_chan(struct stmmac_priv *priv,
> +			       void __iomem *ioaddr,
> +			       struct stmmac_dma_cfg *dma_cfg,
> +			       dma_addr_t dma_addr, u32 chan)
> +{
> +	u32 value;
> +
> +	value = readl(ioaddr + XGMAC_DMA_CH_TX_CONTROL(chan));
> +	value &= ~XGMAC4_TVDMA2TCMP;
> +	value |= (chan << XGMAC4_TVDMA2TCMP_SHIFT) & XGMAC4_TVDMA2TCMP;
> +	writel(value, ioaddr + XGMAC_DMA_CH_TX_CONTROL(chan));
> +
> +	writel(upper_32_bits(dma_addr),
> +	       ioaddr + XGMAC_DMA_CH_TxDESC_HADDR(chan));
> +	writel(lower_32_bits(dma_addr),
> +	       ioaddr + XGMAC_DMA_CH_TxDESC_LADDR(chan));
> +}
> +
> +void dwxgmac4_dma_init_rx_chan(struct stmmac_priv *priv,
> +			       void __iomem *ioaddr,
> +			       struct stmmac_dma_cfg *dma_cfg,
> +			       dma_addr_t dma_addr, u32 chan)
> +{
> +	u32 value;
> +
> +	value = readl(ioaddr + XGMAC_DMA_CH_RX_CONTROL(chan));
> +	value &= ~XGMAC4_RVDMA2TCMP;
> +	value |= (chan << XGMAC4_RVDMA2TCMP_SHIFT) & XGMAC4_RVDMA2TCMP;
> +	writel(value, ioaddr + XGMAC_DMA_CH_RX_CONTROL(chan));
> +
> +	writel(upper_32_bits(dma_addr),
> +	       ioaddr + XGMAC_DMA_CH_RxDESC_HADDR(chan));
> +	writel(lower_32_bits(dma_addr),
> +	       ioaddr + XGMAC_DMA_CH_RxDESC_LADDR(chan));
> +}
> diff --git a/drivers/net/ethernet/stmicro/stmmac/dwxgmac4.h b/drivers/net/ethernet/stmicro/stmmac/dwxgmac4.h
> new file mode 100644
> index 000000000000..0ce1856b0b34
> --- /dev/null

> +++ b/drivers/net/ethernet/stmicro/stmmac/dwxgmac4.h

dw25gmac.h?

> @@ -0,0 +1,84 @@
> +/* SPDX-License-Identifier: GPL-2.0-only */
> +/* Copyright (c) 2024 Broadcom Corporation
> + * XGMAC4 definitions.
> + */
> +#ifndef __STMMAC_DWXGMAC4_H__
> +#define __STMMAC_DWXGMAC4_H__
> +
> +/* DMA Indirect Registers*/

> +#define XGMAC4_DMA_CH_IND_CONTROL	0X00003080

XXVGMAC_*?

> +#define XGMAC4_MODE_SELECT		GENMASK(27, 24)
> +#define XGMAC4_MSEL_SHIFT		24
> +enum dma_ch_ind_modes {
> +	MODE_TXEXTCFG	 = 0x0,	  /* Tx Extended Config */
> +	MODE_RXEXTCFG	 = 0x1,	  /* Rx Extended Config */
> +	MODE_TXDBGSTS	 = 0x2,	  /* Tx Debug Status */
> +	MODE_RXDBGSTS	 = 0x3,	  /* Rx Debug Status */
> +	MODE_TXDESCCTRL	 = 0x4,	  /* Tx Descriptor control */
> +	MODE_RXDESCCTRL	 = 0x5,	  /* Rx Descriptor control */
> +};
> +
> +#define XGMAC4_ADDR_OFFSET		GENMASK(14, 8)
> +#define XGMAC4_AOFF_SHIFT		8
> +#define XGMAC4_AUTO_INCR		GENMASK(5, 4)
> +#define XGMAC4_AUTO_SHIFT		4
> +#define XGMAC4_CMD_TYPE			BIT(1)
> +#define XGMAC4_OB			BIT(0)
> +#define XGMAC4_DMA_CH_IND_DATA		0X00003084
> +
> +/* TX Config definitions */
> +#define XGMAC4_TXPBL			GENMASK(29, 24)
> +#define XGMAC4_TXPBL_SHIFT		24
> +#define XGMAC4_TPBLX8_MODE		BIT(19)
> +#define XGMAC4_TP2TCMP			GENMASK(18, 16)
> +#define XGMAC4_TP2TCMP_SHIFT		16
> +#define XGMAC4_ORRQ			GENMASK(13, 8)
> +/* RX Config definitions */
> +#define XGMAC4_RXPBL			GENMASK(29, 24)
> +#define XGMAC4_RXPBL_SHIFT		24
> +#define XGMAC4_RPBLX8_MODE		BIT(19)
> +#define XGMAC4_RP2TCMP			GENMASK(18, 16)
> +#define XGMAC4_RP2TCMP_SHIFT		16
> +#define XGMAC4_OWRQ			GENMASK(13, 8)
> +/* Tx Descriptor control */
> +#define XGMAC4_TXDCSZ			GENMASK(2, 0)
> +#define XGMAC4_TDPS			GENMASK(5, 3)
> +#define XGMAC4_TDPS_SHIFT		3
> +/* Rx Descriptor control */
> +#define XGMAC4_RXDCSZ			GENMASK(2, 0)
> +#define XGMAC4_RDPS			GENMASK(5, 3)
> +#define XGMAC4_RDPS_SHIFT		3
> +
> +/* DWCXG_DMA_CH(#i) Registers*/
> +#define XGMAC4_DSL			GENMASK(20, 18)
> +#define XGMAC4_MSS			GENMASK(13, 0)
> +#define XGMAC4_TFSEL			GENMASK(30, 29)
> +#define XGMAC4_TQOS			GENMASK(27, 24)
> +#define XGMAC4_IPBL			BIT(15)
> +#define XGMAC4_TVDMA2TCMP		GENMASK(6, 4)
> +#define XGMAC4_TVDMA2TCMP_SHIFT		4
> +#define XGMAC4_RPF			BIT(31)
> +#define XGMAC4_RVDMA2TCMP		GENMASK(30, 28)
> +#define XGMAC4_RVDMA2TCMP_SHIFT		28
> +#define XGMAC4_RQOS			GENMASK(27, 24)
> +

> +/* PDMA Channel count */
> +#define PDMA_TX_CH_COUNT		8
> +#define PDMA_RX_CH_COUNT		10
> +#define PDMA_MAX_TC_COUNT		8
> +
> +/* VDMA channel count */
> +#define VDMA_TOTAL_CH_COUNT		32

These seems like the vendor-specific constant. What are the actual DW
25GMAC constraints?

-Serge(y)

> +
> +void dwxgmac4_dma_init(void __iomem *ioaddr,
> +		       struct stmmac_dma_cfg *dma_cfg, int atds);
> +
> +void dwxgmac4_dma_init_tx_chan(struct stmmac_priv *priv,
> +			       void __iomem *ioaddr,
> +			       struct stmmac_dma_cfg *dma_cfg,
> +			       dma_addr_t dma_addr, u32 chan);
> +void dwxgmac4_dma_init_rx_chan(struct stmmac_priv *priv,
> +			       void __iomem *ioaddr,
> +			       struct stmmac_dma_cfg *dma_cfg,
> +			       dma_addr_t dma_addr, u32 chan);
> +#endif /* __STMMAC_DWXGMAC4_H__ */
> -- 
> 2.34.1
> 
> 


^ permalink raw reply	[flat|nested] 30+ messages in thread

* Re: [PATCH net-next v3 2/3] net: stmmac: Integrate dwxgmac4 into stmmac hwif handling
  2024-08-02  3:18 ` [PATCH net-next v3 2/3] net: stmmac: Integrate dwxgmac4 into stmmac hwif handling jitendra.vegiraju
  2024-08-02  8:23   ` Russell King (Oracle)
  2024-08-02 22:59   ` Andrew Lunn
@ 2024-08-06 22:14   ` Serge Semin
  2024-08-09  1:17     ` Jitendra Vegiraju
  2 siblings, 1 reply; 30+ messages in thread
From: Serge Semin @ 2024-08-06 22:14 UTC (permalink / raw)
  To: jitendra.vegiraju
  Cc: netdev, alexandre.torgue, joabreu, davem, edumazet, kuba, pabeni,
	mcoquelin.stm32, bcm-kernel-feedback-list, richardcochran, ast,
	daniel, hawk, john.fastabend, linux-kernel, linux-stm32,
	linux-arm-kernel, bpf, andrew, linux, horms, florian.fainelli

On Thu, Aug 01, 2024 at 08:18:21PM -0700, jitendra.vegiraju@broadcom.com wrote:
> From: Jitendra Vegiraju <jitendra.vegiraju@broadcom.com>
> 
> Integrate dwxgmac4 support into stmmac hardware interface handling.
> A dwxgmac4 is an xgmac device and hence it inherits properties from
> existing stmmac_hw table entry.
> The quirks handling facility is used to update dma_ops field to
> point to dwxgmac400_dma_ops when the user version field matches.
> 
> Signed-off-by: Jitendra Vegiraju <jitendra.vegiraju@broadcom.com>
> ---
>  drivers/net/ethernet/stmicro/stmmac/common.h |  4 +++
>  drivers/net/ethernet/stmicro/stmmac/hwif.c   | 26 +++++++++++++++++++-
>  drivers/net/ethernet/stmicro/stmmac/hwif.h   |  1 +
>  3 files changed, 30 insertions(+), 1 deletion(-)
> 
> diff --git a/drivers/net/ethernet/stmicro/stmmac/common.h b/drivers/net/ethernet/stmicro/stmmac/common.h
> index cd36ff4da68c..9bf278e11704 100644
> --- a/drivers/net/ethernet/stmicro/stmmac/common.h
> +++ b/drivers/net/ethernet/stmicro/stmmac/common.h
> @@ -37,11 +37,15 @@
>  #define DWXGMAC_CORE_2_10	0x21
>  #define DWXGMAC_CORE_2_20	0x22
>  #define DWXLGMAC_CORE_2_00	0x20

> +#define DWXGMAC_CORE_4_00	0x40

DW25GMAC_CORE_4_00?

>  
>  /* Device ID */
>  #define DWXGMAC_ID		0x76

What is the device ID in your case? Does it match to DWXGMAC_ID?

>  #define DWXLGMAC_ID		0x27
>  
> +/* User Version */
> +#define DWXGMAC_USER_VER_X22	0x22
> +
>  #define STMMAC_CHAN0	0	/* Always supported and default for all chips */
>  
>  /* TX and RX Descriptor Length, these need to be power of two.
> diff --git a/drivers/net/ethernet/stmicro/stmmac/hwif.c b/drivers/net/ethernet/stmicro/stmmac/hwif.c
> index 29367105df54..713cb5aa2c3e 100644
> --- a/drivers/net/ethernet/stmicro/stmmac/hwif.c
> +++ b/drivers/net/ethernet/stmicro/stmmac/hwif.c
> @@ -36,6 +36,18 @@ static u32 stmmac_get_dev_id(struct stmmac_priv *priv, u32 id_reg)
>  	return (reg & GENMASK(15, 8)) >> 8;
>  }
>  

> +static u32 stmmac_get_user_version(struct stmmac_priv *priv, u32 id_reg)
> +{
> +	u32 reg = readl(priv->ioaddr + id_reg);
> +
> +	if (!reg) {
> +		dev_info(priv->device, "User Version not available\n");
> +		return 0x0;
> +	}
> +
> +	return (reg & GENMASK(23, 16)) >> 16;
> +}
> +

The User Version is purely a vendor-specific stuff defined on the
IP-core synthesis stage. Moreover I don't see you'll need it anyway.

>  static void stmmac_dwmac_mode_quirk(struct stmmac_priv *priv)
>  {
>  	struct mac_device_info *mac = priv->hw;
> @@ -82,6 +94,18 @@ static int stmmac_dwmac4_quirks(struct stmmac_priv *priv)
>  	return 0;
>  }
>  

> +static int stmmac_dwxgmac_quirks(struct stmmac_priv *priv)
> +{
> +	struct mac_device_info *mac = priv->hw;
> +	u32 user_ver;
> +
> +	user_ver = stmmac_get_user_version(priv, GMAC4_VERSION);
> +	if (priv->synopsys_id == DWXGMAC_CORE_4_00 &&
> +	    user_ver == DWXGMAC_USER_VER_X22)
> +		mac->dma = &dwxgmac400_dma_ops;
> +	return 0;
> +}
> +
>  static int stmmac_dwxlgmac_quirks(struct stmmac_priv *priv)
>  {
>  	priv->hw->xlgmac = true;
> @@ -256,7 +280,7 @@ static const struct stmmac_hwif_entry {
>  		.mmc = &dwxgmac_mmc_ops,
>  		.est = &dwmac510_est_ops,
>  		.setup = dwxgmac2_setup,
> -		.quirks = NULL,
> +		.quirks = stmmac_dwxgmac_quirks,

Why? You can just introduce a new stmmac_hw[] entry with the DW
25GMAC-specific stmmac_dma_ops instance specified.

-Serge(y)

>  	}, {
>  		.gmac = false,
>  		.gmac4 = false,
> diff --git a/drivers/net/ethernet/stmicro/stmmac/hwif.h b/drivers/net/ethernet/stmicro/stmmac/hwif.h
> index e53c32362774..6213c496385c 100644
> --- a/drivers/net/ethernet/stmicro/stmmac/hwif.h
> +++ b/drivers/net/ethernet/stmicro/stmmac/hwif.h
> @@ -683,6 +683,7 @@ extern const struct stmmac_desc_ops dwxgmac210_desc_ops;
>  extern const struct stmmac_mmc_ops dwmac_mmc_ops;
>  extern const struct stmmac_mmc_ops dwxgmac_mmc_ops;
>  extern const struct stmmac_est_ops dwmac510_est_ops;
> +extern const struct stmmac_dma_ops dwxgmac400_dma_ops;
>  
>  #define GMAC_VERSION		0x00000020	/* GMAC CORE Version */
>  #define GMAC4_VERSION		0x00000110	/* GMAC4+ CORE Version */
> -- 
> 2.34.1
> 
> 


^ permalink raw reply	[flat|nested] 30+ messages in thread

* Re: [PATCH net-next v3 2/3] net: stmmac: Integrate dwxgmac4 into stmmac hwif handling
  2024-08-06  0:36     ` Jitendra Vegiraju
@ 2024-08-06 23:13       ` Andrew Lunn
  2024-08-09  1:49         ` Jitendra Vegiraju
  0 siblings, 1 reply; 30+ messages in thread
From: Andrew Lunn @ 2024-08-06 23:13 UTC (permalink / raw)
  To: Jitendra Vegiraju
  Cc: netdev, alexandre.torgue, joabreu, davem, edumazet, kuba, pabeni,
	mcoquelin.stm32, bcm-kernel-feedback-list, richardcochran, ast,
	daniel, hawk, john.fastabend, linux-kernel, linux-stm32,
	linux-arm-kernel, bpf, linux, horms, florian.fainelli

On Mon, Aug 05, 2024 at 05:36:30PM -0700, Jitendra Vegiraju wrote:
> Hi Andrew,
> On Fri, Aug 2, 2024 at 3:59 PM Andrew Lunn <andrew@lunn.ch> wrote:
> >
> > > +     user_ver = stmmac_get_user_version(priv, GMAC4_VERSION);
> > > +     if (priv->synopsys_id == DWXGMAC_CORE_4_00 &&
> > > +         user_ver == DWXGMAC_USER_VER_X22)
> > > +             mac->dma = &dwxgmac400_dma_ops;
> >
> > I know nothing about this hardware....
> >
> > Does priv->synopsys_id == DWXGMAC_CORE_4_0 not imply
> > dwxgmac400_dma_ops?
> >
> > Could a user synthesise DWXGMAC_CORE_4_00 without using
> > dwxgmac400_dma_ops? Could dwxgmac500_dma_ops or dwxgmac100_dma_ops be
> > used?
> Yes, the user can choose between Enhanced DMA , Hyper DMA , Normal DMA.
> This SoC support has chosen Hyper DMA for future expandability.

Is there a register which describes the synthesis configuration? It is
much better that the hardware tells us what it is, rather than having
to expand this condition for every new devices which gets added.

Also, what is the definition of user_ver. Can we guarantee this is
unique and can actually be used to determine what DMA variant has been
synthesised?

	Andrew


^ permalink raw reply	[flat|nested] 30+ messages in thread

* Re: [PATCH net-next v3 3/3] net: stmmac: Add PCI driver support for BCM8958x
  2024-08-06  0:56     ` Jitendra Vegiraju
@ 2024-08-06 23:15       ` Andrew Lunn
  2024-08-09  1:54         ` Jitendra Vegiraju
  0 siblings, 1 reply; 30+ messages in thread
From: Andrew Lunn @ 2024-08-06 23:15 UTC (permalink / raw)
  To: Jitendra Vegiraju
  Cc: netdev, alexandre.torgue, joabreu, davem, edumazet, kuba, pabeni,
	mcoquelin.stm32, bcm-kernel-feedback-list, richardcochran, ast,
	daniel, hawk, john.fastabend, linux-kernel, linux-stm32,
	linux-arm-kernel, bpf, linux, horms, florian.fainelli

On Mon, Aug 05, 2024 at 05:56:43PM -0700, Jitendra Vegiraju wrote:
> On Fri, Aug 2, 2024 at 4:08 PM Andrew Lunn <andrew@lunn.ch> wrote:
> >
> > > Management of integrated ethernet switch on this SoC is not handled by
> > > the PCIe interface.
> >
> > MDIO? SPI? I2C?
> >
> The device uses SPI interface. The switch has internal ARM M7 for
> controller firmware.

Will there be a DSA driver sometime soon talking over SPI to the
firmware?

	Andrew


^ permalink raw reply	[flat|nested] 30+ messages in thread

* Re: [PATCH net-next v3 0/3] net: stmmac: Add PCI driver support for BCM8958x
  2024-08-05 22:43     ` Serge Semin
@ 2024-08-08 23:03       ` Jitendra Vegiraju
  0 siblings, 0 replies; 30+ messages in thread
From: Jitendra Vegiraju @ 2024-08-08 23:03 UTC (permalink / raw)
  To: Serge Semin
  Cc: netdev, alexandre.torgue, joabreu, davem, edumazet, kuba, pabeni,
	mcoquelin.stm32, bcm-kernel-feedback-list, richardcochran, ast,
	daniel, hawk, john.fastabend, linux-kernel, linux-stm32,
	linux-arm-kernel, bpf, andrew, linux, horms, florian.fainelli

On Mon, Aug 5, 2024 at 3:43 PM Serge Semin <fancer.lancer@gmail.com> wrote:
>
> On Fri, Aug 02, 2024 at 03:06:05PM -0700, Jitendra Vegiraju wrote:
> > On Fri, Aug 2, 2024 at 3:02 AM Serge Semin <fancer.lancer@gmail.com> wrote:
> > >
> > > Hi Jitendra
> > >
> > > On Thu, Aug 01, 2024 at 08:18:19PM -0700, jitendra.vegiraju@broadcom.com wrote:
> > > > From: Jitendra Vegiraju <jitendra.vegiraju@broadcom.com>
> > > >
> > > > This patchset adds basic PCI ethernet device driver support for Broadcom
> > > > BCM8958x Automotive Ethernet switch SoC devices.
> > > >
> > > > This SoC device has PCIe ethernet MAC attached to an integrated ethernet
> > > > switch using XGMII interface. The PCIe ethernet controller is presented to
> > > > the Linux host as PCI network device.
> > > >
> > > > The following block diagram gives an overview of the application.
> > > >              +=================================+
> > > >              |       Host CPU/Linux            |
> > > >              +=================================+
> > > >                         || PCIe
> > > >                         ||
> > > >         +==========================================+
> > > >         |           +--------------+               |
> > > >         |           | PCIE Endpoint|               |
> > > >         |           | Ethernet     |               |
> > > >         |           | Controller   |               |
> > > >         |           |   DMA        |               |
> > > >         |           +--------------+               |
> > > >         |           |   MAC        |   BCM8958X    |
> > > >         |           +--------------+   SoC         |
> > > >         |               || XGMII                   |
> > > >         |               ||                         |
> > > >         |           +--------------+               |
> > > >         |           | Ethernet     |               |
> > > >         |           | switch       |               |
> > > >         |           +--------------+               |
> > > >         |             || || || ||                  |
> > > >         +==========================================+
> > > >                       || || || || More external interfaces
> > > >
> > > > The MAC block on BCM8958x is based on Synopsis XGMAC 4.00a core. This
> > > > driver uses common dwxgmac2 code where applicable.
> > >
> > > Thanks for submitting the series.
> > >
> > > I am curious how come Broadcom got to use an IP-core which hasn't
> > > been even announced by Synopsys. AFAICS the most modern DW XGMAC
> > > IP-core is of v3.xxa version:
> > >
> > > https://www.synopsys.com/dw/ipdir.php?ds=dwc_ether_xgmac
> > >
>
> > I am not sure why the 4.00a IP-code is not announced for general
> > availability yet.
> > The Synopsis documentation for this IP mentions 3.xx IP as reference
> > for this design and lists
> > new features for 4.00a.
> >
> > > Are you sure that your device isn't equipped with some another DW MAC
> > > IP-core, like DW 25G Ethernet MAC? (which BTW is equipped with a new
> > > Hyper DMA engine with a capability to have up to 128/256 channels with
> > > likely indirect addressing.) Do I miss something?
> > >
> > Yes, I briefly mentioned the new DMA architecture in the commit log
> > for patch 1/3.
> > You are correct, the name for the new DMA engine is Hyper DMA. It
> > probably started with some 3.xx IP-Core.
> > This DW-MAC is capable of 25G, but this SOC is not using 25G support.
>
> Then what you have is likely the DW 25GMAC since just DW XGMAC hasn't
> been announced to have neither 25G speed nor the Hyper-DMA with the
> virtualization channels capabilities. Meanwhile the former IP-core
> does have these features:
> https://www.synopsys.com/dw/ipdir.php?ds=dwc_25g_ethernet_mac_ip
>
> Alas I don't have the DW 25GMAC IP-core databook to say for sure, but
> that's the only explanation of why you have the 0x40 Synopsys ID and
> the IP-core version of v4.00a, and the 25G capability of the MAC.
>
> Seeing Synopsys tends to re-use the CSRs mapping even across the major
> IP-core releases it isn't that surprising that the DW XGMAC 3.xx
> IP-core was referenced in the doc. (See the driver, DW XLGMAC is
> almost fully compatible with the DW XGMAC CSRs mapping.)
>
> Moreover the most DMA-capable device currently supported by the
> STMMAC-driver is DW XGMAC/XLGMAC and it can't have more than 16
> DMA-channels. That allows to directly map all the channels CSRs to the
> system memory. But your case is different. The DW 25GMAC IP-core is
> announced to support virtualization up to 128/256 channels, for which
> the direct CSRs mapping could require 16-times more memory. That's
> likely why the indirect addressing was implemented to access the
> settings of all the possible channels. That's also implicitly proofs
> that you have the DW 25GMAC IP-core.
Hi Serge(y)

Thanks for reviewing the patch series.
Sorry for the delay in my response. We waited for a clarification on
the IP version.
Its confirmed that we got an early adapter version of 25GMAC IP-Core.
Added more details in the context of other questions in Patch 1,2.
>
> -Serge(y)
>
> >
> > > * I'll join the patch set review after the weekend, sometime on the
> > > next week.
> > >
> > > -Serge(y)
> > >
> > > > Driver functionality specific to this MAC is implemented in dwxgmac4.c.
> > > > Management of integrated ethernet switch on this SoC is not handled by
> > > > the PCIe interface.
> > > > This SoC device has PCIe ethernet MAC directly attached to an integrated
> > > > ethernet switch using XGMII interface.
> > > >
> > > > v2->v3:
> > > >    Addressed v2 comments from Andrew, Jakub, Russel and Simon.
> > > >    Based on suggestion by Russel and Andrew, added software node to create
> > > >    phylink in fixed-link mode.
> > > >    Moved dwxgmac4 specific functions to new files dwxgmac4.c and dwxgmac4.h
> > > >    in stmmac core module.
> > > >    Reorganized the code to use the existing glue logic support for xgmac in
> > > >    hwif.c and override ops functions for dwxgmac4 specific functions.
> > > >    The patch is split into three parts.
> > > >      Patch#1 Adds dma_ops for dwxgmac4 in stmmac core
> > > >      Patch#2 Hooks in the hardware interface handling for dwxgmac4
> > > >      Patch#3 Adds PCI driver for BCM8958x device
> > > >
> > > > v1->v2:
> > > >    Minor fixes to address coding style issues.
> > > >    Sent v2 too soon by mistake, without waiting for review comments.
> > > >    Received feedback on this version.
> > > >    https://lore.kernel.org/netdev/20240511015924.41457-1-jitendra.vegiraju@broadcom.com/
> > > >
> > > > v1:
> > > >    https://lore.kernel.org/netdev/20240510000331.154486-1-jitendra.vegiraju@broadcom.com/
> > > >
> > > > Jitendra Vegiraju (3):
> > > >   Add basic dwxgmac4 support to stmmac core
> > > >   Integrate dwxgmac4 into stmmac hwif handling
> > > >   Add PCI driver support for BCM8958x
> > > >
> > > >  MAINTAINERS                                   |   8 +
> > > >  drivers/net/ethernet/stmicro/stmmac/Kconfig   |  11 +
> > > >  drivers/net/ethernet/stmicro/stmmac/Makefile  |   3 +-
> > > >  drivers/net/ethernet/stmicro/stmmac/common.h  |   4 +
> > > >  .../net/ethernet/stmicro/stmmac/dwmac-brcm.c  | 517 ++++++++++++++++++
> > > >  .../ethernet/stmicro/stmmac/dwxgmac2_dma.c    |  31 ++
> > > >  .../net/ethernet/stmicro/stmmac/dwxgmac4.c    | 142 +++++
> > > >  .../net/ethernet/stmicro/stmmac/dwxgmac4.h    |  84 +++
> > > >  drivers/net/ethernet/stmicro/stmmac/hwif.c    |  26 +-
> > > >  drivers/net/ethernet/stmicro/stmmac/hwif.h    |   1 +
> > > >  10 files changed, 825 insertions(+), 2 deletions(-)
> > > >  create mode 100644 drivers/net/ethernet/stmicro/stmmac/dwmac-brcm.c
> > > >  create mode 100644 drivers/net/ethernet/stmicro/stmmac/dwxgmac4.c
> > > >  create mode 100644 drivers/net/ethernet/stmicro/stmmac/dwxgmac4.h
> > > >
> > > > --
> > > > 2.34.1
> > > >
> > > >


^ permalink raw reply	[flat|nested] 30+ messages in thread

* Re: [PATCH net-next v3 1/3] net: stmmac: Add basic dwxgmac4 support to stmmac core
  2024-08-06 21:56   ` Serge Semin
@ 2024-08-09  0:41     ` Jitendra Vegiraju
  0 siblings, 0 replies; 30+ messages in thread
From: Jitendra Vegiraju @ 2024-08-09  0:41 UTC (permalink / raw)
  To: Serge Semin
  Cc: netdev, alexandre.torgue, joabreu, davem, edumazet, kuba, pabeni,
	mcoquelin.stm32, bcm-kernel-feedback-list, richardcochran, ast,
	daniel, hawk, john.fastabend, linux-kernel, linux-stm32,
	linux-arm-kernel, bpf, andrew, linux, horms, florian.fainelli

Resending the message since my earlier email turned-in to HTML because of an
attempt to draw asciiart.
On Tue, Aug 6, 2024 at 2:56 PM Serge Semin <fancer.lancer@gmail.com> wrote:
>
> On Thu, Aug 01, 2024 at 08:18:20PM -0700, jitendra.vegiraju@broadcom.com wrote:
> > From: Jitendra Vegiraju <jitendra.vegiraju@broadcom.com>
> >
> > Adds support for DWC_xgmac version 4.00a in stmmac core module.
> > This version adds enhancements to DMA architecture for virtualization
> > scalability. This is realized by decoupling physical DMA channels (PDMA)
> > from Virtual DMA channels (VDMA). The  VDMAs are software abastractions
> > that map to PDMAs for frame transmission and reception.
> >
> > The virtualization enhancements are currently not being used and hence
> > a fixed mapping of VDMA to PDMA is configured in the init functions.
> > Because of the new init functions, a new instance of struct stmmac_dma_ops
> > dwxgmac400_dma_ops is added.
> > Most of the other dma operation functions in existing dwxgamc2_dma.c file
> > can be reused.
>
> As we figured out (didn't we?) that it's actually the DW 25GMAC, then
> it should be taken into account across the entire series.
>
Yes, indeed its 25GMAC IP.
We got confirmation that we used an early adopter version of the 25GMAC IP.
The 25GMAC always come with HDMA DMA engine.
The synopsis revision id is 4.xx and device id is 0x55.
> >
> > Signed-off-by: Jitendra Vegiraju <jitendra.vegiraju@broadcom.com>
> > ---
> >  drivers/net/ethernet/stmicro/stmmac/Makefile  |   2 +-
> >  .../ethernet/stmicro/stmmac/dwxgmac2_dma.c    |  31 ++++
> >  .../net/ethernet/stmicro/stmmac/dwxgmac4.c    | 142 ++++++++++++++++++
> >  .../net/ethernet/stmicro/stmmac/dwxgmac4.h    |  84 +++++++++++
> >  4 files changed, 258 insertions(+), 1 deletion(-)
> >  create mode 100644 drivers/net/ethernet/stmicro/stmmac/dwxgmac4.c
> >  create mode 100644 drivers/net/ethernet/stmicro/stmmac/dwxgmac4.h
> >
> > diff --git a/drivers/net/ethernet/stmicro/stmmac/Makefile b/drivers/net/ethernet/stmicro/stmmac/Makefile
> > index c2f0e91f6bf8..2f637612513d 100644
> > --- a/drivers/net/ethernet/stmicro/stmmac/Makefile
> > +++ b/drivers/net/ethernet/stmicro/stmmac/Makefile
> > @@ -6,7 +6,7 @@ stmmac-objs:= stmmac_main.o stmmac_ethtool.o stmmac_mdio.o ring_mode.o        \
> >             mmc_core.o stmmac_hwtstamp.o stmmac_ptp.o dwmac4_descs.o  \
> >             dwmac4_dma.o dwmac4_lib.o dwmac4_core.o dwmac5.o hwif.o \
> >             stmmac_tc.o dwxgmac2_core.o dwxgmac2_dma.o dwxgmac2_descs.o \
> > -           stmmac_xdp.o stmmac_est.o \
>
> > +           stmmac_xdp.o stmmac_est.o dwxgmac4.o \
>
> dw25gmac.o?
We will rename all applicable reference to 25mac as you suggest for
the entire patch series.

>
> >             $(stmmac-y)
> >
> >  stmmac-$(CONFIG_STMMAC_SELFTESTS) += stmmac_selftests.o
> > diff --git a/drivers/net/ethernet/stmicro/stmmac/dwxgmac2_dma.c b/drivers/net/ethernet/stmicro/stmmac/dwxgmac2_dma.c
> > index dd2ab6185c40..c15f5247aaa8 100644
> > --- a/drivers/net/ethernet/stmicro/stmmac/dwxgmac2_dma.c
> > +++ b/drivers/net/ethernet/stmicro/stmmac/dwxgmac2_dma.c
> > @@ -7,6 +7,7 @@
> >  #include <linux/iopoll.h>
> >  #include "stmmac.h"
> >  #include "dwxgmac2.h"
>
> > +#include "dwxgmac4.h"
>
> "dw25gmac.h"?
>
> >
> >  static int dwxgmac2_dma_reset(void __iomem *ioaddr)
> >  {
> > @@ -641,3 +642,33 @@ const struct stmmac_dma_ops dwxgmac210_dma_ops = {
> >       .enable_sph = dwxgmac2_enable_sph,
> >       .enable_tbs = dwxgmac2_enable_tbs,
> >  };
> > +
>
> > +const struct stmmac_dma_ops dwxgmac400_dma_ops = {
>
> dw25gmac_dma_ops?
>
> > +     .reset = dwxgmac2_dma_reset,
>
> > +     .init = dwxgmac4_dma_init,
> > +     .init_chan = dwxgmac2_dma_init_chan,
> > +     .init_rx_chan = dwxgmac4_dma_init_rx_chan,
> > +     .init_tx_chan = dwxgmac4_dma_init_tx_chan,
>
> dw25gmac_dma_init, dw25gmac_dma_init_rx_chan, dw25gmac_dma_init_tx_chan?
>
> > +     .axi = dwxgmac2_dma_axi,
> > +     .dump_regs = dwxgmac2_dma_dump_regs,
> > +     .dma_rx_mode = dwxgmac2_dma_rx_mode,
> > +     .dma_tx_mode = dwxgmac2_dma_tx_mode,
> > +     .enable_dma_irq = dwxgmac2_enable_dma_irq,
> > +     .disable_dma_irq = dwxgmac2_disable_dma_irq,
> > +     .start_tx = dwxgmac2_dma_start_tx,
> > +     .stop_tx = dwxgmac2_dma_stop_tx,
> > +     .start_rx = dwxgmac2_dma_start_rx,
> > +     .stop_rx = dwxgmac2_dma_stop_rx,
> > +     .dma_interrupt = dwxgmac2_dma_interrupt,
> > +     .get_hw_feature = dwxgmac2_get_hw_feature,
> > +     .rx_watchdog = dwxgmac2_rx_watchdog,
> > +     .set_rx_ring_len = dwxgmac2_set_rx_ring_len,
> > +     .set_tx_ring_len = dwxgmac2_set_tx_ring_len,
> > +     .set_rx_tail_ptr = dwxgmac2_set_rx_tail_ptr,
> > +     .set_tx_tail_ptr = dwxgmac2_set_tx_tail_ptr,
> > +     .enable_tso = dwxgmac2_enable_tso,
> > +     .qmode = dwxgmac2_qmode,
> > +     .set_bfsize = dwxgmac2_set_bfsize,
> > +     .enable_sph = dwxgmac2_enable_sph,
> > +     .enable_tbs = dwxgmac2_enable_tbs,
> > +};
>
> > diff --git a/drivers/net/ethernet/stmicro/stmmac/dwxgmac4.c b/drivers/net/ethernet/stmicro/stmmac/dwxgmac4.c
> > new file mode 100644
> > index 000000000000..9c8748122dc6
> > --- /dev/null
> > +++ b/drivers/net/ethernet/stmicro/stmmac/dwxgmac4.c
>
> dw25gmac.c?
>
> > @@ -0,0 +1,142 @@
> > +// SPDX-License-Identifier: GPL-2.0-only
> > +/*
> > + * Copyright (c) 2024 Broadcom Corporation
> > + */
> > +#include "dwxgmac2.h"
>
> > +#include "dwxgmac4.h"
>
> dw25gmac.h?
>
> > +
> > +static int rd_dma_ch_ind(void __iomem *ioaddr, u8 mode, u32 channel)
> > +{
> > +     u32 reg_val = 0;
> > +     u32 val = 0;
> > +
> > +     reg_val |= mode << XGMAC4_MSEL_SHIFT & XGMAC4_MODE_SELECT;
> > +     reg_val |= channel << XGMAC4_AOFF_SHIFT & XGMAC4_ADDR_OFFSET;
> > +     reg_val |= XGMAC4_CMD_TYPE | XGMAC4_OB;
> > +     writel(reg_val, ioaddr + XGMAC4_DMA_CH_IND_CONTROL);
> > +     val = readl(ioaddr + XGMAC4_DMA_CH_IND_DATA);
> > +     return val;
> > +}
> > +
> > +static void wr_dma_ch_ind(void __iomem *ioaddr, u8 mode, u32 channel, u32 val)
> > +{
> > +     u32 reg_val = 0;
> > +
> > +     writel(val, ioaddr + XGMAC4_DMA_CH_IND_DATA);
> > +     reg_val |= mode << XGMAC4_MSEL_SHIFT & XGMAC4_MODE_SELECT;
> > +     reg_val |= channel << XGMAC4_AOFF_SHIFT & XGMAC4_ADDR_OFFSET;
> > +     reg_val |= XGMAC_OB;
> > +     writel(reg_val, ioaddr + XGMAC4_DMA_CH_IND_CONTROL);
> > +}
> > +
>
> > +static void xgmac4_tp2tc_map(void __iomem *ioaddr, u8 pdma_ch, u32 tc_num)
> > +{
> > +     u32 val = 0;
> > +
> > +     val = rd_dma_ch_ind(ioaddr, MODE_TXEXTCFG, pdma_ch);
> > +     val &= ~XGMAC4_TP2TCMP;
> > +     val |= tc_num << XGMAC4_TP2TCMP_SHIFT & XGMAC4_TP2TCMP;
> > +     wr_dma_ch_ind(ioaddr, MODE_TXEXTCFG, pdma_ch, val);
> > +}
> > +
> > +static void xgmac4_rp2tc_map(void __iomem *ioaddr, u8 pdma_ch, u32 tc_num)
> > +{
> > +     u32 val = 0;
> > +
> > +     val = rd_dma_ch_ind(ioaddr, MODE_RXEXTCFG, pdma_ch);
> > +     val &= ~XGMAC4_RP2TCMP;
> > +     val |= tc_num << XGMAC4_RP2TCMP_SHIFT & XGMAC4_RP2TCMP;
> > +     wr_dma_ch_ind(ioaddr, MODE_RXEXTCFG, pdma_ch, val);
> > +}
>
> What does "tc" stand for? Traffic control? If it's a kind of queue
> then what about implementing the stmmac_ops::map_mtl_to_dma interface
> method?
>
TC stands for "traffic class".
The VDMA to PDMA mapping within HDMA has traffic classification block between
the two blocks to allow control over DMA resource utilization.
VDMA -- TC --- PDMA
Tx VDMAs and RX VDMAs are mapped onto a TC based on TD2TCMP and RD2TCMP.
Multiple VDMAs can be mapped to the same TC.
TCs are further mapped onto PDMAs based on TP2TCMP and RP2TCMP fields
> > +
> > +void dwxgmac4_dma_init(void __iomem *ioaddr,
> > +                    struct stmmac_dma_cfg *dma_cfg, int atds)
> > +{
> > +     u32 value;
> > +     u32 i;
> > +
> > +     value = readl(ioaddr + XGMAC_DMA_SYSBUS_MODE);
> > +
> > +     if (dma_cfg->aal)
> > +             value |= XGMAC_AAL;
> > +
> > +     if (dma_cfg->eame)
> > +             value |= XGMAC_EAME;
> > +
> > +     writel(value, ioaddr + XGMAC_DMA_SYSBUS_MODE);
> > +
> > +     for (i = 0; i < VDMA_TOTAL_CH_COUNT; i++) {
>
> > +             value = rd_dma_ch_ind(ioaddr, MODE_TXDESCCTRL, i);
> > +             value &= ~XGMAC4_TXDCSZ;
> > +             value |= 0x3;
> > +             value &= ~XGMAC4_TDPS;
> > +             value |= (3 << XGMAC4_TDPS_SHIFT) & XGMAC4_TDPS;
> > +             wr_dma_ch_ind(ioaddr, MODE_TXDESCCTRL, i, value);
> > +
> > +             value = rd_dma_ch_ind(ioaddr, MODE_RXDESCCTRL, i);
> > +             value &= ~XGMAC4_RXDCSZ;
> > +             value |= 0x3;
> > +             value &= ~XGMAC4_RDPS;
> > +             value |= (3 << XGMAC4_RDPS_SHIFT) & XGMAC4_RDPS;
> > +             wr_dma_ch_ind(ioaddr, MODE_RXDESCCTRL, i, value);
>
> I know that the TDPS/RDPS means Tx/Rx Descriptor Pre-fetch threshold
> Size. What does the TXDCSZ/RXDCSZ config mean?
>
> Most importantly why are these parameters hardcoded to 3? It
> doesn't seem right.
>
TXDCSZ/RXDCSZ are descriptor cache sizes.
I missed defining macros for valid values, for example 3 indicates 256 bytes.
Will fix it in the next update.

> > +     }
> > +
>
> > +     for (i = 0; i < PDMA_TX_CH_COUNT; i++) {
> > +             value = rd_dma_ch_ind(ioaddr, MODE_TXEXTCFG, i);
> > +             value &= ~(XGMAC4_TXPBL | XGMAC4_TPBLX8_MODE);
> > +             if (dma_cfg->pblx8)
> > +                     value |= XGMAC4_TPBLX8_MODE;
> > +             value |= (dma_cfg->pbl << XGMAC4_TXPBL_SHIFT) & XGMAC4_TXPBL;
> > +             wr_dma_ch_ind(ioaddr, MODE_TXEXTCFG, i, value);
> > +             xgmac4_tp2tc_map(ioaddr, i, i);
> > +     }
> > +
> > +     for (i = 0; i < PDMA_RX_CH_COUNT; i++) {
> > +             value = rd_dma_ch_ind(ioaddr, MODE_RXEXTCFG, i);
> > +             value &= ~(XGMAC4_RXPBL | XGMAC4_RPBLX8_MODE);
> > +             if (dma_cfg->pblx8)
> > +                     value |= XGMAC4_RPBLX8_MODE;
> > +             value |= (dma_cfg->pbl << XGMAC4_RXPBL_SHIFT) & XGMAC4_RXPBL;
> > +             wr_dma_ch_ind(ioaddr, MODE_RXEXTCFG, i, value);
> > +             if (i < PDMA_MAX_TC_COUNT)
> > +                     xgmac4_rp2tc_map(ioaddr, i, i);
> > +             else
> > +                     xgmac4_rp2tc_map(ioaddr, i, PDMA_MAX_TC_COUNT - 1);
> > +     }
>
> Shouldn't these initialization be done on the per-channel basis only
> for only activated queues
> plat_stmmacenet_data::{rx_queues_to_use,tx_queues_to_use} (the STMMAC
> driver one-on-one maps queues and DMA-channels if no custom mapping
> was specified)?
>
These are VDMA to PDMA mappings internal HDMA.
Even though it provides flexibility, a default any to any configuration is used.

> > +}
> > +
> > +void dwxgmac4_dma_init_tx_chan(struct stmmac_priv *priv,
> > +                            void __iomem *ioaddr,
> > +                            struct stmmac_dma_cfg *dma_cfg,
> > +                            dma_addr_t dma_addr, u32 chan)
> > +{
> > +     u32 value;
> > +
> > +     value = readl(ioaddr + XGMAC_DMA_CH_TX_CONTROL(chan));
> > +     value &= ~XGMAC4_TVDMA2TCMP;
> > +     value |= (chan << XGMAC4_TVDMA2TCMP_SHIFT) & XGMAC4_TVDMA2TCMP;
> > +     writel(value, ioaddr + XGMAC_DMA_CH_TX_CONTROL(chan));
> > +
> > +     writel(upper_32_bits(dma_addr),
> > +            ioaddr + XGMAC_DMA_CH_TxDESC_HADDR(chan));
> > +     writel(lower_32_bits(dma_addr),
> > +            ioaddr + XGMAC_DMA_CH_TxDESC_LADDR(chan));
> > +}
> > +
> > +void dwxgmac4_dma_init_rx_chan(struct stmmac_priv *priv,
> > +                            void __iomem *ioaddr,
> > +                            struct stmmac_dma_cfg *dma_cfg,
> > +                            dma_addr_t dma_addr, u32 chan)
> > +{
> > +     u32 value;
> > +
> > +     value = readl(ioaddr + XGMAC_DMA_CH_RX_CONTROL(chan));
> > +     value &= ~XGMAC4_RVDMA2TCMP;
> > +     value |= (chan << XGMAC4_RVDMA2TCMP_SHIFT) & XGMAC4_RVDMA2TCMP;
> > +     writel(value, ioaddr + XGMAC_DMA_CH_RX_CONTROL(chan));
> > +
> > +     writel(upper_32_bits(dma_addr),
> > +            ioaddr + XGMAC_DMA_CH_RxDESC_HADDR(chan));
> > +     writel(lower_32_bits(dma_addr),
> > +            ioaddr + XGMAC_DMA_CH_RxDESC_LADDR(chan));
> > +}
> > diff --git a/drivers/net/ethernet/stmicro/stmmac/dwxgmac4.h b/drivers/net/ethernet/stmicro/stmmac/dwxgmac4.h
> > new file mode 100644
> > index 000000000000..0ce1856b0b34
> > --- /dev/null
>
> > +++ b/drivers/net/ethernet/stmicro/stmmac/dwxgmac4.h
>
> dw25gmac.h?
Will rename all applicable references to 25gmac.
>
> > @@ -0,0 +1,84 @@
> > +/* SPDX-License-Identifier: GPL-2.0-only */
> > +/* Copyright (c) 2024 Broadcom Corporation
> > + * XGMAC4 definitions.
> > + */
> > +#ifndef __STMMAC_DWXGMAC4_H__
> > +#define __STMMAC_DWXGMAC4_H__
> > +
> > +/* DMA Indirect Registers*/
>
> > +#define XGMAC4_DMA_CH_IND_CONTROL    0X00003080
>
> XXVGMAC_*?
>
Thanks, Will use this prefix.

> > +#define XGMAC4_MODE_SELECT           GENMASK(27, 24)
> > +#define XGMAC4_MSEL_SHIFT            24
> > +enum dma_ch_ind_modes {
> > +     MODE_TXEXTCFG    = 0x0,   /* Tx Extended Config */
> > +     MODE_RXEXTCFG    = 0x1,   /* Rx Extended Config */
> > +     MODE_TXDBGSTS    = 0x2,   /* Tx Debug Status */
> > +     MODE_RXDBGSTS    = 0x3,   /* Rx Debug Status */
> > +     MODE_TXDESCCTRL  = 0x4,   /* Tx Descriptor control */
> > +     MODE_RXDESCCTRL  = 0x5,   /* Rx Descriptor control */
> > +};
> > +
> > +#define XGMAC4_ADDR_OFFSET           GENMASK(14, 8)
> > +#define XGMAC4_AOFF_SHIFT            8
> > +#define XGMAC4_AUTO_INCR             GENMASK(5, 4)
> > +#define XGMAC4_AUTO_SHIFT            4
> > +#define XGMAC4_CMD_TYPE                      BIT(1)
> > +#define XGMAC4_OB                    BIT(0)
> > +#define XGMAC4_DMA_CH_IND_DATA               0X00003084
> > +
> > +/* TX Config definitions */
> > +#define XGMAC4_TXPBL                 GENMASK(29, 24)
> > +#define XGMAC4_TXPBL_SHIFT           24
> > +#define XGMAC4_TPBLX8_MODE           BIT(19)
> > +#define XGMAC4_TP2TCMP                       GENMASK(18, 16)
> > +#define XGMAC4_TP2TCMP_SHIFT         16
> > +#define XGMAC4_ORRQ                  GENMASK(13, 8)
> > +/* RX Config definitions */
> > +#define XGMAC4_RXPBL                 GENMASK(29, 24)
> > +#define XGMAC4_RXPBL_SHIFT           24
> > +#define XGMAC4_RPBLX8_MODE           BIT(19)
> > +#define XGMAC4_RP2TCMP                       GENMASK(18, 16)
> > +#define XGMAC4_RP2TCMP_SHIFT         16
> > +#define XGMAC4_OWRQ                  GENMASK(13, 8)
> > +/* Tx Descriptor control */
> > +#define XGMAC4_TXDCSZ                        GENMASK(2, 0)
> > +#define XGMAC4_TDPS                  GENMASK(5, 3)
> > +#define XGMAC4_TDPS_SHIFT            3
> > +/* Rx Descriptor control */
> > +#define XGMAC4_RXDCSZ                        GENMASK(2, 0)
> > +#define XGMAC4_RDPS                  GENMASK(5, 3)
> > +#define XGMAC4_RDPS_SHIFT            3
> > +
> > +/* DWCXG_DMA_CH(#i) Registers*/
> > +#define XGMAC4_DSL                   GENMASK(20, 18)
> > +#define XGMAC4_MSS                   GENMASK(13, 0)
> > +#define XGMAC4_TFSEL                 GENMASK(30, 29)
> > +#define XGMAC4_TQOS                  GENMASK(27, 24)
> > +#define XGMAC4_IPBL                  BIT(15)
> > +#define XGMAC4_TVDMA2TCMP            GENMASK(6, 4)
> > +#define XGMAC4_TVDMA2TCMP_SHIFT              4
> > +#define XGMAC4_RPF                   BIT(31)
> > +#define XGMAC4_RVDMA2TCMP            GENMASK(30, 28)
> > +#define XGMAC4_RVDMA2TCMP_SHIFT              28
> > +#define XGMAC4_RQOS                  GENMASK(27, 24)
> > +
>
> > +/* PDMA Channel count */
> > +#define PDMA_TX_CH_COUNT             8
> > +#define PDMA_RX_CH_COUNT             10
> > +#define PDMA_MAX_TC_COUNT            8
> > +
> > +/* VDMA channel count */
> > +#define VDMA_TOTAL_CH_COUNT          32
>
> These seems like the vendor-specific constant. What are the actual DW
> 25GMAC constraints?
>
These are the limits for this device.
We can read these limits from hardware, I will fix it in the next patch.

> -Serge(y)
>
> > +
> > +void dwxgmac4_dma_init(void __iomem *ioaddr,
> > +                    struct stmmac_dma_cfg *dma_cfg, int atds);
> > +
> > +void dwxgmac4_dma_init_tx_chan(struct stmmac_priv *priv,
> > +                            void __iomem *ioaddr,
> > +                            struct stmmac_dma_cfg *dma_cfg,
> > +                            dma_addr_t dma_addr, u32 chan);
> > +void dwxgmac4_dma_init_rx_chan(struct stmmac_priv *priv,
> > +                            void __iomem *ioaddr,
> > +                            struct stmmac_dma_cfg *dma_cfg,
> > +                            dma_addr_t dma_addr, u32 chan);
> > +#endif /* __STMMAC_DWXGMAC4_H__ */
> > --
> > 2.34.1
> >
> >


^ permalink raw reply	[flat|nested] 30+ messages in thread

* Re: [PATCH net-next v3 2/3] net: stmmac: Integrate dwxgmac4 into stmmac hwif handling
  2024-08-06 22:14   ` Serge Semin
@ 2024-08-09  1:17     ` Jitendra Vegiraju
  0 siblings, 0 replies; 30+ messages in thread
From: Jitendra Vegiraju @ 2024-08-09  1:17 UTC (permalink / raw)
  To: Serge Semin
  Cc: netdev, alexandre.torgue, joabreu, davem, edumazet, kuba, pabeni,
	mcoquelin.stm32, bcm-kernel-feedback-list, richardcochran, ast,
	daniel, hawk, john.fastabend, linux-kernel, linux-stm32,
	linux-arm-kernel, bpf, andrew, linux, horms, florian.fainelli

Hi Serge
On Tue, Aug 6, 2024 at 3:14 PM Serge Semin <fancer.lancer@gmail.com> wrote:
>
> On Thu, Aug 01, 2024 at 08:18:21PM -0700, jitendra.vegiraju@broadcom.com wrote:
> > From: Jitendra Vegiraju <jitendra.vegiraju@broadcom.com>
> >
> > Integrate dwxgmac4 support into stmmac hardware interface handling.
> > A dwxgmac4 is an xgmac device and hence it inherits properties from
> > existing stmmac_hw table entry.
> > The quirks handling facility is used to update dma_ops field to
> > point to dwxgmac400_dma_ops when the user version field matches.
> >
> > Signed-off-by: Jitendra Vegiraju <jitendra.vegiraju@broadcom.com>
> > ---
> >  drivers/net/ethernet/stmicro/stmmac/common.h |  4 +++
> >  drivers/net/ethernet/stmicro/stmmac/hwif.c   | 26 +++++++++++++++++++-
> >  drivers/net/ethernet/stmicro/stmmac/hwif.h   |  1 +
> >  3 files changed, 30 insertions(+), 1 deletion(-)
> >
> > diff --git a/drivers/net/ethernet/stmicro/stmmac/common.h b/drivers/net/ethernet/stmicro/stmmac/common.h
> > index cd36ff4da68c..9bf278e11704 100644
> > --- a/drivers/net/ethernet/stmicro/stmmac/common.h
> > +++ b/drivers/net/ethernet/stmicro/stmmac/common.h
> > @@ -37,11 +37,15 @@
> >  #define DWXGMAC_CORE_2_10    0x21
> >  #define DWXGMAC_CORE_2_20    0x22
> >  #define DWXLGMAC_CORE_2_00   0x20
>
> > +#define DWXGMAC_CORE_4_00    0x40
>
> DW25GMAC_CORE_4_00?
Will do.
>
> >
> >  /* Device ID */
> >  #define DWXGMAC_ID           0x76
>
> What is the device ID in your case? Does it match to DWXGMAC_ID?
The early adopter 25MAC IP core used on this has 0x76.
But, synopsis confirmed the 25GMAC is assigned with value 0x55.
Will define DW25MAC_ID 0x55 and use it for 25GMAC hw_if entry.
However, we would like to get a suggestion for dealing with this early
adopter device_id number.
Can we add override mechanism by defining device_id in stmmac_priv
structure and let the hardware specific setup function in the glue
driver update the device_id to 0x55 function?

>
> >  #define DWXLGMAC_ID          0x27
> >
> > +/* User Version */
> > +#define DWXGMAC_USER_VER_X22 0x22
> > +
> >  #define STMMAC_CHAN0 0       /* Always supported and default for all chips */
> >
> >  /* TX and RX Descriptor Length, these need to be power of two.
> > diff --git a/drivers/net/ethernet/stmicro/stmmac/hwif.c b/drivers/net/ethernet/stmicro/stmmac/hwif.c
> > index 29367105df54..713cb5aa2c3e 100644
> > --- a/drivers/net/ethernet/stmicro/stmmac/hwif.c
> > +++ b/drivers/net/ethernet/stmicro/stmmac/hwif.c
> > @@ -36,6 +36,18 @@ static u32 stmmac_get_dev_id(struct stmmac_priv *priv, u32 id_reg)
> >       return (reg & GENMASK(15, 8)) >> 8;
> >  }
> >
>
> > +static u32 stmmac_get_user_version(struct stmmac_priv *priv, u32 id_reg)
> > +{
> > +     u32 reg = readl(priv->ioaddr + id_reg);
> > +
> > +     if (!reg) {
> > +             dev_info(priv->device, "User Version not available\n");
> > +             return 0x0;
> > +     }
> > +
> > +     return (reg & GENMASK(23, 16)) >> 16;
> > +}
> > +
>
> The User Version is purely a vendor-specific stuff defined on the
> IP-core synthesis stage. Moreover I don't see you'll need it anyway.
>
Yes, we don't need this function with the 25GMAC entry.
> >  static void stmmac_dwmac_mode_quirk(struct stmmac_priv *priv)
> >  {
> >       struct mac_device_info *mac = priv->hw;
> > @@ -82,6 +94,18 @@ static int stmmac_dwmac4_quirks(struct stmmac_priv *priv)
> >       return 0;
> >  }
> >
>
> > +static int stmmac_dwxgmac_quirks(struct stmmac_priv *priv)
> > +{
> > +     struct mac_device_info *mac = priv->hw;
> > +     u32 user_ver;
> > +
> > +     user_ver = stmmac_get_user_version(priv, GMAC4_VERSION);
> > +     if (priv->synopsys_id == DWXGMAC_CORE_4_00 &&
> > +         user_ver == DWXGMAC_USER_VER_X22)
> > +             mac->dma = &dwxgmac400_dma_ops;
> > +     return 0;
> > +}
> > +
Will remove this function.
> >  static int stmmac_dwxlgmac_quirks(struct stmmac_priv *priv)
> >  {
> >       priv->hw->xlgmac = true;
> > @@ -256,7 +280,7 @@ static const struct stmmac_hwif_entry {
> >               .mmc = &dwxgmac_mmc_ops,
> >               .est = &dwmac510_est_ops,
> >               .setup = dwxgmac2_setup,
> > -             .quirks = NULL,
> > +             .quirks = stmmac_dwxgmac_quirks,
>
> Why? You can just introduce a new stmmac_hw[] entry with the DW
> 25GMAC-specific stmmac_dma_ops instance specified.
>
Will do.
> -Serge(y)
>
> >       }, {
> >               .gmac = false,
> >               .gmac4 = false,
> > diff --git a/drivers/net/ethernet/stmicro/stmmac/hwif.h b/drivers/net/ethernet/stmicro/stmmac/hwif.h
> > index e53c32362774..6213c496385c 100644
> > --- a/drivers/net/ethernet/stmicro/stmmac/hwif.h
> > +++ b/drivers/net/ethernet/stmicro/stmmac/hwif.h
> > @@ -683,6 +683,7 @@ extern const struct stmmac_desc_ops dwxgmac210_desc_ops;
> >  extern const struct stmmac_mmc_ops dwmac_mmc_ops;
> >  extern const struct stmmac_mmc_ops dwxgmac_mmc_ops;
> >  extern const struct stmmac_est_ops dwmac510_est_ops;
> > +extern const struct stmmac_dma_ops dwxgmac400_dma_ops;
> >
> >  #define GMAC_VERSION         0x00000020      /* GMAC CORE Version */
> >  #define GMAC4_VERSION                0x00000110      /* GMAC4+ CORE Version */
> > --
> > 2.34.1
> >
> >


^ permalink raw reply	[flat|nested] 30+ messages in thread

* Re: [PATCH net-next v3 2/3] net: stmmac: Integrate dwxgmac4 into stmmac hwif handling
  2024-08-06 23:13       ` Andrew Lunn
@ 2024-08-09  1:49         ` Jitendra Vegiraju
  0 siblings, 0 replies; 30+ messages in thread
From: Jitendra Vegiraju @ 2024-08-09  1:49 UTC (permalink / raw)
  To: Andrew Lunn
  Cc: netdev, alexandre.torgue, joabreu, davem, edumazet, kuba, pabeni,
	mcoquelin.stm32, bcm-kernel-feedback-list, richardcochran, ast,
	daniel, hawk, john.fastabend, linux-kernel, linux-stm32,
	linux-arm-kernel, bpf, linux, horms, florian.fainelli

Hi Andrew

On Tue, Aug 6, 2024 at 4:13 PM Andrew Lunn <andrew@lunn.ch> wrote:
>
> On Mon, Aug 05, 2024 at 05:36:30PM -0700, Jitendra Vegiraju wrote:
> > Hi Andrew,
> > On Fri, Aug 2, 2024 at 3:59 PM Andrew Lunn <andrew@lunn.ch> wrote:
> > >
> > > > +     user_ver = stmmac_get_user_version(priv, GMAC4_VERSION);
> > > > +     if (priv->synopsys_id == DWXGMAC_CORE_4_00 &&
> > > > +         user_ver == DWXGMAC_USER_VER_X22)
> > > > +             mac->dma = &dwxgmac400_dma_ops;
> > >
> > > I know nothing about this hardware....
> > >
> > > Does priv->synopsys_id == DWXGMAC_CORE_4_0 not imply
> > > dwxgmac400_dma_ops?
> > >
> > > Could a user synthesise DWXGMAC_CORE_4_00 without using
> > > dwxgmac400_dma_ops? Could dwxgmac500_dma_ops or dwxgmac100_dma_ops be
> > > used?
> > Yes, the user can choose between Enhanced DMA , Hyper DMA , Normal DMA.
> > This SoC support has chosen Hyper DMA for future expandability.
>
> Is there a register which describes the synthesis configuration? It is
> much better that the hardware tells us what it is, rather than having
> to expand this condition for every new devices which gets added.
>
Sorry, for the delayed response.
We got confirmation that HDMA capability can be identified by the
presence of DWXGMAC_CORE_4_xx and device_id 0x55.

> Also, what is the definition of user_ver. Can we guarantee this is
> unique and can actually be used to determine what DMA variant has been
> synthesised?
The initial information I got on this is that user versions are
allocated and reserved by Synopsis.
We probably don't need to key off this information now.
>
>         Andrew


^ permalink raw reply	[flat|nested] 30+ messages in thread

* Re: [PATCH net-next v3 3/3] net: stmmac: Add PCI driver support for BCM8958x
  2024-08-06 23:15       ` Andrew Lunn
@ 2024-08-09  1:54         ` Jitendra Vegiraju
  2024-08-09 20:12           ` Andrew Lunn
  0 siblings, 1 reply; 30+ messages in thread
From: Jitendra Vegiraju @ 2024-08-09  1:54 UTC (permalink / raw)
  To: Andrew Lunn
  Cc: netdev, alexandre.torgue, joabreu, davem, edumazet, kuba, pabeni,
	mcoquelin.stm32, bcm-kernel-feedback-list, richardcochran, ast,
	daniel, hawk, john.fastabend, linux-kernel, linux-stm32,
	linux-arm-kernel, bpf, linux, horms, florian.fainelli

On Tue, Aug 6, 2024 at 4:15 PM Andrew Lunn <andrew@lunn.ch> wrote:
>
> On Mon, Aug 05, 2024 at 05:56:43PM -0700, Jitendra Vegiraju wrote:
> > On Fri, Aug 2, 2024 at 4:08 PM Andrew Lunn <andrew@lunn.ch> wrote:
> > >
> > > > Management of integrated ethernet switch on this SoC is not handled by
> > > > the PCIe interface.
> > >
> > > MDIO? SPI? I2C?
> > >
> > The device uses SPI interface. The switch has internal ARM M7 for
> > controller firmware.
>
> Will there be a DSA driver sometime soon talking over SPI to the
> firmware?
>
Hi Andrew,
No there is no plan to add DSA driver.
>         Andrew


^ permalink raw reply	[flat|nested] 30+ messages in thread

* Re: [PATCH net-next v3 3/3] net: stmmac: Add PCI driver support for BCM8958x
  2024-08-09  1:54         ` Jitendra Vegiraju
@ 2024-08-09 20:12           ` Andrew Lunn
  2024-08-09 22:10             ` Jitendra Vegiraju
  2024-08-09 22:17             ` Florian Fainelli
  0 siblings, 2 replies; 30+ messages in thread
From: Andrew Lunn @ 2024-08-09 20:12 UTC (permalink / raw)
  To: Jitendra Vegiraju
  Cc: netdev, alexandre.torgue, joabreu, davem, edumazet, kuba, pabeni,
	mcoquelin.stm32, bcm-kernel-feedback-list, richardcochran, ast,
	daniel, hawk, john.fastabend, linux-kernel, linux-stm32,
	linux-arm-kernel, bpf, linux, horms, florian.fainelli

On Thu, Aug 08, 2024 at 06:54:51PM -0700, Jitendra Vegiraju wrote:
> On Tue, Aug 6, 2024 at 4:15 PM Andrew Lunn <andrew@lunn.ch> wrote:
> >
> > On Mon, Aug 05, 2024 at 05:56:43PM -0700, Jitendra Vegiraju wrote:
> > > On Fri, Aug 2, 2024 at 4:08 PM Andrew Lunn <andrew@lunn.ch> wrote:
> > > >
> > > > > Management of integrated ethernet switch on this SoC is not handled by
> > > > > the PCIe interface.
> > > >
> > > > MDIO? SPI? I2C?
> > > >
> > > The device uses SPI interface. The switch has internal ARM M7 for
> > > controller firmware.
> >
> > Will there be a DSA driver sometime soon talking over SPI to the
> > firmware?
> >
> Hi Andrew,

So the switch will be left in dumb switch everything to every port
mode? Or it will be totally autonomous using the in build firmware?

What you cannot expect is we allow you to manage the switch from Linux
using something other than an in kernel driver, probably DSA or pure
switchdev.

	Andrew


^ permalink raw reply	[flat|nested] 30+ messages in thread

* Re: [PATCH net-next v3 3/3] net: stmmac: Add PCI driver support for BCM8958x
  2024-08-09 20:12           ` Andrew Lunn
@ 2024-08-09 22:10             ` Jitendra Vegiraju
  2024-08-09 22:17             ` Florian Fainelli
  1 sibling, 0 replies; 30+ messages in thread
From: Jitendra Vegiraju @ 2024-08-09 22:10 UTC (permalink / raw)
  To: Andrew Lunn
  Cc: netdev, alexandre.torgue, joabreu, davem, edumazet, kuba, pabeni,
	mcoquelin.stm32, bcm-kernel-feedback-list, richardcochran, ast,
	daniel, hawk, john.fastabend, linux-kernel, linux-stm32,
	linux-arm-kernel, bpf, linux, horms, florian.fainelli

On Fri, Aug 9, 2024 at 1:12 PM Andrew Lunn <andrew@lunn.ch> wrote:
>
> On Thu, Aug 08, 2024 at 06:54:51PM -0700, Jitendra Vegiraju wrote:
> > On Tue, Aug 6, 2024 at 4:15 PM Andrew Lunn <andrew@lunn.ch> wrote:
> > >
> > > On Mon, Aug 05, 2024 at 05:56:43PM -0700, Jitendra Vegiraju wrote:
> > > > On Fri, Aug 2, 2024 at 4:08 PM Andrew Lunn <andrew@lunn.ch> wrote:
> > > > >
> > > > > > Management of integrated ethernet switch on this SoC is not handled by
> > > > > > the PCIe interface.
> > > > >
> > > > > MDIO? SPI? I2C?
> > > > >
> > > > The device uses SPI interface. The switch has internal ARM M7 for
> > > > controller firmware.
> > >
> > > Will there be a DSA driver sometime soon talking over SPI to the
> > > firmware?
> > >
> > Hi Andrew,
>
> So the switch will be left in dumb switch everything to every port
> mode? Or it will be totally autonomous using the in build firmware?
>
> What you cannot expect is we allow you to manage the switch from Linux
> using something other than an in kernel driver, probably DSA or pure
> switchdev.

I am starting to get familiar with DSA and switchdev.
The configuration can be sent over the SPI interface.
In the current application, the host receiving PCIE network traffic
need not be the same host that controls the SPI interface.

>
>         Andrew


^ permalink raw reply	[flat|nested] 30+ messages in thread

* Re: [PATCH net-next v3 3/3] net: stmmac: Add PCI driver support for BCM8958x
  2024-08-09 20:12           ` Andrew Lunn
  2024-08-09 22:10             ` Jitendra Vegiraju
@ 2024-08-09 22:17             ` Florian Fainelli
  2024-08-10  0:53               ` Andrew Lunn
  1 sibling, 1 reply; 30+ messages in thread
From: Florian Fainelli @ 2024-08-09 22:17 UTC (permalink / raw)
  To: Andrew Lunn, Jitendra Vegiraju
  Cc: netdev, alexandre.torgue, joabreu, davem, edumazet, kuba, pabeni,
	mcoquelin.stm32, bcm-kernel-feedback-list, richardcochran, ast,
	daniel, hawk, john.fastabend, linux-kernel, linux-stm32,
	linux-arm-kernel, bpf, linux, horms

On 8/9/24 13:12, Andrew Lunn wrote:
> On Thu, Aug 08, 2024 at 06:54:51PM -0700, Jitendra Vegiraju wrote:
>> On Tue, Aug 6, 2024 at 4:15 PM Andrew Lunn <andrew@lunn.ch> wrote:
>>>
>>> On Mon, Aug 05, 2024 at 05:56:43PM -0700, Jitendra Vegiraju wrote:
>>>> On Fri, Aug 2, 2024 at 4:08 PM Andrew Lunn <andrew@lunn.ch> wrote:
>>>>>
>>>>>> Management of integrated ethernet switch on this SoC is not handled by
>>>>>> the PCIe interface.
>>>>>
>>>>> MDIO? SPI? I2C?
>>>>>
>>>> The device uses SPI interface. The switch has internal ARM M7 for
>>>> controller firmware.
>>>
>>> Will there be a DSA driver sometime soon talking over SPI to the
>>> firmware?
>>>
>> Hi Andrew,
> 
> So the switch will be left in dumb switch everything to every port
> mode? Or it will be totally autonomous using the in build firmware?
> 
> What you cannot expect is we allow you to manage the switch from Linux
> using something other than an in kernel driver, probably DSA or pure
> switchdev.

This looks reasonable as an advice about to ideally fit within the 
existing Linux subsystems, however that is purely informational and it 
should not impair the review and acceptance of the stmmac drivers.

Doing otherwise, and rejecting the stmmac changes because now you and 
other reviewers/maintainers know how it gets used in the bigger picture 
means this is starting to be overreaching. Yes silicon vendor companies 
like to do all sorts of proprietary things for random reasons, I think 
we have worked together long enough on DSA that you know my beliefs on 
that aspect.

I think the stmmac changes along have their own merit, and I would 
seriously like to see a proper DSA or switchdev driver for the switching 
silicon that is being used, but I don't think we need to treat the 
latter as a prerequisite for merging the former.

Thanks!
-- 
Florian



^ permalink raw reply	[flat|nested] 30+ messages in thread

* Re: [PATCH net-next v3 3/3] net: stmmac: Add PCI driver support for BCM8958x
  2024-08-09 22:17             ` Florian Fainelli
@ 2024-08-10  0:53               ` Andrew Lunn
  0 siblings, 0 replies; 30+ messages in thread
From: Andrew Lunn @ 2024-08-10  0:53 UTC (permalink / raw)
  To: Florian Fainelli
  Cc: Jitendra Vegiraju, netdev, alexandre.torgue, joabreu, davem,
	edumazet, kuba, pabeni, mcoquelin.stm32, bcm-kernel-feedback-list,
	richardcochran, ast, daniel, hawk, john.fastabend, linux-kernel,
	linux-stm32, linux-arm-kernel, bpf, linux, horms

> > > Hi Andrew,
> > 
> > So the switch will be left in dumb switch everything to every port
> > mode? Or it will be totally autonomous using the in build firmware?
> > 
> > What you cannot expect is we allow you to manage the switch from Linux
> > using something other than an in kernel driver, probably DSA or pure
> > switchdev.
> 
> This looks reasonable as an advice about to ideally fit within the existing
> Linux subsystems, however that is purely informational and it should not
> impair the review and acceptance of the stmmac drivers.
> 
> Doing otherwise, and rejecting the stmmac changes because now you and other
> reviewers/maintainers know how it gets used in the bigger picture means this
> is starting to be overreaching. Yes silicon vendor companies like to do all
> sorts of proprietary things for random reasons, I think we have worked
> together long enough on DSA that you know my beliefs on that aspect.
> 
> I think the stmmac changes along have their own merit, and I would seriously
> like to see a proper DSA or switchdev driver for the switching silicon that
> is being used, but I don't think we need to treat the latter as a
> prerequisite for merging the former.

I fully agree this patchset should be merged without needing a DSA
driver. We have seen a number of automotive systems recently doing
very similar things, Linux is just a host connected to a switch. Linux
is too unreliable to manage the switch, or Linux takes too long to
boot and configure the switch etc. So something else is in control of
the switch. Linux only view onto the switch is as a typical external
device, it can walk the SNMP MIBs etc.

If you decided Linux can manage this switch, then great, please
sometime in the future submit a DSA or switchdev driver. Otherwise
Linux is just a host with no real knowledge of the switch, and the SPI
interface is not used.

	  Andrew


^ permalink raw reply	[flat|nested] 30+ messages in thread

end of thread, other threads:[~2024-08-10  0:54 UTC | newest]

Thread overview: 30+ messages (download: mbox.gz follow: Atom feed
-- links below jump to the message on this page --
2024-08-02  3:18 [PATCH net-next v3 0/3] net: stmmac: Add PCI driver support for BCM8958x jitendra.vegiraju
2024-08-02  3:18 ` [PATCH net-next v3 1/3] net: stmmac: Add basic dwxgmac4 support to stmmac core jitendra.vegiraju
2024-08-02  8:21   ` Russell King (Oracle)
2024-08-02 21:43     ` Jitendra Vegiraju
2024-08-02 14:38   ` Simon Horman
2024-08-02 21:45     ` Jitendra Vegiraju
2024-08-06 21:56   ` Serge Semin
2024-08-09  0:41     ` Jitendra Vegiraju
2024-08-02  3:18 ` [PATCH net-next v3 2/3] net: stmmac: Integrate dwxgmac4 into stmmac hwif handling jitendra.vegiraju
2024-08-02  8:23   ` Russell King (Oracle)
2024-08-02 21:49     ` Jitendra Vegiraju
2024-08-02 22:59   ` Andrew Lunn
2024-08-06  0:36     ` Jitendra Vegiraju
2024-08-06 23:13       ` Andrew Lunn
2024-08-09  1:49         ` Jitendra Vegiraju
2024-08-06 22:14   ` Serge Semin
2024-08-09  1:17     ` Jitendra Vegiraju
2024-08-02  3:18 ` [PATCH net-next v3 3/3] net: stmmac: Add PCI driver support for BCM8958x jitendra.vegiraju
2024-08-02 23:08   ` Andrew Lunn
2024-08-06  0:56     ` Jitendra Vegiraju
2024-08-06 23:15       ` Andrew Lunn
2024-08-09  1:54         ` Jitendra Vegiraju
2024-08-09 20:12           ` Andrew Lunn
2024-08-09 22:10             ` Jitendra Vegiraju
2024-08-09 22:17             ` Florian Fainelli
2024-08-10  0:53               ` Andrew Lunn
2024-08-02 10:02 ` [PATCH net-next v3 0/3] " Serge Semin
2024-08-02 22:06   ` Jitendra Vegiraju
2024-08-05 22:43     ` Serge Semin
2024-08-08 23:03       ` Jitendra Vegiraju

This is a public inbox, see mirroring instructions
for how to clone and mirror all data and code used for this inbox;
as well as URLs for NNTP newsgroup(s).