DPDK patches and discussions
 help / color / mirror / Atom feed
* [PATCH 00/14] Cleanup PCI(e) drivers
@ 2023-08-03  7:50 David Marchand
  2023-08-03  7:50 ` [PATCH 01/14] drivers: remove duplicated PCI master control David Marchand
                   ` (19 more replies)
  0 siblings, 20 replies; 98+ messages in thread
From: David Marchand @ 2023-08-03  7:50 UTC (permalink / raw)
  To: dev; +Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta

Rather than rely on Linux headers to find some PCI(e) standard constants
or reinvent the same PCI capability helper, this series complements the
pci library and the pci bus driver.
PCI drivers can then use OS agnostic macros and helpers.

WARNING: this is only compile tested.

-- 
David Marchand

David Marchand (14):
  drivers: remove duplicated PCI master control
  bus/pci: add const to some experimental API
  bus/pci: find PCI capability
  pci: define some capability constants
  pci: define some MSIX constants
  pci: define some command constants
  pci: define some BAR constants
  pci: define some PM constants
  pci: define some PCIe constants
  pci: define some extended capability constants
  pci: define some ACS constants
  pci: define some PRI constants
  pci: define some AER constants
  devtools: forbid inclusion of Linux header for PCI

 devtools/checkpatches.sh            |   8 ++
 drivers/bus/pci/linux/pci_init.h    |  18 ----
 drivers/bus/pci/linux/pci_uio.c     |  32 +-----
 drivers/bus/pci/linux/pci_vfio.c    | 142 ++++++-------------------
 drivers/bus/pci/pci_common.c        |  49 ++++++++-
 drivers/bus/pci/rte_bus_pci.h       |  35 ++++++-
 drivers/bus/pci/version.map         |   2 +
 drivers/crypto/virtio/virtio_pci.c  |  67 ++++--------
 drivers/event/dlb2/pf/dlb2_main.c   | 156 ++++++++--------------------
 drivers/net/bnx2x/bnx2x.c           |  86 ++++++++-------
 drivers/net/bnx2x/bnx2x.h           |  46 --------
 drivers/net/cxgbe/base/adapter.h    |  31 +-----
 drivers/net/gve/gve_ethdev.c        |  46 +-------
 drivers/net/gve/gve_ethdev.h        |  14 +--
 drivers/net/hns3/hns3_ethdev_vf.c   | 109 +++----------------
 drivers/net/ngbe/base/ngbe_hw.c     |  20 +---
 drivers/net/ngbe/base/ngbe_osdep.h  |   3 -
 drivers/net/virtio/virtio_pci.c     | 131 ++++-------------------
 drivers/vdpa/ifc/base/ifcvf_osdep.h |   4 +-
 lib/pci/rte_pci.h                   |  77 +++++++++++++-
 20 files changed, 346 insertions(+), 730 deletions(-)

-- 
2.41.0


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

* [PATCH 01/14] drivers: remove duplicated PCI master control
  2023-08-03  7:50 [PATCH 00/14] Cleanup PCI(e) drivers David Marchand
@ 2023-08-03  7:50 ` David Marchand
  2023-08-03  9:45   ` Bruce Richardson
  2023-10-07  2:53   ` fengchengwen
  2023-08-03  7:50 ` [PATCH 02/14] bus/pci: add const to some experimental API David Marchand
                   ` (18 subsequent siblings)
  19 siblings, 2 replies; 98+ messages in thread
From: David Marchand @ 2023-08-03  7:50 UTC (permalink / raw)
  To: dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, Anatoly Burakov,
	Dongdong Liu, Yisen Zhuang, Jiawen Wu

Use existing API to cleanup duplicated code.

Signed-off-by: David Marchand <david.marchand@redhat.com>
---
 drivers/bus/pci/linux/pci_uio.c    | 32 +----------------------
 drivers/bus/pci/linux/pci_vfio.c   | 41 ++----------------------------
 drivers/net/hns3/hns3_ethdev_vf.c  | 25 +-----------------
 drivers/net/ngbe/base/ngbe_hw.c    | 20 ++-------------
 drivers/net/ngbe/base/ngbe_osdep.h |  3 ---
 5 files changed, 6 insertions(+), 115 deletions(-)

diff --git a/drivers/bus/pci/linux/pci_uio.c b/drivers/bus/pci/linux/pci_uio.c
index 2bf16e9369..97d740dfe5 100644
--- a/drivers/bus/pci/linux/pci_uio.c
+++ b/drivers/bus/pci/linux/pci_uio.c
@@ -10,7 +10,6 @@
 #include <sys/stat.h>
 #include <sys/mman.h>
 #include <sys/sysmacros.h>
-#include <linux/pci_regs.h>
 
 #if defined(RTE_ARCH_X86)
 #include <sys/io.h>
@@ -77,35 +76,6 @@ pci_uio_mmio_write(const struct rte_pci_device *dev, int bar,
 	return len;
 }
 
-static int
-pci_uio_set_bus_master(int dev_fd)
-{
-	uint16_t reg;
-	int ret;
-
-	ret = pread(dev_fd, &reg, sizeof(reg), PCI_COMMAND);
-	if (ret != sizeof(reg)) {
-		RTE_LOG(ERR, EAL,
-			"Cannot read command from PCI config space!\n");
-		return -1;
-	}
-
-	/* return if bus mastering is already on */
-	if (reg & PCI_COMMAND_MASTER)
-		return 0;
-
-	reg |= PCI_COMMAND_MASTER;
-
-	ret = pwrite(dev_fd, &reg, sizeof(reg), PCI_COMMAND);
-	if (ret != sizeof(reg)) {
-		RTE_LOG(ERR, EAL,
-			"Cannot write command to PCI config space!\n");
-		return -1;
-	}
-
-	return 0;
-}
-
 static int
 pci_mknod_uio_dev(const char *sysfs_uio_path, unsigned uio_num)
 {
@@ -299,7 +269,7 @@ pci_uio_alloc_resource(struct rte_pci_device *dev,
 			goto error;
 
 		/* set bus master that is not done by uio_pci_generic */
-		if (pci_uio_set_bus_master(uio_cfg_fd)) {
+		if (rte_pci_set_bus_master(dev, true)) {
 			RTE_LOG(ERR, EAL, "Cannot set up bus mastering!\n");
 			goto error;
 		}
diff --git a/drivers/bus/pci/linux/pci_vfio.c b/drivers/bus/pci/linux/pci_vfio.c
index e634de8322..8fa7fa458f 100644
--- a/drivers/bus/pci/linux/pci_vfio.c
+++ b/drivers/bus/pci/linux/pci_vfio.c
@@ -223,42 +223,6 @@ pci_vfio_enable_bus_memory(struct rte_pci_device *dev, int dev_fd)
 	return 0;
 }
 
-/* set PCI bus mastering */
-static int
-pci_vfio_set_bus_master(const struct rte_pci_device *dev, int dev_fd, bool op)
-{
-	uint64_t size, offset;
-	uint16_t reg;
-	int ret;
-
-	if (pci_vfio_get_region(dev, VFIO_PCI_CONFIG_REGION_INDEX,
-		&size, &offset) != 0) {
-		RTE_LOG(ERR, EAL, "Cannot get offset of CONFIG region.\n");
-		return -1;
-	}
-
-	ret = pread64(dev_fd, &reg, sizeof(reg), offset + PCI_COMMAND);
-	if (ret != sizeof(reg)) {
-		RTE_LOG(ERR, EAL, "Cannot read command from PCI config space!\n");
-		return -1;
-	}
-
-	if (op)
-		/* set the master bit */
-		reg |= PCI_COMMAND_MASTER;
-	else
-		reg &= ~(PCI_COMMAND_MASTER);
-
-	ret = pwrite64(dev_fd, &reg, sizeof(reg), offset + PCI_COMMAND);
-
-	if (ret != sizeof(reg)) {
-		RTE_LOG(ERR, EAL, "Cannot write command to PCI config space!\n");
-		return -1;
-	}
-
-	return 0;
-}
-
 /* set up interrupt support (but not enable interrupts) */
 static int
 pci_vfio_setup_interrupts(struct rte_pci_device *dev, int vfio_dev_fd)
@@ -535,8 +499,7 @@ pci_rte_vfio_setup_device(struct rte_pci_device *dev, int vfio_dev_fd)
 		return -1;
 	}
 
-	/* set bus mastering for the device */
-	if (pci_vfio_set_bus_master(dev, vfio_dev_fd, true)) {
+	if (rte_pci_set_bus_master(dev, true)) {
 		RTE_LOG(ERR, EAL, "Cannot set up bus mastering!\n");
 		return -1;
 	}
@@ -1226,7 +1189,7 @@ pci_vfio_unmap_resource_primary(struct rte_pci_device *dev)
 	if (vfio_dev_fd < 0)
 		return -1;
 
-	if (pci_vfio_set_bus_master(dev, vfio_dev_fd, false)) {
+	if (rte_pci_set_bus_master(dev, false)) {
 		RTE_LOG(ERR, EAL, "%s cannot unset bus mastering for PCI device!\n",
 				pci_addr);
 		return -1;
diff --git a/drivers/net/hns3/hns3_ethdev_vf.c b/drivers/net/hns3/hns3_ethdev_vf.c
index 5aac62a41f..7b3c5dc168 100644
--- a/drivers/net/hns3/hns3_ethdev_vf.c
+++ b/drivers/net/hns3/hns3_ethdev_vf.c
@@ -49,29 +49,6 @@ static int hns3vf_remove_mc_mac_addr(struct hns3_hw *hw,
 static int hns3vf_dev_link_update(struct rte_eth_dev *eth_dev,
 				   __rte_unused int wait_to_complete);
 
-/* set PCI bus mastering */
-static int
-hns3vf_set_bus_master(const struct rte_pci_device *device, bool op)
-{
-	uint16_t reg;
-	int ret;
-
-	ret = rte_pci_read_config(device, &reg, sizeof(reg), PCI_COMMAND);
-	if (ret < 0) {
-		PMD_INIT_LOG(ERR, "Failed to read PCI offset 0x%x",
-			     PCI_COMMAND);
-		return ret;
-	}
-
-	if (op)
-		/* set the master bit */
-		reg |= PCI_COMMAND_MASTER;
-	else
-		reg &= ~(PCI_COMMAND_MASTER);
-
-	return rte_pci_write_config(device, &reg, sizeof(reg), PCI_COMMAND);
-}
-
 /**
  * hns3vf_find_pci_capability - lookup a capability in the PCI capability list
  * @cap: the capability
@@ -2140,7 +2117,7 @@ hns3vf_reinit_dev(struct hns3_adapter *hns)
 
 	if (hw->reset.level == HNS3_VF_FULL_RESET) {
 		rte_intr_disable(pci_dev->intr_handle);
-		ret = hns3vf_set_bus_master(pci_dev, true);
+		ret = rte_pci_set_bus_master(pci_dev, true);
 		if (ret < 0) {
 			hns3_err(hw, "failed to set pci bus, ret = %d", ret);
 			return ret;
diff --git a/drivers/net/ngbe/base/ngbe_hw.c b/drivers/net/ngbe/base/ngbe_hw.c
index 27243d85c8..22ccdb0b7d 100644
--- a/drivers/net/ngbe/base/ngbe_hw.c
+++ b/drivers/net/ngbe/base/ngbe_hw.c
@@ -1061,26 +1061,10 @@ s32 ngbe_set_pcie_master(struct ngbe_hw *hw, bool enable)
 {
 	struct rte_pci_device *pci_dev = (struct rte_pci_device *)hw->back;
 	s32 status = 0;
-	s32 ret = 0;
 	u32 i;
-	u16 reg;
 
-	ret = rte_pci_read_config(pci_dev, &reg,
-			sizeof(reg), PCI_COMMAND);
-	if (ret != sizeof(reg)) {
-		DEBUGOUT("Cannot read command from PCI config space!\n");
-		return -1;
-	}
-
-	if (enable)
-		reg |= PCI_COMMAND_MASTER;
-	else
-		reg &= ~PCI_COMMAND_MASTER;
-
-	ret = rte_pci_write_config(pci_dev, &reg,
-			sizeof(reg), PCI_COMMAND);
-	if (ret != sizeof(reg)) {
-		DEBUGOUT("Cannot write command to PCI config space!\n");
+	if (rte_pci_set_bus_master(pci_dev, enable) < 0) {
+		DEBUGOUT("Cannot configure PCI bus master\n");
 		return -1;
 	}
 
diff --git a/drivers/net/ngbe/base/ngbe_osdep.h b/drivers/net/ngbe/base/ngbe_osdep.h
index 8783fce4dd..30598a240a 100644
--- a/drivers/net/ngbe/base/ngbe_osdep.h
+++ b/drivers/net/ngbe/base/ngbe_osdep.h
@@ -181,7 +181,4 @@ static inline u64 REVERT_BIT_MASK64(u64 mask)
 #define ETH_P_8021Q      0x8100
 #define ETH_P_8021AD     0x88A8
 
-#define PCI_COMMAND		0x04
-#define  PCI_COMMAND_MASTER	0x4
-
 #endif /* _NGBE_OS_H_ */
-- 
2.41.0


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

* [PATCH 02/14] bus/pci: add const to some experimental API
  2023-08-03  7:50 [PATCH 00/14] Cleanup PCI(e) drivers David Marchand
  2023-08-03  7:50 ` [PATCH 01/14] drivers: remove duplicated PCI master control David Marchand
@ 2023-08-03  7:50 ` David Marchand
  2023-08-03  9:46   ` Bruce Richardson
  2023-08-03  7:50 ` [PATCH 03/14] bus/pci: find PCI capability David Marchand
                   ` (17 subsequent siblings)
  19 siblings, 1 reply; 98+ messages in thread
From: David Marchand @ 2023-08-03  7:50 UTC (permalink / raw)
  To: dev; +Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta

Those functions are fine with a const on the device pointer.

Signed-off-by: David Marchand <david.marchand@redhat.com>
---
 drivers/bus/pci/pci_common.c  | 4 ++--
 drivers/bus/pci/rte_bus_pci.h | 4 ++--
 2 files changed, 4 insertions(+), 4 deletions(-)

diff --git a/drivers/bus/pci/pci_common.c b/drivers/bus/pci/pci_common.c
index 52404ab0fe..382b0b8946 100644
--- a/drivers/bus/pci/pci_common.c
+++ b/drivers/bus/pci/pci_common.c
@@ -814,7 +814,7 @@ rte_pci_get_iommu_class(void)
 }
 
 off_t
-rte_pci_find_ext_capability(struct rte_pci_device *dev, uint32_t cap)
+rte_pci_find_ext_capability(const struct rte_pci_device *dev, uint32_t cap)
 {
 	off_t offset = RTE_PCI_CFG_SPACE_SIZE;
 	uint32_t header;
@@ -857,7 +857,7 @@ rte_pci_find_ext_capability(struct rte_pci_device *dev, uint32_t cap)
 }
 
 int
-rte_pci_set_bus_master(struct rte_pci_device *dev, bool enable)
+rte_pci_set_bus_master(const struct rte_pci_device *dev, bool enable)
 {
 	uint16_t old_cmd, cmd;
 
diff --git a/drivers/bus/pci/rte_bus_pci.h b/drivers/bus/pci/rte_bus_pci.h
index 9d59c4aef3..75d0030eae 100644
--- a/drivers/bus/pci/rte_bus_pci.h
+++ b/drivers/bus/pci/rte_bus_pci.h
@@ -85,7 +85,7 @@ void rte_pci_dump(FILE *f);
  *  = 0: Device does not support it.
  */
 __rte_experimental
-off_t rte_pci_find_ext_capability(struct rte_pci_device *dev, uint32_t cap);
+off_t rte_pci_find_ext_capability(const struct rte_pci_device *dev, uint32_t cap);
 
 /**
  * Enables/Disables Bus Master for device's PCI command register.
@@ -99,7 +99,7 @@ off_t rte_pci_find_ext_capability(struct rte_pci_device *dev, uint32_t cap);
  *  0 on success, -1 on error in PCI config space read/write.
  */
 __rte_experimental
-int rte_pci_set_bus_master(struct rte_pci_device *dev, bool enable);
+int rte_pci_set_bus_master(const struct rte_pci_device *dev, bool enable);
 
 /**
  * Read PCI config space.
-- 
2.41.0


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

* [PATCH 03/14] bus/pci: find PCI capability
  2023-08-03  7:50 [PATCH 00/14] Cleanup PCI(e) drivers David Marchand
  2023-08-03  7:50 ` [PATCH 01/14] drivers: remove duplicated PCI master control David Marchand
  2023-08-03  7:50 ` [PATCH 02/14] bus/pci: add const to some experimental API David Marchand
@ 2023-08-03  7:50 ` David Marchand
  2023-08-03  9:49   ` Bruce Richardson
  2023-08-03  7:50 ` [PATCH 04/14] pci: define some capability constants David Marchand
                   ` (16 subsequent siblings)
  19 siblings, 1 reply; 98+ messages in thread
From: David Marchand @ 2023-08-03  7:50 UTC (permalink / raw)
  To: dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, Anatoly Burakov,
	Jay Zhou, Timothy McDaniel, Julien Aube, Rahul Lakkireddy,
	Junfeng Guo, Jeroen de Borst, Rushil Gupta, Joshua Washington,
	Dongdong Liu, Yisen Zhuang, Maxime Coquelin, Gaetan Rivet

Introduce two helpers so that drivers stop reinventing the wheel.
Use it in existing drivers.

Note:
- base/ drivers code is left untouched, only some wrappers in cxgbe
  are touched,
- bnx2x maintained a per device cache of capabilities, this code has been
  reworked to only cache the capabilities used in this driver,

Signed-off-by: David Marchand <david.marchand@redhat.com>
---
 drivers/bus/pci/linux/pci_vfio.c   |  86 +++++---------------
 drivers/bus/pci/pci_common.c       |  45 +++++++++++
 drivers/bus/pci/rte_bus_pci.h      |  31 ++++++++
 drivers/bus/pci/version.map        |   2 +
 drivers/crypto/virtio/virtio_pci.c |  57 +++++---------
 drivers/event/dlb2/pf/dlb2_main.c  |  42 +---------
 drivers/net/bnx2x/bnx2x.c          |  41 +++++-----
 drivers/net/cxgbe/base/adapter.h   |  28 +------
 drivers/net/gve/gve_ethdev.c       |  46 ++---------
 drivers/net/gve/gve_ethdev.h       |   4 -
 drivers/net/hns3/hns3_ethdev_vf.c  |  79 +++----------------
 drivers/net/virtio/virtio_pci.c    | 121 +++++------------------------
 lib/pci/rte_pci.h                  |  10 +++
 13 files changed, 186 insertions(+), 406 deletions(-)

diff --git a/drivers/bus/pci/linux/pci_vfio.c b/drivers/bus/pci/linux/pci_vfio.c
index 8fa7fa458f..d683fc17e1 100644
--- a/drivers/bus/pci/linux/pci_vfio.c
+++ b/drivers/bus/pci/linux/pci_vfio.c
@@ -107,84 +107,38 @@ pci_vfio_write_config(const struct rte_pci_device *dev,
 
 /* get PCI BAR number where MSI-X interrupts are */
 static int
-pci_vfio_get_msix_bar(const struct rte_pci_device *dev, int fd,
+pci_vfio_get_msix_bar(const struct rte_pci_device *dev,
 	struct pci_msix_table *msix_table)
 {
-	int ret;
-	uint32_t reg;
-	uint16_t flags;
-	uint8_t cap_id, cap_offset;
-	uint64_t size, offset;
-
-	if (pci_vfio_get_region(dev, VFIO_PCI_CONFIG_REGION_INDEX,
-		&size, &offset) != 0) {
-		RTE_LOG(ERR, EAL, "Cannot get offset of CONFIG region.\n");
-		return -1;
-	}
+	off_t cap_offset;
 
-	/* read PCI capability pointer from config space */
-	ret = pread64(fd, &reg, sizeof(reg), offset + PCI_CAPABILITY_LIST);
-	if (ret != sizeof(reg)) {
-		RTE_LOG(ERR, EAL,
-			"Cannot read capability pointer from PCI config space!\n");
+	cap_offset = rte_pci_find_capability(dev, PCI_CAP_ID_MSIX);
+	if (cap_offset < 0)
 		return -1;
-	}
 
-	/* we need first byte */
-	cap_offset = reg & 0xFF;
+	if (cap_offset != 0) {
+		uint16_t flags;
+		uint32_t reg;
 
-	while (cap_offset) {
-
-		/* read PCI capability ID */
-		ret = pread64(fd, &reg, sizeof(reg), offset + cap_offset);
-		if (ret != sizeof(reg)) {
+		/* table offset resides in the next 4 bytes */
+		if (rte_pci_read_config(dev, &reg, sizeof(reg), cap_offset + 4) < 0) {
 			RTE_LOG(ERR, EAL,
-				"Cannot read capability ID from PCI config space!\n");
+				"Cannot read MSIX table from PCI config space!\n");
 			return -1;
 		}
 
-		/* we need first byte */
-		cap_id = reg & 0xFF;
-
-		/* if we haven't reached MSI-X, check next capability */
-		if (cap_id != PCI_CAP_ID_MSIX) {
-			ret = pread64(fd, &reg, sizeof(reg), offset + cap_offset);
-			if (ret != sizeof(reg)) {
-				RTE_LOG(ERR, EAL,
-					"Cannot read capability pointer from PCI config space!\n");
-				return -1;
-			}
-
-			/* we need second byte */
-			cap_offset = (reg & 0xFF00) >> 8;
-
-			continue;
+		if (rte_pci_read_config(dev, &flags, sizeof(flags), cap_offset + 2) < 0) {
+			RTE_LOG(ERR, EAL,
+				"Cannot read MSIX flags from PCI config space!\n");
+			return -1;
 		}
-		/* else, read table offset */
-		else {
-			/* table offset resides in the next 4 bytes */
-			ret = pread64(fd, &reg, sizeof(reg), offset + cap_offset + 4);
-			if (ret != sizeof(reg)) {
-				RTE_LOG(ERR, EAL,
-					"Cannot read table offset from PCI config space!\n");
-				return -1;
-			}
 
-			ret = pread64(fd, &flags, sizeof(flags), offset + cap_offset + 2);
-			if (ret != sizeof(flags)) {
-				RTE_LOG(ERR, EAL,
-					"Cannot read table flags from PCI config space!\n");
-				return -1;
-			}
-
-			msix_table->bar_index = reg & RTE_PCI_MSIX_TABLE_BIR;
-			msix_table->offset = reg & RTE_PCI_MSIX_TABLE_OFFSET;
-			msix_table->size =
-				16 * (1 + (flags & RTE_PCI_MSIX_FLAGS_QSIZE));
-
-			return 0;
-		}
+		msix_table->bar_index = reg & PCI_MSIX_TABLE_BIR;
+		msix_table->offset = reg & PCI_MSIX_TABLE_OFFSET;
+		msix_table->size =
+			16 * (1 + (flags & PCI_MSIX_FLAGS_QSIZE));
 	}
+
 	return 0;
 }
 
@@ -869,7 +823,7 @@ pci_vfio_map_resource_primary(struct rte_pci_device *dev)
 	/* get MSI-X BAR, if any (we have to know where it is because we can't
 	 * easily mmap it when using VFIO)
 	 */
-	ret = pci_vfio_get_msix_bar(dev, vfio_dev_fd, &vfio_res->msix_table);
+	ret = pci_vfio_get_msix_bar(dev, &vfio_res->msix_table);
 	if (ret < 0) {
 		RTE_LOG(ERR, EAL, "%s cannot get MSI-X BAR number!\n",
 				pci_addr);
diff --git a/drivers/bus/pci/pci_common.c b/drivers/bus/pci/pci_common.c
index 382b0b8946..52272617eb 100644
--- a/drivers/bus/pci/pci_common.c
+++ b/drivers/bus/pci/pci_common.c
@@ -813,6 +813,51 @@ rte_pci_get_iommu_class(void)
 	return iova_mode;
 }
 
+bool
+rte_pci_has_capability_list(const struct rte_pci_device *dev)
+{
+	uint16_t status;
+
+	if (rte_pci_read_config(dev, &status, sizeof(status), RTE_PCI_STATUS) != sizeof(status))
+		return false;
+
+	return (status & RTE_PCI_STATUS_CAP_LIST) != 0;
+}
+
+off_t
+rte_pci_find_capability(const struct rte_pci_device *dev, uint8_t cap)
+{
+	off_t offset;
+	uint8_t pos;
+	int ttl;
+
+	offset = RTE_PCI_CAPABILITY_LIST;
+	ttl = (RTE_PCI_CFG_SPACE_SIZE - RTE_PCI_STD_HEADER_SIZEOF) / RTE_PCI_CAP_SIZEOF;
+
+	if (rte_pci_read_config(dev, &pos, sizeof(pos), offset) < 0)
+		return -1;
+
+	while (pos && ttl--) {
+		uint16_t ent;
+		uint8_t id;
+
+		offset = pos;
+		if (rte_pci_read_config(dev, &ent, sizeof(ent), offset) < 0)
+			return -1;
+
+		id = ent & 0xff;
+		if (id == 0xff)
+			break;
+
+		if (id == cap)
+			return offset;
+
+		pos = (ent >> 8);
+	}
+
+	return 0;
+}
+
 off_t
 rte_pci_find_ext_capability(const struct rte_pci_device *dev, uint32_t cap)
 {
diff --git a/drivers/bus/pci/rte_bus_pci.h b/drivers/bus/pci/rte_bus_pci.h
index 75d0030eae..1ed33dbf3d 100644
--- a/drivers/bus/pci/rte_bus_pci.h
+++ b/drivers/bus/pci/rte_bus_pci.h
@@ -68,6 +68,37 @@ void rte_pci_unmap_device(struct rte_pci_device *dev);
  */
 void rte_pci_dump(FILE *f);
 
+/**
+ * Check whether this device has a PCI capability list.
+ *
+ *  @param dev
+ *    A pointer to rte_pci_device structure.
+ *
+ *  @return
+ *    true/false
+ */
+__rte_experimental
+bool rte_pci_has_capability_list(const struct rte_pci_device *dev);
+
+/**
+ * Find device's PCI capability.
+ *
+ *  @param dev
+ *    A pointer to rte_pci_device structure.
+ *
+ *  @param cap
+ *    Capability to be found, which can be any from
+ *    RTE_PCI_CAP_ID_*, defined in librte_pci.
+ *
+ *  @return
+ *  > 0: The offset of the next matching capability structure
+ *       within the device's PCI configuration space.
+ *  < 0: An error in PCI config space read.
+ *  = 0: Device does not support it.
+ */
+__rte_experimental
+off_t rte_pci_find_capability(const struct rte_pci_device *dev, uint8_t cap);
+
 /**
  * Find device's extended PCI capability.
  *
diff --git a/drivers/bus/pci/version.map b/drivers/bus/pci/version.map
index a0000f7938..4397e33e3f 100644
--- a/drivers/bus/pci/version.map
+++ b/drivers/bus/pci/version.map
@@ -25,6 +25,8 @@ EXPERIMENTAL {
 	# added in 23.07
 	rte_pci_mmio_read;
 	rte_pci_mmio_write;
+	rte_pci_find_capability;
+	rte_pci_has_capability_list;
 };
 
 INTERNAL {
diff --git a/drivers/crypto/virtio/virtio_pci.c b/drivers/crypto/virtio/virtio_pci.c
index 95a43c8801..abc52b4701 100644
--- a/drivers/crypto/virtio/virtio_pci.c
+++ b/drivers/crypto/virtio/virtio_pci.c
@@ -19,7 +19,6 @@
  * we can't simply include that header here, as there is no such
  * file for non-Linux platform.
  */
-#define PCI_CAPABILITY_LIST	0x34
 #define PCI_CAP_ID_VNDR		0x09
 #define PCI_CAP_ID_MSIX		0x11
 
@@ -343,8 +342,9 @@ get_cfg_addr(struct rte_pci_device *dev, struct virtio_pci_cap *cap)
 static int
 virtio_read_caps(struct rte_pci_device *dev, struct virtio_crypto_hw *hw)
 {
-	uint8_t pos;
 	struct virtio_pci_cap cap;
+	uint16_t flags;
+	off_t pos;
 	int ret;
 
 	if (rte_pci_map_device(dev)) {
@@ -352,44 +352,26 @@ virtio_read_caps(struct rte_pci_device *dev, struct virtio_crypto_hw *hw)
 		return -1;
 	}
 
-	ret = rte_pci_read_config(dev, &pos, 1, PCI_CAPABILITY_LIST);
-	if (ret < 0) {
-		VIRTIO_CRYPTO_INIT_LOG_DBG("failed to read pci capability list");
-		return -1;
+	/*
+	 * Transitional devices would also have this capability,
+	 * that's why we also check if msix is enabled.
+	 */
+	pos = rte_pci_find_capability(dev, PCI_CAP_ID_MSIX);
+	if (pos > 0 && rte_pci_read_config(dev, &flags, sizeof(flags),
+			pos + 2) == sizeof(flags)) {
+		if (flags & PCI_MSIX_ENABLE)
+			hw->use_msix = VIRTIO_MSIX_ENABLED;
+		else
+			hw->use_msix = VIRTIO_MSIX_DISABLED;
+	} else {
+		hw->use_msix = VIRTIO_MSIX_NONE;
 	}
 
-	while (pos) {
-		ret = rte_pci_read_config(dev, &cap, sizeof(cap), pos);
-		if (ret < 0) {
-			VIRTIO_CRYPTO_INIT_LOG_ERR(
-				"failed to read pci cap at pos: %x", pos);
-			break;
-		}
-
-		if (cap.cap_vndr == PCI_CAP_ID_MSIX) {
-			/* Transitional devices would also have this capability,
-			 * that's why we also check if msix is enabled.
-			 * 1st byte is cap ID; 2nd byte is the position of next
-			 * cap; next two bytes are the flags.
-			 */
-			uint16_t flags = ((uint16_t *)&cap)[1];
-
-			if (flags & PCI_MSIX_ENABLE)
-				hw->use_msix = VIRTIO_MSIX_ENABLED;
-			else
-				hw->use_msix = VIRTIO_MSIX_DISABLED;
-		}
-
-		if (cap.cap_vndr != PCI_CAP_ID_VNDR) {
-			VIRTIO_CRYPTO_INIT_LOG_DBG(
-				"[%2x] skipping non VNDR cap id: %02x",
-				pos, cap.cap_vndr);
-			goto next;
-		}
-
+	pos = rte_pci_find_capability(dev, PCI_CAP_ID_VNDR);
+	if (pos > 0 && rte_pci_read_config(dev, &cap, sizeof(cap), pos) == sizeof(cap)) {
 		VIRTIO_CRYPTO_INIT_LOG_DBG(
 			"[%2x] cfg type: %u, bar: %u, offset: %04x, len: %u",
-			pos, cap.cfg_type, cap.bar, cap.offset, cap.length);
+			(unsigned int)pos, cap.cfg_type, cap.bar, cap.offset, cap.length);
 
 		switch (cap.cfg_type) {
 		case VIRTIO_PCI_CAP_COMMON_CFG:
@@ -411,9 +393,6 @@ virtio_read_caps(struct rte_pci_device *dev, struct virtio_crypto_hw *hw)
 			hw->isr = get_cfg_addr(dev, &cap);
 			break;
 		}
-
-next:
-		pos = cap.cap_next;
 	}
 
 	if (hw->common_cfg == NULL || hw->notify_base == NULL ||
diff --git a/drivers/event/dlb2/pf/dlb2_main.c b/drivers/event/dlb2/pf/dlb2_main.c
index 717aa4fc08..40e5cb594f 100644
--- a/drivers/event/dlb2/pf/dlb2_main.c
+++ b/drivers/event/dlb2/pf/dlb2_main.c
@@ -27,10 +27,6 @@
 #define NO_OWNER_VF 0	/* PF ONLY! */
 #define NOT_VF_REQ false /* PF ONLY! */
 
-#define DLB2_PCI_CAP_POINTER 0x34
-#define DLB2_PCI_CAP_NEXT(hdr) (((hdr) >> 8) & 0xFC)
-#define DLB2_PCI_CAP_ID(hdr) ((hdr) & 0xFF)
-
 #define DLB2_PCI_LNKCTL 16
 #define DLB2_PCI_SLTCTL 24
 #define DLB2_PCI_RTCTL 28
@@ -65,35 +61,6 @@
 #define DLB2_PCI_ACS_UF                  0x10
 #define DLB2_PCI_ACS_EC                  0x20
 
-static int dlb2_pci_find_capability(struct rte_pci_device *pdev, uint32_t id)
-{
-	uint8_t pos;
-	int ret;
-	uint16_t hdr;
-
-	ret = rte_pci_read_config(pdev, &pos, 1, DLB2_PCI_CAP_POINTER);
-	pos &= 0xFC;
-
-	if (ret != 1)
-		return -1;
-
-	while (pos > 0x3F) {
-		ret = rte_pci_read_config(pdev, &hdr, 2, pos);
-		if (ret != 2)
-			return -1;
-
-		if (DLB2_PCI_CAP_ID(hdr) == id)
-			return pos;
-
-		if (DLB2_PCI_CAP_ID(hdr) == 0xFF)
-			return -1;
-
-		pos = DLB2_PCI_CAP_NEXT(hdr);
-	}
-
-	return -1;
-}
-
 static int
 dlb2_pf_init_driver_state(struct dlb2_dev *dlb2_dev)
 {
@@ -258,9 +225,9 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 	uint32_t pri_reqs_dword;
 	uint16_t pri_ctrl_word;
 
-	int pcie_cap_offset;
+	off_t pcie_cap_offset;
 	int pri_cap_offset;
-	int msix_cap_offset;
+	off_t msix_cap_offset;
 	int err_cap_offset;
 	int acs_cap_offset;
 	int wait_count;
@@ -277,7 +244,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 	}
 
-	pcie_cap_offset = dlb2_pci_find_capability(pdev, DLB2_PCI_CAP_ID_EXP);
+	pcie_cap_offset = rte_pci_find_capability(pdev, DLB2_PCI_CAP_ID_EXP);
 
 	if (pcie_cap_offset < 0) {
 		DLB2_LOG_ERR("[%s()] failed to find the pcie capability\n",
@@ -516,8 +483,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 		}
 	}
 
-	msix_cap_offset = dlb2_pci_find_capability(pdev,
-						   DLB2_PCI_CAP_ID_MSIX);
+	msix_cap_offset = rte_pci_find_capability(pdev, DLB2_PCI_CAP_ID_MSIX);
 	if (msix_cap_offset >= 0) {
 		off = msix_cap_offset + DLB2_PCI_MSIX_FLAGS;
 		if (rte_pci_read_config(pdev, &cmd, 2, off) == 2) {
diff --git a/drivers/net/bnx2x/bnx2x.c b/drivers/net/bnx2x/bnx2x.c
index 29c16bb207..06f2949885 100644
--- a/drivers/net/bnx2x/bnx2x.c
+++ b/drivers/net/bnx2x/bnx2x.c
@@ -9586,14 +9586,17 @@ static void bnx2x_init_multi_cos(struct bnx2x_softc *sc)
 	}
 }
 
+static uint8_t bnx2x_pci_capabilities[] = {
+	PCIY_EXPRESS,
+	PCIY_PMG,
+	PCIY_MSI,
+	PCIY_MSIX,
+};
+
 static int bnx2x_pci_get_caps(struct bnx2x_softc *sc)
 {
-	struct {
-		uint8_t id;
-		uint8_t next;
-	} pci_cap;
-	uint16_t status;
 	struct bnx2x_pci_cap *cap;
+	unsigned int i;
 
 	cap = sc->pci_caps = rte_zmalloc("caps", sizeof(struct bnx2x_pci_cap),
 					 RTE_CACHE_LINE_SIZE);
@@ -9602,29 +9605,21 @@ static int bnx2x_pci_get_caps(struct bnx2x_softc *sc)
 		return -ENOMEM;
 	}
 
-#ifndef RTE_EXEC_ENV_FREEBSD
-	pci_read(sc, PCI_STATUS, &status, 2);
-	if (!(status & PCI_STATUS_CAP_LIST)) {
-#else
-	pci_read(sc, PCIR_STATUS, &status, 2);
-	if (!(status & PCIM_STATUS_CAPPRESENT)) {
-#endif
+	if (!rte_pci_has_capability_list(sc->pci_dev)) {
 		PMD_DRV_LOG(NOTICE, sc, "PCIe capability reading failed");
 		return -1;
 	}
 
-#ifndef RTE_EXEC_ENV_FREEBSD
-	pci_read(sc, PCI_CAPABILITY_LIST, &pci_cap.next, 1);
-#else
-	pci_read(sc, PCIR_CAP_PTR, &pci_cap.next, 1);
-#endif
-	while (pci_cap.next) {
-		cap->addr = pci_cap.next & ~3;
-		pci_read(sc, pci_cap.next & ~3, &pci_cap, 2);
-		if (pci_cap.id == 0xff)
-			break;
-		cap->id = pci_cap.id;
+	for (i = 0; i < RTE_DIM(bnx2x_pci_capabilities); i++) {
+		off_t pos = rte_pci_find_capability(sc->pci_dev,
+			bnx2x_pci_capabilities[i]);
+
+		if (pos <= 0)
+			continue;
+
+		cap->id = bnx2x_pci_capabilities[i];
 		cap->type = BNX2X_PCI_CAP;
+		cap->addr = pos;
 		cap->next = rte_zmalloc("pci_cap",
 					sizeof(struct bnx2x_pci_cap),
 					RTE_CACHE_LINE_SIZE);
diff --git a/drivers/net/cxgbe/base/adapter.h b/drivers/net/cxgbe/base/adapter.h
index 8f2ffa0eeb..00d7591ea4 100644
--- a/drivers/net/cxgbe/base/adapter.h
+++ b/drivers/net/cxgbe/base/adapter.h
@@ -511,13 +511,8 @@ static inline void t4_write_reg64(struct adapter *adapter, u32 reg_addr,
 	CXGBE_WRITE_REG64(adapter, reg_addr, val);
 }
 
-#define PCI_STATUS              0x06    /* 16 bits */
-#define PCI_STATUS_CAP_LIST     0x10    /* Support Capability List */
-#define PCI_CAPABILITY_LIST     0x34
 /* Offset of first capability list entry */
 #define PCI_CAP_ID_EXP          0x10    /* PCI Express */
-#define PCI_CAP_LIST_ID         0       /* Capability ID */
-#define PCI_CAP_LIST_NEXT       1       /* Next capability in the list */
 #define PCI_EXP_DEVCTL          0x0008  /* Device control */
 #define PCI_EXP_DEVCTL2         40      /* Device Control 2 */
 #define PCI_EXP_DEVCTL_EXT_TAG  0x0100  /* Extended Tag Field Enable */
@@ -620,31 +615,12 @@ static inline void t4_os_pci_read_cfg(struct adapter *adapter, size_t addr,
  */
 static inline int t4_os_find_pci_capability(struct adapter *adapter, int cap)
 {
-	u16 status;
-	int ttl = 48;
-	u8 pos = 0;
-	u8 id = 0;
-
-	t4_os_pci_read_cfg2(adapter, PCI_STATUS, &status);
-	if (!(status & PCI_STATUS_CAP_LIST)) {
+	if (!rte_pci_has_capability_list(adapter->pdev)) {
 		dev_err(adapter, "PCIe capability reading failed\n");
 		return -1;
 	}
 
-	t4_os_pci_read_cfg(adapter, PCI_CAPABILITY_LIST, &pos);
-	while (ttl-- && pos >= 0x40) {
-		pos &= ~3;
-		t4_os_pci_read_cfg(adapter, (pos + PCI_CAP_LIST_ID), &id);
-
-		if (id == 0xff)
-			break;
-
-		if (id == cap)
-			return (int)pos;
-
-		t4_os_pci_read_cfg(adapter, (pos + PCI_CAP_LIST_NEXT), &pos);
-	}
-	return 0;
+	return rte_pci_find_capability(adapter->pdev, cap);
 }
 
 /**
diff --git a/drivers/net/gve/gve_ethdev.c b/drivers/net/gve/gve_ethdev.c
index aa75abe102..c276b9e68e 100644
--- a/drivers/net/gve/gve_ethdev.c
+++ b/drivers/net/gve/gve_ethdev.c
@@ -606,53 +606,17 @@ gve_teardown_device_resources(struct gve_priv *priv)
 	gve_clear_device_resources_ok(priv);
 }
 
-static uint8_t
-pci_dev_find_capability(struct rte_pci_device *pdev, int cap)
-{
-	uint8_t pos, id;
-	uint16_t ent;
-	int loops;
-	int ret;
-
-	ret = rte_pci_read_config(pdev, &pos, sizeof(pos), PCI_CAPABILITY_LIST);
-	if (ret != sizeof(pos))
-		return 0;
-
-	loops = (PCI_CFG_SPACE_SIZE - PCI_STD_HEADER_SIZEOF) / PCI_CAP_SIZEOF;
-
-	while (pos && loops--) {
-		ret = rte_pci_read_config(pdev, &ent, sizeof(ent), pos);
-		if (ret != sizeof(ent))
-			return 0;
-
-		id = ent & 0xff;
-		if (id == 0xff)
-			break;
-
-		if (id == cap)
-			return pos;
-
-		pos = (ent >> 8);
-	}
-
-	return 0;
-}
-
 static int
 pci_dev_msix_vec_count(struct rte_pci_device *pdev)
 {
-	uint8_t msix_cap = pci_dev_find_capability(pdev, PCI_CAP_ID_MSIX);
+	off_t msix_pos = rte_pci_find_capability(pdev, PCI_CAP_ID_MSIX);
 	uint16_t control;
-	int ret;
 
-	if (!msix_cap)
-		return 0;
-
-	ret = rte_pci_read_config(pdev, &control, sizeof(control), msix_cap + PCI_MSIX_FLAGS);
-	if (ret != sizeof(control))
-		return 0;
+	if (msix_pos > 0 && rte_pci_read_config(pdev, &control, sizeof(control),
+			msix_pos + PCI_MSIX_FLAGS) == sizeof(control))
+		return (control & PCI_MSIX_FLAGS_QSIZE) + 1;
 
-	return (control & PCI_MSIX_FLAGS_QSIZE) + 1;
+	return 0;
 }
 
 static int
diff --git a/drivers/net/gve/gve_ethdev.h b/drivers/net/gve/gve_ethdev.h
index c9bcfa553c..8759b1c76e 100644
--- a/drivers/net/gve/gve_ethdev.h
+++ b/drivers/net/gve/gve_ethdev.h
@@ -19,10 +19,6 @@
  * we can't simply include that header here, as there is no such
  * file for non-Linux platform.
  */
-#define PCI_CFG_SPACE_SIZE	256
-#define PCI_CAPABILITY_LIST	0x34	/* Offset of first capability list entry */
-#define PCI_STD_HEADER_SIZEOF	64
-#define PCI_CAP_SIZEOF		4
 #define PCI_CAP_ID_MSIX		0x11	/* MSI-X */
 #define PCI_MSIX_FLAGS		2	/* Message Control */
 #define PCI_MSIX_FLAGS_QSIZE	0x07FF	/* Table size */
diff --git a/drivers/net/hns3/hns3_ethdev_vf.c b/drivers/net/hns3/hns3_ethdev_vf.c
index 7b3c5dc168..b731850b01 100644
--- a/drivers/net/hns3/hns3_ethdev_vf.c
+++ b/drivers/net/hns3/hns3_ethdev_vf.c
@@ -49,80 +49,24 @@ static int hns3vf_remove_mc_mac_addr(struct hns3_hw *hw,
 static int hns3vf_dev_link_update(struct rte_eth_dev *eth_dev,
 				   __rte_unused int wait_to_complete);
 
-/**
- * hns3vf_find_pci_capability - lookup a capability in the PCI capability list
- * @cap: the capability
- *
- * Return the address of the given capability within the PCI capability list.
- */
 static int
-hns3vf_find_pci_capability(const struct rte_pci_device *device, int cap)
+hns3vf_enable_msix(const struct rte_pci_device *device, bool op)
 {
-#define MAX_PCIE_CAPABILITY 48
-	uint16_t status;
-	uint8_t pos;
-	uint8_t id;
-	int ttl;
+	uint16_t control;
+	off_t pos;
 	int ret;
 
-	ret = rte_pci_read_config(device, &status, sizeof(status), PCI_STATUS);
-	if (ret < 0) {
-		PMD_INIT_LOG(ERR, "Failed to read PCI offset 0x%x", PCI_STATUS);
-		return 0;
-	}
-
-	if (!(status & PCI_STATUS_CAP_LIST))
-		return 0;
-
-	ttl = MAX_PCIE_CAPABILITY;
-	ret = rte_pci_read_config(device, &pos, sizeof(pos),
-				  PCI_CAPABILITY_LIST);
-	if (ret < 0) {
-		PMD_INIT_LOG(ERR, "Failed to read PCI offset 0x%x",
-			     PCI_CAPABILITY_LIST);
+	if (!rte_pci_has_capability_list(device)) {
+		PMD_INIT_LOG(ERR, "Failed to read PCI capability list");
 		return 0;
 	}
 
-	while (ttl-- && pos >= PCI_STD_HEADER_SIZEOF) {
-		ret = rte_pci_read_config(device, &id, sizeof(id),
-					  (pos + PCI_CAP_LIST_ID));
-		if (ret < 0) {
-			PMD_INIT_LOG(ERR, "Failed to read PCI offset 0x%x",
-				     (pos + PCI_CAP_LIST_ID));
-			break;
-		}
-
-		if (id == 0xFF)
-			break;
-
-		if (id == cap)
-			return (int)pos;
-
-		ret = rte_pci_read_config(device, &pos, sizeof(pos),
-					  (pos + PCI_CAP_LIST_NEXT));
-		if (ret < 0) {
-			PMD_INIT_LOG(ERR, "Failed to read PCI offset 0x%x",
-				     (pos + PCI_CAP_LIST_NEXT));
-			break;
-		}
-	}
-	return 0;
-}
-
-static int
-hns3vf_enable_msix(const struct rte_pci_device *device, bool op)
-{
-	uint16_t control;
-	int pos;
-	int ret;
-
-	pos = hns3vf_find_pci_capability(device, PCI_CAP_ID_MSIX);
-	if (pos) {
+	pos = rte_pci_find_capability(device, PCI_CAP_ID_MSIX);
+	if (pos > 0) {
 		ret = rte_pci_read_config(device, &control, sizeof(control),
-					  (pos + PCI_MSIX_FLAGS));
+			pos + PCI_MSIX_FLAGS);
 		if (ret < 0) {
-			PMD_INIT_LOG(ERR, "Failed to read PCI offset 0x%x",
-				     (pos + PCI_MSIX_FLAGS));
+			PMD_INIT_LOG(ERR, "Failed to read MSIX flags");
 			return -ENXIO;
 		}
 
@@ -131,10 +75,9 @@ hns3vf_enable_msix(const struct rte_pci_device *device, bool op)
 		else
 			control &= ~PCI_MSIX_FLAGS_ENABLE;
 		ret = rte_pci_write_config(device, &control, sizeof(control),
-					   (pos + PCI_MSIX_FLAGS));
+			pos + PCI_MSIX_FLAGS);
 		if (ret < 0) {
-			PMD_INIT_LOG(ERR, "failed to write PCI offset 0x%x",
-				     (pos + PCI_MSIX_FLAGS));
+			PMD_INIT_LOG(ERR, "failed to write MSIX flags");
 			return -ENXIO;
 		}
 
diff --git a/drivers/net/virtio/virtio_pci.c b/drivers/net/virtio/virtio_pci.c
index 29eb739b04..9fd9db3e03 100644
--- a/drivers/net/virtio/virtio_pci.c
+++ b/drivers/net/virtio/virtio_pci.c
@@ -20,7 +20,6 @@
  * we can't simply include that header here, as there is no such
  * file for non-Linux platform.
  */
-#define PCI_CAPABILITY_LIST	0x34
 #define PCI_CAP_ID_VNDR		0x09
 #define PCI_CAP_ID_MSIX		0x11
 
@@ -38,46 +37,16 @@ struct virtio_pci_internal virtio_pci_internal[RTE_MAX_ETHPORTS];
 static enum virtio_msix_status
 vtpci_msix_detect(struct rte_pci_device *dev)
 {
-	uint8_t pos;
-	int ret;
+	uint16_t flags;
+	off_t pos;
 
-	ret = rte_pci_read_config(dev, &pos, 1, PCI_CAPABILITY_LIST);
-	if (ret != 1) {
-		PMD_INIT_LOG(DEBUG,
-			     "failed to read pci capability list, ret %d", ret);
-		return VIRTIO_MSIX_NONE;
-	}
-
-	while (pos) {
-		uint8_t cap[2];
-
-		ret = rte_pci_read_config(dev, cap, sizeof(cap), pos);
-		if (ret != sizeof(cap)) {
-			PMD_INIT_LOG(DEBUG,
-				     "failed to read pci cap at pos: %x ret %d",
-				     pos, ret);
-			break;
-		}
-
-		if (cap[0] == PCI_CAP_ID_MSIX) {
-			uint16_t flags;
-
-			ret = rte_pci_read_config(dev, &flags, sizeof(flags),
-					pos + sizeof(cap));
-			if (ret != sizeof(flags)) {
-				PMD_INIT_LOG(DEBUG,
-					     "failed to read pci cap at pos:"
-					     " %x ret %d", pos + 2, ret);
-				break;
-			}
-
-			if (flags & PCI_MSIX_ENABLE)
-				return VIRTIO_MSIX_ENABLED;
-			else
-				return VIRTIO_MSIX_DISABLED;
-		}
-
-		pos = cap[1];
+	pos = rte_pci_find_capability(dev, PCI_CAP_ID_MSIX);
+	if (pos > 0 && rte_pci_read_config(dev, &flags, sizeof(flags),
+			pos + 2) == sizeof(flags)) {
+		if (flags & PCI_MSIX_ENABLE)
+			return VIRTIO_MSIX_ENABLED;
+		else
+			return VIRTIO_MSIX_DISABLED;
 	}
 
 	return VIRTIO_MSIX_NONE;
@@ -623,8 +592,8 @@ static int
 virtio_read_caps(struct rte_pci_device *pci_dev, struct virtio_hw *hw)
 {
 	struct virtio_pci_dev *dev = virtio_pci_get_dev(hw);
-	uint8_t pos;
 	struct virtio_pci_cap cap;
+	off_t pos;
 	int ret;
 
 	if (rte_pci_map_device(pci_dev)) {
@@ -632,72 +601,25 @@ virtio_read_caps(struct rte_pci_device *pci_dev, struct virtio_hw *hw)
 		return -1;
 	}
 
-	ret = rte_pci_read_config(pci_dev, &pos, 1, PCI_CAPABILITY_LIST);
-	if (ret != 1) {
-		PMD_INIT_LOG(DEBUG,
-			     "failed to read pci capability list, ret %d", ret);
-		return -1;
-	}
-
-	while (pos) {
-		ret = rte_pci_read_config(pci_dev, &cap, 2, pos);
-		if (ret != 2) {
-			PMD_INIT_LOG(DEBUG,
-				     "failed to read pci cap at pos: %x ret %d",
-				     pos, ret);
-			break;
-		}
-
-		if (cap.cap_vndr == PCI_CAP_ID_MSIX) {
-			/* Transitional devices would also have this capability,
-			 * that's why we also check if msix is enabled.
-			 * 1st byte is cap ID; 2nd byte is the position of next
-			 * cap; next two bytes are the flags.
-			 */
-			uint16_t flags;
-
-			ret = rte_pci_read_config(pci_dev, &flags, sizeof(flags),
-					pos + 2);
-			if (ret != sizeof(flags)) {
-				PMD_INIT_LOG(DEBUG,
-					     "failed to read pci cap at pos:"
-					     " %x ret %d", pos + 2, ret);
-				break;
-			}
-
-			if (flags & PCI_MSIX_ENABLE)
-				dev->msix_status = VIRTIO_MSIX_ENABLED;
-			else
-				dev->msix_status = VIRTIO_MSIX_DISABLED;
-		}
-
-		if (cap.cap_vndr != PCI_CAP_ID_VNDR) {
-			PMD_INIT_LOG(DEBUG,
-				"[%2x] skipping non VNDR cap id: %02x",
-				pos, cap.cap_vndr);
-			goto next;
-		}
-
-		ret = rte_pci_read_config(pci_dev, &cap, sizeof(cap), pos);
-		if (ret != sizeof(cap)) {
-			PMD_INIT_LOG(DEBUG,
-				     "failed to read pci cap at pos: %x ret %d",
-				     pos, ret);
-			break;
-		}
+	/*
+	 * Transitional devices would also have this capability,
+	 * that's why we also check if msix is enabled.
+	 */
+	dev->msix_status = vtpci_msix_detect(pci_dev);
 
+	pos = rte_pci_find_capability(pci_dev, PCI_CAP_ID_VNDR);
+	if (pos > 0 && rte_pci_read_config(pci_dev, &cap, sizeof(cap), pos) == sizeof(cap)) {
 		PMD_INIT_LOG(DEBUG,
 			"[%2x] cfg type: %u, bar: %u, offset: %04x, len: %u",
-			pos, cap.cfg_type, cap.bar, cap.offset, cap.length);
+			(unsigned int)pos, cap.cfg_type, cap.bar, cap.offset, cap.length);
 
 		switch (cap.cfg_type) {
 		case VIRTIO_PCI_CAP_COMMON_CFG:
 			dev->common_cfg = get_cfg_addr(pci_dev, &cap);
 			break;
 		case VIRTIO_PCI_CAP_NOTIFY_CFG:
-			ret = rte_pci_read_config(pci_dev,
-					&dev->notify_off_multiplier,
-					4, pos + sizeof(cap));
+			ret = rte_pci_read_config(pci_dev, &dev->notify_off_multiplier,
+				4, pos + sizeof(cap));
 			if (ret != 4)
 				PMD_INIT_LOG(DEBUG,
 					"failed to read notify_off_multiplier, ret %d",
@@ -712,9 +634,6 @@ virtio_read_caps(struct rte_pci_device *pci_dev, struct virtio_hw *hw)
 			dev->isr = get_cfg_addr(pci_dev, &cap);
 			break;
 		}
-
-next:
-		pos = cap.cap_next;
 	}
 
 	if (dev->common_cfg == NULL || dev->notify_base == NULL ||
diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
index aab761b918..3b2d3cfe4e 100644
--- a/lib/pci/rte_pci.h
+++ b/lib/pci/rte_pci.h
@@ -28,6 +28,8 @@ extern "C" {
 #define RTE_PCI_CFG_SPACE_SIZE		256
 #define RTE_PCI_CFG_SPACE_EXP_SIZE	4096
 
+#define RTE_PCI_STD_HEADER_SIZEOF	64
+
 #define RTE_PCI_VENDOR_ID	0x00	/* 16 bits */
 #define RTE_PCI_DEVICE_ID	0x02	/* 16 bits */
 #define RTE_PCI_COMMAND		0x04	/* 16 bits */
@@ -35,6 +37,14 @@ extern "C" {
 /* PCI Command Register */
 #define RTE_PCI_COMMAND_MASTER	0x4	/* Bus Master Enable */
 
+/* PCI Status Register */
+#define RTE_PCI_STATUS		0x06	/* 16 bits */
+#define RTE_PCI_STATUS_CAP_LIST	0x10	/* Support Capability List */
+
+/* Capability registers */
+#define RTE_PCI_CAPABILITY_LIST	0x34	/* Offset of first capability list entry */
+#define RTE_PCI_CAP_SIZEOF	4
+
 /* PCI Express capability registers */
 #define RTE_PCI_EXP_DEVCTL	8	/* Device Control */
 
-- 
2.41.0


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

* [PATCH 04/14] pci: define some capability constants
  2023-08-03  7:50 [PATCH 00/14] Cleanup PCI(e) drivers David Marchand
                   ` (2 preceding siblings ...)
  2023-08-03  7:50 ` [PATCH 03/14] bus/pci: find PCI capability David Marchand
@ 2023-08-03  7:50 ` David Marchand
  2023-08-03  9:51   ` Bruce Richardson
  2023-08-03  7:50 ` [PATCH 05/14] pci: define some MSIX constants David Marchand
                   ` (15 subsequent siblings)
  19 siblings, 1 reply; 98+ messages in thread
From: David Marchand @ 2023-08-03  7:50 UTC (permalink / raw)
  To: dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, Anatoly Burakov,
	Jay Zhou, Timothy McDaniel, Julien Aube, Rahul Lakkireddy,
	Junfeng Guo, Jeroen de Borst, Rushil Gupta, Joshua Washington,
	Dongdong Liu, Yisen Zhuang, Maxime Coquelin, Xiao Wang,
	Gaetan Rivet

Define some PCI capability constants and use them in existing drivers.

Signed-off-by: David Marchand <david.marchand@redhat.com>
---
 drivers/bus/pci/linux/pci_vfio.c    |  2 +-
 drivers/crypto/virtio/virtio_pci.c  | 12 ++----------
 drivers/event/dlb2/pf/dlb2_main.c   |  6 ++----
 drivers/net/bnx2x/bnx2x.c           | 16 ++++++++--------
 drivers/net/bnx2x/bnx2x.h           |  4 ----
 drivers/net/cxgbe/base/adapter.h    |  3 +--
 drivers/net/gve/gve_ethdev.c        |  2 +-
 drivers/net/gve/gve_ethdev.h        |  2 +-
 drivers/net/hns3/hns3_ethdev_vf.c   |  2 +-
 drivers/net/virtio/virtio_pci.c     | 12 ++----------
 drivers/vdpa/ifc/base/ifcvf_osdep.h |  4 +++-
 lib/pci/rte_pci.h                   |  5 +++++
 12 files changed, 27 insertions(+), 43 deletions(-)

diff --git a/drivers/bus/pci/linux/pci_vfio.c b/drivers/bus/pci/linux/pci_vfio.c
index d683fc17e1..ac5a2c78b5 100644
--- a/drivers/bus/pci/linux/pci_vfio.c
+++ b/drivers/bus/pci/linux/pci_vfio.c
@@ -112,7 +112,7 @@ pci_vfio_get_msix_bar(const struct rte_pci_device *dev,
 {
 	off_t cap_offset;
 
-	cap_offset = rte_pci_find_capability(dev, PCI_CAP_ID_MSIX);
+	cap_offset = rte_pci_find_capability(dev, RTE_PCI_CAP_ID_MSIX);
 	if (cap_offset < 0)
 		return -1;
 
diff --git a/drivers/crypto/virtio/virtio_pci.c b/drivers/crypto/virtio/virtio_pci.c
index abc52b4701..9e340f2b0d 100644
--- a/drivers/crypto/virtio/virtio_pci.c
+++ b/drivers/crypto/virtio/virtio_pci.c
@@ -14,14 +14,6 @@
 #include "virtio_pci.h"
 #include "virtqueue.h"
 
-/*
- * Following macros are derived from linux/pci_regs.h, however,
- * we can't simply include that header here, as there is no such
- * file for non-Linux platform.
- */
-#define PCI_CAP_ID_VNDR		0x09
-#define PCI_CAP_ID_MSIX		0x11
-
 /*
  * The remaining space is defined by each driver as the per-driver
  * configuration space.
@@ -356,7 +348,7 @@ virtio_read_caps(struct rte_pci_device *dev, struct virtio_crypto_hw *hw)
 	 * Transitional devices would also have this capability,
 	 * that's why we also check if msix is enabled.
 	 */
-	pos = rte_pci_find_capability(dev, PCI_CAP_ID_MSIX);
+	pos = rte_pci_find_capability(dev, RTE_PCI_CAP_ID_MSIX);
 	if (pos > 0 && rte_pci_read_config(dev, &flags, sizeof(flags),
 			pos + 2) == sizeof(flags)) {
 		if (flags & PCI_MSIX_ENABLE)
@@ -367,7 +359,7 @@ virtio_read_caps(struct rte_pci_device *dev, struct virtio_crypto_hw *hw)
 		hw->use_msix = VIRTIO_MSIX_NONE;
 	}
 
-	pos = rte_pci_find_capability(dev, PCI_CAP_ID_VNDR);
+	pos = rte_pci_find_capability(dev, RTE_PCI_CAP_ID_VNDR);
 	if (pos > 0 && rte_pci_read_config(dev, &cap, sizeof(cap), pos) == sizeof(cap)) {
 		VIRTIO_CRYPTO_INIT_LOG_DBG(
 			"[%2x] cfg type: %u, bar: %u, offset: %04x, len: %u",
diff --git a/drivers/event/dlb2/pf/dlb2_main.c b/drivers/event/dlb2/pf/dlb2_main.c
index 40e5cb594f..1a229baee0 100644
--- a/drivers/event/dlb2/pf/dlb2_main.c
+++ b/drivers/event/dlb2/pf/dlb2_main.c
@@ -38,8 +38,6 @@
 #define DLB2_PCI_EXP_DEVSTA_TRPND 0x20
 #define DLB2_PCI_EXP_DEVCTL_BCR_FLR 0x8000
 
-#define DLB2_PCI_CAP_ID_EXP       0x10
-#define DLB2_PCI_CAP_ID_MSIX      0x11
 #define DLB2_PCI_EXT_CAP_ID_PRI   0x13
 #define DLB2_PCI_EXT_CAP_ID_ACS   0xD
 
@@ -244,7 +242,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 	}
 
-	pcie_cap_offset = rte_pci_find_capability(pdev, DLB2_PCI_CAP_ID_EXP);
+	pcie_cap_offset = rte_pci_find_capability(pdev, RTE_PCI_CAP_ID_EXP);
 
 	if (pcie_cap_offset < 0) {
 		DLB2_LOG_ERR("[%s()] failed to find the pcie capability\n",
@@ -483,7 +481,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 		}
 	}
 
-	msix_cap_offset = rte_pci_find_capability(pdev, DLB2_PCI_CAP_ID_MSIX);
+	msix_cap_offset = rte_pci_find_capability(pdev, RTE_PCI_CAP_ID_MSIX);
 	if (msix_cap_offset >= 0) {
 		off = msix_cap_offset + DLB2_PCI_MSIX_FLAGS;
 		if (rte_pci_read_config(pdev, &cmd, 2, off) == 2) {
diff --git a/drivers/net/bnx2x/bnx2x.c b/drivers/net/bnx2x/bnx2x.c
index 06f2949885..8a97de8806 100644
--- a/drivers/net/bnx2x/bnx2x.c
+++ b/drivers/net/bnx2x/bnx2x.c
@@ -7613,7 +7613,7 @@ static uint32_t bnx2x_pcie_capability_read(struct bnx2x_softc *sc, int reg)
 	struct bnx2x_pci_cap *caps;
 
 	/* ensure PCIe capability is enabled */
-	caps = pci_find_cap(sc, PCIY_EXPRESS, BNX2X_PCI_CAP);
+	caps = pci_find_cap(sc, RTE_PCI_CAP_ID_EXP, BNX2X_PCI_CAP);
 	if (NULL != caps) {
 		PMD_DRV_LOG(DEBUG, sc, "Found PCIe capability: "
 			    "id=0x%04X type=0x%04X addr=0x%08X",
@@ -7647,7 +7647,7 @@ static void bnx2x_probe_pci_caps(struct bnx2x_softc *sc)
 	int reg = 0;
 
 	/* check if PCI Power Management is enabled */
-	caps = pci_find_cap(sc, PCIY_PMG, BNX2X_PCI_CAP);
+	caps = pci_find_cap(sc, RTE_PCI_CAP_ID_PM, BNX2X_PCI_CAP);
 	if (NULL != caps) {
 		PMD_DRV_LOG(DEBUG, sc, "Found PM capability: "
 			    "id=0x%04X type=0x%04X addr=0x%08X",
@@ -7669,7 +7669,7 @@ static void bnx2x_probe_pci_caps(struct bnx2x_softc *sc)
 	sc->devinfo.pcie_cap_flags |= BNX2X_PCIE_CAPABLE_FLAG;
 
 	/* check if MSI capability is enabled */
-	caps = pci_find_cap(sc, PCIY_MSI, BNX2X_PCI_CAP);
+	caps = pci_find_cap(sc, RTE_PCI_CAP_ID_MSI, BNX2X_PCI_CAP);
 	if (NULL != caps) {
 		PMD_DRV_LOG(DEBUG, sc, "Found MSI capability at 0x%04x", reg);
 
@@ -7678,7 +7678,7 @@ static void bnx2x_probe_pci_caps(struct bnx2x_softc *sc)
 	}
 
 	/* check if MSI-X capability is enabled */
-	caps = pci_find_cap(sc, PCIY_MSIX, BNX2X_PCI_CAP);
+	caps = pci_find_cap(sc, RTE_PCI_CAP_ID_MSIX, BNX2X_PCI_CAP);
 	if (NULL != caps) {
 		PMD_DRV_LOG(DEBUG, sc, "Found MSI-X capability at 0x%04x", reg);
 
@@ -9587,10 +9587,10 @@ static void bnx2x_init_multi_cos(struct bnx2x_softc *sc)
 }
 
 static uint8_t bnx2x_pci_capabilities[] = {
-	PCIY_EXPRESS,
-	PCIY_PMG,
-	PCIY_MSI,
-	PCIY_MSIX,
+	RTE_PCI_CAP_ID_EXP,
+	RTE_PCI_CAP_ID_PM,
+	RTE_PCI_CAP_ID_MSI,
+	RTE_PCI_CAP_ID_MSIX,
 };
 
 static int bnx2x_pci_get_caps(struct bnx2x_softc *sc)
diff --git a/drivers/net/bnx2x/bnx2x.h b/drivers/net/bnx2x/bnx2x.h
index 89414ac88a..07ef0567c2 100644
--- a/drivers/net/bnx2x/bnx2x.h
+++ b/drivers/net/bnx2x/bnx2x.h
@@ -33,10 +33,6 @@
 #ifndef RTE_EXEC_ENV_FREEBSD
 #include <linux/pci_regs.h>
 
-#define PCIY_PMG                       PCI_CAP_ID_PM
-#define PCIY_MSI                       PCI_CAP_ID_MSI
-#define PCIY_EXPRESS                   PCI_CAP_ID_EXP
-#define PCIY_MSIX                      PCI_CAP_ID_MSIX
 #define PCIR_EXPRESS_DEVICE_STA        PCI_EXP_TYPE_RC_EC
 #define PCIM_EXP_STA_TRANSACTION_PND   PCI_EXP_DEVSTA_TRPND
 #define PCIR_EXPRESS_LINK_STA          PCI_EXP_LNKSTA
diff --git a/drivers/net/cxgbe/base/adapter.h b/drivers/net/cxgbe/base/adapter.h
index 00d7591ea4..7bee5cf3a8 100644
--- a/drivers/net/cxgbe/base/adapter.h
+++ b/drivers/net/cxgbe/base/adapter.h
@@ -511,8 +511,7 @@ static inline void t4_write_reg64(struct adapter *adapter, u32 reg_addr,
 	CXGBE_WRITE_REG64(adapter, reg_addr, val);
 }
 
-/* Offset of first capability list entry */
-#define PCI_CAP_ID_EXP          0x10    /* PCI Express */
+#define PCI_CAP_ID_EXP          RTE_PCI_CAP_ID_EXP
 #define PCI_EXP_DEVCTL          0x0008  /* Device control */
 #define PCI_EXP_DEVCTL2         40      /* Device Control 2 */
 #define PCI_EXP_DEVCTL_EXT_TAG  0x0100  /* Extended Tag Field Enable */
diff --git a/drivers/net/gve/gve_ethdev.c b/drivers/net/gve/gve_ethdev.c
index c276b9e68e..9ea5dbaeea 100644
--- a/drivers/net/gve/gve_ethdev.c
+++ b/drivers/net/gve/gve_ethdev.c
@@ -609,7 +609,7 @@ gve_teardown_device_resources(struct gve_priv *priv)
 static int
 pci_dev_msix_vec_count(struct rte_pci_device *pdev)
 {
-	off_t msix_pos = rte_pci_find_capability(pdev, PCI_CAP_ID_MSIX);
+	off_t msix_pos = rte_pci_find_capability(pdev, RTE_PCI_CAP_ID_MSIX);
 	uint16_t control;
 
 	if (msix_pos > 0 && rte_pci_read_config(pdev, &control, sizeof(control),
diff --git a/drivers/net/gve/gve_ethdev.h b/drivers/net/gve/gve_ethdev.h
index 8759b1c76e..d604a75b7f 100644
--- a/drivers/net/gve/gve_ethdev.h
+++ b/drivers/net/gve/gve_ethdev.h
@@ -8,6 +8,7 @@
 #include <ethdev_driver.h>
 #include <ethdev_pci.h>
 #include <rte_ether.h>
+#include <rte_pci.h>
 
 #include "base/gve.h"
 
@@ -19,7 +20,6 @@
  * we can't simply include that header here, as there is no such
  * file for non-Linux platform.
  */
-#define PCI_CAP_ID_MSIX		0x11	/* MSI-X */
 #define PCI_MSIX_FLAGS		2	/* Message Control */
 #define PCI_MSIX_FLAGS_QSIZE	0x07FF	/* Table size */
 
diff --git a/drivers/net/hns3/hns3_ethdev_vf.c b/drivers/net/hns3/hns3_ethdev_vf.c
index b731850b01..eab5c55f5e 100644
--- a/drivers/net/hns3/hns3_ethdev_vf.c
+++ b/drivers/net/hns3/hns3_ethdev_vf.c
@@ -61,7 +61,7 @@ hns3vf_enable_msix(const struct rte_pci_device *device, bool op)
 		return 0;
 	}
 
-	pos = rte_pci_find_capability(device, PCI_CAP_ID_MSIX);
+	pos = rte_pci_find_capability(device, RTE_PCI_CAP_ID_MSIX);
 	if (pos > 0) {
 		ret = rte_pci_read_config(device, &control, sizeof(control),
 			pos + PCI_MSIX_FLAGS);
diff --git a/drivers/net/virtio/virtio_pci.c b/drivers/net/virtio/virtio_pci.c
index 9fd9db3e03..81d5dd0a4a 100644
--- a/drivers/net/virtio/virtio_pci.c
+++ b/drivers/net/virtio/virtio_pci.c
@@ -15,14 +15,6 @@
 #include "virtio_logs.h"
 #include "virtqueue.h"
 
-/*
- * Following macros are derived from linux/pci_regs.h, however,
- * we can't simply include that header here, as there is no such
- * file for non-Linux platform.
- */
-#define PCI_CAP_ID_VNDR		0x09
-#define PCI_CAP_ID_MSIX		0x11
-
 /*
  * The remaining space is defined by each driver as the per-driver
  * configuration space.
@@ -40,7 +32,7 @@ vtpci_msix_detect(struct rte_pci_device *dev)
 	uint16_t flags;
 	off_t pos;
 
-	pos = rte_pci_find_capability(dev, PCI_CAP_ID_MSIX);
+	pos = rte_pci_find_capability(dev, RTE_PCI_CAP_ID_MSIX);
 	if (pos > 0 && rte_pci_read_config(dev, &flags, sizeof(flags),
 			pos + 2) == sizeof(flags)) {
 		if (flags & PCI_MSIX_ENABLE)
@@ -607,7 +599,7 @@ virtio_read_caps(struct rte_pci_device *pci_dev, struct virtio_hw *hw)
 	 */
 	dev->msix_status = vtpci_msix_detect(pci_dev);
 
-	pos = rte_pci_find_capability(pci_dev, PCI_CAP_ID_VNDR);
+	pos = rte_pci_find_capability(pci_dev, RTE_PCI_CAP_ID_VNDR);
 	if (pos > 0 && rte_pci_read_config(pci_dev, &cap, sizeof(cap), pos) == sizeof(cap)) {
 		PMD_INIT_LOG(DEBUG,
 			"[%2x] cfg type: %u, bar: %u, offset: %04x, len: %u",
diff --git a/drivers/vdpa/ifc/base/ifcvf_osdep.h b/drivers/vdpa/ifc/base/ifcvf_osdep.h
index 6444d7f72c..dd2ff08f77 100644
--- a/drivers/vdpa/ifc/base/ifcvf_osdep.h
+++ b/drivers/vdpa/ifc/base/ifcvf_osdep.h
@@ -6,7 +6,6 @@
 #define _IFCVF_OSDEP_H_
 
 #include <stdint.h>
-#include <linux/pci_regs.h>
 
 #include <rte_cycles.h>
 #include <rte_pci.h>
@@ -35,6 +34,9 @@ typedef struct rte_pci_device PCI_DEV;
 #define PCI_READ_CONFIG_DWORD(dev, val, where) \
 	rte_pci_read_config(dev, val, 4, where)
 
+#define PCI_CAPABILITY_LIST RTE_PCI_CAPABILITY_LIST
+#define PCI_CAP_ID_VNDR RTE_PCI_CAP_ID_VNDR
+
 typedef uint8_t    u8;
 typedef int8_t     s8;
 typedef uint16_t   u16;
diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
index 3b2d3cfe4e..5d81839ef3 100644
--- a/lib/pci/rte_pci.h
+++ b/lib/pci/rte_pci.h
@@ -43,6 +43,11 @@ extern "C" {
 
 /* Capability registers */
 #define RTE_PCI_CAPABILITY_LIST	0x34	/* Offset of first capability list entry */
+#define RTE_PCI_CAP_ID_PM	0x01	/* Power Management */
+#define RTE_PCI_CAP_ID_MSI	0x05	/* Message Signalled Interrupts */
+#define RTE_PCI_CAP_ID_VNDR	0x09	/* Vendor-Specific */
+#define RTE_PCI_CAP_ID_EXP	0x10	/* PCI Express */
+#define RTE_PCI_CAP_ID_MSIX	0x11	/* MSI-X */
 #define RTE_PCI_CAP_SIZEOF	4
 
 /* PCI Express capability registers */
-- 
2.41.0


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

* [PATCH 05/14] pci: define some MSIX constants
  2023-08-03  7:50 [PATCH 00/14] Cleanup PCI(e) drivers David Marchand
                   ` (3 preceding siblings ...)
  2023-08-03  7:50 ` [PATCH 04/14] pci: define some capability constants David Marchand
@ 2023-08-03  7:50 ` David Marchand
  2023-08-03  9:53   ` Bruce Richardson
  2023-08-03  7:50 ` [PATCH 06/14] pci: define some command constants David Marchand
                   ` (14 subsequent siblings)
  19 siblings, 1 reply; 98+ messages in thread
From: David Marchand @ 2023-08-03  7:50 UTC (permalink / raw)
  To: dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, Anatoly Burakov,
	Jay Zhou, Timothy McDaniel, Julien Aube, Junfeng Guo,
	Jeroen de Borst, Rushil Gupta, Joshua Washington, Dongdong Liu,
	Yisen Zhuang, Maxime Coquelin, Gaetan Rivet

Define some PCI MSIX constants and use them in existing drivers.

Signed-off-by: David Marchand <david.marchand@redhat.com>
---
 drivers/bus/pci/linux/pci_init.h   | 18 ------------------
 drivers/bus/pci/linux/pci_vfio.c   | 14 +++++++-------
 drivers/crypto/virtio/virtio_pci.c |  6 ++----
 drivers/event/dlb2/pf/dlb2_main.c  | 13 +++++--------
 drivers/net/bnx2x/bnx2x.c          |  4 ++--
 drivers/net/bnx2x/bnx2x.h          |  2 --
 drivers/net/gve/gve_ethdev.c       |  4 ++--
 drivers/net/gve/gve_ethdev.h       |  8 --------
 drivers/net/hns3/hns3_ethdev_vf.c  |  9 ++++-----
 drivers/net/virtio/virtio_pci.c    |  6 ++----
 lib/pci/rte_pci.h                  | 10 ++++++++++
 11 files changed, 34 insertions(+), 60 deletions(-)

diff --git a/drivers/bus/pci/linux/pci_init.h b/drivers/bus/pci/linux/pci_init.h
index d842809ccd..a4d37c0d0a 100644
--- a/drivers/bus/pci/linux/pci_init.h
+++ b/drivers/bus/pci/linux/pci_init.h
@@ -52,24 +52,6 @@ int pci_uio_ioport_unmap(struct rte_pci_ioport *p);
 
 #ifdef VFIO_PRESENT
 
-#ifdef PCI_MSIX_TABLE_BIR
-#define RTE_PCI_MSIX_TABLE_BIR    PCI_MSIX_TABLE_BIR
-#else
-#define RTE_PCI_MSIX_TABLE_BIR    0x7
-#endif
-
-#ifdef PCI_MSIX_TABLE_OFFSET
-#define RTE_PCI_MSIX_TABLE_OFFSET PCI_MSIX_TABLE_OFFSET
-#else
-#define RTE_PCI_MSIX_TABLE_OFFSET 0xfffffff8
-#endif
-
-#ifdef PCI_MSIX_FLAGS_QSIZE
-#define RTE_PCI_MSIX_FLAGS_QSIZE  PCI_MSIX_FLAGS_QSIZE
-#else
-#define RTE_PCI_MSIX_FLAGS_QSIZE  0x07ff
-#endif
-
 /* access config space */
 int pci_vfio_read_config(const struct rte_pci_device *dev,
 			 void *buf, size_t len, off_t offs);
diff --git a/drivers/bus/pci/linux/pci_vfio.c b/drivers/bus/pci/linux/pci_vfio.c
index ac5a2c78b5..6d13cafdcf 100644
--- a/drivers/bus/pci/linux/pci_vfio.c
+++ b/drivers/bus/pci/linux/pci_vfio.c
@@ -120,23 +120,23 @@ pci_vfio_get_msix_bar(const struct rte_pci_device *dev,
 		uint16_t flags;
 		uint32_t reg;
 
-		/* table offset resides in the next 4 bytes */
-		if (rte_pci_read_config(dev, &reg, sizeof(reg), cap_offset + 4) < 0) {
+		if (rte_pci_read_config(dev, &reg, sizeof(reg), cap_offset +
+				RTE_PCI_MSIX_TABLE) < 0) {
 			RTE_LOG(ERR, EAL,
 				"Cannot read MSIX table from PCI config space!\n");
 			return -1;
 		}
 
-		if (rte_pci_read_config(dev, &flags, sizeof(flags), cap_offset + 2) < 0) {
+		if (rte_pci_read_config(dev, &flags, sizeof(flags), cap_offset +
+				RTE_PCI_MSIX_FLAGS) < 0) {
 			RTE_LOG(ERR, EAL,
 				"Cannot read MSIX flags from PCI config space!\n");
 			return -1;
 		}
 
-		msix_table->bar_index = reg & PCI_MSIX_TABLE_BIR;
-		msix_table->offset = reg & PCI_MSIX_TABLE_OFFSET;
-		msix_table->size =
-			16 * (1 + (flags & PCI_MSIX_FLAGS_QSIZE));
+		msix_table->bar_index = reg & RTE_PCI_MSIX_TABLE_BIR;
+		msix_table->offset = reg & RTE_PCI_MSIX_TABLE_OFFSET;
+		msix_table->size = 16 * (1 + (flags & RTE_PCI_MSIX_FLAGS_QSIZE));
 	}
 
 	return 0;
diff --git a/drivers/crypto/virtio/virtio_pci.c b/drivers/crypto/virtio/virtio_pci.c
index 9e340f2b0d..c9fb1087a9 100644
--- a/drivers/crypto/virtio/virtio_pci.c
+++ b/drivers/crypto/virtio/virtio_pci.c
@@ -329,8 +329,6 @@ get_cfg_addr(struct rte_pci_device *dev, struct virtio_pci_cap *cap)
 	return base + offset;
 }
 
-#define PCI_MSIX_ENABLE 0x8000
-
 static int
 virtio_read_caps(struct rte_pci_device *dev, struct virtio_crypto_hw *hw)
 {
@@ -350,8 +348,8 @@ virtio_read_caps(struct rte_pci_device *dev, struct virtio_crypto_hw *hw)
 	 */
 	pos = rte_pci_find_capability(dev, RTE_PCI_CAP_ID_MSIX);
 	if (pos > 0 && rte_pci_read_config(dev, &flags, sizeof(flags),
-			pos + 2) == sizeof(flags)) {
-		if (flags & PCI_MSIX_ENABLE)
+			pos + RTE_PCI_MSIX_FLAGS) == sizeof(flags)) {
+		if (flags & RTE_PCI_MSIX_FLAGS_ENABLE)
 			hw->use_msix = VIRTIO_MSIX_ENABLED;
 		else
 			hw->use_msix = VIRTIO_MSIX_DISABLED;
diff --git a/drivers/event/dlb2/pf/dlb2_main.c b/drivers/event/dlb2/pf/dlb2_main.c
index 1a229baee0..c6606a9bee 100644
--- a/drivers/event/dlb2/pf/dlb2_main.c
+++ b/drivers/event/dlb2/pf/dlb2_main.c
@@ -44,9 +44,6 @@
 #define DLB2_PCI_PRI_CTRL_ENABLE         0x1
 #define DLB2_PCI_PRI_ALLOC_REQ           0xC
 #define DLB2_PCI_PRI_CTRL                0x4
-#define DLB2_PCI_MSIX_FLAGS              0x2
-#define DLB2_PCI_MSIX_FLAGS_ENABLE       0x8000
-#define DLB2_PCI_MSIX_FLAGS_MASKALL      0x4000
 #define DLB2_PCI_ERR_ROOT_STATUS         0x30
 #define DLB2_PCI_ERR_COR_STATUS          0x10
 #define DLB2_PCI_ERR_UNCOR_STATUS        0x4
@@ -483,10 +480,10 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 
 	msix_cap_offset = rte_pci_find_capability(pdev, RTE_PCI_CAP_ID_MSIX);
 	if (msix_cap_offset >= 0) {
-		off = msix_cap_offset + DLB2_PCI_MSIX_FLAGS;
+		off = msix_cap_offset + RTE_PCI_MSIX_FLAGS;
 		if (rte_pci_read_config(pdev, &cmd, 2, off) == 2) {
-			cmd |= DLB2_PCI_MSIX_FLAGS_ENABLE;
-			cmd |= DLB2_PCI_MSIX_FLAGS_MASKALL;
+			cmd |= RTE_PCI_MSIX_FLAGS_ENABLE;
+			cmd |= RTE_PCI_MSIX_FLAGS_MASKALL;
 			if (rte_pci_write_config(pdev, &cmd, 2, off) != 2) {
 				DLB2_LOG_ERR("[%s()] failed to write msix flags\n",
 				       __func__);
@@ -494,9 +491,9 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			}
 		}
 
-		off = msix_cap_offset + DLB2_PCI_MSIX_FLAGS;
+		off = msix_cap_offset + RTE_PCI_MSIX_FLAGS;
 		if (rte_pci_read_config(pdev, &cmd, 2, off) == 2) {
-			cmd &= ~DLB2_PCI_MSIX_FLAGS_MASKALL;
+			cmd &= ~RTE_PCI_MSIX_FLAGS_MASKALL;
 			if (rte_pci_write_config(pdev, &cmd, 2, off) != 2) {
 				DLB2_LOG_ERR("[%s()] failed to write msix flags\n",
 				       __func__);
diff --git a/drivers/net/bnx2x/bnx2x.c b/drivers/net/bnx2x/bnx2x.c
index 8a97de8806..e3f14400cc 100644
--- a/drivers/net/bnx2x/bnx2x.c
+++ b/drivers/net/bnx2x/bnx2x.c
@@ -9766,9 +9766,9 @@ int bnx2x_attach(struct bnx2x_softc *sc)
 	if (sc->devinfo.pcie_msix_cap_reg != 0) {
 		uint32_t val;
 		pci_read(sc,
-			 (sc->devinfo.pcie_msix_cap_reg + PCIR_MSIX_CTRL), &val,
+			 (sc->devinfo.pcie_msix_cap_reg + RTE_PCI_MSIX_FLAGS), &val,
 			 2);
-		sc->igu_sb_cnt = (val & PCIM_MSIXCTRL_TABLE_SIZE) + 1;
+		sc->igu_sb_cnt = (val & RTE_PCI_MSIX_FLAGS_QSIZE) + 1;
 	} else {
 		sc->igu_sb_cnt = 1;
 	}
diff --git a/drivers/net/bnx2x/bnx2x.h b/drivers/net/bnx2x/bnx2x.h
index 07ef0567c2..60af75d336 100644
--- a/drivers/net/bnx2x/bnx2x.h
+++ b/drivers/net/bnx2x/bnx2x.h
@@ -46,8 +46,6 @@
 #define PCIM_PSTAT_PME                 PCI_PM_CTRL_PME_STATUS
 #define PCIM_PSTAT_D3                  0x3
 #define PCIM_PSTAT_PMEENABLE           PCI_PM_CTRL_PME_ENABLE
-#define PCIR_MSIX_CTRL                 PCI_MSIX_FLAGS
-#define PCIM_MSIXCTRL_TABLE_SIZE       PCI_MSIX_FLAGS_QSIZE
 #else
 #include <dev/pci/pcireg.h>
 #endif
diff --git a/drivers/net/gve/gve_ethdev.c b/drivers/net/gve/gve_ethdev.c
index 9ea5dbaeea..9b25f3036b 100644
--- a/drivers/net/gve/gve_ethdev.c
+++ b/drivers/net/gve/gve_ethdev.c
@@ -613,8 +613,8 @@ pci_dev_msix_vec_count(struct rte_pci_device *pdev)
 	uint16_t control;
 
 	if (msix_pos > 0 && rte_pci_read_config(pdev, &control, sizeof(control),
-			msix_pos + PCI_MSIX_FLAGS) == sizeof(control))
-		return (control & PCI_MSIX_FLAGS_QSIZE) + 1;
+			msix_pos + RTE_PCI_MSIX_FLAGS) == sizeof(control))
+		return (control & RTE_PCI_MSIX_FLAGS_QSIZE) + 1;
 
 	return 0;
 }
diff --git a/drivers/net/gve/gve_ethdev.h b/drivers/net/gve/gve_ethdev.h
index d604a75b7f..c47b4d454d 100644
--- a/drivers/net/gve/gve_ethdev.h
+++ b/drivers/net/gve/gve_ethdev.h
@@ -15,14 +15,6 @@
 /* TODO: this is a workaround to ensure that Tx complq is enough */
 #define DQO_TX_MULTIPLIER 4
 
-/*
- * Following macros are derived from linux/pci_regs.h, however,
- * we can't simply include that header here, as there is no such
- * file for non-Linux platform.
- */
-#define PCI_MSIX_FLAGS		2	/* Message Control */
-#define PCI_MSIX_FLAGS_QSIZE	0x07FF	/* Table size */
-
 #define GVE_DEFAULT_RX_FREE_THRESH  512
 #define GVE_DEFAULT_TX_FREE_THRESH   32
 #define GVE_DEFAULT_TX_RS_THRESH     32
diff --git a/drivers/net/hns3/hns3_ethdev_vf.c b/drivers/net/hns3/hns3_ethdev_vf.c
index eab5c55f5e..444fd3c3e4 100644
--- a/drivers/net/hns3/hns3_ethdev_vf.c
+++ b/drivers/net/hns3/hns3_ethdev_vf.c
@@ -2,7 +2,6 @@
  * Copyright(c) 2018-2021 HiSilicon Limited.
  */
 
-#include <linux/pci_regs.h>
 #include <rte_alarm.h>
 #include <ethdev_pci.h>
 #include <rte_io.h>
@@ -64,18 +63,18 @@ hns3vf_enable_msix(const struct rte_pci_device *device, bool op)
 	pos = rte_pci_find_capability(device, RTE_PCI_CAP_ID_MSIX);
 	if (pos > 0) {
 		ret = rte_pci_read_config(device, &control, sizeof(control),
-			pos + PCI_MSIX_FLAGS);
+			pos + RTE_PCI_MSIX_FLAGS);
 		if (ret < 0) {
 			PMD_INIT_LOG(ERR, "Failed to read MSIX flags");
 			return -ENXIO;
 		}
 
 		if (op)
-			control |= PCI_MSIX_FLAGS_ENABLE;
+			control |= RTE_PCI_MSIX_FLAGS_ENABLE;
 		else
-			control &= ~PCI_MSIX_FLAGS_ENABLE;
+			control &= ~RTE_PCI_MSIX_FLAGS_ENABLE;
 		ret = rte_pci_write_config(device, &control, sizeof(control),
-			pos + PCI_MSIX_FLAGS);
+				pos + RTE_PCI_MSIX_FLAGS);
 		if (ret < 0) {
 			PMD_INIT_LOG(ERR, "failed to write MSIX flags");
 			return -ENXIO;
diff --git a/drivers/net/virtio/virtio_pci.c b/drivers/net/virtio/virtio_pci.c
index 81d5dd0a4a..cdffef267f 100644
--- a/drivers/net/virtio/virtio_pci.c
+++ b/drivers/net/virtio/virtio_pci.c
@@ -24,8 +24,6 @@
 
 struct virtio_pci_internal virtio_pci_internal[RTE_MAX_ETHPORTS];
 
-#define PCI_MSIX_ENABLE 0x8000
-
 static enum virtio_msix_status
 vtpci_msix_detect(struct rte_pci_device *dev)
 {
@@ -34,8 +32,8 @@ vtpci_msix_detect(struct rte_pci_device *dev)
 
 	pos = rte_pci_find_capability(dev, RTE_PCI_CAP_ID_MSIX);
 	if (pos > 0 && rte_pci_read_config(dev, &flags, sizeof(flags),
-			pos + 2) == sizeof(flags)) {
-		if (flags & PCI_MSIX_ENABLE)
+			pos + RTE_PCI_MSIX_FLAGS) == sizeof(flags)) {
+		if (flags & RTE_PCI_MSIX_FLAGS_ENABLE)
 			return VIRTIO_MSIX_ENABLED;
 		else
 			return VIRTIO_MSIX_DISABLED;
diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
index 5d81839ef3..a055a28592 100644
--- a/lib/pci/rte_pci.h
+++ b/lib/pci/rte_pci.h
@@ -50,6 +50,16 @@ extern "C" {
 #define RTE_PCI_CAP_ID_MSIX	0x11	/* MSI-X */
 #define RTE_PCI_CAP_SIZEOF	4
 
+/* MSI-X registers */
+#define RTE_PCI_MSIX_FLAGS		2	/* Message Control */
+#define RTE_PCI_MSIX_FLAGS_QSIZE	0x07ff	/* Table size */
+#define RTE_PCI_MSIX_FLAGS_MASKALL	0x4000	/* Mask all vectors for this function */
+#define RTE_PCI_MSIX_FLAGS_ENABLE	0x8000	/* MSI-X enable */
+
+#define RTE_PCI_MSIX_TABLE		4	/* Table offset */
+#define RTE_PCI_MSIX_TABLE_BIR		0x00000007 /* BAR index */
+#define RTE_PCI_MSIX_TABLE_OFFSET	0xfffffff8 /* Offset into specified BAR */
+
 /* PCI Express capability registers */
 #define RTE_PCI_EXP_DEVCTL	8	/* Device Control */
 
-- 
2.41.0


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

* [PATCH 06/14] pci: define some command constants
  2023-08-03  7:50 [PATCH 00/14] Cleanup PCI(e) drivers David Marchand
                   ` (4 preceding siblings ...)
  2023-08-03  7:50 ` [PATCH 05/14] pci: define some MSIX constants David Marchand
@ 2023-08-03  7:50 ` David Marchand
  2023-08-03  9:57   ` Bruce Richardson
  2023-08-22 19:23   ` Adam Hassick
  2023-08-03  7:50 ` [PATCH 07/14] pci: define some BAR constants David Marchand
                   ` (13 subsequent siblings)
  19 siblings, 2 replies; 98+ messages in thread
From: David Marchand @ 2023-08-03  7:50 UTC (permalink / raw)
  To: dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, Anatoly Burakov,
	Timothy McDaniel, Gaetan Rivet

Define some PCI command constants and use them in existing drivers.

Signed-off-by: David Marchand <david.marchand@redhat.com>
---
 drivers/bus/pci/linux/pci_vfio.c  | 8 ++++----
 drivers/event/dlb2/pf/dlb2_main.c | 8 +++-----
 lib/pci/rte_pci.h                 | 4 +++-
 3 files changed, 10 insertions(+), 10 deletions(-)

diff --git a/drivers/bus/pci/linux/pci_vfio.c b/drivers/bus/pci/linux/pci_vfio.c
index 6d13cafdcf..f96b3ce7fb 100644
--- a/drivers/bus/pci/linux/pci_vfio.c
+++ b/drivers/bus/pci/linux/pci_vfio.c
@@ -156,18 +156,18 @@ pci_vfio_enable_bus_memory(struct rte_pci_device *dev, int dev_fd)
 		return -1;
 	}
 
-	ret = pread64(dev_fd, &cmd, sizeof(cmd), offset + PCI_COMMAND);
+	ret = pread64(dev_fd, &cmd, sizeof(cmd), offset + RTE_PCI_COMMAND);
 
 	if (ret != sizeof(cmd)) {
 		RTE_LOG(ERR, EAL, "Cannot read command from PCI config space!\n");
 		return -1;
 	}
 
-	if (cmd & PCI_COMMAND_MEMORY)
+	if (cmd & RTE_PCI_COMMAND_MEMORY)
 		return 0;
 
-	cmd |= PCI_COMMAND_MEMORY;
-	ret = pwrite64(dev_fd, &cmd, sizeof(cmd), offset + PCI_COMMAND);
+	cmd |= RTE_PCI_COMMAND_MEMORY;
+	ret = pwrite64(dev_fd, &cmd, sizeof(cmd), offset + RTE_PCI_COMMAND);
 
 	if (ret != sizeof(cmd)) {
 		RTE_LOG(ERR, EAL, "Cannot write command to PCI config space!\n");
diff --git a/drivers/event/dlb2/pf/dlb2_main.c b/drivers/event/dlb2/pf/dlb2_main.c
index c6606a9bee..6dbaa2ff97 100644
--- a/drivers/event/dlb2/pf/dlb2_main.c
+++ b/drivers/event/dlb2/pf/dlb2_main.c
@@ -33,7 +33,6 @@
 #define DLB2_PCI_EXP_DEVCTL2 40
 #define DLB2_PCI_LNKCTL2 48
 #define DLB2_PCI_SLTCTL2 56
-#define DLB2_PCI_CMD 4
 #define DLB2_PCI_EXP_DEVSTA 10
 #define DLB2_PCI_EXP_DEVSTA_TRPND 0x20
 #define DLB2_PCI_EXP_DEVCTL_BCR_FLR 0x8000
@@ -47,7 +46,6 @@
 #define DLB2_PCI_ERR_ROOT_STATUS         0x30
 #define DLB2_PCI_ERR_COR_STATUS          0x10
 #define DLB2_PCI_ERR_UNCOR_STATUS        0x4
-#define DLB2_PCI_COMMAND_INTX_DISABLE    0x400
 #define DLB2_PCI_ACS_CAP                 0x4
 #define DLB2_PCI_ACS_CTRL                0x6
 #define DLB2_PCI_ACS_SV                  0x1
@@ -286,7 +284,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 
 	/* clear the PCI command register before issuing the FLR */
 
-	off = DLB2_PCI_CMD;
+	off = RTE_PCI_COMMAND;
 	cmd = 0;
 	if (rte_pci_write_config(pdev, &cmd, 2, off) != 2) {
 		DLB2_LOG_ERR("[%s()] failed to write the pci command\n",
@@ -468,9 +466,9 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 		}
 	}
 
-	off = DLB2_PCI_CMD;
+	off = RTE_PCI_COMMAND;
 	if (rte_pci_read_config(pdev, &cmd, 2, off) == 2) {
-		cmd &= ~DLB2_PCI_COMMAND_INTX_DISABLE;
+		cmd &= ~RTE_PCI_COMMAND_INTX_DISABLE;
 		if (rte_pci_write_config(pdev, &cmd, 2, off) != 2) {
 			DLB2_LOG_ERR("[%s()] failed to write the pci command\n",
 			       __func__);
diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
index a055a28592..bf2b2639f4 100644
--- a/lib/pci/rte_pci.h
+++ b/lib/pci/rte_pci.h
@@ -32,10 +32,12 @@ extern "C" {
 
 #define RTE_PCI_VENDOR_ID	0x00	/* 16 bits */
 #define RTE_PCI_DEVICE_ID	0x02	/* 16 bits */
-#define RTE_PCI_COMMAND		0x04	/* 16 bits */
 
 /* PCI Command Register */
+#define RTE_PCI_COMMAND		0x04	/* 16 bits */
+#define RTE_PCI_COMMAND_MEMORY	0x2	/* Enable response in Memory space */
 #define RTE_PCI_COMMAND_MASTER	0x4	/* Bus Master Enable */
+#define RTE_PCI_COMMAND_INTX_DISABLE 0x400 /* INTx Emulation Disable */
 
 /* PCI Status Register */
 #define RTE_PCI_STATUS		0x06	/* 16 bits */
-- 
2.41.0


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

* [PATCH 07/14] pci: define some BAR constants
  2023-08-03  7:50 [PATCH 00/14] Cleanup PCI(e) drivers David Marchand
                   ` (5 preceding siblings ...)
  2023-08-03  7:50 ` [PATCH 06/14] pci: define some command constants David Marchand
@ 2023-08-03  7:50 ` David Marchand
  2023-08-03  9:58   ` Bruce Richardson
  2023-08-03  7:50 ` [PATCH 08/14] pci: define some PM constants David Marchand
                   ` (12 subsequent siblings)
  19 siblings, 1 reply; 98+ messages in thread
From: David Marchand @ 2023-08-03  7:50 UTC (permalink / raw)
  To: dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, Anatoly Burakov,
	Gaetan Rivet

Define some PCI BAR constants and use them in existing drivers.

Signed-off-by: David Marchand <david.marchand@redhat.com>
---
 drivers/bus/pci/linux/pci_vfio.c | 7 +++----
 lib/pci/rte_pci.h                | 4 ++++
 2 files changed, 7 insertions(+), 4 deletions(-)

diff --git a/drivers/bus/pci/linux/pci_vfio.c b/drivers/bus/pci/linux/pci_vfio.c
index f96b3ce7fb..c2e3d2f4b5 100644
--- a/drivers/bus/pci/linux/pci_vfio.c
+++ b/drivers/bus/pci/linux/pci_vfio.c
@@ -5,7 +5,6 @@
 #include <unistd.h>
 #include <string.h>
 #include <fcntl.h>
-#include <linux/pci_regs.h>
 #include <sys/eventfd.h>
 #include <sys/socket.h>
 #include <sys/ioctl.h>
@@ -430,14 +429,14 @@ pci_vfio_is_ioport_bar(const struct rte_pci_device *dev, int vfio_dev_fd,
 	}
 
 	ret = pread64(vfio_dev_fd, &ioport_bar, sizeof(ioport_bar),
-			  offset + PCI_BASE_ADDRESS_0 + bar_index * 4);
+			  offset + RTE_PCI_BASE_ADDRESS_0 + bar_index * 4);
 	if (ret != sizeof(ioport_bar)) {
 		RTE_LOG(ERR, EAL, "Cannot read command (%x) from config space!\n",
-			PCI_BASE_ADDRESS_0 + bar_index*4);
+			RTE_PCI_BASE_ADDRESS_0 + bar_index*4);
 		return -1;
 	}
 
-	return (ioport_bar & PCI_BASE_ADDRESS_SPACE_IO) != 0;
+	return (ioport_bar & RTE_PCI_BASE_ADDRESS_SPACE_IO) != 0;
 }
 
 static int
diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
index bf2b2639f4..429904cff9 100644
--- a/lib/pci/rte_pci.h
+++ b/lib/pci/rte_pci.h
@@ -43,6 +43,10 @@ extern "C" {
 #define RTE_PCI_STATUS		0x06	/* 16 bits */
 #define RTE_PCI_STATUS_CAP_LIST	0x10	/* Support Capability List */
 
+/* Base addresses */
+#define RTE_PCI_BASE_ADDRESS_0		0x10	/* 32 bits */
+#define RTE_PCI_BASE_ADDRESS_SPACE_IO	0x01
+
 /* Capability registers */
 #define RTE_PCI_CAPABILITY_LIST	0x34	/* Offset of first capability list entry */
 #define RTE_PCI_CAP_ID_PM	0x01	/* Power Management */
-- 
2.41.0


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

* [PATCH 08/14] pci: define some PM constants
  2023-08-03  7:50 [PATCH 00/14] Cleanup PCI(e) drivers David Marchand
                   ` (6 preceding siblings ...)
  2023-08-03  7:50 ` [PATCH 07/14] pci: define some BAR constants David Marchand
@ 2023-08-03  7:50 ` David Marchand
  2023-08-03  9:59   ` Bruce Richardson
  2023-08-03  7:50 ` [PATCH 09/14] pci: define some PCIe constants David Marchand
                   ` (11 subsequent siblings)
  19 siblings, 1 reply; 98+ messages in thread
From: David Marchand @ 2023-08-03  7:50 UTC (permalink / raw)
  To: dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, Julien Aube, Gaetan Rivet

Define some PCI Power Management constants and use them in existing
drivers.

Signed-off-by: David Marchand <david.marchand@redhat.com>
---
 drivers/net/bnx2x/bnx2x.c | 17 +++++++++--------
 drivers/net/bnx2x/bnx2x.h |  5 -----
 lib/pci/rte_pci.h         |  6 ++++++
 3 files changed, 15 insertions(+), 13 deletions(-)

diff --git a/drivers/net/bnx2x/bnx2x.c b/drivers/net/bnx2x/bnx2x.c
index e3f14400cc..faf061beba 100644
--- a/drivers/net/bnx2x/bnx2x.c
+++ b/drivers/net/bnx2x/bnx2x.c
@@ -5843,17 +5843,17 @@ static int bnx2x_set_power_state(struct bnx2x_softc *sc, uint8_t state)
 		return 0;
 	}
 
-	pci_read(sc, (sc->devinfo.pcie_pm_cap_reg + PCIR_POWER_STATUS), &pmcsr,
+	pci_read(sc, (sc->devinfo.pcie_pm_cap_reg + RTE_PCI_PM_CTRL), &pmcsr,
 		 2);
 
 	switch (state) {
 	case PCI_PM_D0:
 		pci_write_word(sc,
 			       (sc->devinfo.pcie_pm_cap_reg +
-				PCIR_POWER_STATUS),
-			       ((pmcsr & ~PCIM_PSTAT_DMASK) | PCIM_PSTAT_PME));
+				RTE_PCI_PM_CTRL),
+			       ((pmcsr & ~RTE_PCI_PM_CTRL_STATE_MASK) | RTE_PCI_PM_CTRL_PME_STATUS));
 
-		if (pmcsr & PCIM_PSTAT_DMASK) {
+		if (pmcsr & RTE_PCI_PM_CTRL_STATE_MASK) {
 			/* delay required during transition out of D3hot */
 			DELAY(20000);
 		}
@@ -5866,16 +5866,17 @@ static int bnx2x_set_power_state(struct bnx2x_softc *sc, uint8_t state)
 			return 0;
 		}
 
-		pmcsr &= ~PCIM_PSTAT_DMASK;
-		pmcsr |= PCIM_PSTAT_D3;
+		pmcsr &= ~RTE_PCI_PM_CTRL_STATE_MASK;
+		/* D3 power state */
+		pmcsr |= 0x3;
 
 		if (sc->wol) {
-			pmcsr |= PCIM_PSTAT_PMEENABLE;
+			pmcsr |= RTE_PCI_PM_CTRL_PME_ENABLE;
 		}
 
 		pci_write_long(sc,
 			       (sc->devinfo.pcie_pm_cap_reg +
-				PCIR_POWER_STATUS), pmcsr);
+				RTE_PCI_PM_CTRL), pmcsr);
 
 		/*
 		 * No more memory access after this point until device is brought back
diff --git a/drivers/net/bnx2x/bnx2x.h b/drivers/net/bnx2x/bnx2x.h
index 60af75d336..1efa166316 100644
--- a/drivers/net/bnx2x/bnx2x.h
+++ b/drivers/net/bnx2x/bnx2x.h
@@ -41,11 +41,6 @@
 #define PCIR_EXPRESS_DEVICE_CTL        PCI_EXP_DEVCTL
 #define PCIM_EXP_CTL_MAX_PAYLOAD       PCI_EXP_DEVCTL_PAYLOAD
 #define PCIM_EXP_CTL_MAX_READ_REQUEST  PCI_EXP_DEVCTL_READRQ
-#define PCIR_POWER_STATUS              PCI_PM_CTRL
-#define PCIM_PSTAT_DMASK               PCI_PM_CTRL_STATE_MASK
-#define PCIM_PSTAT_PME                 PCI_PM_CTRL_PME_STATUS
-#define PCIM_PSTAT_D3                  0x3
-#define PCIM_PSTAT_PMEENABLE           PCI_PM_CTRL_PME_ENABLE
 #else
 #include <dev/pci/pcireg.h>
 #endif
diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
index 429904cff9..b7e1ff5d78 100644
--- a/lib/pci/rte_pci.h
+++ b/lib/pci/rte_pci.h
@@ -56,6 +56,12 @@ extern "C" {
 #define RTE_PCI_CAP_ID_MSIX	0x11	/* MSI-X */
 #define RTE_PCI_CAP_SIZEOF	4
 
+/* Power Management Registers */
+#define RTE_PCI_PM_CTRL			4	/* PM control and status register */
+#define RTE_PCI_PM_CTRL_STATE_MASK	0x0003	/* Current power state (D0 to D3) */
+#define RTE_PCI_PM_CTRL_PME_ENABLE	0x0100	/* PME pin enable */
+#define RTE_PCI_PM_CTRL_PME_STATUS	0x8000	/* PME pin status */
+
 /* MSI-X registers */
 #define RTE_PCI_MSIX_FLAGS		2	/* Message Control */
 #define RTE_PCI_MSIX_FLAGS_QSIZE	0x07ff	/* Table size */
-- 
2.41.0


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

* [PATCH 09/14] pci: define some PCIe constants
  2023-08-03  7:50 [PATCH 00/14] Cleanup PCI(e) drivers David Marchand
                   ` (7 preceding siblings ...)
  2023-08-03  7:50 ` [PATCH 08/14] pci: define some PM constants David Marchand
@ 2023-08-03  7:50 ` David Marchand
  2023-08-03 10:01   ` Bruce Richardson
  2023-08-03  7:50 ` [PATCH 10/14] pci: define some extended capability constants David Marchand
                   ` (10 subsequent siblings)
  19 siblings, 1 reply; 98+ messages in thread
From: David Marchand @ 2023-08-03  7:50 UTC (permalink / raw)
  To: dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, Timothy McDaniel,
	Julien Aube, Gaetan Rivet

Define some PCI Express constants and use them in existing drivers.

Signed-off-by: David Marchand <david.marchand@redhat.com>
---
 drivers/event/dlb2/pf/dlb2_main.c | 40 ++++++++++++-------------------
 drivers/net/bnx2x/bnx2x.c         | 16 ++++++-------
 drivers/net/bnx2x/bnx2x.h         | 35 ---------------------------
 lib/pci/rte_pci.h                 | 17 ++++++++++++-
 4 files changed, 39 insertions(+), 69 deletions(-)

diff --git a/drivers/event/dlb2/pf/dlb2_main.c b/drivers/event/dlb2/pf/dlb2_main.c
index 6dbaa2ff97..8d960edef6 100644
--- a/drivers/event/dlb2/pf/dlb2_main.c
+++ b/drivers/event/dlb2/pf/dlb2_main.c
@@ -27,16 +27,6 @@
 #define NO_OWNER_VF 0	/* PF ONLY! */
 #define NOT_VF_REQ false /* PF ONLY! */
 
-#define DLB2_PCI_LNKCTL 16
-#define DLB2_PCI_SLTCTL 24
-#define DLB2_PCI_RTCTL 28
-#define DLB2_PCI_EXP_DEVCTL2 40
-#define DLB2_PCI_LNKCTL2 48
-#define DLB2_PCI_SLTCTL2 56
-#define DLB2_PCI_EXP_DEVSTA 10
-#define DLB2_PCI_EXP_DEVSTA_TRPND 0x20
-#define DLB2_PCI_EXP_DEVCTL_BCR_FLR 0x8000
-
 #define DLB2_PCI_EXT_CAP_ID_PRI   0x13
 #define DLB2_PCI_EXT_CAP_ID_ACS   0xD
 
@@ -249,27 +239,27 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 	if (rte_pci_read_config(pdev, &dev_ctl_word, 2, off) != 2)
 		dev_ctl_word = 0;
 
-	off = pcie_cap_offset + DLB2_PCI_LNKCTL;
+	off = pcie_cap_offset + RTE_PCI_EXP_LNKCTL;
 	if (rte_pci_read_config(pdev, &lnk_word, 2, off) != 2)
 		lnk_word = 0;
 
-	off = pcie_cap_offset + DLB2_PCI_SLTCTL;
+	off = pcie_cap_offset + RTE_PCI_EXP_SLTCTL;
 	if (rte_pci_read_config(pdev, &slt_word, 2, off) != 2)
 		slt_word = 0;
 
-	off = pcie_cap_offset + DLB2_PCI_RTCTL;
+	off = pcie_cap_offset + RTE_PCI_EXP_RTCTL;
 	if (rte_pci_read_config(pdev, &rt_ctl_word, 2, off) != 2)
 		rt_ctl_word = 0;
 
-	off = pcie_cap_offset + DLB2_PCI_EXP_DEVCTL2;
+	off = pcie_cap_offset + RTE_PCI_EXP_DEVCTL2;
 	if (rte_pci_read_config(pdev, &dev_ctl2_word, 2, off) != 2)
 		dev_ctl2_word = 0;
 
-	off = pcie_cap_offset + DLB2_PCI_LNKCTL2;
+	off = pcie_cap_offset + RTE_PCI_EXP_LNKCTL2;
 	if (rte_pci_read_config(pdev, &lnk_word2, 2, off) != 2)
 		lnk_word2 = 0;
 
-	off = pcie_cap_offset + DLB2_PCI_SLTCTL2;
+	off = pcie_cap_offset + RTE_PCI_EXP_SLTCTL2;
 	if (rte_pci_read_config(pdev, &slt_word2, 2, off) != 2)
 		slt_word2 = 0;
 
@@ -296,7 +286,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 	for (wait_count = 0; wait_count < 4; wait_count++) {
 		int sleep_time;
 
-		off = pcie_cap_offset + DLB2_PCI_EXP_DEVSTA;
+		off = pcie_cap_offset + RTE_PCI_EXP_DEVSTA;
 		ret = rte_pci_read_config(pdev, &devsta_busy_word, 2, off);
 		if (ret != 2) {
 			DLB2_LOG_ERR("[%s()] failed to read the pci device status\n",
@@ -304,7 +294,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 		}
 
-		if (!(devsta_busy_word & DLB2_PCI_EXP_DEVSTA_TRPND))
+		if (!(devsta_busy_word & RTE_PCI_EXP_DEVSTA_TRPND))
 			break;
 
 		sleep_time = (1 << (wait_count)) * 100;
@@ -325,7 +315,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 		return ret;
 	}
 
-	devctl_word |= DLB2_PCI_EXP_DEVCTL_BCR_FLR;
+	devctl_word |= RTE_PCI_EXP_DEVCTL_BCR_FLR;
 
 	ret = rte_pci_write_config(pdev, &devctl_word, 2, off);
 	if (ret != 2) {
@@ -347,7 +337,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 		}
 
-		off = pcie_cap_offset + DLB2_PCI_LNKCTL;
+		off = pcie_cap_offset + RTE_PCI_EXP_LNKCTL;
 		ret = rte_pci_write_config(pdev, &lnk_word, 2, off);
 		if (ret != 2) {
 			DLB2_LOG_ERR("[%s()] failed to write the pcie config space at offset %d\n",
@@ -355,7 +345,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 		}
 
-		off = pcie_cap_offset + DLB2_PCI_SLTCTL;
+		off = pcie_cap_offset + RTE_PCI_EXP_SLTCTL;
 		ret = rte_pci_write_config(pdev, &slt_word, 2, off);
 		if (ret != 2) {
 			DLB2_LOG_ERR("[%s()] failed to write the pcie config space at offset %d\n",
@@ -363,7 +353,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 		}
 
-		off = pcie_cap_offset + DLB2_PCI_RTCTL;
+		off = pcie_cap_offset + RTE_PCI_EXP_RTCTL;
 		ret = rte_pci_write_config(pdev, &rt_ctl_word, 2, off);
 		if (ret != 2) {
 			DLB2_LOG_ERR("[%s()] failed to write the pcie config space at offset %d\n",
@@ -371,7 +361,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 		}
 
-		off = pcie_cap_offset + DLB2_PCI_EXP_DEVCTL2;
+		off = pcie_cap_offset + RTE_PCI_EXP_DEVCTL2;
 		ret = rte_pci_write_config(pdev, &dev_ctl2_word, 2, off);
 		if (ret != 2) {
 			DLB2_LOG_ERR("[%s()] failed to write the pcie config space at offset %d\n",
@@ -379,7 +369,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 		}
 
-		off = pcie_cap_offset + DLB2_PCI_LNKCTL2;
+		off = pcie_cap_offset + RTE_PCI_EXP_LNKCTL2;
 		ret = rte_pci_write_config(pdev, &lnk_word2, 2, off);
 		if (ret != 2) {
 			DLB2_LOG_ERR("[%s()] failed to write the pcie config space at offset %d\n",
@@ -387,7 +377,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 		}
 
-		off = pcie_cap_offset + DLB2_PCI_SLTCTL2;
+		off = pcie_cap_offset + RTE_PCI_EXP_SLTCTL2;
 		ret = rte_pci_write_config(pdev, &slt_word2, 2, off);
 		if (ret != 2) {
 			DLB2_LOG_ERR("[%s()] failed to write the pcie config space at offset %d\n",
diff --git a/drivers/net/bnx2x/bnx2x.c b/drivers/net/bnx2x/bnx2x.c
index faf061beba..cfd8e35aa3 100644
--- a/drivers/net/bnx2x/bnx2x.c
+++ b/drivers/net/bnx2x/bnx2x.c
@@ -7630,8 +7630,8 @@ static uint32_t bnx2x_pcie_capability_read(struct bnx2x_softc *sc, int reg)
 
 static uint8_t bnx2x_is_pcie_pending(struct bnx2x_softc *sc)
 {
-	return bnx2x_pcie_capability_read(sc, PCIR_EXPRESS_DEVICE_STA) &
-		PCIM_EXP_STA_TRANSACTION_PND;
+	return bnx2x_pcie_capability_read(sc, RTE_PCI_EXP_TYPE_RC_EC) &
+		RTE_PCI_EXP_DEVSTA_TRPND;
 }
 
 /*
@@ -7658,11 +7658,11 @@ static void bnx2x_probe_pci_caps(struct bnx2x_softc *sc)
 		sc->devinfo.pcie_pm_cap_reg = caps->addr;
 	}
 
-	link_status = bnx2x_pcie_capability_read(sc, PCIR_EXPRESS_LINK_STA);
+	link_status = bnx2x_pcie_capability_read(sc, RTE_PCI_EXP_LNKSTA);
 
-	sc->devinfo.pcie_link_speed = (link_status & PCIM_LINK_STA_SPEED);
+	sc->devinfo.pcie_link_speed = (link_status & RTE_PCI_EXP_LNKSTA_CLS);
 	sc->devinfo.pcie_link_width =
-	    ((link_status & PCIM_LINK_STA_WIDTH) >> 4);
+	    ((link_status & RTE_PCI_EXP_LNKSTA_NLW) >> 4);
 
 	PMD_DRV_LOG(DEBUG, sc, "PCIe link speed=%d width=%d",
 		    sc->devinfo.pcie_link_speed, sc->devinfo.pcie_link_width);
@@ -9979,10 +9979,10 @@ static void bnx2x_init_pxp(struct bnx2x_softc *sc)
 	uint16_t devctl;
 	int r_order, w_order;
 
-	devctl = bnx2x_pcie_capability_read(sc, PCIR_EXPRESS_DEVICE_CTL);
+	devctl = bnx2x_pcie_capability_read(sc, RTE_PCI_EXP_DEVCTL);
 
-	w_order = ((devctl & PCIM_EXP_CTL_MAX_PAYLOAD) >> 5);
-	r_order = ((devctl & PCIM_EXP_CTL_MAX_READ_REQUEST) >> 12);
+	w_order = ((devctl & RTE_PCI_EXP_DEVCTL_PAYLOAD) >> 5);
+	r_order = ((devctl & RTE_PCI_EXP_DEVCTL_READRQ) >> 12);
 
 	ecore_init_pxp_arb(sc, r_order, w_order);
 }
diff --git a/drivers/net/bnx2x/bnx2x.h b/drivers/net/bnx2x/bnx2x.h
index 1efa166316..35206b4758 100644
--- a/drivers/net/bnx2x/bnx2x.h
+++ b/drivers/net/bnx2x/bnx2x.h
@@ -30,45 +30,10 @@
 
 #include "elink.h"
 
-#ifndef RTE_EXEC_ENV_FREEBSD
-#include <linux/pci_regs.h>
-
-#define PCIR_EXPRESS_DEVICE_STA        PCI_EXP_TYPE_RC_EC
-#define PCIM_EXP_STA_TRANSACTION_PND   PCI_EXP_DEVSTA_TRPND
-#define PCIR_EXPRESS_LINK_STA          PCI_EXP_LNKSTA
-#define PCIM_LINK_STA_WIDTH            PCI_EXP_LNKSTA_NLW
-#define PCIM_LINK_STA_SPEED            PCI_EXP_LNKSTA_CLS
-#define PCIR_EXPRESS_DEVICE_CTL        PCI_EXP_DEVCTL
-#define PCIM_EXP_CTL_MAX_PAYLOAD       PCI_EXP_DEVCTL_PAYLOAD
-#define PCIM_EXP_CTL_MAX_READ_REQUEST  PCI_EXP_DEVCTL_READRQ
-#else
-#include <dev/pci/pcireg.h>
-#endif
-
 #define IFM_10G_CX4                    20 /* 10GBase CX4 copper */
 #define IFM_10G_TWINAX                 22 /* 10GBase Twinax copper */
 #define IFM_10G_T                      26 /* 10GBase-T - RJ45 */
 
-#ifndef RTE_EXEC_ENV_FREEBSD
-#define PCIR_EXPRESS_DEVICE_STA        PCI_EXP_TYPE_RC_EC
-#define PCIM_EXP_STA_TRANSACTION_PND   PCI_EXP_DEVSTA_TRPND
-#define PCIR_EXPRESS_LINK_STA          PCI_EXP_LNKSTA
-#define PCIM_LINK_STA_WIDTH            PCI_EXP_LNKSTA_NLW
-#define PCIM_LINK_STA_SPEED            PCI_EXP_LNKSTA_CLS
-#define PCIR_EXPRESS_DEVICE_CTL        PCI_EXP_DEVCTL
-#define PCIM_EXP_CTL_MAX_PAYLOAD       PCI_EXP_DEVCTL_PAYLOAD
-#define PCIM_EXP_CTL_MAX_READ_REQUEST  PCI_EXP_DEVCTL_READRQ
-#else
-#define PCIR_EXPRESS_DEVICE_STA	PCIER_DEVICE_STA
-#define PCIM_EXP_STA_TRANSACTION_PND   PCIEM_STA_TRANSACTION_PND
-#define PCIR_EXPRESS_LINK_STA          PCIER_LINK_STA
-#define PCIM_LINK_STA_WIDTH            PCIEM_LINK_STA_WIDTH
-#define PCIM_LINK_STA_SPEED            PCIEM_LINK_STA_SPEED
-#define PCIR_EXPRESS_DEVICE_CTL        PCIER_DEVICE_CTL
-#define PCIM_EXP_CTL_MAX_PAYLOAD       PCIEM_CTL_MAX_PAYLOAD
-#define PCIM_EXP_CTL_MAX_READ_REQUEST  PCIEM_CTL_MAX_READ_REQUEST
-#endif
-
 #ifndef ARRAY_SIZE
 #define ARRAY_SIZE(arr) RTE_DIM(arr)
 #endif
diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
index b7e1ff5d78..a83f6abe14 100644
--- a/lib/pci/rte_pci.h
+++ b/lib/pci/rte_pci.h
@@ -73,7 +73,22 @@ extern "C" {
 #define RTE_PCI_MSIX_TABLE_OFFSET	0xfffffff8 /* Offset into specified BAR */
 
 /* PCI Express capability registers */
-#define RTE_PCI_EXP_DEVCTL	8	/* Device Control */
+#define RTE_PCI_EXP_TYPE_RC_EC		0xa	/* Root Complex Event Collector */
+#define RTE_PCI_EXP_DEVCTL		0x08	/* Device Control */
+#define RTE_PCI_EXP_DEVCTL_PAYLOAD	0x00e0	/* Max_Payload_Size */
+#define RTE_PCI_EXP_DEVCTL_READRQ	0x7000	/* Max_Read_Request_Size */
+#define RTE_PCI_EXP_DEVCTL_BCR_FLR	0x8000	/* Bridge Configuration Retry / FLR */
+#define RTE_PCI_EXP_DEVSTA		0x0a	/* Device Status */
+#define RTE_PCI_EXP_DEVSTA_TRPND	0x0020	/* Transactions Pending */
+#define RTE_PCI_EXP_LNKCTL		0x10	/* Link Control */
+#define RTE_PCI_EXP_LNKSTA		0x12	/* Link Status */
+#define RTE_PCI_EXP_LNKSTA_CLS		0x000f	/* Current Link Speed */
+#define RTE_PCI_EXP_LNKSTA_NLW		0x03f0	/* Negotiated Link Width */
+#define RTE_PCI_EXP_SLTCTL		0x18	/* Slot Control */
+#define RTE_PCI_EXP_RTCTL		0x1c	/* Root Control */
+#define RTE_PCI_EXP_DEVCTL2		0x28	/* Device Control 2 */
+#define RTE_PCI_EXP_LNKCTL2		0x30	/* Link Control 2 */
+#define RTE_PCI_EXP_SLTCTL2		0x38	/* Slot Control 2 */
 
 /* Extended Capabilities (PCI-X 2.0 and Express) */
 #define RTE_PCI_EXT_CAP_ID(header)	(header & 0x0000ffff)
-- 
2.41.0


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

* [PATCH 10/14] pci: define some extended capability constants
  2023-08-03  7:50 [PATCH 00/14] Cleanup PCI(e) drivers David Marchand
                   ` (8 preceding siblings ...)
  2023-08-03  7:50 ` [PATCH 09/14] pci: define some PCIe constants David Marchand
@ 2023-08-03  7:50 ` David Marchand
  2023-08-03  7:50 ` [PATCH 11/14] pci: define some ACS constants David Marchand
                   ` (9 subsequent siblings)
  19 siblings, 0 replies; 98+ messages in thread
From: David Marchand @ 2023-08-03  7:50 UTC (permalink / raw)
  To: dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, Timothy McDaniel,
	Gaetan Rivet

Define some PCI extended capability constants and use them in existing
drivers.

Signed-off-by: David Marchand <david.marchand@redhat.com>
---
 drivers/event/dlb2/pf/dlb2_main.c | 7 ++-----
 lib/pci/rte_pci.h                 | 2 ++
 2 files changed, 4 insertions(+), 5 deletions(-)

diff --git a/drivers/event/dlb2/pf/dlb2_main.c b/drivers/event/dlb2/pf/dlb2_main.c
index 8d960edef6..29e3001627 100644
--- a/drivers/event/dlb2/pf/dlb2_main.c
+++ b/drivers/event/dlb2/pf/dlb2_main.c
@@ -27,9 +27,6 @@
 #define NO_OWNER_VF 0	/* PF ONLY! */
 #define NOT_VF_REQ false /* PF ONLY! */
 
-#define DLB2_PCI_EXT_CAP_ID_PRI   0x13
-#define DLB2_PCI_EXT_CAP_ID_ACS   0xD
-
 #define DLB2_PCI_PRI_CTRL_ENABLE         0x1
 #define DLB2_PCI_PRI_ALLOC_REQ           0xC
 #define DLB2_PCI_PRI_CTRL                0x4
@@ -263,7 +260,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 	if (rte_pci_read_config(pdev, &slt_word2, 2, off) != 2)
 		slt_word2 = 0;
 
-	off = DLB2_PCI_EXT_CAP_ID_PRI;
+	off = RTE_PCI_EXT_CAP_ID_PRI;
 	pri_cap_offset = rte_pci_find_ext_capability(pdev, off);
 
 	if (pri_cap_offset >= 0) {
@@ -490,7 +487,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 		}
 	}
 
-	off = DLB2_PCI_EXT_CAP_ID_ACS;
+	off = RTE_PCI_EXT_CAP_ID_ACS;
 	acs_cap_offset = rte_pci_find_ext_capability(pdev, off);
 
 	if (acs_cap_offset >= 0) {
diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
index a83f6abe14..67b34a0af2 100644
--- a/lib/pci/rte_pci.h
+++ b/lib/pci/rte_pci.h
@@ -96,7 +96,9 @@ extern "C" {
 
 #define RTE_PCI_EXT_CAP_ID_ERR		0x01	/* Advanced Error Reporting */
 #define RTE_PCI_EXT_CAP_ID_DSN		0x03	/* Device Serial Number */
+#define RTE_PCI_EXT_CAP_ID_ACS		0x0d	/* Access Control Services */
 #define RTE_PCI_EXT_CAP_ID_SRIOV	0x10	/* SR-IOV*/
+#define RTE_PCI_EXT_CAP_ID_PRI		0x13	/* Page Request Interface */
 
 /* Single Root I/O Virtualization */
 #define RTE_PCI_SRIOV_CAP		0x04	/* SR-IOV Capabilities */
-- 
2.41.0


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

* [PATCH 11/14] pci: define some ACS constants
  2023-08-03  7:50 [PATCH 00/14] Cleanup PCI(e) drivers David Marchand
                   ` (9 preceding siblings ...)
  2023-08-03  7:50 ` [PATCH 10/14] pci: define some extended capability constants David Marchand
@ 2023-08-03  7:50 ` David Marchand
  2023-08-03  7:50 ` [PATCH 12/14] pci: define some PRI constants David Marchand
                   ` (8 subsequent siblings)
  19 siblings, 0 replies; 98+ messages in thread
From: David Marchand @ 2023-08-03  7:50 UTC (permalink / raw)
  To: dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, Timothy McDaniel,
	Gaetan Rivet

Define some PCI ACS extended feature constants and use them in existing
drivers.

Signed-off-by: David Marchand <david.marchand@redhat.com>
---
 drivers/event/dlb2/pf/dlb2_main.c | 23 ++++++++---------------
 lib/pci/rte_pci.h                 |  9 +++++++++
 2 files changed, 17 insertions(+), 15 deletions(-)

diff --git a/drivers/event/dlb2/pf/dlb2_main.c b/drivers/event/dlb2/pf/dlb2_main.c
index 29e3001627..8e729d1964 100644
--- a/drivers/event/dlb2/pf/dlb2_main.c
+++ b/drivers/event/dlb2/pf/dlb2_main.c
@@ -33,13 +33,6 @@
 #define DLB2_PCI_ERR_ROOT_STATUS         0x30
 #define DLB2_PCI_ERR_COR_STATUS          0x10
 #define DLB2_PCI_ERR_UNCOR_STATUS        0x4
-#define DLB2_PCI_ACS_CAP                 0x4
-#define DLB2_PCI_ACS_CTRL                0x6
-#define DLB2_PCI_ACS_SV                  0x1
-#define DLB2_PCI_ACS_RR                  0x4
-#define DLB2_PCI_ACS_CR                  0x8
-#define DLB2_PCI_ACS_UF                  0x10
-#define DLB2_PCI_ACS_EC                  0x20
 
 static int
 dlb2_pf_init_driver_state(struct dlb2_dev *dlb2_dev)
@@ -492,16 +485,16 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 
 	if (acs_cap_offset >= 0) {
 		uint16_t acs_cap, acs_ctrl, acs_mask;
-		off = acs_cap_offset + DLB2_PCI_ACS_CAP;
+		off = acs_cap_offset + RTE_PCI_ACS_CAP;
 		if (rte_pci_read_config(pdev, &acs_cap, 2, off) != 2)
 			acs_cap = 0;
 
-		off = acs_cap_offset + DLB2_PCI_ACS_CTRL;
+		off = acs_cap_offset + RTE_PCI_ACS_CTRL;
 		if (rte_pci_read_config(pdev, &acs_ctrl, 2, off) != 2)
 			acs_ctrl = 0;
 
-		acs_mask = DLB2_PCI_ACS_SV | DLB2_PCI_ACS_RR;
-		acs_mask |= (DLB2_PCI_ACS_CR | DLB2_PCI_ACS_UF);
+		acs_mask = RTE_PCI_ACS_SV | RTE_PCI_ACS_RR;
+		acs_mask |= (RTE_PCI_ACS_CR | RTE_PCI_ACS_UF);
 		acs_ctrl |= (acs_cap & acs_mask);
 
 		ret = rte_pci_write_config(pdev, &acs_ctrl, 2, off);
@@ -511,15 +504,15 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 		}
 
-		off = acs_cap_offset + DLB2_PCI_ACS_CTRL;
+		off = acs_cap_offset + RTE_PCI_ACS_CTRL;
 		if (rte_pci_read_config(pdev, &acs_ctrl, 2, off) != 2)
 			acs_ctrl = 0;
 
-		acs_mask = DLB2_PCI_ACS_RR | DLB2_PCI_ACS_CR;
-		acs_mask |= DLB2_PCI_ACS_EC;
+		acs_mask = RTE_PCI_ACS_RR | RTE_PCI_ACS_CR;
+		acs_mask |= RTE_PCI_ACS_EC;
 		acs_ctrl &= ~acs_mask;
 
-		off = acs_cap_offset + DLB2_PCI_ACS_CTRL;
+		off = acs_cap_offset + RTE_PCI_ACS_CTRL;
 		ret = rte_pci_write_config(pdev, &acs_ctrl, 2, off);
 		if (ret != 2) {
 			DLB2_LOG_ERR("[%s()] failed to write the pcie config space at offset %d\n",
diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
index 67b34a0af2..315c37571d 100644
--- a/lib/pci/rte_pci.h
+++ b/lib/pci/rte_pci.h
@@ -100,6 +100,15 @@ extern "C" {
 #define RTE_PCI_EXT_CAP_ID_SRIOV	0x10	/* SR-IOV*/
 #define RTE_PCI_EXT_CAP_ID_PRI		0x13	/* Page Request Interface */
 
+/* Access Control Service */
+#define RTE_PCI_ACS_CAP			0x04	/* ACS Capability Register */
+#define RTE_PCI_ACS_CTRL		0x06	/* ACS Control Register */
+#define RTE_PCI_ACS_SV			0x0001	/* Source Validation */
+#define RTE_PCI_ACS_RR			0x0004	/* P2P Request Redirect */
+#define RTE_PCI_ACS_CR			0x0008	/* P2P Completion Redirect */
+#define RTE_PCI_ACS_UF			0x0010	/* Upstream Forwarding */
+#define RTE_PCI_ACS_EC			0x0020	/* P2P Egress Control */
+
 /* Single Root I/O Virtualization */
 #define RTE_PCI_SRIOV_CAP		0x04	/* SR-IOV Capabilities */
 #define RTE_PCI_SRIOV_CTRL		0x08	/* SR-IOV Control */
-- 
2.41.0


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

* [PATCH 12/14] pci: define some PRI constants
  2023-08-03  7:50 [PATCH 00/14] Cleanup PCI(e) drivers David Marchand
                   ` (10 preceding siblings ...)
  2023-08-03  7:50 ` [PATCH 11/14] pci: define some ACS constants David Marchand
@ 2023-08-03  7:50 ` David Marchand
  2023-08-03  7:50 ` [PATCH 13/14] pci: define some AER constants David Marchand
                   ` (7 subsequent siblings)
  19 siblings, 0 replies; 98+ messages in thread
From: David Marchand @ 2023-08-03  7:50 UTC (permalink / raw)
  To: dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, Timothy McDaniel,
	Gaetan Rivet

Define some PCI PRI extended feature constants and use them in existing
drivers.

Signed-off-by: David Marchand <david.marchand@redhat.com>
---
 drivers/event/dlb2/pf/dlb2_main.c | 11 ++++-------
 lib/pci/rte_pci.h                 |  5 +++++
 2 files changed, 9 insertions(+), 7 deletions(-)

diff --git a/drivers/event/dlb2/pf/dlb2_main.c b/drivers/event/dlb2/pf/dlb2_main.c
index 8e729d1964..187a356c24 100644
--- a/drivers/event/dlb2/pf/dlb2_main.c
+++ b/drivers/event/dlb2/pf/dlb2_main.c
@@ -27,9 +27,6 @@
 #define NO_OWNER_VF 0	/* PF ONLY! */
 #define NOT_VF_REQ false /* PF ONLY! */
 
-#define DLB2_PCI_PRI_CTRL_ENABLE         0x1
-#define DLB2_PCI_PRI_ALLOC_REQ           0xC
-#define DLB2_PCI_PRI_CTRL                0x4
 #define DLB2_PCI_ERR_ROOT_STATUS         0x30
 #define DLB2_PCI_ERR_COR_STATUS          0x10
 #define DLB2_PCI_ERR_UNCOR_STATUS        0x4
@@ -257,7 +254,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 	pri_cap_offset = rte_pci_find_ext_capability(pdev, off);
 
 	if (pri_cap_offset >= 0) {
-		off = pri_cap_offset + DLB2_PCI_PRI_ALLOC_REQ;
+		off = pri_cap_offset + RTE_PCI_PRI_ALLOC_REQ;
 		if (rte_pci_read_config(pdev, &pri_reqs_dword, 4, off) != 4)
 			pri_reqs_dword = 0;
 	}
@@ -377,9 +374,9 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 	}
 
 	if (pri_cap_offset >= 0) {
-		pri_ctrl_word = DLB2_PCI_PRI_CTRL_ENABLE;
+		pri_ctrl_word = RTE_PCI_PRI_CTRL_ENABLE;
 
-		off = pri_cap_offset + DLB2_PCI_PRI_ALLOC_REQ;
+		off = pri_cap_offset + RTE_PCI_PRI_ALLOC_REQ;
 		ret = rte_pci_write_config(pdev, &pri_reqs_dword, 4, off);
 		if (ret != 4) {
 			DLB2_LOG_ERR("[%s()] failed to write the pcie config space at offset %d\n",
@@ -387,7 +384,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 		}
 
-		off = pri_cap_offset + DLB2_PCI_PRI_CTRL;
+		off = pri_cap_offset + RTE_PCI_PRI_CTRL;
 		ret = rte_pci_write_config(pdev, &pri_ctrl_word, 2, off);
 		if (ret != 2) {
 			DLB2_LOG_ERR("[%s()] failed to write the pcie config space at offset %d\n",
diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
index 315c37571d..0dc8733e1d 100644
--- a/lib/pci/rte_pci.h
+++ b/lib/pci/rte_pci.h
@@ -121,6 +121,11 @@ extern "C" {
 #define RTE_PCI_SRIOV_VF_DID		0x1a	/* VF Device ID */
 #define RTE_PCI_SRIOV_SUP_PGSIZE	0x1c	/* Supported Page Sizes */
 
+/* Page Request Interface */
+#define RTE_PCI_PRI_CTRL		0x04	/* PRI control register */
+#define RTE_PCI_PRI_CTRL_ENABLE		0x0001	/* Enable */
+#define RTE_PCI_PRI_ALLOC_REQ		0x0c	/* PRI max reqs allowed */
+
 /** Formatting string for PCI device identifier: Ex: 0000:00:01.0 */
 #define PCI_PRI_FMT "%.4" PRIx32 ":%.2" PRIx8 ":%.2" PRIx8 ".%" PRIx8
 #define PCI_PRI_STR_SIZE sizeof("XXXXXXXX:XX:XX.X")
-- 
2.41.0


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

* [PATCH 13/14] pci: define some AER constants
  2023-08-03  7:50 [PATCH 00/14] Cleanup PCI(e) drivers David Marchand
                   ` (11 preceding siblings ...)
  2023-08-03  7:50 ` [PATCH 12/14] pci: define some PRI constants David Marchand
@ 2023-08-03  7:50 ` David Marchand
  2023-08-03  7:50 ` [PATCH 14/14] devtools: forbid inclusion of Linux header for PCI David Marchand
                   ` (6 subsequent siblings)
  19 siblings, 0 replies; 98+ messages in thread
From: David Marchand @ 2023-08-03  7:50 UTC (permalink / raw)
  To: dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, Timothy McDaniel,
	Gaetan Rivet

Define some Advanced Error Reporting constants and use them in existing
drivers.

Signed-off-by: David Marchand <david.marchand@redhat.com>
---
 drivers/event/dlb2/pf/dlb2_main.c | 10 +++-------
 lib/pci/rte_pci.h                 |  5 +++++
 2 files changed, 8 insertions(+), 7 deletions(-)

diff --git a/drivers/event/dlb2/pf/dlb2_main.c b/drivers/event/dlb2/pf/dlb2_main.c
index 187a356c24..aa03e4c311 100644
--- a/drivers/event/dlb2/pf/dlb2_main.c
+++ b/drivers/event/dlb2/pf/dlb2_main.c
@@ -27,10 +27,6 @@
 #define NO_OWNER_VF 0	/* PF ONLY! */
 #define NOT_VF_REQ false /* PF ONLY! */
 
-#define DLB2_PCI_ERR_ROOT_STATUS         0x30
-#define DLB2_PCI_ERR_COR_STATUS          0x10
-#define DLB2_PCI_ERR_UNCOR_STATUS        0x4
-
 static int
 dlb2_pf_init_driver_state(struct dlb2_dev *dlb2_dev)
 {
@@ -399,7 +395,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 	if (err_cap_offset >= 0) {
 		uint32_t tmp;
 
-		off = err_cap_offset + DLB2_PCI_ERR_ROOT_STATUS;
+		off = err_cap_offset + RTE_PCI_ERR_ROOT_STATUS;
 		if (rte_pci_read_config(pdev, &tmp, 4, off) != 4)
 			tmp = 0;
 
@@ -410,7 +406,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 		}
 
-		off = err_cap_offset + DLB2_PCI_ERR_COR_STATUS;
+		off = err_cap_offset + RTE_PCI_ERR_COR_STATUS;
 		if (rte_pci_read_config(pdev, &tmp, 4, off) != 4)
 			tmp = 0;
 
@@ -421,7 +417,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 		}
 
-		off = err_cap_offset + DLB2_PCI_ERR_UNCOR_STATUS;
+		off = err_cap_offset + RTE_PCI_ERR_UNCOR_STATUS;
 		if (rte_pci_read_config(pdev, &tmp, 4, off) != 4)
 			tmp = 0;
 
diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
index 0dc8733e1d..c7552a53eb 100644
--- a/lib/pci/rte_pci.h
+++ b/lib/pci/rte_pci.h
@@ -100,6 +100,11 @@ extern "C" {
 #define RTE_PCI_EXT_CAP_ID_SRIOV	0x10	/* SR-IOV*/
 #define RTE_PCI_EXT_CAP_ID_PRI		0x13	/* Page Request Interface */
 
+/* Advanced Error Reporting */
+#define RTE_PCI_ERR_UNCOR_STATUS	0x04	/* Uncorrectable Error Status */
+#define RTE_PCI_ERR_COR_STATUS		0x10	/* Correctable Error Status */
+#define RTE_PCI_ERR_ROOT_STATUS		0x30
+
 /* Access Control Service */
 #define RTE_PCI_ACS_CAP			0x04	/* ACS Capability Register */
 #define RTE_PCI_ACS_CTRL		0x06	/* ACS Control Register */
-- 
2.41.0


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

* [PATCH 14/14] devtools: forbid inclusion of Linux header for PCI
  2023-08-03  7:50 [PATCH 00/14] Cleanup PCI(e) drivers David Marchand
                   ` (12 preceding siblings ...)
  2023-08-03  7:50 ` [PATCH 13/14] pci: define some AER constants David Marchand
@ 2023-08-03  7:50 ` David Marchand
  2023-08-03 10:03 ` [PATCH 00/14] Cleanup PCI(e) drivers Bruce Richardson
                   ` (5 subsequent siblings)
  19 siblings, 0 replies; 98+ messages in thread
From: David Marchand @ 2023-08-03  7:50 UTC (permalink / raw)
  To: dev; +Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta

Refrain from including Linux-only pci_regs.h header.
Instead, prefer our own definitions from the pci library.

Signed-off-by: David Marchand <david.marchand@redhat.com>
---
 devtools/checkpatches.sh | 8 ++++++++
 1 file changed, 8 insertions(+)

diff --git a/devtools/checkpatches.sh b/devtools/checkpatches.sh
index 43f5e36a18..5d3c5aaba5 100755
--- a/devtools/checkpatches.sh
+++ b/devtools/checkpatches.sh
@@ -127,6 +127,14 @@ check_forbidden_additions() { # <patch>
 		-f $(dirname $(readlink -f $0))/check-forbidden-tokens.awk \
 		"$1" || res=1
 
+	# forbid inclusion of Linux header for PCI constants
+	awk -v FOLDERS="lib drivers app examples" \
+		-v EXPRESSIONS='include.*linux/pci_regs\\.h' \
+		-v RET_ON_FAIL=1 \
+		-v MESSAGE='Using linux/pci_regs.h, prefer rte_pci.h' \
+		-f $(dirname $(readlink -f $0))/check-forbidden-tokens.awk \
+		"$1" || res=1
+
 	# forbid use of experimental build flag except in examples
 	awk -v FOLDERS='lib drivers app' \
 		-v EXPRESSIONS='-DALLOW_EXPERIMENTAL_API allow_experimental_apis' \
-- 
2.41.0


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

* Re: [PATCH 01/14] drivers: remove duplicated PCI master control
  2023-08-03  7:50 ` [PATCH 01/14] drivers: remove duplicated PCI master control David Marchand
@ 2023-08-03  9:45   ` Bruce Richardson
  2023-10-07  2:53   ` fengchengwen
  1 sibling, 0 replies; 98+ messages in thread
From: Bruce Richardson @ 2023-08-03  9:45 UTC (permalink / raw)
  To: David Marchand
  Cc: dev, thomas, ferruh.yigit, chenbo.xia, nipun.gupta,
	Anatoly Burakov, Dongdong Liu, Yisen Zhuang, Jiawen Wu

On Thu, Aug 03, 2023 at 09:50:24AM +0200, David Marchand wrote:
> Use existing API to cleanup duplicated code.
> 
> Signed-off-by: David Marchand <david.marchand@redhat.com>
> ---
Acked-by: Bruce Richardson <bruce.richardson@intel.com>

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

* Re: [PATCH 02/14] bus/pci: add const to some experimental API
  2023-08-03  7:50 ` [PATCH 02/14] bus/pci: add const to some experimental API David Marchand
@ 2023-08-03  9:46   ` Bruce Richardson
  2023-08-03 11:50     ` David Marchand
  0 siblings, 1 reply; 98+ messages in thread
From: Bruce Richardson @ 2023-08-03  9:46 UTC (permalink / raw)
  To: David Marchand; +Cc: dev, thomas, ferruh.yigit, chenbo.xia, nipun.gupta

On Thu, Aug 03, 2023 at 09:50:25AM +0200, David Marchand wrote:
> Those functions are fine with a const on the device pointer.
> 
> Signed-off-by: David Marchand <david.marchand@redhat.com>
> ---
>  drivers/bus/pci/pci_common.c  | 4 ++--
>  drivers/bus/pci/rte_bus_pci.h | 4 ++--
>  2 files changed, 4 insertions(+), 4 deletions(-)
> 
> diff --git a/drivers/bus/pci/pci_common.c b/drivers/bus/pci/pci_common.c
> index 52404ab0fe..382b0b8946 100644
> --- a/drivers/bus/pci/pci_common.c
> +++ b/drivers/bus/pci/pci_common.c
> @@ -814,7 +814,7 @@ rte_pci_get_iommu_class(void)
>  }
>  
>  off_t
> -rte_pci_find_ext_capability(struct rte_pci_device *dev, uint32_t cap)
> +rte_pci_find_ext_capability(const struct rte_pci_device *dev, uint32_t cap)
>  {
>  	off_t offset = RTE_PCI_CFG_SPACE_SIZE;
>  	uint32_t header;
> @@ -857,7 +857,7 @@ rte_pci_find_ext_capability(struct rte_pci_device *dev, uint32_t cap)
>  }
>  
>  int
> -rte_pci_set_bus_master(struct rte_pci_device *dev, bool enable)
> +rte_pci_set_bus_master(const struct rte_pci_device *dev, bool enable)
>  {
>  	uint16_t old_cmd, cmd;
>  

While generally I'm a big fan of using const everywhere we can, I wonder if
this is confusing here, since you are changing a setting, i.e. it's not
a read-only function.
That said, since const works, I have no strong objection to going with it.

Acked-by: Bruce Richardson <bruce.richardson@intel.com>


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

* Re: [PATCH 03/14] bus/pci: find PCI capability
  2023-08-03  7:50 ` [PATCH 03/14] bus/pci: find PCI capability David Marchand
@ 2023-08-03  9:49   ` Bruce Richardson
  2023-08-03  9:52     ` Bruce Richardson
  0 siblings, 1 reply; 98+ messages in thread
From: Bruce Richardson @ 2023-08-03  9:49 UTC (permalink / raw)
  To: David Marchand
  Cc: dev, thomas, ferruh.yigit, chenbo.xia, nipun.gupta,
	Anatoly Burakov, Jay Zhou, Timothy McDaniel, Julien Aube,
	Rahul Lakkireddy, Junfeng Guo, Jeroen de Borst, Rushil Gupta,
	Joshua Washington, Dongdong Liu, Yisen Zhuang, Maxime Coquelin,
	Gaetan Rivet

On Thu, Aug 03, 2023 at 09:50:26AM +0200, David Marchand wrote:
> Introduce two helpers so that drivers stop reinventing the wheel.
> Use it in existing drivers.
> 

Can you give a little more context on the new helpers and the changes in
the patch? A lot of the changes are not that self-explanatory.

Thanks,
/Bruce

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

* Re: [PATCH 04/14] pci: define some capability constants
  2023-08-03  7:50 ` [PATCH 04/14] pci: define some capability constants David Marchand
@ 2023-08-03  9:51   ` Bruce Richardson
  0 siblings, 0 replies; 98+ messages in thread
From: Bruce Richardson @ 2023-08-03  9:51 UTC (permalink / raw)
  To: David Marchand
  Cc: dev, thomas, ferruh.yigit, chenbo.xia, nipun.gupta,
	Anatoly Burakov, Jay Zhou, Timothy McDaniel, Julien Aube,
	Rahul Lakkireddy, Junfeng Guo, Jeroen de Borst, Rushil Gupta,
	Joshua Washington, Dongdong Liu, Yisen Zhuang, Maxime Coquelin,
	Xiao Wang, Gaetan Rivet

On Thu, Aug 03, 2023 at 09:50:27AM +0200, David Marchand wrote:
> Define some PCI capability constants and use them in existing drivers.
> 
> Signed-off-by: David Marchand <david.marchand@redhat.com>
> ---
Acked-by: Bruce Richardson <bruce.richardson@intel.com>

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

* Re: [PATCH 03/14] bus/pci: find PCI capability
  2023-08-03  9:49   ` Bruce Richardson
@ 2023-08-03  9:52     ` Bruce Richardson
  2023-08-03 11:49       ` David Marchand
  0 siblings, 1 reply; 98+ messages in thread
From: Bruce Richardson @ 2023-08-03  9:52 UTC (permalink / raw)
  To: David Marchand
  Cc: dev, thomas, ferruh.yigit, chenbo.xia, nipun.gupta,
	Anatoly Burakov, Jay Zhou, Timothy McDaniel, Julien Aube,
	Rahul Lakkireddy, Junfeng Guo, Jeroen de Borst, Rushil Gupta,
	Joshua Washington, Dongdong Liu, Yisen Zhuang, Maxime Coquelin,
	Gaetan Rivet

On Thu, Aug 03, 2023 at 10:49:54AM +0100, Bruce Richardson wrote:
> On Thu, Aug 03, 2023 at 09:50:26AM +0200, David Marchand wrote:
> > Introduce two helpers so that drivers stop reinventing the wheel.
> > Use it in existing drivers.
> > 
> 
> Can you give a little more context on the new helpers and the changes in
> the patch? A lot of the changes are not that self-explanatory.
> 
Reading through the patch a second time, I get a better idea of what is
happening, and it looks fine [though still think a little more detail is
needed in the log]

Acked-by: Bruce Richardson <bruce.richardson@intel.com>

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

* Re: [PATCH 05/14] pci: define some MSIX constants
  2023-08-03  7:50 ` [PATCH 05/14] pci: define some MSIX constants David Marchand
@ 2023-08-03  9:53   ` Bruce Richardson
  0 siblings, 0 replies; 98+ messages in thread
From: Bruce Richardson @ 2023-08-03  9:53 UTC (permalink / raw)
  To: David Marchand
  Cc: dev, thomas, ferruh.yigit, chenbo.xia, nipun.gupta,
	Anatoly Burakov, Jay Zhou, Timothy McDaniel, Julien Aube,
	Junfeng Guo, Jeroen de Borst, Rushil Gupta, Joshua Washington,
	Dongdong Liu, Yisen Zhuang, Maxime Coquelin, Gaetan Rivet

On Thu, Aug 03, 2023 at 09:50:28AM +0200, David Marchand wrote:
> Define some PCI MSIX constants and use them in existing drivers.
> 
> Signed-off-by: David Marchand <david.marchand@redhat.com>
> ---
Acked-by: Bruce Richardson <bruce.richardson@intel.com>

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

* Re: [PATCH 06/14] pci: define some command constants
  2023-08-03  7:50 ` [PATCH 06/14] pci: define some command constants David Marchand
@ 2023-08-03  9:57   ` Bruce Richardson
  2023-08-03 11:51     ` David Marchand
  2023-08-22 19:23   ` Adam Hassick
  1 sibling, 1 reply; 98+ messages in thread
From: Bruce Richardson @ 2023-08-03  9:57 UTC (permalink / raw)
  To: David Marchand
  Cc: dev, thomas, ferruh.yigit, chenbo.xia, nipun.gupta,
	Anatoly Burakov, Timothy McDaniel, Gaetan Rivet

On Thu, Aug 03, 2023 at 09:50:29AM +0200, David Marchand wrote:
> Define some PCI command constants and use them in existing drivers.
> 
> Signed-off-by: David Marchand <david.marchand@redhat.com>
> ---

For the idea, all good, but for the implementation, one comment inline
below.

With the below reworked:

Acked-by: Bruce Richardson <bruce.richardson@intel.com>

>  drivers/bus/pci/linux/pci_vfio.c  | 8 ++++----
>  drivers/event/dlb2/pf/dlb2_main.c | 8 +++-----
>  lib/pci/rte_pci.h                 | 4 +++-
>  3 files changed, 10 insertions(+), 10 deletions(-)
> 
> diff --git a/drivers/bus/pci/linux/pci_vfio.c b/drivers/bus/pci/linux/pci_vfio.c
> index 6d13cafdcf..f96b3ce7fb 100644
> --- a/drivers/bus/pci/linux/pci_vfio.c
> +++ b/drivers/bus/pci/linux/pci_vfio.c
> @@ -156,18 +156,18 @@ pci_vfio_enable_bus_memory(struct rte_pci_device *dev, int dev_fd)
>  		return -1;
>  	}
>  
> -	ret = pread64(dev_fd, &cmd, sizeof(cmd), offset + PCI_COMMAND);
> +	ret = pread64(dev_fd, &cmd, sizeof(cmd), offset + RTE_PCI_COMMAND);
>  
>  	if (ret != sizeof(cmd)) {
>  		RTE_LOG(ERR, EAL, "Cannot read command from PCI config space!\n");
>  		return -1;
>  	}
>  
> -	if (cmd & PCI_COMMAND_MEMORY)
> +	if (cmd & RTE_PCI_COMMAND_MEMORY)
>  		return 0;
>  
> -	cmd |= PCI_COMMAND_MEMORY;
> -	ret = pwrite64(dev_fd, &cmd, sizeof(cmd), offset + PCI_COMMAND);
> +	cmd |= RTE_PCI_COMMAND_MEMORY;
> +	ret = pwrite64(dev_fd, &cmd, sizeof(cmd), offset + RTE_PCI_COMMAND);
>  
>  	if (ret != sizeof(cmd)) {
>  		RTE_LOG(ERR, EAL, "Cannot write command to PCI config space!\n");
> diff --git a/drivers/event/dlb2/pf/dlb2_main.c b/drivers/event/dlb2/pf/dlb2_main.c
> index c6606a9bee..6dbaa2ff97 100644
> --- a/drivers/event/dlb2/pf/dlb2_main.c
> +++ b/drivers/event/dlb2/pf/dlb2_main.c
> @@ -33,7 +33,6 @@
>  #define DLB2_PCI_EXP_DEVCTL2 40
>  #define DLB2_PCI_LNKCTL2 48
>  #define DLB2_PCI_SLTCTL2 56
> -#define DLB2_PCI_CMD 4
>  #define DLB2_PCI_EXP_DEVSTA 10
>  #define DLB2_PCI_EXP_DEVSTA_TRPND 0x20
>  #define DLB2_PCI_EXP_DEVCTL_BCR_FLR 0x8000
> @@ -47,7 +46,6 @@
>  #define DLB2_PCI_ERR_ROOT_STATUS         0x30
>  #define DLB2_PCI_ERR_COR_STATUS          0x10
>  #define DLB2_PCI_ERR_UNCOR_STATUS        0x4
> -#define DLB2_PCI_COMMAND_INTX_DISABLE    0x400
>  #define DLB2_PCI_ACS_CAP                 0x4
>  #define DLB2_PCI_ACS_CTRL                0x6
>  #define DLB2_PCI_ACS_SV                  0x1
> @@ -286,7 +284,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
>  
>  	/* clear the PCI command register before issuing the FLR */
>  
> -	off = DLB2_PCI_CMD;
> +	off = RTE_PCI_COMMAND;
>  	cmd = 0;
>  	if (rte_pci_write_config(pdev, &cmd, 2, off) != 2) {
>  		DLB2_LOG_ERR("[%s()] failed to write the pci command\n",
> @@ -468,9 +466,9 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
>  		}
>  	}
>  
> -	off = DLB2_PCI_CMD;
> +	off = RTE_PCI_COMMAND;
>  	if (rte_pci_read_config(pdev, &cmd, 2, off) == 2) {
> -		cmd &= ~DLB2_PCI_COMMAND_INTX_DISABLE;
> +		cmd &= ~RTE_PCI_COMMAND_INTX_DISABLE;
>  		if (rte_pci_write_config(pdev, &cmd, 2, off) != 2) {
>  			DLB2_LOG_ERR("[%s()] failed to write the pci command\n",
>  			       __func__);
> diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
> index a055a28592..bf2b2639f4 100644
> --- a/lib/pci/rte_pci.h
> +++ b/lib/pci/rte_pci.h
> @@ -32,10 +32,12 @@ extern "C" {
>  
>  #define RTE_PCI_VENDOR_ID	0x00	/* 16 bits */
>  #define RTE_PCI_DEVICE_ID	0x02	/* 16 bits */
> -#define RTE_PCI_COMMAND		0x04	/* 16 bits */
>  
>  /* PCI Command Register */
> +#define RTE_PCI_COMMAND		0x04	/* 16 bits */
> +#define RTE_PCI_COMMAND_MEMORY	0x2	/* Enable response in Memory space */
>  #define RTE_PCI_COMMAND_MASTER	0x4	/* Bus Master Enable */
> +#define RTE_PCI_COMMAND_INTX_DISABLE 0x400 /* INTx Emulation Disable */
>  

It's weird here to have two defines in the same block with the same value -
even if one is 0x04 and the other is 0x4. That implies that the two values
don't belong in the same block of defines.

Question - would enums make sense for defining any of these? It allows
the groups to be named?


>  /* PCI Status Register */
>  #define RTE_PCI_STATUS		0x06	/* 16 bits */
> -- 
> 2.41.0
> 

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

* Re: [PATCH 07/14] pci: define some BAR constants
  2023-08-03  7:50 ` [PATCH 07/14] pci: define some BAR constants David Marchand
@ 2023-08-03  9:58   ` Bruce Richardson
  0 siblings, 0 replies; 98+ messages in thread
From: Bruce Richardson @ 2023-08-03  9:58 UTC (permalink / raw)
  To: David Marchand
  Cc: dev, thomas, ferruh.yigit, chenbo.xia, nipun.gupta,
	Anatoly Burakov, Gaetan Rivet

On Thu, Aug 03, 2023 at 09:50:30AM +0200, David Marchand wrote:
> Define some PCI BAR constants and use them in existing drivers.
> 
> Signed-off-by: David Marchand <david.marchand@redhat.com>
> ---
Acked-by: Bruce Richardson <bruce.richardson@intel.com>

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

* Re: [PATCH 08/14] pci: define some PM constants
  2023-08-03  7:50 ` [PATCH 08/14] pci: define some PM constants David Marchand
@ 2023-08-03  9:59   ` Bruce Richardson
  0 siblings, 0 replies; 98+ messages in thread
From: Bruce Richardson @ 2023-08-03  9:59 UTC (permalink / raw)
  To: David Marchand
  Cc: dev, thomas, ferruh.yigit, chenbo.xia, nipun.gupta, Julien Aube,
	Gaetan Rivet

On Thu, Aug 03, 2023 at 09:50:31AM +0200, David Marchand wrote:
> Define some PCI Power Management constants and use them in existing
> drivers.
> 
> Signed-off-by: David Marchand <david.marchand@redhat.com>
> ---
Acked-by: Bruce Richardson <bruce.richardson@intel.com>

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

* Re: [PATCH 09/14] pci: define some PCIe constants
  2023-08-03  7:50 ` [PATCH 09/14] pci: define some PCIe constants David Marchand
@ 2023-08-03 10:01   ` Bruce Richardson
  0 siblings, 0 replies; 98+ messages in thread
From: Bruce Richardson @ 2023-08-03 10:01 UTC (permalink / raw)
  To: David Marchand
  Cc: dev, thomas, ferruh.yigit, chenbo.xia, nipun.gupta,
	Timothy McDaniel, Julien Aube, Gaetan Rivet

On Thu, Aug 03, 2023 at 09:50:32AM +0200, David Marchand wrote:
> Define some PCI Express constants and use them in existing drivers.
> 
> Signed-off-by: David Marchand <david.marchand@redhat.com>
> ---
Acked-by: Bruce Richardson <bruce.richardson@intel.com>

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

* Re: [PATCH 00/14] Cleanup PCI(e) drivers
  2023-08-03  7:50 [PATCH 00/14] Cleanup PCI(e) drivers David Marchand
                   ` (13 preceding siblings ...)
  2023-08-03  7:50 ` [PATCH 14/14] devtools: forbid inclusion of Linux header for PCI David Marchand
@ 2023-08-03 10:03 ` Bruce Richardson
  2023-08-21 11:35 ` [PATCH v2 00/15] " David Marchand
                   ` (4 subsequent siblings)
  19 siblings, 0 replies; 98+ messages in thread
From: Bruce Richardson @ 2023-08-03 10:03 UTC (permalink / raw)
  To: David Marchand; +Cc: dev, thomas, ferruh.yigit, chenbo.xia, nipun.gupta

On Thu, Aug 03, 2023 at 09:50:23AM +0200, David Marchand wrote:
> Rather than rely on Linux headers to find some PCI(e) standard constants
> or reinvent the same PCI capability helper, this series complements the
> pci library and the pci bus driver.
> PCI drivers can then use OS agnostic macros and helpers.
> 
> WARNING: this is only compile tested.
> 
> -- 
> David Marchand
> 
> David Marchand (14):
>   drivers: remove duplicated PCI master control
>   bus/pci: add const to some experimental API
>   bus/pci: find PCI capability
>   pci: define some capability constants
>   pci: define some MSIX constants
>   pci: define some command constants
>   pci: define some BAR constants
>   pci: define some PM constants
>   pci: define some PCIe constants
>   pci: define some extended capability constants
>   pci: define some ACS constants
>   pci: define some PRI constants
>   pci: define some AER constants
>   devtools: forbid inclusion of Linux header for PCI
> 
For the rest of the patches I haven't already acked, assume no comments
from me.

Series-acked-by: Bruce Richardson <bruce.richardson@intel.com>

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

* Re: [PATCH 03/14] bus/pci: find PCI capability
  2023-08-03  9:52     ` Bruce Richardson
@ 2023-08-03 11:49       ` David Marchand
  0 siblings, 0 replies; 98+ messages in thread
From: David Marchand @ 2023-08-03 11:49 UTC (permalink / raw)
  To: Bruce Richardson
  Cc: dev, thomas, ferruh.yigit, chenbo.xia, nipun.gupta,
	Anatoly Burakov, Jay Zhou, Timothy McDaniel, Julien Aube,
	Rahul Lakkireddy, Junfeng Guo, Jeroen de Borst, Rushil Gupta,
	Joshua Washington, Dongdong Liu, Yisen Zhuang, Maxime Coquelin,
	Gaetan Rivet

On Thu, Aug 3, 2023 at 11:53 AM Bruce Richardson
<bruce.richardson@intel.com> wrote:
>
> On Thu, Aug 03, 2023 at 10:49:54AM +0100, Bruce Richardson wrote:
> > On Thu, Aug 03, 2023 at 09:50:26AM +0200, David Marchand wrote:
> > > Introduce two helpers so that drivers stop reinventing the wheel.
> > > Use it in existing drivers.
> > >
> >
> > Can you give a little more context on the new helpers and the changes in
> > the patch? A lot of the changes are not that self-explanatory.
> >
> Reading through the patch a second time, I get a better idea of what is
> happening, and it looks fine [though still think a little more detail is
> needed in the log]
>
> Acked-by: Bruce Richardson <bruce.richardson@intel.com>

Sure, I'll update in v2.


-- 
David Marchand


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

* Re: [PATCH 02/14] bus/pci: add const to some experimental API
  2023-08-03  9:46   ` Bruce Richardson
@ 2023-08-03 11:50     ` David Marchand
  0 siblings, 0 replies; 98+ messages in thread
From: David Marchand @ 2023-08-03 11:50 UTC (permalink / raw)
  To: Bruce Richardson; +Cc: dev, thomas, ferruh.yigit, chenbo.xia, nipun.gupta

On Thu, Aug 3, 2023 at 11:47 AM Bruce Richardson
<bruce.richardson@intel.com> wrote:
>
> On Thu, Aug 03, 2023 at 09:50:25AM +0200, David Marchand wrote:
> > Those functions are fine with a const on the device pointer.
> >
> > Signed-off-by: David Marchand <david.marchand@redhat.com>
> > ---
> >  drivers/bus/pci/pci_common.c  | 4 ++--
> >  drivers/bus/pci/rte_bus_pci.h | 4 ++--
> >  2 files changed, 4 insertions(+), 4 deletions(-)
> >
> > diff --git a/drivers/bus/pci/pci_common.c b/drivers/bus/pci/pci_common.c
> > index 52404ab0fe..382b0b8946 100644
> > --- a/drivers/bus/pci/pci_common.c
> > +++ b/drivers/bus/pci/pci_common.c
> > @@ -814,7 +814,7 @@ rte_pci_get_iommu_class(void)
> >  }
> >
> >  off_t
> > -rte_pci_find_ext_capability(struct rte_pci_device *dev, uint32_t cap)
> > +rte_pci_find_ext_capability(const struct rte_pci_device *dev, uint32_t cap)
> >  {
> >       off_t offset = RTE_PCI_CFG_SPACE_SIZE;
> >       uint32_t header;
> > @@ -857,7 +857,7 @@ rte_pci_find_ext_capability(struct rte_pci_device *dev, uint32_t cap)
> >  }
> >
> >  int
> > -rte_pci_set_bus_master(struct rte_pci_device *dev, bool enable)
> > +rte_pci_set_bus_master(const struct rte_pci_device *dev, bool enable)
> >  {
> >       uint16_t old_cmd, cmd;
> >
>
> While generally I'm a big fan of using const everywhere we can, I wonder if
> this is confusing here, since you are changing a setting, i.e. it's not
> a read-only function.

Changing a setting in the underlying hardware, yes, but the C object
is left untouched.


-- 
David Marchand


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

* Re: [PATCH 06/14] pci: define some command constants
  2023-08-03  9:57   ` Bruce Richardson
@ 2023-08-03 11:51     ` David Marchand
  2023-08-08  9:20       ` David Marchand
  0 siblings, 1 reply; 98+ messages in thread
From: David Marchand @ 2023-08-03 11:51 UTC (permalink / raw)
  To: Bruce Richardson
  Cc: dev, thomas, ferruh.yigit, chenbo.xia, nipun.gupta,
	Anatoly Burakov, Timothy McDaniel, Gaetan Rivet

On Thu, Aug 3, 2023 at 11:58 AM Bruce Richardson
<bruce.richardson@intel.com> wrote:
>
> On Thu, Aug 03, 2023 at 09:50:29AM +0200, David Marchand wrote:
> > Define some PCI command constants and use them in existing drivers.
> >
> > Signed-off-by: David Marchand <david.marchand@redhat.com>
> > ---
>
> For the idea, all good, but for the implementation, one comment inline
> below.
>
> With the below reworked:
>
> Acked-by: Bruce Richardson <bruce.richardson@intel.com>
>
> >  drivers/bus/pci/linux/pci_vfio.c  | 8 ++++----
> >  drivers/event/dlb2/pf/dlb2_main.c | 8 +++-----
> >  lib/pci/rte_pci.h                 | 4 +++-
> >  3 files changed, 10 insertions(+), 10 deletions(-)
> >
> > diff --git a/drivers/bus/pci/linux/pci_vfio.c b/drivers/bus/pci/linux/pci_vfio.c
> > index 6d13cafdcf..f96b3ce7fb 100644
> > --- a/drivers/bus/pci/linux/pci_vfio.c
> > +++ b/drivers/bus/pci/linux/pci_vfio.c
> > @@ -156,18 +156,18 @@ pci_vfio_enable_bus_memory(struct rte_pci_device *dev, int dev_fd)
> >               return -1;
> >       }
> >
> > -     ret = pread64(dev_fd, &cmd, sizeof(cmd), offset + PCI_COMMAND);
> > +     ret = pread64(dev_fd, &cmd, sizeof(cmd), offset + RTE_PCI_COMMAND);
> >
> >       if (ret != sizeof(cmd)) {
> >               RTE_LOG(ERR, EAL, "Cannot read command from PCI config space!\n");
> >               return -1;
> >       }
> >
> > -     if (cmd & PCI_COMMAND_MEMORY)
> > +     if (cmd & RTE_PCI_COMMAND_MEMORY)
> >               return 0;
> >
> > -     cmd |= PCI_COMMAND_MEMORY;
> > -     ret = pwrite64(dev_fd, &cmd, sizeof(cmd), offset + PCI_COMMAND);
> > +     cmd |= RTE_PCI_COMMAND_MEMORY;
> > +     ret = pwrite64(dev_fd, &cmd, sizeof(cmd), offset + RTE_PCI_COMMAND);
> >
> >       if (ret != sizeof(cmd)) {
> >               RTE_LOG(ERR, EAL, "Cannot write command to PCI config space!\n");
> > diff --git a/drivers/event/dlb2/pf/dlb2_main.c b/drivers/event/dlb2/pf/dlb2_main.c
> > index c6606a9bee..6dbaa2ff97 100644
> > --- a/drivers/event/dlb2/pf/dlb2_main.c
> > +++ b/drivers/event/dlb2/pf/dlb2_main.c
> > @@ -33,7 +33,6 @@
> >  #define DLB2_PCI_EXP_DEVCTL2 40
> >  #define DLB2_PCI_LNKCTL2 48
> >  #define DLB2_PCI_SLTCTL2 56
> > -#define DLB2_PCI_CMD 4
> >  #define DLB2_PCI_EXP_DEVSTA 10
> >  #define DLB2_PCI_EXP_DEVSTA_TRPND 0x20
> >  #define DLB2_PCI_EXP_DEVCTL_BCR_FLR 0x8000
> > @@ -47,7 +46,6 @@
> >  #define DLB2_PCI_ERR_ROOT_STATUS         0x30
> >  #define DLB2_PCI_ERR_COR_STATUS          0x10
> >  #define DLB2_PCI_ERR_UNCOR_STATUS        0x4
> > -#define DLB2_PCI_COMMAND_INTX_DISABLE    0x400
> >  #define DLB2_PCI_ACS_CAP                 0x4
> >  #define DLB2_PCI_ACS_CTRL                0x6
> >  #define DLB2_PCI_ACS_SV                  0x1
> > @@ -286,7 +284,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
> >
> >       /* clear the PCI command register before issuing the FLR */
> >
> > -     off = DLB2_PCI_CMD;
> > +     off = RTE_PCI_COMMAND;
> >       cmd = 0;
> >       if (rte_pci_write_config(pdev, &cmd, 2, off) != 2) {
> >               DLB2_LOG_ERR("[%s()] failed to write the pci command\n",
> > @@ -468,9 +466,9 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
> >               }
> >       }
> >
> > -     off = DLB2_PCI_CMD;
> > +     off = RTE_PCI_COMMAND;
> >       if (rte_pci_read_config(pdev, &cmd, 2, off) == 2) {
> > -             cmd &= ~DLB2_PCI_COMMAND_INTX_DISABLE;
> > +             cmd &= ~RTE_PCI_COMMAND_INTX_DISABLE;
> >               if (rte_pci_write_config(pdev, &cmd, 2, off) != 2) {
> >                       DLB2_LOG_ERR("[%s()] failed to write the pci command\n",
> >                              __func__);
> > diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
> > index a055a28592..bf2b2639f4 100644
> > --- a/lib/pci/rte_pci.h
> > +++ b/lib/pci/rte_pci.h
> > @@ -32,10 +32,12 @@ extern "C" {
> >
> >  #define RTE_PCI_VENDOR_ID    0x00    /* 16 bits */
> >  #define RTE_PCI_DEVICE_ID    0x02    /* 16 bits */
> > -#define RTE_PCI_COMMAND              0x04    /* 16 bits */
> >
> >  /* PCI Command Register */
> > +#define RTE_PCI_COMMAND              0x04    /* 16 bits */
> > +#define RTE_PCI_COMMAND_MEMORY       0x2     /* Enable response in Memory space */
> >  #define RTE_PCI_COMMAND_MASTER       0x4     /* Bus Master Enable */
> > +#define RTE_PCI_COMMAND_INTX_DISABLE 0x400 /* INTx Emulation Disable */
> >
>
> It's weird here to have two defines in the same block with the same value -
> even if one is 0x04 and the other is 0x4. That implies that the two values
> don't belong in the same block of defines.
>
> Question - would enums make sense for defining any of these? It allows
> the groups to be named?

That's something I will look into, or at least better organise the defines..


-- 
David Marchand


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

* Re: [PATCH 06/14] pci: define some command constants
  2023-08-03 11:51     ` David Marchand
@ 2023-08-08  9:20       ` David Marchand
  2023-08-08 10:08         ` Bruce Richardson
  0 siblings, 1 reply; 98+ messages in thread
From: David Marchand @ 2023-08-08  9:20 UTC (permalink / raw)
  To: Bruce Richardson
  Cc: dev, thomas, ferruh.yigit, chenbo.xia, nipun.gupta,
	Anatoly Burakov, Timothy McDaniel, Gaetan Rivet

On Thu, Aug 3, 2023 at 1:51 PM David Marchand <david.marchand@redhat.com> wrote:
>
> On Thu, Aug 3, 2023 at 11:58 AM Bruce Richardson
> <bruce.richardson@intel.com> wrote:
> >
> > On Thu, Aug 03, 2023 at 09:50:29AM +0200, David Marchand wrote:
> > > Define some PCI command constants and use them in existing drivers.
> > >
> > > Signed-off-by: David Marchand <david.marchand@redhat.com>
> > > ---
> >
> > For the idea, all good, but for the implementation, one comment inline
> > below.
> >
> > With the below reworked:
> >
> > Acked-by: Bruce Richardson <bruce.richardson@intel.com>
> >
> > >  drivers/bus/pci/linux/pci_vfio.c  | 8 ++++----
> > >  drivers/event/dlb2/pf/dlb2_main.c | 8 +++-----
> > >  lib/pci/rte_pci.h                 | 4 +++-
> > >  3 files changed, 10 insertions(+), 10 deletions(-)
> > >
> > > diff --git a/drivers/bus/pci/linux/pci_vfio.c b/drivers/bus/pci/linux/pci_vfio.c
> > > index 6d13cafdcf..f96b3ce7fb 100644
> > > --- a/drivers/bus/pci/linux/pci_vfio.c
> > > +++ b/drivers/bus/pci/linux/pci_vfio.c
> > > @@ -156,18 +156,18 @@ pci_vfio_enable_bus_memory(struct rte_pci_device *dev, int dev_fd)
> > >               return -1;
> > >       }
> > >
> > > -     ret = pread64(dev_fd, &cmd, sizeof(cmd), offset + PCI_COMMAND);
> > > +     ret = pread64(dev_fd, &cmd, sizeof(cmd), offset + RTE_PCI_COMMAND);
> > >
> > >       if (ret != sizeof(cmd)) {
> > >               RTE_LOG(ERR, EAL, "Cannot read command from PCI config space!\n");
> > >               return -1;
> > >       }
> > >
> > > -     if (cmd & PCI_COMMAND_MEMORY)
> > > +     if (cmd & RTE_PCI_COMMAND_MEMORY)
> > >               return 0;
> > >
> > > -     cmd |= PCI_COMMAND_MEMORY;
> > > -     ret = pwrite64(dev_fd, &cmd, sizeof(cmd), offset + PCI_COMMAND);
> > > +     cmd |= RTE_PCI_COMMAND_MEMORY;
> > > +     ret = pwrite64(dev_fd, &cmd, sizeof(cmd), offset + RTE_PCI_COMMAND);
> > >
> > >       if (ret != sizeof(cmd)) {
> > >               RTE_LOG(ERR, EAL, "Cannot write command to PCI config space!\n");
> > > diff --git a/drivers/event/dlb2/pf/dlb2_main.c b/drivers/event/dlb2/pf/dlb2_main.c
> > > index c6606a9bee..6dbaa2ff97 100644
> > > --- a/drivers/event/dlb2/pf/dlb2_main.c
> > > +++ b/drivers/event/dlb2/pf/dlb2_main.c
> > > @@ -33,7 +33,6 @@
> > >  #define DLB2_PCI_EXP_DEVCTL2 40
> > >  #define DLB2_PCI_LNKCTL2 48
> > >  #define DLB2_PCI_SLTCTL2 56
> > > -#define DLB2_PCI_CMD 4
> > >  #define DLB2_PCI_EXP_DEVSTA 10
> > >  #define DLB2_PCI_EXP_DEVSTA_TRPND 0x20
> > >  #define DLB2_PCI_EXP_DEVCTL_BCR_FLR 0x8000
> > > @@ -47,7 +46,6 @@
> > >  #define DLB2_PCI_ERR_ROOT_STATUS         0x30
> > >  #define DLB2_PCI_ERR_COR_STATUS          0x10
> > >  #define DLB2_PCI_ERR_UNCOR_STATUS        0x4
> > > -#define DLB2_PCI_COMMAND_INTX_DISABLE    0x400
> > >  #define DLB2_PCI_ACS_CAP                 0x4
> > >  #define DLB2_PCI_ACS_CTRL                0x6
> > >  #define DLB2_PCI_ACS_SV                  0x1
> > > @@ -286,7 +284,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
> > >
> > >       /* clear the PCI command register before issuing the FLR */
> > >
> > > -     off = DLB2_PCI_CMD;
> > > +     off = RTE_PCI_COMMAND;
> > >       cmd = 0;
> > >       if (rte_pci_write_config(pdev, &cmd, 2, off) != 2) {
> > >               DLB2_LOG_ERR("[%s()] failed to write the pci command\n",
> > > @@ -468,9 +466,9 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
> > >               }
> > >       }
> > >
> > > -     off = DLB2_PCI_CMD;
> > > +     off = RTE_PCI_COMMAND;
> > >       if (rte_pci_read_config(pdev, &cmd, 2, off) == 2) {
> > > -             cmd &= ~DLB2_PCI_COMMAND_INTX_DISABLE;
> > > +             cmd &= ~RTE_PCI_COMMAND_INTX_DISABLE;
> > >               if (rte_pci_write_config(pdev, &cmd, 2, off) != 2) {
> > >                       DLB2_LOG_ERR("[%s()] failed to write the pci command\n",
> > >                              __func__);
> > > diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
> > > index a055a28592..bf2b2639f4 100644
> > > --- a/lib/pci/rte_pci.h
> > > +++ b/lib/pci/rte_pci.h
> > > @@ -32,10 +32,12 @@ extern "C" {
> > >
> > >  #define RTE_PCI_VENDOR_ID    0x00    /* 16 bits */
> > >  #define RTE_PCI_DEVICE_ID    0x02    /* 16 bits */
> > > -#define RTE_PCI_COMMAND              0x04    /* 16 bits */
> > >
> > >  /* PCI Command Register */
> > > +#define RTE_PCI_COMMAND              0x04    /* 16 bits */
> > > +#define RTE_PCI_COMMAND_MEMORY       0x2     /* Enable response in Memory space */
> > >  #define RTE_PCI_COMMAND_MASTER       0x4     /* Bus Master Enable */
> > > +#define RTE_PCI_COMMAND_INTX_DISABLE 0x400 /* INTx Emulation Disable */
> > >
> >
> > It's weird here to have two defines in the same block with the same value -
> > even if one is 0x04 and the other is 0x4. That implies that the two values
> > don't belong in the same block of defines.
> >
> > Question - would enums make sense for defining any of these? It allows
> > the groups to be named?
>
> That's something I will look into, or at least better organise the defines..

At least, using enum would be a (minor) change in the API, as macros
were used so far and maybe some users were relying on them (#ifdef /
#ifndef).

I relooked at linux/pci_regs.h which organises those defines a bit as
I did, but with some kind of indentation (double space) to separate
the first offset of a block and the rest of the defines related to
said block of defines/registers.
Example:
#define PCI_COMMAND             0x04    /* 16 bits */
#define  PCI_COMMAND_IO         0x1     /* Enable response in I/O space */
#define  PCI_COMMAND_MEMORY     0x2     /* Enable response in Memory space */
#define  PCI_COMMAND_MASTER     0x4     /* Enable bus mastering */
#define  PCI_COMMAND_SPECIAL    0x8     /* Enable response to special cycles */


-- 
David Marchand


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

* Re: [PATCH 06/14] pci: define some command constants
  2023-08-08  9:20       ` David Marchand
@ 2023-08-08 10:08         ` Bruce Richardson
  0 siblings, 0 replies; 98+ messages in thread
From: Bruce Richardson @ 2023-08-08 10:08 UTC (permalink / raw)
  To: David Marchand
  Cc: dev, thomas, ferruh.yigit, chenbo.xia, nipun.gupta,
	Anatoly Burakov, Timothy McDaniel, Gaetan Rivet

On Tue, Aug 08, 2023 at 11:20:28AM +0200, David Marchand wrote:
> On Thu, Aug 3, 2023 at 1:51 PM David Marchand <david.marchand@redhat.com> wrote:
> >
> > On Thu, Aug 3, 2023 at 11:58 AM Bruce Richardson
> > <bruce.richardson@intel.com> wrote:
> > >
> > > On Thu, Aug 03, 2023 at 09:50:29AM +0200, David Marchand wrote:
> > > > Define some PCI command constants and use them in existing drivers.
> > > >
> > > > Signed-off-by: David Marchand <david.marchand@redhat.com>
> > > > ---
> > >
> > > For the idea, all good, but for the implementation, one comment inline
> > > below.
> > >
> > > With the below reworked:
> > >
> > > Acked-by: Bruce Richardson <bruce.richardson@intel.com>
> > >
> > > >  drivers/bus/pci/linux/pci_vfio.c  | 8 ++++----
> > > >  drivers/event/dlb2/pf/dlb2_main.c | 8 +++-----
> > > >  lib/pci/rte_pci.h                 | 4 +++-
> > > >  3 files changed, 10 insertions(+), 10 deletions(-)
> > > >
> > > > diff --git a/drivers/bus/pci/linux/pci_vfio.c b/drivers/bus/pci/linux/pci_vfio.c
> > > > index 6d13cafdcf..f96b3ce7fb 100644
> > > > --- a/drivers/bus/pci/linux/pci_vfio.c
> > > > +++ b/drivers/bus/pci/linux/pci_vfio.c
> > > > @@ -156,18 +156,18 @@ pci_vfio_enable_bus_memory(struct rte_pci_device *dev, int dev_fd)
> > > >               return -1;
> > > >       }
> > > >
> > > > -     ret = pread64(dev_fd, &cmd, sizeof(cmd), offset + PCI_COMMAND);
> > > > +     ret = pread64(dev_fd, &cmd, sizeof(cmd), offset + RTE_PCI_COMMAND);
> > > >
> > > >       if (ret != sizeof(cmd)) {
> > > >               RTE_LOG(ERR, EAL, "Cannot read command from PCI config space!\n");
> > > >               return -1;
> > > >       }
> > > >
> > > > -     if (cmd & PCI_COMMAND_MEMORY)
> > > > +     if (cmd & RTE_PCI_COMMAND_MEMORY)
> > > >               return 0;
> > > >
> > > > -     cmd |= PCI_COMMAND_MEMORY;
> > > > -     ret = pwrite64(dev_fd, &cmd, sizeof(cmd), offset + PCI_COMMAND);
> > > > +     cmd |= RTE_PCI_COMMAND_MEMORY;
> > > > +     ret = pwrite64(dev_fd, &cmd, sizeof(cmd), offset + RTE_PCI_COMMAND);
> > > >
> > > >       if (ret != sizeof(cmd)) {
> > > >               RTE_LOG(ERR, EAL, "Cannot write command to PCI config space!\n");
> > > > diff --git a/drivers/event/dlb2/pf/dlb2_main.c b/drivers/event/dlb2/pf/dlb2_main.c
> > > > index c6606a9bee..6dbaa2ff97 100644
> > > > --- a/drivers/event/dlb2/pf/dlb2_main.c
> > > > +++ b/drivers/event/dlb2/pf/dlb2_main.c
> > > > @@ -33,7 +33,6 @@
> > > >  #define DLB2_PCI_EXP_DEVCTL2 40
> > > >  #define DLB2_PCI_LNKCTL2 48
> > > >  #define DLB2_PCI_SLTCTL2 56
> > > > -#define DLB2_PCI_CMD 4
> > > >  #define DLB2_PCI_EXP_DEVSTA 10
> > > >  #define DLB2_PCI_EXP_DEVSTA_TRPND 0x20
> > > >  #define DLB2_PCI_EXP_DEVCTL_BCR_FLR 0x8000
> > > > @@ -47,7 +46,6 @@
> > > >  #define DLB2_PCI_ERR_ROOT_STATUS         0x30
> > > >  #define DLB2_PCI_ERR_COR_STATUS          0x10
> > > >  #define DLB2_PCI_ERR_UNCOR_STATUS        0x4
> > > > -#define DLB2_PCI_COMMAND_INTX_DISABLE    0x400
> > > >  #define DLB2_PCI_ACS_CAP                 0x4
> > > >  #define DLB2_PCI_ACS_CTRL                0x6
> > > >  #define DLB2_PCI_ACS_SV                  0x1
> > > > @@ -286,7 +284,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
> > > >
> > > >       /* clear the PCI command register before issuing the FLR */
> > > >
> > > > -     off = DLB2_PCI_CMD;
> > > > +     off = RTE_PCI_COMMAND;
> > > >       cmd = 0;
> > > >       if (rte_pci_write_config(pdev, &cmd, 2, off) != 2) {
> > > >               DLB2_LOG_ERR("[%s()] failed to write the pci command\n",
> > > > @@ -468,9 +466,9 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
> > > >               }
> > > >       }
> > > >
> > > > -     off = DLB2_PCI_CMD;
> > > > +     off = RTE_PCI_COMMAND;
> > > >       if (rte_pci_read_config(pdev, &cmd, 2, off) == 2) {
> > > > -             cmd &= ~DLB2_PCI_COMMAND_INTX_DISABLE;
> > > > +             cmd &= ~RTE_PCI_COMMAND_INTX_DISABLE;
> > > >               if (rte_pci_write_config(pdev, &cmd, 2, off) != 2) {
> > > >                       DLB2_LOG_ERR("[%s()] failed to write the pci command\n",
> > > >                              __func__);
> > > > diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
> > > > index a055a28592..bf2b2639f4 100644
> > > > --- a/lib/pci/rte_pci.h
> > > > +++ b/lib/pci/rte_pci.h
> > > > @@ -32,10 +32,12 @@ extern "C" {
> > > >
> > > >  #define RTE_PCI_VENDOR_ID    0x00    /* 16 bits */
> > > >  #define RTE_PCI_DEVICE_ID    0x02    /* 16 bits */
> > > > -#define RTE_PCI_COMMAND              0x04    /* 16 bits */
> > > >
> > > >  /* PCI Command Register */
> > > > +#define RTE_PCI_COMMAND              0x04    /* 16 bits */
> > > > +#define RTE_PCI_COMMAND_MEMORY       0x2     /* Enable response in Memory space */
> > > >  #define RTE_PCI_COMMAND_MASTER       0x4     /* Bus Master Enable */
> > > > +#define RTE_PCI_COMMAND_INTX_DISABLE 0x400 /* INTx Emulation Disable */
> > > >
> > >
> > > It's weird here to have two defines in the same block with the same value -
> > > even if one is 0x04 and the other is 0x4. That implies that the two values
> > > don't belong in the same block of defines.
> > >
> > > Question - would enums make sense for defining any of these? It allows
> > > the groups to be named?
> >
> > That's something I will look into, or at least better organise the defines..
> 
> At least, using enum would be a (minor) change in the API, as macros
> were used so far and maybe some users were relying on them (#ifdef /
> #ifndef).
>
> I relooked at linux/pci_regs.h which organises those defines a bit as
> I did, but with some kind of indentation (double space) to separate
> the first offset of a block and the rest of the defines related to
> said block of defines/registers.
> Example:
> #define PCI_COMMAND             0x04    /* 16 bits */
> #define  PCI_COMMAND_IO         0x1     /* Enable response in I/O space */
> #define  PCI_COMMAND_MEMORY     0x2     /* Enable response in Memory space */
> #define  PCI_COMMAND_MASTER     0x4     /* Enable bus mastering */
> #define  PCI_COMMAND_SPECIAL    0x8     /* Enable response to special cycles */
> 
> 
I'd still prefer grouping with enums, but ok with this approach too.

/Bruce

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

* [PATCH v2 00/15] Cleanup PCI(e) drivers
  2023-08-03  7:50 [PATCH 00/14] Cleanup PCI(e) drivers David Marchand
                   ` (14 preceding siblings ...)
  2023-08-03 10:03 ` [PATCH 00/14] Cleanup PCI(e) drivers Bruce Richardson
@ 2023-08-21 11:35 ` David Marchand
  2023-08-21 11:35   ` [PATCH v2 01/15] drivers: remove duplicated PCI master control David Marchand
                     ` (15 more replies)
  2023-08-22 16:09 ` [PATCH 00/14] " Adam Hassick
                   ` (3 subsequent siblings)
  19 siblings, 16 replies; 98+ messages in thread
From: David Marchand @ 2023-08-21 11:35 UTC (permalink / raw)
  To: dev; +Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, bruce.richardson

Rather than rely on Linux headers to find some PCI(e) standard constants
or reinvent the same PCI capability helper, this series complements the
pci library and the pci bus driver.
PCI drivers can then use OS agnostic macros and helpers.


-- 
David Marchand

Changes since v1:
- fix VFIO-backed drivers broken by v1 patch 3,
- enhanced rte_pci.h defines organisation,

David Marchand (15):
  drivers: remove duplicated PCI master control
  bus/pci: add const to some experimental API
  bus/pci: rework MSIX discovery with VFIO
  bus/pci: find PCI capability
  pci: define some capability constants
  pci: define some MSIX constants
  pci: define some command constants
  pci: define some BAR constants
  pci: define some PM constants
  pci: define some PCIe constants
  pci: define some extended capability constants
  pci: define some ACS constants
  pci: define some PRI constants
  pci: define some AER constants
  devtools: forbid inclusion of Linux header for PCI

 devtools/checkpatches.sh            |   8 ++
 drivers/bus/pci/linux/pci_init.h    |  18 ----
 drivers/bus/pci/linux/pci_uio.c     |  32 +-----
 drivers/bus/pci/linux/pci_vfio.c    | 148 ++++++--------------------
 drivers/bus/pci/pci_common.c        |  49 ++++++++-
 drivers/bus/pci/rte_bus_pci.h       |  35 ++++++-
 drivers/bus/pci/version.map         |   4 +
 drivers/crypto/virtio/virtio_pci.c  |  67 ++++--------
 drivers/event/dlb2/pf/dlb2_main.c   | 156 ++++++++--------------------
 drivers/net/bnx2x/bnx2x.c           |  86 ++++++++-------
 drivers/net/bnx2x/bnx2x.h           |  46 --------
 drivers/net/cxgbe/base/adapter.h    |  31 +-----
 drivers/net/gve/gve_ethdev.c        |  46 +-------
 drivers/net/gve/gve_ethdev.h        |  14 +--
 drivers/net/hns3/hns3_ethdev_vf.c   | 109 +++----------------
 drivers/net/ngbe/base/ngbe_hw.c     |  20 +---
 drivers/net/ngbe/base/ngbe_osdep.h  |   3 -
 drivers/net/virtio/virtio_pci.c     | 131 ++++-------------------
 drivers/vdpa/ifc/base/ifcvf_osdep.h |   4 +-
 lib/pci/rte_pci.h                   |  90 ++++++++++++++--
 20 files changed, 358 insertions(+), 739 deletions(-)

-- 
2.41.0


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

* [PATCH v2 01/15] drivers: remove duplicated PCI master control
  2023-08-21 11:35 ` [PATCH v2 00/15] " David Marchand
@ 2023-08-21 11:35   ` David Marchand
  2023-09-06 13:02     ` Xia, Chenbo
  2023-08-21 11:35   ` [PATCH v2 02/15] bus/pci: add const to some experimental API David Marchand
                     ` (14 subsequent siblings)
  15 siblings, 1 reply; 98+ messages in thread
From: David Marchand @ 2023-08-21 11:35 UTC (permalink / raw)
  To: dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, bruce.richardson,
	Anatoly Burakov, Dongdong Liu, Yisen Zhuang, Jiawen Wu

Use existing API to cleanup duplicated code.

Signed-off-by: David Marchand <david.marchand@redhat.com>
Acked-by: Bruce Richardson <bruce.richardson@intel.com>
---
 drivers/bus/pci/linux/pci_uio.c    | 32 +----------------------
 drivers/bus/pci/linux/pci_vfio.c   | 41 ++----------------------------
 drivers/net/hns3/hns3_ethdev_vf.c  | 25 +-----------------
 drivers/net/ngbe/base/ngbe_hw.c    | 20 ++-------------
 drivers/net/ngbe/base/ngbe_osdep.h |  3 ---
 5 files changed, 6 insertions(+), 115 deletions(-)

diff --git a/drivers/bus/pci/linux/pci_uio.c b/drivers/bus/pci/linux/pci_uio.c
index 2bf16e9369..97d740dfe5 100644
--- a/drivers/bus/pci/linux/pci_uio.c
+++ b/drivers/bus/pci/linux/pci_uio.c
@@ -10,7 +10,6 @@
 #include <sys/stat.h>
 #include <sys/mman.h>
 #include <sys/sysmacros.h>
-#include <linux/pci_regs.h>
 
 #if defined(RTE_ARCH_X86)
 #include <sys/io.h>
@@ -77,35 +76,6 @@ pci_uio_mmio_write(const struct rte_pci_device *dev, int bar,
 	return len;
 }
 
-static int
-pci_uio_set_bus_master(int dev_fd)
-{
-	uint16_t reg;
-	int ret;
-
-	ret = pread(dev_fd, &reg, sizeof(reg), PCI_COMMAND);
-	if (ret != sizeof(reg)) {
-		RTE_LOG(ERR, EAL,
-			"Cannot read command from PCI config space!\n");
-		return -1;
-	}
-
-	/* return if bus mastering is already on */
-	if (reg & PCI_COMMAND_MASTER)
-		return 0;
-
-	reg |= PCI_COMMAND_MASTER;
-
-	ret = pwrite(dev_fd, &reg, sizeof(reg), PCI_COMMAND);
-	if (ret != sizeof(reg)) {
-		RTE_LOG(ERR, EAL,
-			"Cannot write command to PCI config space!\n");
-		return -1;
-	}
-
-	return 0;
-}
-
 static int
 pci_mknod_uio_dev(const char *sysfs_uio_path, unsigned uio_num)
 {
@@ -299,7 +269,7 @@ pci_uio_alloc_resource(struct rte_pci_device *dev,
 			goto error;
 
 		/* set bus master that is not done by uio_pci_generic */
-		if (pci_uio_set_bus_master(uio_cfg_fd)) {
+		if (rte_pci_set_bus_master(dev, true)) {
 			RTE_LOG(ERR, EAL, "Cannot set up bus mastering!\n");
 			goto error;
 		}
diff --git a/drivers/bus/pci/linux/pci_vfio.c b/drivers/bus/pci/linux/pci_vfio.c
index e634de8322..8fa7fa458f 100644
--- a/drivers/bus/pci/linux/pci_vfio.c
+++ b/drivers/bus/pci/linux/pci_vfio.c
@@ -223,42 +223,6 @@ pci_vfio_enable_bus_memory(struct rte_pci_device *dev, int dev_fd)
 	return 0;
 }
 
-/* set PCI bus mastering */
-static int
-pci_vfio_set_bus_master(const struct rte_pci_device *dev, int dev_fd, bool op)
-{
-	uint64_t size, offset;
-	uint16_t reg;
-	int ret;
-
-	if (pci_vfio_get_region(dev, VFIO_PCI_CONFIG_REGION_INDEX,
-		&size, &offset) != 0) {
-		RTE_LOG(ERR, EAL, "Cannot get offset of CONFIG region.\n");
-		return -1;
-	}
-
-	ret = pread64(dev_fd, &reg, sizeof(reg), offset + PCI_COMMAND);
-	if (ret != sizeof(reg)) {
-		RTE_LOG(ERR, EAL, "Cannot read command from PCI config space!\n");
-		return -1;
-	}
-
-	if (op)
-		/* set the master bit */
-		reg |= PCI_COMMAND_MASTER;
-	else
-		reg &= ~(PCI_COMMAND_MASTER);
-
-	ret = pwrite64(dev_fd, &reg, sizeof(reg), offset + PCI_COMMAND);
-
-	if (ret != sizeof(reg)) {
-		RTE_LOG(ERR, EAL, "Cannot write command to PCI config space!\n");
-		return -1;
-	}
-
-	return 0;
-}
-
 /* set up interrupt support (but not enable interrupts) */
 static int
 pci_vfio_setup_interrupts(struct rte_pci_device *dev, int vfio_dev_fd)
@@ -535,8 +499,7 @@ pci_rte_vfio_setup_device(struct rte_pci_device *dev, int vfio_dev_fd)
 		return -1;
 	}
 
-	/* set bus mastering for the device */
-	if (pci_vfio_set_bus_master(dev, vfio_dev_fd, true)) {
+	if (rte_pci_set_bus_master(dev, true)) {
 		RTE_LOG(ERR, EAL, "Cannot set up bus mastering!\n");
 		return -1;
 	}
@@ -1226,7 +1189,7 @@ pci_vfio_unmap_resource_primary(struct rte_pci_device *dev)
 	if (vfio_dev_fd < 0)
 		return -1;
 
-	if (pci_vfio_set_bus_master(dev, vfio_dev_fd, false)) {
+	if (rte_pci_set_bus_master(dev, false)) {
 		RTE_LOG(ERR, EAL, "%s cannot unset bus mastering for PCI device!\n",
 				pci_addr);
 		return -1;
diff --git a/drivers/net/hns3/hns3_ethdev_vf.c b/drivers/net/hns3/hns3_ethdev_vf.c
index 5aac62a41f..7b3c5dc168 100644
--- a/drivers/net/hns3/hns3_ethdev_vf.c
+++ b/drivers/net/hns3/hns3_ethdev_vf.c
@@ -49,29 +49,6 @@ static int hns3vf_remove_mc_mac_addr(struct hns3_hw *hw,
 static int hns3vf_dev_link_update(struct rte_eth_dev *eth_dev,
 				   __rte_unused int wait_to_complete);
 
-/* set PCI bus mastering */
-static int
-hns3vf_set_bus_master(const struct rte_pci_device *device, bool op)
-{
-	uint16_t reg;
-	int ret;
-
-	ret = rte_pci_read_config(device, &reg, sizeof(reg), PCI_COMMAND);
-	if (ret < 0) {
-		PMD_INIT_LOG(ERR, "Failed to read PCI offset 0x%x",
-			     PCI_COMMAND);
-		return ret;
-	}
-
-	if (op)
-		/* set the master bit */
-		reg |= PCI_COMMAND_MASTER;
-	else
-		reg &= ~(PCI_COMMAND_MASTER);
-
-	return rte_pci_write_config(device, &reg, sizeof(reg), PCI_COMMAND);
-}
-
 /**
  * hns3vf_find_pci_capability - lookup a capability in the PCI capability list
  * @cap: the capability
@@ -2140,7 +2117,7 @@ hns3vf_reinit_dev(struct hns3_adapter *hns)
 
 	if (hw->reset.level == HNS3_VF_FULL_RESET) {
 		rte_intr_disable(pci_dev->intr_handle);
-		ret = hns3vf_set_bus_master(pci_dev, true);
+		ret = rte_pci_set_bus_master(pci_dev, true);
 		if (ret < 0) {
 			hns3_err(hw, "failed to set pci bus, ret = %d", ret);
 			return ret;
diff --git a/drivers/net/ngbe/base/ngbe_hw.c b/drivers/net/ngbe/base/ngbe_hw.c
index 27243d85c8..22ccdb0b7d 100644
--- a/drivers/net/ngbe/base/ngbe_hw.c
+++ b/drivers/net/ngbe/base/ngbe_hw.c
@@ -1061,26 +1061,10 @@ s32 ngbe_set_pcie_master(struct ngbe_hw *hw, bool enable)
 {
 	struct rte_pci_device *pci_dev = (struct rte_pci_device *)hw->back;
 	s32 status = 0;
-	s32 ret = 0;
 	u32 i;
-	u16 reg;
 
-	ret = rte_pci_read_config(pci_dev, &reg,
-			sizeof(reg), PCI_COMMAND);
-	if (ret != sizeof(reg)) {
-		DEBUGOUT("Cannot read command from PCI config space!\n");
-		return -1;
-	}
-
-	if (enable)
-		reg |= PCI_COMMAND_MASTER;
-	else
-		reg &= ~PCI_COMMAND_MASTER;
-
-	ret = rte_pci_write_config(pci_dev, &reg,
-			sizeof(reg), PCI_COMMAND);
-	if (ret != sizeof(reg)) {
-		DEBUGOUT("Cannot write command to PCI config space!\n");
+	if (rte_pci_set_bus_master(pci_dev, enable) < 0) {
+		DEBUGOUT("Cannot configure PCI bus master\n");
 		return -1;
 	}
 
diff --git a/drivers/net/ngbe/base/ngbe_osdep.h b/drivers/net/ngbe/base/ngbe_osdep.h
index 8783fce4dd..30598a240a 100644
--- a/drivers/net/ngbe/base/ngbe_osdep.h
+++ b/drivers/net/ngbe/base/ngbe_osdep.h
@@ -181,7 +181,4 @@ static inline u64 REVERT_BIT_MASK64(u64 mask)
 #define ETH_P_8021Q      0x8100
 #define ETH_P_8021AD     0x88A8
 
-#define PCI_COMMAND		0x04
-#define  PCI_COMMAND_MASTER	0x4
-
 #endif /* _NGBE_OS_H_ */
-- 
2.41.0


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

* [PATCH v2 02/15] bus/pci: add const to some experimental API
  2023-08-21 11:35 ` [PATCH v2 00/15] " David Marchand
  2023-08-21 11:35   ` [PATCH v2 01/15] drivers: remove duplicated PCI master control David Marchand
@ 2023-08-21 11:35   ` David Marchand
  2023-08-21 16:14     ` Tyler Retzlaff
  2023-09-06 13:02     ` Xia, Chenbo
  2023-08-21 11:35   ` [PATCH v2 03/15] bus/pci: rework MSIX discovery with VFIO David Marchand
                     ` (13 subsequent siblings)
  15 siblings, 2 replies; 98+ messages in thread
From: David Marchand @ 2023-08-21 11:35 UTC (permalink / raw)
  To: dev; +Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, bruce.richardson

Those functions are fine with a const on the device pointer.

Signed-off-by: David Marchand <david.marchand@redhat.com>
Acked-by: Bruce Richardson <bruce.richardson@intel.com>
---
 drivers/bus/pci/pci_common.c  | 4 ++--
 drivers/bus/pci/rte_bus_pci.h | 4 ++--
 2 files changed, 4 insertions(+), 4 deletions(-)

diff --git a/drivers/bus/pci/pci_common.c b/drivers/bus/pci/pci_common.c
index 52404ab0fe..382b0b8946 100644
--- a/drivers/bus/pci/pci_common.c
+++ b/drivers/bus/pci/pci_common.c
@@ -814,7 +814,7 @@ rte_pci_get_iommu_class(void)
 }
 
 off_t
-rte_pci_find_ext_capability(struct rte_pci_device *dev, uint32_t cap)
+rte_pci_find_ext_capability(const struct rte_pci_device *dev, uint32_t cap)
 {
 	off_t offset = RTE_PCI_CFG_SPACE_SIZE;
 	uint32_t header;
@@ -857,7 +857,7 @@ rte_pci_find_ext_capability(struct rte_pci_device *dev, uint32_t cap)
 }
 
 int
-rte_pci_set_bus_master(struct rte_pci_device *dev, bool enable)
+rte_pci_set_bus_master(const struct rte_pci_device *dev, bool enable)
 {
 	uint16_t old_cmd, cmd;
 
diff --git a/drivers/bus/pci/rte_bus_pci.h b/drivers/bus/pci/rte_bus_pci.h
index 9d59c4aef3..75d0030eae 100644
--- a/drivers/bus/pci/rte_bus_pci.h
+++ b/drivers/bus/pci/rte_bus_pci.h
@@ -85,7 +85,7 @@ void rte_pci_dump(FILE *f);
  *  = 0: Device does not support it.
  */
 __rte_experimental
-off_t rte_pci_find_ext_capability(struct rte_pci_device *dev, uint32_t cap);
+off_t rte_pci_find_ext_capability(const struct rte_pci_device *dev, uint32_t cap);
 
 /**
  * Enables/Disables Bus Master for device's PCI command register.
@@ -99,7 +99,7 @@ off_t rte_pci_find_ext_capability(struct rte_pci_device *dev, uint32_t cap);
  *  0 on success, -1 on error in PCI config space read/write.
  */
 __rte_experimental
-int rte_pci_set_bus_master(struct rte_pci_device *dev, bool enable);
+int rte_pci_set_bus_master(const struct rte_pci_device *dev, bool enable);
 
 /**
  * Read PCI config space.
-- 
2.41.0


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

* [PATCH v2 03/15] bus/pci: rework MSIX discovery with VFIO
  2023-08-21 11:35 ` [PATCH v2 00/15] " David Marchand
  2023-08-21 11:35   ` [PATCH v2 01/15] drivers: remove duplicated PCI master control David Marchand
  2023-08-21 11:35   ` [PATCH v2 02/15] bus/pci: add const to some experimental API David Marchand
@ 2023-08-21 11:35   ` David Marchand
  2023-09-06 13:03     ` Xia, Chenbo
  2023-08-21 11:35   ` [PATCH v2 04/15] bus/pci: find PCI capability David Marchand
                     ` (12 subsequent siblings)
  15 siblings, 1 reply; 98+ messages in thread
From: David Marchand @ 2023-08-21 11:35 UTC (permalink / raw)
  To: dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, bruce.richardson,
	Anatoly Burakov

This is a preparatory step before using new helpers for finding PCI
capabilities.
In the code querying PCI capabilities for checking MSIX availability,
replace direct calls to VFIO fd with the existing helpers for reading
PCI configuration space: this requires setting VFIO fd in the PCI
device object than was done before this change and removes the need to
pass around this vfio_dev_fd variable.

Signed-off-by: David Marchand <david.marchand@redhat.com>
---
 drivers/bus/pci/linux/pci_vfio.c | 27 ++++++++++-----------------
 1 file changed, 10 insertions(+), 17 deletions(-)

diff --git a/drivers/bus/pci/linux/pci_vfio.c b/drivers/bus/pci/linux/pci_vfio.c
index 8fa7fa458f..958f8b3b52 100644
--- a/drivers/bus/pci/linux/pci_vfio.c
+++ b/drivers/bus/pci/linux/pci_vfio.c
@@ -107,23 +107,16 @@ pci_vfio_write_config(const struct rte_pci_device *dev,
 
 /* get PCI BAR number where MSI-X interrupts are */
 static int
-pci_vfio_get_msix_bar(const struct rte_pci_device *dev, int fd,
+pci_vfio_get_msix_bar(const struct rte_pci_device *dev,
 	struct pci_msix_table *msix_table)
 {
 	int ret;
 	uint32_t reg;
 	uint16_t flags;
 	uint8_t cap_id, cap_offset;
-	uint64_t size, offset;
-
-	if (pci_vfio_get_region(dev, VFIO_PCI_CONFIG_REGION_INDEX,
-		&size, &offset) != 0) {
-		RTE_LOG(ERR, EAL, "Cannot get offset of CONFIG region.\n");
-		return -1;
-	}
 
 	/* read PCI capability pointer from config space */
-	ret = pread64(fd, &reg, sizeof(reg), offset + PCI_CAPABILITY_LIST);
+	ret = rte_pci_read_config(dev, &reg, sizeof(reg), PCI_CAPABILITY_LIST);
 	if (ret != sizeof(reg)) {
 		RTE_LOG(ERR, EAL,
 			"Cannot read capability pointer from PCI config space!\n");
@@ -136,7 +129,7 @@ pci_vfio_get_msix_bar(const struct rte_pci_device *dev, int fd,
 	while (cap_offset) {
 
 		/* read PCI capability ID */
-		ret = pread64(fd, &reg, sizeof(reg), offset + cap_offset);
+		ret = rte_pci_read_config(dev, &reg, sizeof(reg), cap_offset);
 		if (ret != sizeof(reg)) {
 			RTE_LOG(ERR, EAL,
 				"Cannot read capability ID from PCI config space!\n");
@@ -148,7 +141,7 @@ pci_vfio_get_msix_bar(const struct rte_pci_device *dev, int fd,
 
 		/* if we haven't reached MSI-X, check next capability */
 		if (cap_id != PCI_CAP_ID_MSIX) {
-			ret = pread64(fd, &reg, sizeof(reg), offset + cap_offset);
+			ret = rte_pci_read_config(dev, &reg, sizeof(reg), cap_offset);
 			if (ret != sizeof(reg)) {
 				RTE_LOG(ERR, EAL,
 					"Cannot read capability pointer from PCI config space!\n");
@@ -163,14 +156,14 @@ pci_vfio_get_msix_bar(const struct rte_pci_device *dev, int fd,
 		/* else, read table offset */
 		else {
 			/* table offset resides in the next 4 bytes */
-			ret = pread64(fd, &reg, sizeof(reg), offset + cap_offset + 4);
+			ret = rte_pci_read_config(dev, &reg, sizeof(reg), cap_offset + 4);
 			if (ret != sizeof(reg)) {
 				RTE_LOG(ERR, EAL,
 					"Cannot read table offset from PCI config space!\n");
 				return -1;
 			}
 
-			ret = pread64(fd, &flags, sizeof(flags), offset + cap_offset + 2);
+			ret = rte_pci_read_config(dev, &flags, sizeof(flags), cap_offset + 2);
 			if (ret != sizeof(flags)) {
 				RTE_LOG(ERR, EAL,
 					"Cannot read table flags from PCI config space!\n");
@@ -306,9 +299,6 @@ pci_vfio_setup_interrupts(struct rte_pci_device *dev, int vfio_dev_fd)
 		if (rte_intr_fd_set(dev->intr_handle, fd))
 			return -1;
 
-		if (rte_intr_dev_fd_set(dev->intr_handle, vfio_dev_fd))
-			return -1;
-
 		switch (i) {
 		case VFIO_PCI_MSIX_IRQ_INDEX:
 			intr_mode = RTE_INTR_MODE_MSIX;
@@ -838,6 +828,9 @@ pci_vfio_map_resource_primary(struct rte_pci_device *dev)
 	if (ret)
 		return ret;
 
+	if (rte_intr_dev_fd_set(dev->intr_handle, vfio_dev_fd))
+		goto err_vfio_dev_fd;
+
 	/* allocate vfio_res and get region info */
 	vfio_res = rte_zmalloc("VFIO_RES", sizeof(*vfio_res), 0);
 	if (vfio_res == NULL) {
@@ -869,7 +862,7 @@ pci_vfio_map_resource_primary(struct rte_pci_device *dev)
 	/* get MSI-X BAR, if any (we have to know where it is because we can't
 	 * easily mmap it when using VFIO)
 	 */
-	ret = pci_vfio_get_msix_bar(dev, vfio_dev_fd, &vfio_res->msix_table);
+	ret = pci_vfio_get_msix_bar(dev, &vfio_res->msix_table);
 	if (ret < 0) {
 		RTE_LOG(ERR, EAL, "%s cannot get MSI-X BAR number!\n",
 				pci_addr);
-- 
2.41.0


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

* [PATCH v2 04/15] bus/pci: find PCI capability
  2023-08-21 11:35 ` [PATCH v2 00/15] " David Marchand
                     ` (2 preceding siblings ...)
  2023-08-21 11:35   ` [PATCH v2 03/15] bus/pci: rework MSIX discovery with VFIO David Marchand
@ 2023-08-21 11:35   ` David Marchand
  2023-09-07 12:43     ` Xia, Chenbo
  2023-08-21 11:35   ` [PATCH v2 05/15] pci: define some capability constants David Marchand
                     ` (11 subsequent siblings)
  15 siblings, 1 reply; 98+ messages in thread
From: David Marchand @ 2023-08-21 11:35 UTC (permalink / raw)
  To: dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, bruce.richardson,
	Anatoly Burakov, Jay Zhou, Timothy McDaniel, Julien Aube,
	Rahul Lakkireddy, Junfeng Guo, Jeroen de Borst, Rushil Gupta,
	Joshua Washington, Dongdong Liu, Yisen Zhuang, Maxime Coquelin,
	Gaetan Rivet

Introduce two helpers so that drivers stop reinventing the wheel when it
comes to finding capabilities in a device PCI configuration space.
Use it in existing drivers.

Note:
- base/ drivers code is left untouched, only some wrappers in cxgbe
  are touched,
- bnx2x maintained a per device cache of capabilities, this code has been
  reworked to only cache the capabilities used in this driver,

Signed-off-by: David Marchand <david.marchand@redhat.com>
Acked-by: Bruce Richardson <bruce.richardson@intel.com>
---
Changes since v1:
- updated commitlog,
- separated VFIO changes for using standard PCI helper in a separate
  patch,
- marked new experimental symbols with current version,
- reordered defines in rte_pci.h,

---
 drivers/bus/pci/linux/pci_vfio.c   |  74 ++++--------------
 drivers/bus/pci/pci_common.c       |  45 +++++++++++
 drivers/bus/pci/rte_bus_pci.h      |  31 ++++++++
 drivers/bus/pci/version.map        |   4 +
 drivers/crypto/virtio/virtio_pci.c |  57 +++++---------
 drivers/event/dlb2/pf/dlb2_main.c  |  42 +---------
 drivers/net/bnx2x/bnx2x.c          |  41 +++++-----
 drivers/net/cxgbe/base/adapter.h   |  28 +------
 drivers/net/gve/gve_ethdev.c       |  46 ++---------
 drivers/net/gve/gve_ethdev.h       |   4 -
 drivers/net/hns3/hns3_ethdev_vf.c  |  79 +++----------------
 drivers/net/virtio/virtio_pci.c    | 121 +++++------------------------
 lib/pci/rte_pci.h                  |  11 +++
 13 files changed, 186 insertions(+), 397 deletions(-)

diff --git a/drivers/bus/pci/linux/pci_vfio.c b/drivers/bus/pci/linux/pci_vfio.c
index 958f8b3b52..614ed5d696 100644
--- a/drivers/bus/pci/linux/pci_vfio.c
+++ b/drivers/bus/pci/linux/pci_vfio.c
@@ -110,74 +110,34 @@ static int
 pci_vfio_get_msix_bar(const struct rte_pci_device *dev,
 	struct pci_msix_table *msix_table)
 {
-	int ret;
-	uint32_t reg;
-	uint16_t flags;
-	uint8_t cap_id, cap_offset;
+	off_t cap_offset;
 
-	/* read PCI capability pointer from config space */
-	ret = rte_pci_read_config(dev, &reg, sizeof(reg), PCI_CAPABILITY_LIST);
-	if (ret != sizeof(reg)) {
-		RTE_LOG(ERR, EAL,
-			"Cannot read capability pointer from PCI config space!\n");
+	cap_offset = rte_pci_find_capability(dev, PCI_CAP_ID_MSIX);
+	if (cap_offset < 0)
 		return -1;
-	}
 
-	/* we need first byte */
-	cap_offset = reg & 0xFF;
+	if (cap_offset != 0) {
+		uint16_t flags;
+		uint32_t reg;
 
-	while (cap_offset) {
-
-		/* read PCI capability ID */
-		ret = rte_pci_read_config(dev, &reg, sizeof(reg), cap_offset);
-		if (ret != sizeof(reg)) {
+		/* table offset resides in the next 4 bytes */
+		if (rte_pci_read_config(dev, &reg, sizeof(reg), cap_offset + 4) < 0) {
 			RTE_LOG(ERR, EAL,
-				"Cannot read capability ID from PCI config space!\n");
+				"Cannot read MSIX table from PCI config space!\n");
 			return -1;
 		}
 
-		/* we need first byte */
-		cap_id = reg & 0xFF;
-
-		/* if we haven't reached MSI-X, check next capability */
-		if (cap_id != PCI_CAP_ID_MSIX) {
-			ret = rte_pci_read_config(dev, &reg, sizeof(reg), cap_offset);
-			if (ret != sizeof(reg)) {
-				RTE_LOG(ERR, EAL,
-					"Cannot read capability pointer from PCI config space!\n");
-				return -1;
-			}
-
-			/* we need second byte */
-			cap_offset = (reg & 0xFF00) >> 8;
-
-			continue;
+		if (rte_pci_read_config(dev, &flags, sizeof(flags), cap_offset + 2) < 0) {
+			RTE_LOG(ERR, EAL,
+				"Cannot read MSIX flags from PCI config space!\n");
+			return -1;
 		}
-		/* else, read table offset */
-		else {
-			/* table offset resides in the next 4 bytes */
-			ret = rte_pci_read_config(dev, &reg, sizeof(reg), cap_offset + 4);
-			if (ret != sizeof(reg)) {
-				RTE_LOG(ERR, EAL,
-					"Cannot read table offset from PCI config space!\n");
-				return -1;
-			}
-
-			ret = rte_pci_read_config(dev, &flags, sizeof(flags), cap_offset + 2);
-			if (ret != sizeof(flags)) {
-				RTE_LOG(ERR, EAL,
-					"Cannot read table flags from PCI config space!\n");
-				return -1;
-			}
-
-			msix_table->bar_index = reg & RTE_PCI_MSIX_TABLE_BIR;
-			msix_table->offset = reg & RTE_PCI_MSIX_TABLE_OFFSET;
-			msix_table->size =
-				16 * (1 + (flags & RTE_PCI_MSIX_FLAGS_QSIZE));
 
-			return 0;
-		}
+		msix_table->bar_index = reg & RTE_PCI_MSIX_TABLE_BIR;
+		msix_table->offset = reg & RTE_PCI_MSIX_TABLE_OFFSET;
+		msix_table->size = 16 * (1 + (flags & RTE_PCI_MSIX_FLAGS_QSIZE));
 	}
+
 	return 0;
 }
 
diff --git a/drivers/bus/pci/pci_common.c b/drivers/bus/pci/pci_common.c
index 382b0b8946..52272617eb 100644
--- a/drivers/bus/pci/pci_common.c
+++ b/drivers/bus/pci/pci_common.c
@@ -813,6 +813,51 @@ rte_pci_get_iommu_class(void)
 	return iova_mode;
 }
 
+bool
+rte_pci_has_capability_list(const struct rte_pci_device *dev)
+{
+	uint16_t status;
+
+	if (rte_pci_read_config(dev, &status, sizeof(status), RTE_PCI_STATUS) != sizeof(status))
+		return false;
+
+	return (status & RTE_PCI_STATUS_CAP_LIST) != 0;
+}
+
+off_t
+rte_pci_find_capability(const struct rte_pci_device *dev, uint8_t cap)
+{
+	off_t offset;
+	uint8_t pos;
+	int ttl;
+
+	offset = RTE_PCI_CAPABILITY_LIST;
+	ttl = (RTE_PCI_CFG_SPACE_SIZE - RTE_PCI_STD_HEADER_SIZEOF) / RTE_PCI_CAP_SIZEOF;
+
+	if (rte_pci_read_config(dev, &pos, sizeof(pos), offset) < 0)
+		return -1;
+
+	while (pos && ttl--) {
+		uint16_t ent;
+		uint8_t id;
+
+		offset = pos;
+		if (rte_pci_read_config(dev, &ent, sizeof(ent), offset) < 0)
+			return -1;
+
+		id = ent & 0xff;
+		if (id == 0xff)
+			break;
+
+		if (id == cap)
+			return offset;
+
+		pos = (ent >> 8);
+	}
+
+	return 0;
+}
+
 off_t
 rte_pci_find_ext_capability(const struct rte_pci_device *dev, uint32_t cap)
 {
diff --git a/drivers/bus/pci/rte_bus_pci.h b/drivers/bus/pci/rte_bus_pci.h
index 75d0030eae..1ed33dbf3d 100644
--- a/drivers/bus/pci/rte_bus_pci.h
+++ b/drivers/bus/pci/rte_bus_pci.h
@@ -68,6 +68,37 @@ void rte_pci_unmap_device(struct rte_pci_device *dev);
  */
 void rte_pci_dump(FILE *f);
 
+/**
+ * Check whether this device has a PCI capability list.
+ *
+ *  @param dev
+ *    A pointer to rte_pci_device structure.
+ *
+ *  @return
+ *    true/false
+ */
+__rte_experimental
+bool rte_pci_has_capability_list(const struct rte_pci_device *dev);
+
+/**
+ * Find device's PCI capability.
+ *
+ *  @param dev
+ *    A pointer to rte_pci_device structure.
+ *
+ *  @param cap
+ *    Capability to be found, which can be any from
+ *    RTE_PCI_CAP_ID_*, defined in librte_pci.
+ *
+ *  @return
+ *  > 0: The offset of the next matching capability structure
+ *       within the device's PCI configuration space.
+ *  < 0: An error in PCI config space read.
+ *  = 0: Device does not support it.
+ */
+__rte_experimental
+off_t rte_pci_find_capability(const struct rte_pci_device *dev, uint8_t cap);
+
 /**
  * Find device's extended PCI capability.
  *
diff --git a/drivers/bus/pci/version.map b/drivers/bus/pci/version.map
index a0000f7938..2674f30235 100644
--- a/drivers/bus/pci/version.map
+++ b/drivers/bus/pci/version.map
@@ -25,6 +25,10 @@ EXPERIMENTAL {
 	# added in 23.07
 	rte_pci_mmio_read;
 	rte_pci_mmio_write;
+
+	# added in 23.11
+	rte_pci_find_capability;
+	rte_pci_has_capability_list;
 };
 
 INTERNAL {
diff --git a/drivers/crypto/virtio/virtio_pci.c b/drivers/crypto/virtio/virtio_pci.c
index 95a43c8801..abc52b4701 100644
--- a/drivers/crypto/virtio/virtio_pci.c
+++ b/drivers/crypto/virtio/virtio_pci.c
@@ -19,7 +19,6 @@
  * we can't simply include that header here, as there is no such
  * file for non-Linux platform.
  */
-#define PCI_CAPABILITY_LIST	0x34
 #define PCI_CAP_ID_VNDR		0x09
 #define PCI_CAP_ID_MSIX		0x11
 
@@ -343,8 +342,9 @@ get_cfg_addr(struct rte_pci_device *dev, struct virtio_pci_cap *cap)
 static int
 virtio_read_caps(struct rte_pci_device *dev, struct virtio_crypto_hw *hw)
 {
-	uint8_t pos;
 	struct virtio_pci_cap cap;
+	uint16_t flags;
+	off_t pos;
 	int ret;
 
 	if (rte_pci_map_device(dev)) {
@@ -352,44 +352,26 @@ virtio_read_caps(struct rte_pci_device *dev, struct virtio_crypto_hw *hw)
 		return -1;
 	}
 
-	ret = rte_pci_read_config(dev, &pos, 1, PCI_CAPABILITY_LIST);
-	if (ret < 0) {
-		VIRTIO_CRYPTO_INIT_LOG_DBG("failed to read pci capability list");
-		return -1;
+	/*
+	 * Transitional devices would also have this capability,
+	 * that's why we also check if msix is enabled.
+	 */
+	pos = rte_pci_find_capability(dev, PCI_CAP_ID_MSIX);
+	if (pos > 0 && rte_pci_read_config(dev, &flags, sizeof(flags),
+			pos + 2) == sizeof(flags)) {
+		if (flags & PCI_MSIX_ENABLE)
+			hw->use_msix = VIRTIO_MSIX_ENABLED;
+		else
+			hw->use_msix = VIRTIO_MSIX_DISABLED;
+	} else {
+		hw->use_msix = VIRTIO_MSIX_NONE;
 	}
 
-	while (pos) {
-		ret = rte_pci_read_config(dev, &cap, sizeof(cap), pos);
-		if (ret < 0) {
-			VIRTIO_CRYPTO_INIT_LOG_ERR(
-				"failed to read pci cap at pos: %x", pos);
-			break;
-		}
-
-		if (cap.cap_vndr == PCI_CAP_ID_MSIX) {
-			/* Transitional devices would also have this capability,
-			 * that's why we also check if msix is enabled.
-			 * 1st byte is cap ID; 2nd byte is the position of next
-			 * cap; next two bytes are the flags.
-			 */
-			uint16_t flags = ((uint16_t *)&cap)[1];
-
-			if (flags & PCI_MSIX_ENABLE)
-				hw->use_msix = VIRTIO_MSIX_ENABLED;
-			else
-				hw->use_msix = VIRTIO_MSIX_DISABLED;
-		}
-
-		if (cap.cap_vndr != PCI_CAP_ID_VNDR) {
-			VIRTIO_CRYPTO_INIT_LOG_DBG(
-				"[%2x] skipping non VNDR cap id: %02x",
-				pos, cap.cap_vndr);
-			goto next;
-		}
-
+	pos = rte_pci_find_capability(dev, PCI_CAP_ID_VNDR);
+	if (pos > 0 && rte_pci_read_config(dev, &cap, sizeof(cap), pos) == sizeof(cap)) {
 		VIRTIO_CRYPTO_INIT_LOG_DBG(
 			"[%2x] cfg type: %u, bar: %u, offset: %04x, len: %u",
-			pos, cap.cfg_type, cap.bar, cap.offset, cap.length);
+			(unsigned int)pos, cap.cfg_type, cap.bar, cap.offset, cap.length);
 
 		switch (cap.cfg_type) {
 		case VIRTIO_PCI_CAP_COMMON_CFG:
@@ -411,9 +393,6 @@ virtio_read_caps(struct rte_pci_device *dev, struct virtio_crypto_hw *hw)
 			hw->isr = get_cfg_addr(dev, &cap);
 			break;
 		}
-
-next:
-		pos = cap.cap_next;
 	}
 
 	if (hw->common_cfg == NULL || hw->notify_base == NULL ||
diff --git a/drivers/event/dlb2/pf/dlb2_main.c b/drivers/event/dlb2/pf/dlb2_main.c
index 717aa4fc08..40e5cb594f 100644
--- a/drivers/event/dlb2/pf/dlb2_main.c
+++ b/drivers/event/dlb2/pf/dlb2_main.c
@@ -27,10 +27,6 @@
 #define NO_OWNER_VF 0	/* PF ONLY! */
 #define NOT_VF_REQ false /* PF ONLY! */
 
-#define DLB2_PCI_CAP_POINTER 0x34
-#define DLB2_PCI_CAP_NEXT(hdr) (((hdr) >> 8) & 0xFC)
-#define DLB2_PCI_CAP_ID(hdr) ((hdr) & 0xFF)
-
 #define DLB2_PCI_LNKCTL 16
 #define DLB2_PCI_SLTCTL 24
 #define DLB2_PCI_RTCTL 28
@@ -65,35 +61,6 @@
 #define DLB2_PCI_ACS_UF                  0x10
 #define DLB2_PCI_ACS_EC                  0x20
 
-static int dlb2_pci_find_capability(struct rte_pci_device *pdev, uint32_t id)
-{
-	uint8_t pos;
-	int ret;
-	uint16_t hdr;
-
-	ret = rte_pci_read_config(pdev, &pos, 1, DLB2_PCI_CAP_POINTER);
-	pos &= 0xFC;
-
-	if (ret != 1)
-		return -1;
-
-	while (pos > 0x3F) {
-		ret = rte_pci_read_config(pdev, &hdr, 2, pos);
-		if (ret != 2)
-			return -1;
-
-		if (DLB2_PCI_CAP_ID(hdr) == id)
-			return pos;
-
-		if (DLB2_PCI_CAP_ID(hdr) == 0xFF)
-			return -1;
-
-		pos = DLB2_PCI_CAP_NEXT(hdr);
-	}
-
-	return -1;
-}
-
 static int
 dlb2_pf_init_driver_state(struct dlb2_dev *dlb2_dev)
 {
@@ -258,9 +225,9 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 	uint32_t pri_reqs_dword;
 	uint16_t pri_ctrl_word;
 
-	int pcie_cap_offset;
+	off_t pcie_cap_offset;
 	int pri_cap_offset;
-	int msix_cap_offset;
+	off_t msix_cap_offset;
 	int err_cap_offset;
 	int acs_cap_offset;
 	int wait_count;
@@ -277,7 +244,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 	}
 
-	pcie_cap_offset = dlb2_pci_find_capability(pdev, DLB2_PCI_CAP_ID_EXP);
+	pcie_cap_offset = rte_pci_find_capability(pdev, DLB2_PCI_CAP_ID_EXP);
 
 	if (pcie_cap_offset < 0) {
 		DLB2_LOG_ERR("[%s()] failed to find the pcie capability\n",
@@ -516,8 +483,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 		}
 	}
 
-	msix_cap_offset = dlb2_pci_find_capability(pdev,
-						   DLB2_PCI_CAP_ID_MSIX);
+	msix_cap_offset = rte_pci_find_capability(pdev, DLB2_PCI_CAP_ID_MSIX);
 	if (msix_cap_offset >= 0) {
 		off = msix_cap_offset + DLB2_PCI_MSIX_FLAGS;
 		if (rte_pci_read_config(pdev, &cmd, 2, off) == 2) {
diff --git a/drivers/net/bnx2x/bnx2x.c b/drivers/net/bnx2x/bnx2x.c
index 29c16bb207..06f2949885 100644
--- a/drivers/net/bnx2x/bnx2x.c
+++ b/drivers/net/bnx2x/bnx2x.c
@@ -9586,14 +9586,17 @@ static void bnx2x_init_multi_cos(struct bnx2x_softc *sc)
 	}
 }
 
+static uint8_t bnx2x_pci_capabilities[] = {
+	PCIY_EXPRESS,
+	PCIY_PMG,
+	PCIY_MSI,
+	PCIY_MSIX,
+};
+
 static int bnx2x_pci_get_caps(struct bnx2x_softc *sc)
 {
-	struct {
-		uint8_t id;
-		uint8_t next;
-	} pci_cap;
-	uint16_t status;
 	struct bnx2x_pci_cap *cap;
+	unsigned int i;
 
 	cap = sc->pci_caps = rte_zmalloc("caps", sizeof(struct bnx2x_pci_cap),
 					 RTE_CACHE_LINE_SIZE);
@@ -9602,29 +9605,21 @@ static int bnx2x_pci_get_caps(struct bnx2x_softc *sc)
 		return -ENOMEM;
 	}
 
-#ifndef RTE_EXEC_ENV_FREEBSD
-	pci_read(sc, PCI_STATUS, &status, 2);
-	if (!(status & PCI_STATUS_CAP_LIST)) {
-#else
-	pci_read(sc, PCIR_STATUS, &status, 2);
-	if (!(status & PCIM_STATUS_CAPPRESENT)) {
-#endif
+	if (!rte_pci_has_capability_list(sc->pci_dev)) {
 		PMD_DRV_LOG(NOTICE, sc, "PCIe capability reading failed");
 		return -1;
 	}
 
-#ifndef RTE_EXEC_ENV_FREEBSD
-	pci_read(sc, PCI_CAPABILITY_LIST, &pci_cap.next, 1);
-#else
-	pci_read(sc, PCIR_CAP_PTR, &pci_cap.next, 1);
-#endif
-	while (pci_cap.next) {
-		cap->addr = pci_cap.next & ~3;
-		pci_read(sc, pci_cap.next & ~3, &pci_cap, 2);
-		if (pci_cap.id == 0xff)
-			break;
-		cap->id = pci_cap.id;
+	for (i = 0; i < RTE_DIM(bnx2x_pci_capabilities); i++) {
+		off_t pos = rte_pci_find_capability(sc->pci_dev,
+			bnx2x_pci_capabilities[i]);
+
+		if (pos <= 0)
+			continue;
+
+		cap->id = bnx2x_pci_capabilities[i];
 		cap->type = BNX2X_PCI_CAP;
+		cap->addr = pos;
 		cap->next = rte_zmalloc("pci_cap",
 					sizeof(struct bnx2x_pci_cap),
 					RTE_CACHE_LINE_SIZE);
diff --git a/drivers/net/cxgbe/base/adapter.h b/drivers/net/cxgbe/base/adapter.h
index 8f2ffa0eeb..00d7591ea4 100644
--- a/drivers/net/cxgbe/base/adapter.h
+++ b/drivers/net/cxgbe/base/adapter.h
@@ -511,13 +511,8 @@ static inline void t4_write_reg64(struct adapter *adapter, u32 reg_addr,
 	CXGBE_WRITE_REG64(adapter, reg_addr, val);
 }
 
-#define PCI_STATUS              0x06    /* 16 bits */
-#define PCI_STATUS_CAP_LIST     0x10    /* Support Capability List */
-#define PCI_CAPABILITY_LIST     0x34
 /* Offset of first capability list entry */
 #define PCI_CAP_ID_EXP          0x10    /* PCI Express */
-#define PCI_CAP_LIST_ID         0       /* Capability ID */
-#define PCI_CAP_LIST_NEXT       1       /* Next capability in the list */
 #define PCI_EXP_DEVCTL          0x0008  /* Device control */
 #define PCI_EXP_DEVCTL2         40      /* Device Control 2 */
 #define PCI_EXP_DEVCTL_EXT_TAG  0x0100  /* Extended Tag Field Enable */
@@ -620,31 +615,12 @@ static inline void t4_os_pci_read_cfg(struct adapter *adapter, size_t addr,
  */
 static inline int t4_os_find_pci_capability(struct adapter *adapter, int cap)
 {
-	u16 status;
-	int ttl = 48;
-	u8 pos = 0;
-	u8 id = 0;
-
-	t4_os_pci_read_cfg2(adapter, PCI_STATUS, &status);
-	if (!(status & PCI_STATUS_CAP_LIST)) {
+	if (!rte_pci_has_capability_list(adapter->pdev)) {
 		dev_err(adapter, "PCIe capability reading failed\n");
 		return -1;
 	}
 
-	t4_os_pci_read_cfg(adapter, PCI_CAPABILITY_LIST, &pos);
-	while (ttl-- && pos >= 0x40) {
-		pos &= ~3;
-		t4_os_pci_read_cfg(adapter, (pos + PCI_CAP_LIST_ID), &id);
-
-		if (id == 0xff)
-			break;
-
-		if (id == cap)
-			return (int)pos;
-
-		t4_os_pci_read_cfg(adapter, (pos + PCI_CAP_LIST_NEXT), &pos);
-	}
-	return 0;
+	return rte_pci_find_capability(adapter->pdev, cap);
 }
 
 /**
diff --git a/drivers/net/gve/gve_ethdev.c b/drivers/net/gve/gve_ethdev.c
index aa75abe102..c276b9e68e 100644
--- a/drivers/net/gve/gve_ethdev.c
+++ b/drivers/net/gve/gve_ethdev.c
@@ -606,53 +606,17 @@ gve_teardown_device_resources(struct gve_priv *priv)
 	gve_clear_device_resources_ok(priv);
 }
 
-static uint8_t
-pci_dev_find_capability(struct rte_pci_device *pdev, int cap)
-{
-	uint8_t pos, id;
-	uint16_t ent;
-	int loops;
-	int ret;
-
-	ret = rte_pci_read_config(pdev, &pos, sizeof(pos), PCI_CAPABILITY_LIST);
-	if (ret != sizeof(pos))
-		return 0;
-
-	loops = (PCI_CFG_SPACE_SIZE - PCI_STD_HEADER_SIZEOF) / PCI_CAP_SIZEOF;
-
-	while (pos && loops--) {
-		ret = rte_pci_read_config(pdev, &ent, sizeof(ent), pos);
-		if (ret != sizeof(ent))
-			return 0;
-
-		id = ent & 0xff;
-		if (id == 0xff)
-			break;
-
-		if (id == cap)
-			return pos;
-
-		pos = (ent >> 8);
-	}
-
-	return 0;
-}
-
 static int
 pci_dev_msix_vec_count(struct rte_pci_device *pdev)
 {
-	uint8_t msix_cap = pci_dev_find_capability(pdev, PCI_CAP_ID_MSIX);
+	off_t msix_pos = rte_pci_find_capability(pdev, PCI_CAP_ID_MSIX);
 	uint16_t control;
-	int ret;
 
-	if (!msix_cap)
-		return 0;
-
-	ret = rte_pci_read_config(pdev, &control, sizeof(control), msix_cap + PCI_MSIX_FLAGS);
-	if (ret != sizeof(control))
-		return 0;
+	if (msix_pos > 0 && rte_pci_read_config(pdev, &control, sizeof(control),
+			msix_pos + PCI_MSIX_FLAGS) == sizeof(control))
+		return (control & PCI_MSIX_FLAGS_QSIZE) + 1;
 
-	return (control & PCI_MSIX_FLAGS_QSIZE) + 1;
+	return 0;
 }
 
 static int
diff --git a/drivers/net/gve/gve_ethdev.h b/drivers/net/gve/gve_ethdev.h
index c9bcfa553c..8759b1c76e 100644
--- a/drivers/net/gve/gve_ethdev.h
+++ b/drivers/net/gve/gve_ethdev.h
@@ -19,10 +19,6 @@
  * we can't simply include that header here, as there is no such
  * file for non-Linux platform.
  */
-#define PCI_CFG_SPACE_SIZE	256
-#define PCI_CAPABILITY_LIST	0x34	/* Offset of first capability list entry */
-#define PCI_STD_HEADER_SIZEOF	64
-#define PCI_CAP_SIZEOF		4
 #define PCI_CAP_ID_MSIX		0x11	/* MSI-X */
 #define PCI_MSIX_FLAGS		2	/* Message Control */
 #define PCI_MSIX_FLAGS_QSIZE	0x07FF	/* Table size */
diff --git a/drivers/net/hns3/hns3_ethdev_vf.c b/drivers/net/hns3/hns3_ethdev_vf.c
index 7b3c5dc168..b731850b01 100644
--- a/drivers/net/hns3/hns3_ethdev_vf.c
+++ b/drivers/net/hns3/hns3_ethdev_vf.c
@@ -49,80 +49,24 @@ static int hns3vf_remove_mc_mac_addr(struct hns3_hw *hw,
 static int hns3vf_dev_link_update(struct rte_eth_dev *eth_dev,
 				   __rte_unused int wait_to_complete);
 
-/**
- * hns3vf_find_pci_capability - lookup a capability in the PCI capability list
- * @cap: the capability
- *
- * Return the address of the given capability within the PCI capability list.
- */
 static int
-hns3vf_find_pci_capability(const struct rte_pci_device *device, int cap)
+hns3vf_enable_msix(const struct rte_pci_device *device, bool op)
 {
-#define MAX_PCIE_CAPABILITY 48
-	uint16_t status;
-	uint8_t pos;
-	uint8_t id;
-	int ttl;
+	uint16_t control;
+	off_t pos;
 	int ret;
 
-	ret = rte_pci_read_config(device, &status, sizeof(status), PCI_STATUS);
-	if (ret < 0) {
-		PMD_INIT_LOG(ERR, "Failed to read PCI offset 0x%x", PCI_STATUS);
-		return 0;
-	}
-
-	if (!(status & PCI_STATUS_CAP_LIST))
-		return 0;
-
-	ttl = MAX_PCIE_CAPABILITY;
-	ret = rte_pci_read_config(device, &pos, sizeof(pos),
-				  PCI_CAPABILITY_LIST);
-	if (ret < 0) {
-		PMD_INIT_LOG(ERR, "Failed to read PCI offset 0x%x",
-			     PCI_CAPABILITY_LIST);
+	if (!rte_pci_has_capability_list(device)) {
+		PMD_INIT_LOG(ERR, "Failed to read PCI capability list");
 		return 0;
 	}
 
-	while (ttl-- && pos >= PCI_STD_HEADER_SIZEOF) {
-		ret = rte_pci_read_config(device, &id, sizeof(id),
-					  (pos + PCI_CAP_LIST_ID));
-		if (ret < 0) {
-			PMD_INIT_LOG(ERR, "Failed to read PCI offset 0x%x",
-				     (pos + PCI_CAP_LIST_ID));
-			break;
-		}
-
-		if (id == 0xFF)
-			break;
-
-		if (id == cap)
-			return (int)pos;
-
-		ret = rte_pci_read_config(device, &pos, sizeof(pos),
-					  (pos + PCI_CAP_LIST_NEXT));
-		if (ret < 0) {
-			PMD_INIT_LOG(ERR, "Failed to read PCI offset 0x%x",
-				     (pos + PCI_CAP_LIST_NEXT));
-			break;
-		}
-	}
-	return 0;
-}
-
-static int
-hns3vf_enable_msix(const struct rte_pci_device *device, bool op)
-{
-	uint16_t control;
-	int pos;
-	int ret;
-
-	pos = hns3vf_find_pci_capability(device, PCI_CAP_ID_MSIX);
-	if (pos) {
+	pos = rte_pci_find_capability(device, PCI_CAP_ID_MSIX);
+	if (pos > 0) {
 		ret = rte_pci_read_config(device, &control, sizeof(control),
-					  (pos + PCI_MSIX_FLAGS));
+			pos + PCI_MSIX_FLAGS);
 		if (ret < 0) {
-			PMD_INIT_LOG(ERR, "Failed to read PCI offset 0x%x",
-				     (pos + PCI_MSIX_FLAGS));
+			PMD_INIT_LOG(ERR, "Failed to read MSIX flags");
 			return -ENXIO;
 		}
 
@@ -131,10 +75,9 @@ hns3vf_enable_msix(const struct rte_pci_device *device, bool op)
 		else
 			control &= ~PCI_MSIX_FLAGS_ENABLE;
 		ret = rte_pci_write_config(device, &control, sizeof(control),
-					   (pos + PCI_MSIX_FLAGS));
+			pos + PCI_MSIX_FLAGS);
 		if (ret < 0) {
-			PMD_INIT_LOG(ERR, "failed to write PCI offset 0x%x",
-				     (pos + PCI_MSIX_FLAGS));
+			PMD_INIT_LOG(ERR, "failed to write MSIX flags");
 			return -ENXIO;
 		}
 
diff --git a/drivers/net/virtio/virtio_pci.c b/drivers/net/virtio/virtio_pci.c
index 29eb739b04..9fd9db3e03 100644
--- a/drivers/net/virtio/virtio_pci.c
+++ b/drivers/net/virtio/virtio_pci.c
@@ -20,7 +20,6 @@
  * we can't simply include that header here, as there is no such
  * file for non-Linux platform.
  */
-#define PCI_CAPABILITY_LIST	0x34
 #define PCI_CAP_ID_VNDR		0x09
 #define PCI_CAP_ID_MSIX		0x11
 
@@ -38,46 +37,16 @@ struct virtio_pci_internal virtio_pci_internal[RTE_MAX_ETHPORTS];
 static enum virtio_msix_status
 vtpci_msix_detect(struct rte_pci_device *dev)
 {
-	uint8_t pos;
-	int ret;
+	uint16_t flags;
+	off_t pos;
 
-	ret = rte_pci_read_config(dev, &pos, 1, PCI_CAPABILITY_LIST);
-	if (ret != 1) {
-		PMD_INIT_LOG(DEBUG,
-			     "failed to read pci capability list, ret %d", ret);
-		return VIRTIO_MSIX_NONE;
-	}
-
-	while (pos) {
-		uint8_t cap[2];
-
-		ret = rte_pci_read_config(dev, cap, sizeof(cap), pos);
-		if (ret != sizeof(cap)) {
-			PMD_INIT_LOG(DEBUG,
-				     "failed to read pci cap at pos: %x ret %d",
-				     pos, ret);
-			break;
-		}
-
-		if (cap[0] == PCI_CAP_ID_MSIX) {
-			uint16_t flags;
-
-			ret = rte_pci_read_config(dev, &flags, sizeof(flags),
-					pos + sizeof(cap));
-			if (ret != sizeof(flags)) {
-				PMD_INIT_LOG(DEBUG,
-					     "failed to read pci cap at pos:"
-					     " %x ret %d", pos + 2, ret);
-				break;
-			}
-
-			if (flags & PCI_MSIX_ENABLE)
-				return VIRTIO_MSIX_ENABLED;
-			else
-				return VIRTIO_MSIX_DISABLED;
-		}
-
-		pos = cap[1];
+	pos = rte_pci_find_capability(dev, PCI_CAP_ID_MSIX);
+	if (pos > 0 && rte_pci_read_config(dev, &flags, sizeof(flags),
+			pos + 2) == sizeof(flags)) {
+		if (flags & PCI_MSIX_ENABLE)
+			return VIRTIO_MSIX_ENABLED;
+		else
+			return VIRTIO_MSIX_DISABLED;
 	}
 
 	return VIRTIO_MSIX_NONE;
@@ -623,8 +592,8 @@ static int
 virtio_read_caps(struct rte_pci_device *pci_dev, struct virtio_hw *hw)
 {
 	struct virtio_pci_dev *dev = virtio_pci_get_dev(hw);
-	uint8_t pos;
 	struct virtio_pci_cap cap;
+	off_t pos;
 	int ret;
 
 	if (rte_pci_map_device(pci_dev)) {
@@ -632,72 +601,25 @@ virtio_read_caps(struct rte_pci_device *pci_dev, struct virtio_hw *hw)
 		return -1;
 	}
 
-	ret = rte_pci_read_config(pci_dev, &pos, 1, PCI_CAPABILITY_LIST);
-	if (ret != 1) {
-		PMD_INIT_LOG(DEBUG,
-			     "failed to read pci capability list, ret %d", ret);
-		return -1;
-	}
-
-	while (pos) {
-		ret = rte_pci_read_config(pci_dev, &cap, 2, pos);
-		if (ret != 2) {
-			PMD_INIT_LOG(DEBUG,
-				     "failed to read pci cap at pos: %x ret %d",
-				     pos, ret);
-			break;
-		}
-
-		if (cap.cap_vndr == PCI_CAP_ID_MSIX) {
-			/* Transitional devices would also have this capability,
-			 * that's why we also check if msix is enabled.
-			 * 1st byte is cap ID; 2nd byte is the position of next
-			 * cap; next two bytes are the flags.
-			 */
-			uint16_t flags;
-
-			ret = rte_pci_read_config(pci_dev, &flags, sizeof(flags),
-					pos + 2);
-			if (ret != sizeof(flags)) {
-				PMD_INIT_LOG(DEBUG,
-					     "failed to read pci cap at pos:"
-					     " %x ret %d", pos + 2, ret);
-				break;
-			}
-
-			if (flags & PCI_MSIX_ENABLE)
-				dev->msix_status = VIRTIO_MSIX_ENABLED;
-			else
-				dev->msix_status = VIRTIO_MSIX_DISABLED;
-		}
-
-		if (cap.cap_vndr != PCI_CAP_ID_VNDR) {
-			PMD_INIT_LOG(DEBUG,
-				"[%2x] skipping non VNDR cap id: %02x",
-				pos, cap.cap_vndr);
-			goto next;
-		}
-
-		ret = rte_pci_read_config(pci_dev, &cap, sizeof(cap), pos);
-		if (ret != sizeof(cap)) {
-			PMD_INIT_LOG(DEBUG,
-				     "failed to read pci cap at pos: %x ret %d",
-				     pos, ret);
-			break;
-		}
+	/*
+	 * Transitional devices would also have this capability,
+	 * that's why we also check if msix is enabled.
+	 */
+	dev->msix_status = vtpci_msix_detect(pci_dev);
 
+	pos = rte_pci_find_capability(pci_dev, PCI_CAP_ID_VNDR);
+	if (pos > 0 && rte_pci_read_config(pci_dev, &cap, sizeof(cap), pos) == sizeof(cap)) {
 		PMD_INIT_LOG(DEBUG,
 			"[%2x] cfg type: %u, bar: %u, offset: %04x, len: %u",
-			pos, cap.cfg_type, cap.bar, cap.offset, cap.length);
+			(unsigned int)pos, cap.cfg_type, cap.bar, cap.offset, cap.length);
 
 		switch (cap.cfg_type) {
 		case VIRTIO_PCI_CAP_COMMON_CFG:
 			dev->common_cfg = get_cfg_addr(pci_dev, &cap);
 			break;
 		case VIRTIO_PCI_CAP_NOTIFY_CFG:
-			ret = rte_pci_read_config(pci_dev,
-					&dev->notify_off_multiplier,
-					4, pos + sizeof(cap));
+			ret = rte_pci_read_config(pci_dev, &dev->notify_off_multiplier,
+				4, pos + sizeof(cap));
 			if (ret != 4)
 				PMD_INIT_LOG(DEBUG,
 					"failed to read notify_off_multiplier, ret %d",
@@ -712,9 +634,6 @@ virtio_read_caps(struct rte_pci_device *pci_dev, struct virtio_hw *hw)
 			dev->isr = get_cfg_addr(pci_dev, &cap);
 			break;
 		}
-
-next:
-		pos = cap.cap_next;
 	}
 
 	if (dev->common_cfg == NULL || dev->notify_base == NULL ||
diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
index aab761b918..49fd5b1d02 100644
--- a/lib/pci/rte_pci.h
+++ b/lib/pci/rte_pci.h
@@ -28,13 +28,24 @@ extern "C" {
 #define RTE_PCI_CFG_SPACE_SIZE		256
 #define RTE_PCI_CFG_SPACE_EXP_SIZE	4096
 
+#define RTE_PCI_STD_HEADER_SIZEOF	64
+
+/* Standard register offsets in the PCI configuration space */
 #define RTE_PCI_VENDOR_ID	0x00	/* 16 bits */
 #define RTE_PCI_DEVICE_ID	0x02	/* 16 bits */
 #define RTE_PCI_COMMAND		0x04	/* 16 bits */
+#define RTE_PCI_STATUS		0x06	/* 16 bits */
+#define RTE_PCI_CAPABILITY_LIST	0x34	/* 32 bits */
 
 /* PCI Command Register */
 #define RTE_PCI_COMMAND_MASTER	0x4	/* Bus Master Enable */
 
+/* PCI Status Register (RTE_PCI_STATUS) */
+#define RTE_PCI_STATUS_CAP_LIST		0x10	/* Support Capability List */
+
+/* Capability registers (RTE_PCI_CAPABILITY_LIST) */
+#define RTE_PCI_CAP_SIZEOF		4
+
 /* PCI Express capability registers */
 #define RTE_PCI_EXP_DEVCTL	8	/* Device Control */
 
-- 
2.41.0


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

* [PATCH v2 05/15] pci: define some capability constants
  2023-08-21 11:35 ` [PATCH v2 00/15] " David Marchand
                     ` (3 preceding siblings ...)
  2023-08-21 11:35   ` [PATCH v2 04/15] bus/pci: find PCI capability David Marchand
@ 2023-08-21 11:35   ` David Marchand
  2023-09-07 13:15     ` Xia, Chenbo
  2023-08-21 11:35   ` [PATCH v2 06/15] pci: define some MSIX constants David Marchand
                     ` (10 subsequent siblings)
  15 siblings, 1 reply; 98+ messages in thread
From: David Marchand @ 2023-08-21 11:35 UTC (permalink / raw)
  To: dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, bruce.richardson,
	Anatoly Burakov, Jay Zhou, Timothy McDaniel, Julien Aube,
	Rahul Lakkireddy, Junfeng Guo, Jeroen de Borst, Rushil Gupta,
	Joshua Washington, Dongdong Liu, Yisen Zhuang, Maxime Coquelin,
	Xiao Wang, Gaetan Rivet

Define some PCI capability constants and use them in existing drivers.

Signed-off-by: David Marchand <david.marchand@redhat.com>
Acked-by: Bruce Richardson <bruce.richardson@intel.com>
---
 drivers/bus/pci/linux/pci_vfio.c    |  2 +-
 drivers/crypto/virtio/virtio_pci.c  | 12 ++----------
 drivers/event/dlb2/pf/dlb2_main.c   |  6 ++----
 drivers/net/bnx2x/bnx2x.c           | 16 ++++++++--------
 drivers/net/bnx2x/bnx2x.h           |  4 ----
 drivers/net/cxgbe/base/adapter.h    |  3 +--
 drivers/net/gve/gve_ethdev.c        |  2 +-
 drivers/net/gve/gve_ethdev.h        |  2 +-
 drivers/net/hns3/hns3_ethdev_vf.c   |  2 +-
 drivers/net/virtio/virtio_pci.c     | 12 ++----------
 drivers/vdpa/ifc/base/ifcvf_osdep.h |  4 +++-
 lib/pci/rte_pci.h                   |  5 +++++
 12 files changed, 27 insertions(+), 43 deletions(-)

diff --git a/drivers/bus/pci/linux/pci_vfio.c b/drivers/bus/pci/linux/pci_vfio.c
index 614ed5d696..bfedbc1bed 100644
--- a/drivers/bus/pci/linux/pci_vfio.c
+++ b/drivers/bus/pci/linux/pci_vfio.c
@@ -112,7 +112,7 @@ pci_vfio_get_msix_bar(const struct rte_pci_device *dev,
 {
 	off_t cap_offset;
 
-	cap_offset = rte_pci_find_capability(dev, PCI_CAP_ID_MSIX);
+	cap_offset = rte_pci_find_capability(dev, RTE_PCI_CAP_ID_MSIX);
 	if (cap_offset < 0)
 		return -1;
 
diff --git a/drivers/crypto/virtio/virtio_pci.c b/drivers/crypto/virtio/virtio_pci.c
index abc52b4701..9e340f2b0d 100644
--- a/drivers/crypto/virtio/virtio_pci.c
+++ b/drivers/crypto/virtio/virtio_pci.c
@@ -14,14 +14,6 @@
 #include "virtio_pci.h"
 #include "virtqueue.h"
 
-/*
- * Following macros are derived from linux/pci_regs.h, however,
- * we can't simply include that header here, as there is no such
- * file for non-Linux platform.
- */
-#define PCI_CAP_ID_VNDR		0x09
-#define PCI_CAP_ID_MSIX		0x11
-
 /*
  * The remaining space is defined by each driver as the per-driver
  * configuration space.
@@ -356,7 +348,7 @@ virtio_read_caps(struct rte_pci_device *dev, struct virtio_crypto_hw *hw)
 	 * Transitional devices would also have this capability,
 	 * that's why we also check if msix is enabled.
 	 */
-	pos = rte_pci_find_capability(dev, PCI_CAP_ID_MSIX);
+	pos = rte_pci_find_capability(dev, RTE_PCI_CAP_ID_MSIX);
 	if (pos > 0 && rte_pci_read_config(dev, &flags, sizeof(flags),
 			pos + 2) == sizeof(flags)) {
 		if (flags & PCI_MSIX_ENABLE)
@@ -367,7 +359,7 @@ virtio_read_caps(struct rte_pci_device *dev, struct virtio_crypto_hw *hw)
 		hw->use_msix = VIRTIO_MSIX_NONE;
 	}
 
-	pos = rte_pci_find_capability(dev, PCI_CAP_ID_VNDR);
+	pos = rte_pci_find_capability(dev, RTE_PCI_CAP_ID_VNDR);
 	if (pos > 0 && rte_pci_read_config(dev, &cap, sizeof(cap), pos) == sizeof(cap)) {
 		VIRTIO_CRYPTO_INIT_LOG_DBG(
 			"[%2x] cfg type: %u, bar: %u, offset: %04x, len: %u",
diff --git a/drivers/event/dlb2/pf/dlb2_main.c b/drivers/event/dlb2/pf/dlb2_main.c
index 40e5cb594f..1a229baee0 100644
--- a/drivers/event/dlb2/pf/dlb2_main.c
+++ b/drivers/event/dlb2/pf/dlb2_main.c
@@ -38,8 +38,6 @@
 #define DLB2_PCI_EXP_DEVSTA_TRPND 0x20
 #define DLB2_PCI_EXP_DEVCTL_BCR_FLR 0x8000
 
-#define DLB2_PCI_CAP_ID_EXP       0x10
-#define DLB2_PCI_CAP_ID_MSIX      0x11
 #define DLB2_PCI_EXT_CAP_ID_PRI   0x13
 #define DLB2_PCI_EXT_CAP_ID_ACS   0xD
 
@@ -244,7 +242,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 	}
 
-	pcie_cap_offset = rte_pci_find_capability(pdev, DLB2_PCI_CAP_ID_EXP);
+	pcie_cap_offset = rte_pci_find_capability(pdev, RTE_PCI_CAP_ID_EXP);
 
 	if (pcie_cap_offset < 0) {
 		DLB2_LOG_ERR("[%s()] failed to find the pcie capability\n",
@@ -483,7 +481,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 		}
 	}
 
-	msix_cap_offset = rte_pci_find_capability(pdev, DLB2_PCI_CAP_ID_MSIX);
+	msix_cap_offset = rte_pci_find_capability(pdev, RTE_PCI_CAP_ID_MSIX);
 	if (msix_cap_offset >= 0) {
 		off = msix_cap_offset + DLB2_PCI_MSIX_FLAGS;
 		if (rte_pci_read_config(pdev, &cmd, 2, off) == 2) {
diff --git a/drivers/net/bnx2x/bnx2x.c b/drivers/net/bnx2x/bnx2x.c
index 06f2949885..8a97de8806 100644
--- a/drivers/net/bnx2x/bnx2x.c
+++ b/drivers/net/bnx2x/bnx2x.c
@@ -7613,7 +7613,7 @@ static uint32_t bnx2x_pcie_capability_read(struct bnx2x_softc *sc, int reg)
 	struct bnx2x_pci_cap *caps;
 
 	/* ensure PCIe capability is enabled */
-	caps = pci_find_cap(sc, PCIY_EXPRESS, BNX2X_PCI_CAP);
+	caps = pci_find_cap(sc, RTE_PCI_CAP_ID_EXP, BNX2X_PCI_CAP);
 	if (NULL != caps) {
 		PMD_DRV_LOG(DEBUG, sc, "Found PCIe capability: "
 			    "id=0x%04X type=0x%04X addr=0x%08X",
@@ -7647,7 +7647,7 @@ static void bnx2x_probe_pci_caps(struct bnx2x_softc *sc)
 	int reg = 0;
 
 	/* check if PCI Power Management is enabled */
-	caps = pci_find_cap(sc, PCIY_PMG, BNX2X_PCI_CAP);
+	caps = pci_find_cap(sc, RTE_PCI_CAP_ID_PM, BNX2X_PCI_CAP);
 	if (NULL != caps) {
 		PMD_DRV_LOG(DEBUG, sc, "Found PM capability: "
 			    "id=0x%04X type=0x%04X addr=0x%08X",
@@ -7669,7 +7669,7 @@ static void bnx2x_probe_pci_caps(struct bnx2x_softc *sc)
 	sc->devinfo.pcie_cap_flags |= BNX2X_PCIE_CAPABLE_FLAG;
 
 	/* check if MSI capability is enabled */
-	caps = pci_find_cap(sc, PCIY_MSI, BNX2X_PCI_CAP);
+	caps = pci_find_cap(sc, RTE_PCI_CAP_ID_MSI, BNX2X_PCI_CAP);
 	if (NULL != caps) {
 		PMD_DRV_LOG(DEBUG, sc, "Found MSI capability at 0x%04x", reg);
 
@@ -7678,7 +7678,7 @@ static void bnx2x_probe_pci_caps(struct bnx2x_softc *sc)
 	}
 
 	/* check if MSI-X capability is enabled */
-	caps = pci_find_cap(sc, PCIY_MSIX, BNX2X_PCI_CAP);
+	caps = pci_find_cap(sc, RTE_PCI_CAP_ID_MSIX, BNX2X_PCI_CAP);
 	if (NULL != caps) {
 		PMD_DRV_LOG(DEBUG, sc, "Found MSI-X capability at 0x%04x", reg);
 
@@ -9587,10 +9587,10 @@ static void bnx2x_init_multi_cos(struct bnx2x_softc *sc)
 }
 
 static uint8_t bnx2x_pci_capabilities[] = {
-	PCIY_EXPRESS,
-	PCIY_PMG,
-	PCIY_MSI,
-	PCIY_MSIX,
+	RTE_PCI_CAP_ID_EXP,
+	RTE_PCI_CAP_ID_PM,
+	RTE_PCI_CAP_ID_MSI,
+	RTE_PCI_CAP_ID_MSIX,
 };
 
 static int bnx2x_pci_get_caps(struct bnx2x_softc *sc)
diff --git a/drivers/net/bnx2x/bnx2x.h b/drivers/net/bnx2x/bnx2x.h
index 89414ac88a..07ef0567c2 100644
--- a/drivers/net/bnx2x/bnx2x.h
+++ b/drivers/net/bnx2x/bnx2x.h
@@ -33,10 +33,6 @@
 #ifndef RTE_EXEC_ENV_FREEBSD
 #include <linux/pci_regs.h>
 
-#define PCIY_PMG                       PCI_CAP_ID_PM
-#define PCIY_MSI                       PCI_CAP_ID_MSI
-#define PCIY_EXPRESS                   PCI_CAP_ID_EXP
-#define PCIY_MSIX                      PCI_CAP_ID_MSIX
 #define PCIR_EXPRESS_DEVICE_STA        PCI_EXP_TYPE_RC_EC
 #define PCIM_EXP_STA_TRANSACTION_PND   PCI_EXP_DEVSTA_TRPND
 #define PCIR_EXPRESS_LINK_STA          PCI_EXP_LNKSTA
diff --git a/drivers/net/cxgbe/base/adapter.h b/drivers/net/cxgbe/base/adapter.h
index 00d7591ea4..7bee5cf3a8 100644
--- a/drivers/net/cxgbe/base/adapter.h
+++ b/drivers/net/cxgbe/base/adapter.h
@@ -511,8 +511,7 @@ static inline void t4_write_reg64(struct adapter *adapter, u32 reg_addr,
 	CXGBE_WRITE_REG64(adapter, reg_addr, val);
 }
 
-/* Offset of first capability list entry */
-#define PCI_CAP_ID_EXP          0x10    /* PCI Express */
+#define PCI_CAP_ID_EXP          RTE_PCI_CAP_ID_EXP
 #define PCI_EXP_DEVCTL          0x0008  /* Device control */
 #define PCI_EXP_DEVCTL2         40      /* Device Control 2 */
 #define PCI_EXP_DEVCTL_EXT_TAG  0x0100  /* Extended Tag Field Enable */
diff --git a/drivers/net/gve/gve_ethdev.c b/drivers/net/gve/gve_ethdev.c
index c276b9e68e..9ea5dbaeea 100644
--- a/drivers/net/gve/gve_ethdev.c
+++ b/drivers/net/gve/gve_ethdev.c
@@ -609,7 +609,7 @@ gve_teardown_device_resources(struct gve_priv *priv)
 static int
 pci_dev_msix_vec_count(struct rte_pci_device *pdev)
 {
-	off_t msix_pos = rte_pci_find_capability(pdev, PCI_CAP_ID_MSIX);
+	off_t msix_pos = rte_pci_find_capability(pdev, RTE_PCI_CAP_ID_MSIX);
 	uint16_t control;
 
 	if (msix_pos > 0 && rte_pci_read_config(pdev, &control, sizeof(control),
diff --git a/drivers/net/gve/gve_ethdev.h b/drivers/net/gve/gve_ethdev.h
index 8759b1c76e..d604a75b7f 100644
--- a/drivers/net/gve/gve_ethdev.h
+++ b/drivers/net/gve/gve_ethdev.h
@@ -8,6 +8,7 @@
 #include <ethdev_driver.h>
 #include <ethdev_pci.h>
 #include <rte_ether.h>
+#include <rte_pci.h>
 
 #include "base/gve.h"
 
@@ -19,7 +20,6 @@
  * we can't simply include that header here, as there is no such
  * file for non-Linux platform.
  */
-#define PCI_CAP_ID_MSIX		0x11	/* MSI-X */
 #define PCI_MSIX_FLAGS		2	/* Message Control */
 #define PCI_MSIX_FLAGS_QSIZE	0x07FF	/* Table size */
 
diff --git a/drivers/net/hns3/hns3_ethdev_vf.c b/drivers/net/hns3/hns3_ethdev_vf.c
index b731850b01..eab5c55f5e 100644
--- a/drivers/net/hns3/hns3_ethdev_vf.c
+++ b/drivers/net/hns3/hns3_ethdev_vf.c
@@ -61,7 +61,7 @@ hns3vf_enable_msix(const struct rte_pci_device *device, bool op)
 		return 0;
 	}
 
-	pos = rte_pci_find_capability(device, PCI_CAP_ID_MSIX);
+	pos = rte_pci_find_capability(device, RTE_PCI_CAP_ID_MSIX);
 	if (pos > 0) {
 		ret = rte_pci_read_config(device, &control, sizeof(control),
 			pos + PCI_MSIX_FLAGS);
diff --git a/drivers/net/virtio/virtio_pci.c b/drivers/net/virtio/virtio_pci.c
index 9fd9db3e03..81d5dd0a4a 100644
--- a/drivers/net/virtio/virtio_pci.c
+++ b/drivers/net/virtio/virtio_pci.c
@@ -15,14 +15,6 @@
 #include "virtio_logs.h"
 #include "virtqueue.h"
 
-/*
- * Following macros are derived from linux/pci_regs.h, however,
- * we can't simply include that header here, as there is no such
- * file for non-Linux platform.
- */
-#define PCI_CAP_ID_VNDR		0x09
-#define PCI_CAP_ID_MSIX		0x11
-
 /*
  * The remaining space is defined by each driver as the per-driver
  * configuration space.
@@ -40,7 +32,7 @@ vtpci_msix_detect(struct rte_pci_device *dev)
 	uint16_t flags;
 	off_t pos;
 
-	pos = rte_pci_find_capability(dev, PCI_CAP_ID_MSIX);
+	pos = rte_pci_find_capability(dev, RTE_PCI_CAP_ID_MSIX);
 	if (pos > 0 && rte_pci_read_config(dev, &flags, sizeof(flags),
 			pos + 2) == sizeof(flags)) {
 		if (flags & PCI_MSIX_ENABLE)
@@ -607,7 +599,7 @@ virtio_read_caps(struct rte_pci_device *pci_dev, struct virtio_hw *hw)
 	 */
 	dev->msix_status = vtpci_msix_detect(pci_dev);
 
-	pos = rte_pci_find_capability(pci_dev, PCI_CAP_ID_VNDR);
+	pos = rte_pci_find_capability(pci_dev, RTE_PCI_CAP_ID_VNDR);
 	if (pos > 0 && rte_pci_read_config(pci_dev, &cap, sizeof(cap), pos) == sizeof(cap)) {
 		PMD_INIT_LOG(DEBUG,
 			"[%2x] cfg type: %u, bar: %u, offset: %04x, len: %u",
diff --git a/drivers/vdpa/ifc/base/ifcvf_osdep.h b/drivers/vdpa/ifc/base/ifcvf_osdep.h
index 6444d7f72c..dd2ff08f77 100644
--- a/drivers/vdpa/ifc/base/ifcvf_osdep.h
+++ b/drivers/vdpa/ifc/base/ifcvf_osdep.h
@@ -6,7 +6,6 @@
 #define _IFCVF_OSDEP_H_
 
 #include <stdint.h>
-#include <linux/pci_regs.h>
 
 #include <rte_cycles.h>
 #include <rte_pci.h>
@@ -35,6 +34,9 @@ typedef struct rte_pci_device PCI_DEV;
 #define PCI_READ_CONFIG_DWORD(dev, val, where) \
 	rte_pci_read_config(dev, val, 4, where)
 
+#define PCI_CAPABILITY_LIST RTE_PCI_CAPABILITY_LIST
+#define PCI_CAP_ID_VNDR RTE_PCI_CAP_ID_VNDR
+
 typedef uint8_t    u8;
 typedef int8_t     s8;
 typedef uint16_t   u16;
diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
index 49fd5b1d02..5a04a5a4b5 100644
--- a/lib/pci/rte_pci.h
+++ b/lib/pci/rte_pci.h
@@ -44,6 +44,11 @@ extern "C" {
 #define RTE_PCI_STATUS_CAP_LIST		0x10	/* Support Capability List */
 
 /* Capability registers (RTE_PCI_CAPABILITY_LIST) */
+#define RTE_PCI_CAP_ID_PM		0x01	/* Power Management */
+#define RTE_PCI_CAP_ID_MSI		0x05	/* Message Signalled Interrupts */
+#define RTE_PCI_CAP_ID_VNDR		0x09	/* Vendor-Specific */
+#define RTE_PCI_CAP_ID_EXP		0x10	/* PCI Express */
+#define RTE_PCI_CAP_ID_MSIX		0x11	/* MSI-X */
 #define RTE_PCI_CAP_SIZEOF		4
 
 /* PCI Express capability registers */
-- 
2.41.0


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

* [PATCH v2 06/15] pci: define some MSIX constants
  2023-08-21 11:35 ` [PATCH v2 00/15] " David Marchand
                     ` (4 preceding siblings ...)
  2023-08-21 11:35   ` [PATCH v2 05/15] pci: define some capability constants David Marchand
@ 2023-08-21 11:35   ` David Marchand
  2023-09-07 13:15     ` Xia, Chenbo
  2023-08-21 11:35   ` [PATCH v2 07/15] pci: define some command constants David Marchand
                     ` (9 subsequent siblings)
  15 siblings, 1 reply; 98+ messages in thread
From: David Marchand @ 2023-08-21 11:35 UTC (permalink / raw)
  To: dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, bruce.richardson,
	Anatoly Burakov, Jay Zhou, Timothy McDaniel, Julien Aube,
	Junfeng Guo, Jeroen de Borst, Rushil Gupta, Joshua Washington,
	Dongdong Liu, Yisen Zhuang, Maxime Coquelin, Gaetan Rivet

Define some PCI MSIX constants and use them in existing drivers.

Signed-off-by: David Marchand <david.marchand@redhat.com>
Acked-by: Bruce Richardson <bruce.richardson@intel.com>
---
 drivers/bus/pci/linux/pci_init.h   | 18 ------------------
 drivers/bus/pci/linux/pci_vfio.c   |  7 ++++---
 drivers/crypto/virtio/virtio_pci.c |  6 ++----
 drivers/event/dlb2/pf/dlb2_main.c  | 13 +++++--------
 drivers/net/bnx2x/bnx2x.c          |  4 ++--
 drivers/net/bnx2x/bnx2x.h          |  2 --
 drivers/net/gve/gve_ethdev.c       |  4 ++--
 drivers/net/gve/gve_ethdev.h       |  8 --------
 drivers/net/hns3/hns3_ethdev_vf.c  |  9 ++++-----
 drivers/net/virtio/virtio_pci.c    |  6 ++----
 lib/pci/rte_pci.h                  | 10 ++++++++++
 11 files changed, 31 insertions(+), 56 deletions(-)

diff --git a/drivers/bus/pci/linux/pci_init.h b/drivers/bus/pci/linux/pci_init.h
index d842809ccd..a4d37c0d0a 100644
--- a/drivers/bus/pci/linux/pci_init.h
+++ b/drivers/bus/pci/linux/pci_init.h
@@ -52,24 +52,6 @@ int pci_uio_ioport_unmap(struct rte_pci_ioport *p);
 
 #ifdef VFIO_PRESENT
 
-#ifdef PCI_MSIX_TABLE_BIR
-#define RTE_PCI_MSIX_TABLE_BIR    PCI_MSIX_TABLE_BIR
-#else
-#define RTE_PCI_MSIX_TABLE_BIR    0x7
-#endif
-
-#ifdef PCI_MSIX_TABLE_OFFSET
-#define RTE_PCI_MSIX_TABLE_OFFSET PCI_MSIX_TABLE_OFFSET
-#else
-#define RTE_PCI_MSIX_TABLE_OFFSET 0xfffffff8
-#endif
-
-#ifdef PCI_MSIX_FLAGS_QSIZE
-#define RTE_PCI_MSIX_FLAGS_QSIZE  PCI_MSIX_FLAGS_QSIZE
-#else
-#define RTE_PCI_MSIX_FLAGS_QSIZE  0x07ff
-#endif
-
 /* access config space */
 int pci_vfio_read_config(const struct rte_pci_device *dev,
 			 void *buf, size_t len, off_t offs);
diff --git a/drivers/bus/pci/linux/pci_vfio.c b/drivers/bus/pci/linux/pci_vfio.c
index bfedbc1bed..7881b7a946 100644
--- a/drivers/bus/pci/linux/pci_vfio.c
+++ b/drivers/bus/pci/linux/pci_vfio.c
@@ -120,14 +120,15 @@ pci_vfio_get_msix_bar(const struct rte_pci_device *dev,
 		uint16_t flags;
 		uint32_t reg;
 
-		/* table offset resides in the next 4 bytes */
-		if (rte_pci_read_config(dev, &reg, sizeof(reg), cap_offset + 4) < 0) {
+		if (rte_pci_read_config(dev, &reg, sizeof(reg), cap_offset +
+				RTE_PCI_MSIX_TABLE) < 0) {
 			RTE_LOG(ERR, EAL,
 				"Cannot read MSIX table from PCI config space!\n");
 			return -1;
 		}
 
-		if (rte_pci_read_config(dev, &flags, sizeof(flags), cap_offset + 2) < 0) {
+		if (rte_pci_read_config(dev, &flags, sizeof(flags), cap_offset +
+				RTE_PCI_MSIX_FLAGS) < 0) {
 			RTE_LOG(ERR, EAL,
 				"Cannot read MSIX flags from PCI config space!\n");
 			return -1;
diff --git a/drivers/crypto/virtio/virtio_pci.c b/drivers/crypto/virtio/virtio_pci.c
index 9e340f2b0d..c9fb1087a9 100644
--- a/drivers/crypto/virtio/virtio_pci.c
+++ b/drivers/crypto/virtio/virtio_pci.c
@@ -329,8 +329,6 @@ get_cfg_addr(struct rte_pci_device *dev, struct virtio_pci_cap *cap)
 	return base + offset;
 }
 
-#define PCI_MSIX_ENABLE 0x8000
-
 static int
 virtio_read_caps(struct rte_pci_device *dev, struct virtio_crypto_hw *hw)
 {
@@ -350,8 +348,8 @@ virtio_read_caps(struct rte_pci_device *dev, struct virtio_crypto_hw *hw)
 	 */
 	pos = rte_pci_find_capability(dev, RTE_PCI_CAP_ID_MSIX);
 	if (pos > 0 && rte_pci_read_config(dev, &flags, sizeof(flags),
-			pos + 2) == sizeof(flags)) {
-		if (flags & PCI_MSIX_ENABLE)
+			pos + RTE_PCI_MSIX_FLAGS) == sizeof(flags)) {
+		if (flags & RTE_PCI_MSIX_FLAGS_ENABLE)
 			hw->use_msix = VIRTIO_MSIX_ENABLED;
 		else
 			hw->use_msix = VIRTIO_MSIX_DISABLED;
diff --git a/drivers/event/dlb2/pf/dlb2_main.c b/drivers/event/dlb2/pf/dlb2_main.c
index 1a229baee0..c6606a9bee 100644
--- a/drivers/event/dlb2/pf/dlb2_main.c
+++ b/drivers/event/dlb2/pf/dlb2_main.c
@@ -44,9 +44,6 @@
 #define DLB2_PCI_PRI_CTRL_ENABLE         0x1
 #define DLB2_PCI_PRI_ALLOC_REQ           0xC
 #define DLB2_PCI_PRI_CTRL                0x4
-#define DLB2_PCI_MSIX_FLAGS              0x2
-#define DLB2_PCI_MSIX_FLAGS_ENABLE       0x8000
-#define DLB2_PCI_MSIX_FLAGS_MASKALL      0x4000
 #define DLB2_PCI_ERR_ROOT_STATUS         0x30
 #define DLB2_PCI_ERR_COR_STATUS          0x10
 #define DLB2_PCI_ERR_UNCOR_STATUS        0x4
@@ -483,10 +480,10 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 
 	msix_cap_offset = rte_pci_find_capability(pdev, RTE_PCI_CAP_ID_MSIX);
 	if (msix_cap_offset >= 0) {
-		off = msix_cap_offset + DLB2_PCI_MSIX_FLAGS;
+		off = msix_cap_offset + RTE_PCI_MSIX_FLAGS;
 		if (rte_pci_read_config(pdev, &cmd, 2, off) == 2) {
-			cmd |= DLB2_PCI_MSIX_FLAGS_ENABLE;
-			cmd |= DLB2_PCI_MSIX_FLAGS_MASKALL;
+			cmd |= RTE_PCI_MSIX_FLAGS_ENABLE;
+			cmd |= RTE_PCI_MSIX_FLAGS_MASKALL;
 			if (rte_pci_write_config(pdev, &cmd, 2, off) != 2) {
 				DLB2_LOG_ERR("[%s()] failed to write msix flags\n",
 				       __func__);
@@ -494,9 +491,9 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			}
 		}
 
-		off = msix_cap_offset + DLB2_PCI_MSIX_FLAGS;
+		off = msix_cap_offset + RTE_PCI_MSIX_FLAGS;
 		if (rte_pci_read_config(pdev, &cmd, 2, off) == 2) {
-			cmd &= ~DLB2_PCI_MSIX_FLAGS_MASKALL;
+			cmd &= ~RTE_PCI_MSIX_FLAGS_MASKALL;
 			if (rte_pci_write_config(pdev, &cmd, 2, off) != 2) {
 				DLB2_LOG_ERR("[%s()] failed to write msix flags\n",
 				       __func__);
diff --git a/drivers/net/bnx2x/bnx2x.c b/drivers/net/bnx2x/bnx2x.c
index 8a97de8806..e3f14400cc 100644
--- a/drivers/net/bnx2x/bnx2x.c
+++ b/drivers/net/bnx2x/bnx2x.c
@@ -9766,9 +9766,9 @@ int bnx2x_attach(struct bnx2x_softc *sc)
 	if (sc->devinfo.pcie_msix_cap_reg != 0) {
 		uint32_t val;
 		pci_read(sc,
-			 (sc->devinfo.pcie_msix_cap_reg + PCIR_MSIX_CTRL), &val,
+			 (sc->devinfo.pcie_msix_cap_reg + RTE_PCI_MSIX_FLAGS), &val,
 			 2);
-		sc->igu_sb_cnt = (val & PCIM_MSIXCTRL_TABLE_SIZE) + 1;
+		sc->igu_sb_cnt = (val & RTE_PCI_MSIX_FLAGS_QSIZE) + 1;
 	} else {
 		sc->igu_sb_cnt = 1;
 	}
diff --git a/drivers/net/bnx2x/bnx2x.h b/drivers/net/bnx2x/bnx2x.h
index 07ef0567c2..60af75d336 100644
--- a/drivers/net/bnx2x/bnx2x.h
+++ b/drivers/net/bnx2x/bnx2x.h
@@ -46,8 +46,6 @@
 #define PCIM_PSTAT_PME                 PCI_PM_CTRL_PME_STATUS
 #define PCIM_PSTAT_D3                  0x3
 #define PCIM_PSTAT_PMEENABLE           PCI_PM_CTRL_PME_ENABLE
-#define PCIR_MSIX_CTRL                 PCI_MSIX_FLAGS
-#define PCIM_MSIXCTRL_TABLE_SIZE       PCI_MSIX_FLAGS_QSIZE
 #else
 #include <dev/pci/pcireg.h>
 #endif
diff --git a/drivers/net/gve/gve_ethdev.c b/drivers/net/gve/gve_ethdev.c
index 9ea5dbaeea..9b25f3036b 100644
--- a/drivers/net/gve/gve_ethdev.c
+++ b/drivers/net/gve/gve_ethdev.c
@@ -613,8 +613,8 @@ pci_dev_msix_vec_count(struct rte_pci_device *pdev)
 	uint16_t control;
 
 	if (msix_pos > 0 && rte_pci_read_config(pdev, &control, sizeof(control),
-			msix_pos + PCI_MSIX_FLAGS) == sizeof(control))
-		return (control & PCI_MSIX_FLAGS_QSIZE) + 1;
+			msix_pos + RTE_PCI_MSIX_FLAGS) == sizeof(control))
+		return (control & RTE_PCI_MSIX_FLAGS_QSIZE) + 1;
 
 	return 0;
 }
diff --git a/drivers/net/gve/gve_ethdev.h b/drivers/net/gve/gve_ethdev.h
index d604a75b7f..c47b4d454d 100644
--- a/drivers/net/gve/gve_ethdev.h
+++ b/drivers/net/gve/gve_ethdev.h
@@ -15,14 +15,6 @@
 /* TODO: this is a workaround to ensure that Tx complq is enough */
 #define DQO_TX_MULTIPLIER 4
 
-/*
- * Following macros are derived from linux/pci_regs.h, however,
- * we can't simply include that header here, as there is no such
- * file for non-Linux platform.
- */
-#define PCI_MSIX_FLAGS		2	/* Message Control */
-#define PCI_MSIX_FLAGS_QSIZE	0x07FF	/* Table size */
-
 #define GVE_DEFAULT_RX_FREE_THRESH  512
 #define GVE_DEFAULT_TX_FREE_THRESH   32
 #define GVE_DEFAULT_TX_RS_THRESH     32
diff --git a/drivers/net/hns3/hns3_ethdev_vf.c b/drivers/net/hns3/hns3_ethdev_vf.c
index eab5c55f5e..3729615159 100644
--- a/drivers/net/hns3/hns3_ethdev_vf.c
+++ b/drivers/net/hns3/hns3_ethdev_vf.c
@@ -2,7 +2,6 @@
  * Copyright(c) 2018-2021 HiSilicon Limited.
  */
 
-#include <linux/pci_regs.h>
 #include <rte_alarm.h>
 #include <ethdev_pci.h>
 #include <rte_io.h>
@@ -64,18 +63,18 @@ hns3vf_enable_msix(const struct rte_pci_device *device, bool op)
 	pos = rte_pci_find_capability(device, RTE_PCI_CAP_ID_MSIX);
 	if (pos > 0) {
 		ret = rte_pci_read_config(device, &control, sizeof(control),
-			pos + PCI_MSIX_FLAGS);
+			pos + RTE_PCI_MSIX_FLAGS);
 		if (ret < 0) {
 			PMD_INIT_LOG(ERR, "Failed to read MSIX flags");
 			return -ENXIO;
 		}
 
 		if (op)
-			control |= PCI_MSIX_FLAGS_ENABLE;
+			control |= RTE_PCI_MSIX_FLAGS_ENABLE;
 		else
-			control &= ~PCI_MSIX_FLAGS_ENABLE;
+			control &= ~RTE_PCI_MSIX_FLAGS_ENABLE;
 		ret = rte_pci_write_config(device, &control, sizeof(control),
-			pos + PCI_MSIX_FLAGS);
+			pos + RTE_PCI_MSIX_FLAGS);
 		if (ret < 0) {
 			PMD_INIT_LOG(ERR, "failed to write MSIX flags");
 			return -ENXIO;
diff --git a/drivers/net/virtio/virtio_pci.c b/drivers/net/virtio/virtio_pci.c
index 81d5dd0a4a..cdffef267f 100644
--- a/drivers/net/virtio/virtio_pci.c
+++ b/drivers/net/virtio/virtio_pci.c
@@ -24,8 +24,6 @@
 
 struct virtio_pci_internal virtio_pci_internal[RTE_MAX_ETHPORTS];
 
-#define PCI_MSIX_ENABLE 0x8000
-
 static enum virtio_msix_status
 vtpci_msix_detect(struct rte_pci_device *dev)
 {
@@ -34,8 +32,8 @@ vtpci_msix_detect(struct rte_pci_device *dev)
 
 	pos = rte_pci_find_capability(dev, RTE_PCI_CAP_ID_MSIX);
 	if (pos > 0 && rte_pci_read_config(dev, &flags, sizeof(flags),
-			pos + 2) == sizeof(flags)) {
-		if (flags & PCI_MSIX_ENABLE)
+			pos + RTE_PCI_MSIX_FLAGS) == sizeof(flags)) {
+		if (flags & RTE_PCI_MSIX_FLAGS_ENABLE)
 			return VIRTIO_MSIX_ENABLED;
 		else
 			return VIRTIO_MSIX_DISABLED;
diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
index 5a04a5a4b5..41dc725cc4 100644
--- a/lib/pci/rte_pci.h
+++ b/lib/pci/rte_pci.h
@@ -51,6 +51,16 @@ extern "C" {
 #define RTE_PCI_CAP_ID_MSIX		0x11	/* MSI-X */
 #define RTE_PCI_CAP_SIZEOF		4
 
+/* MSI-X registers (RTE_PCI_CAP_ID_MSIX) */
+#define RTE_PCI_MSIX_FLAGS		2	/* Message Control */
+#define RTE_PCI_MSIX_FLAGS_QSIZE	0x07ff	/* Table size */
+#define RTE_PCI_MSIX_FLAGS_MASKALL	0x4000	/* Mask all vectors for this function */
+#define RTE_PCI_MSIX_FLAGS_ENABLE	0x8000	/* MSI-X enable */
+
+#define RTE_PCI_MSIX_TABLE		4	/* Table offset */
+#define RTE_PCI_MSIX_TABLE_BIR		0x00000007 /* BAR index */
+#define RTE_PCI_MSIX_TABLE_OFFSET	0xfffffff8 /* Offset into specified BAR */
+
 /* PCI Express capability registers */
 #define RTE_PCI_EXP_DEVCTL	8	/* Device Control */
 
-- 
2.41.0


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

* [PATCH v2 07/15] pci: define some command constants
  2023-08-21 11:35 ` [PATCH v2 00/15] " David Marchand
                     ` (5 preceding siblings ...)
  2023-08-21 11:35   ` [PATCH v2 06/15] pci: define some MSIX constants David Marchand
@ 2023-08-21 11:35   ` David Marchand
  2023-09-07 13:15     ` Xia, Chenbo
  2023-08-21 11:35   ` [PATCH v2 08/15] pci: define some BAR constants David Marchand
                     ` (8 subsequent siblings)
  15 siblings, 1 reply; 98+ messages in thread
From: David Marchand @ 2023-08-21 11:35 UTC (permalink / raw)
  To: dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, bruce.richardson,
	Anatoly Burakov, Timothy McDaniel, Gaetan Rivet

Define some PCI command constants and use them in existing drivers.

Signed-off-by: David Marchand <david.marchand@redhat.com>
Acked-by: Bruce Richardson <bruce.richardson@intel.com>
---
 drivers/bus/pci/linux/pci_vfio.c  | 8 ++++----
 drivers/event/dlb2/pf/dlb2_main.c | 8 +++-----
 lib/pci/rte_pci.h                 | 6 ++++--
 3 files changed, 11 insertions(+), 11 deletions(-)

diff --git a/drivers/bus/pci/linux/pci_vfio.c b/drivers/bus/pci/linux/pci_vfio.c
index 7881b7a946..bf91492dd9 100644
--- a/drivers/bus/pci/linux/pci_vfio.c
+++ b/drivers/bus/pci/linux/pci_vfio.c
@@ -156,18 +156,18 @@ pci_vfio_enable_bus_memory(struct rte_pci_device *dev, int dev_fd)
 		return -1;
 	}
 
-	ret = pread64(dev_fd, &cmd, sizeof(cmd), offset + PCI_COMMAND);
+	ret = pread64(dev_fd, &cmd, sizeof(cmd), offset + RTE_PCI_COMMAND);
 
 	if (ret != sizeof(cmd)) {
 		RTE_LOG(ERR, EAL, "Cannot read command from PCI config space!\n");
 		return -1;
 	}
 
-	if (cmd & PCI_COMMAND_MEMORY)
+	if (cmd & RTE_PCI_COMMAND_MEMORY)
 		return 0;
 
-	cmd |= PCI_COMMAND_MEMORY;
-	ret = pwrite64(dev_fd, &cmd, sizeof(cmd), offset + PCI_COMMAND);
+	cmd |= RTE_PCI_COMMAND_MEMORY;
+	ret = pwrite64(dev_fd, &cmd, sizeof(cmd), offset + RTE_PCI_COMMAND);
 
 	if (ret != sizeof(cmd)) {
 		RTE_LOG(ERR, EAL, "Cannot write command to PCI config space!\n");
diff --git a/drivers/event/dlb2/pf/dlb2_main.c b/drivers/event/dlb2/pf/dlb2_main.c
index c6606a9bee..6dbaa2ff97 100644
--- a/drivers/event/dlb2/pf/dlb2_main.c
+++ b/drivers/event/dlb2/pf/dlb2_main.c
@@ -33,7 +33,6 @@
 #define DLB2_PCI_EXP_DEVCTL2 40
 #define DLB2_PCI_LNKCTL2 48
 #define DLB2_PCI_SLTCTL2 56
-#define DLB2_PCI_CMD 4
 #define DLB2_PCI_EXP_DEVSTA 10
 #define DLB2_PCI_EXP_DEVSTA_TRPND 0x20
 #define DLB2_PCI_EXP_DEVCTL_BCR_FLR 0x8000
@@ -47,7 +46,6 @@
 #define DLB2_PCI_ERR_ROOT_STATUS         0x30
 #define DLB2_PCI_ERR_COR_STATUS          0x10
 #define DLB2_PCI_ERR_UNCOR_STATUS        0x4
-#define DLB2_PCI_COMMAND_INTX_DISABLE    0x400
 #define DLB2_PCI_ACS_CAP                 0x4
 #define DLB2_PCI_ACS_CTRL                0x6
 #define DLB2_PCI_ACS_SV                  0x1
@@ -286,7 +284,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 
 	/* clear the PCI command register before issuing the FLR */
 
-	off = DLB2_PCI_CMD;
+	off = RTE_PCI_COMMAND;
 	cmd = 0;
 	if (rte_pci_write_config(pdev, &cmd, 2, off) != 2) {
 		DLB2_LOG_ERR("[%s()] failed to write the pci command\n",
@@ -468,9 +466,9 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 		}
 	}
 
-	off = DLB2_PCI_CMD;
+	off = RTE_PCI_COMMAND;
 	if (rte_pci_read_config(pdev, &cmd, 2, off) == 2) {
-		cmd &= ~DLB2_PCI_COMMAND_INTX_DISABLE;
+		cmd &= ~RTE_PCI_COMMAND_INTX_DISABLE;
 		if (rte_pci_write_config(pdev, &cmd, 2, off) != 2) {
 			DLB2_LOG_ERR("[%s()] failed to write the pci command\n",
 			       __func__);
diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
index 41dc725cc4..9eb8f85ceb 100644
--- a/lib/pci/rte_pci.h
+++ b/lib/pci/rte_pci.h
@@ -37,8 +37,10 @@ extern "C" {
 #define RTE_PCI_STATUS		0x06	/* 16 bits */
 #define RTE_PCI_CAPABILITY_LIST	0x34	/* 32 bits */
 
-/* PCI Command Register */
-#define RTE_PCI_COMMAND_MASTER	0x4	/* Bus Master Enable */
+/* PCI Command Register (RTE_PCI_COMMAND) */
+#define RTE_PCI_COMMAND_MEMORY		0x2	/* Enable response in Memory space */
+#define RTE_PCI_COMMAND_MASTER		0x4	/* Bus Master Enable */
+#define RTE_PCI_COMMAND_INTX_DISABLE	0x400	/* INTx Emulation Disable */
 
 /* PCI Status Register (RTE_PCI_STATUS) */
 #define RTE_PCI_STATUS_CAP_LIST		0x10	/* Support Capability List */
-- 
2.41.0


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

* [PATCH v2 08/15] pci: define some BAR constants
  2023-08-21 11:35 ` [PATCH v2 00/15] " David Marchand
                     ` (6 preceding siblings ...)
  2023-08-21 11:35   ` [PATCH v2 07/15] pci: define some command constants David Marchand
@ 2023-08-21 11:35   ` David Marchand
  2023-09-07 13:16     ` Xia, Chenbo
  2023-08-21 11:35   ` [PATCH v2 09/15] pci: define some PM constants David Marchand
                     ` (7 subsequent siblings)
  15 siblings, 1 reply; 98+ messages in thread
From: David Marchand @ 2023-08-21 11:35 UTC (permalink / raw)
  To: dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, bruce.richardson,
	Anatoly Burakov, Gaetan Rivet

Define some PCI BAR constants and use them in existing drivers.

Signed-off-by: David Marchand <david.marchand@redhat.com>
Acked-by: Bruce Richardson <bruce.richardson@intel.com>
---
 drivers/bus/pci/linux/pci_vfio.c | 7 +++----
 lib/pci/rte_pci.h                | 4 ++++
 2 files changed, 7 insertions(+), 4 deletions(-)

diff --git a/drivers/bus/pci/linux/pci_vfio.c b/drivers/bus/pci/linux/pci_vfio.c
index bf91492dd9..3f3201daf2 100644
--- a/drivers/bus/pci/linux/pci_vfio.c
+++ b/drivers/bus/pci/linux/pci_vfio.c
@@ -5,7 +5,6 @@
 #include <unistd.h>
 #include <string.h>
 #include <fcntl.h>
-#include <linux/pci_regs.h>
 #include <sys/eventfd.h>
 #include <sys/socket.h>
 #include <sys/ioctl.h>
@@ -427,14 +426,14 @@ pci_vfio_is_ioport_bar(const struct rte_pci_device *dev, int vfio_dev_fd,
 	}
 
 	ret = pread64(vfio_dev_fd, &ioport_bar, sizeof(ioport_bar),
-			  offset + PCI_BASE_ADDRESS_0 + bar_index * 4);
+			  offset + RTE_PCI_BASE_ADDRESS_0 + bar_index * 4);
 	if (ret != sizeof(ioport_bar)) {
 		RTE_LOG(ERR, EAL, "Cannot read command (%x) from config space!\n",
-			PCI_BASE_ADDRESS_0 + bar_index*4);
+			RTE_PCI_BASE_ADDRESS_0 + bar_index*4);
 		return -1;
 	}
 
-	return (ioport_bar & PCI_BASE_ADDRESS_SPACE_IO) != 0;
+	return (ioport_bar & RTE_PCI_BASE_ADDRESS_SPACE_IO) != 0;
 }
 
 static int
diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
index 9eb8f85ceb..62bf87aa10 100644
--- a/lib/pci/rte_pci.h
+++ b/lib/pci/rte_pci.h
@@ -35,6 +35,7 @@ extern "C" {
 #define RTE_PCI_DEVICE_ID	0x02	/* 16 bits */
 #define RTE_PCI_COMMAND		0x04	/* 16 bits */
 #define RTE_PCI_STATUS		0x06	/* 16 bits */
+#define RTE_PCI_BASE_ADDRESS_0	0x10	/* 32 bits */
 #define RTE_PCI_CAPABILITY_LIST	0x34	/* 32 bits */
 
 /* PCI Command Register (RTE_PCI_COMMAND) */
@@ -45,6 +46,9 @@ extern "C" {
 /* PCI Status Register (RTE_PCI_STATUS) */
 #define RTE_PCI_STATUS_CAP_LIST		0x10	/* Support Capability List */
 
+/* Base addresses (RTE_PCI_BASE_ADDRESS_*) */
+#define RTE_PCI_BASE_ADDRESS_SPACE_IO	0x01
+
 /* Capability registers (RTE_PCI_CAPABILITY_LIST) */
 #define RTE_PCI_CAP_ID_PM		0x01	/* Power Management */
 #define RTE_PCI_CAP_ID_MSI		0x05	/* Message Signalled Interrupts */
-- 
2.41.0


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

* [PATCH v2 09/15] pci: define some PM constants
  2023-08-21 11:35 ` [PATCH v2 00/15] " David Marchand
                     ` (7 preceding siblings ...)
  2023-08-21 11:35   ` [PATCH v2 08/15] pci: define some BAR constants David Marchand
@ 2023-08-21 11:35   ` David Marchand
  2023-09-07 13:16     ` Xia, Chenbo
  2023-08-21 11:35   ` [PATCH v2 10/15] pci: define some PCIe constants David Marchand
                     ` (6 subsequent siblings)
  15 siblings, 1 reply; 98+ messages in thread
From: David Marchand @ 2023-08-21 11:35 UTC (permalink / raw)
  To: dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, bruce.richardson,
	Julien Aube, Gaetan Rivet

Define some PCI Power Management constants and use them in existing
drivers.

Signed-off-by: David Marchand <david.marchand@redhat.com>
Acked-by: Bruce Richardson <bruce.richardson@intel.com>
---
 drivers/net/bnx2x/bnx2x.c | 17 +++++++++--------
 drivers/net/bnx2x/bnx2x.h |  5 -----
 lib/pci/rte_pci.h         |  6 ++++++
 3 files changed, 15 insertions(+), 13 deletions(-)

diff --git a/drivers/net/bnx2x/bnx2x.c b/drivers/net/bnx2x/bnx2x.c
index e3f14400cc..faf061beba 100644
--- a/drivers/net/bnx2x/bnx2x.c
+++ b/drivers/net/bnx2x/bnx2x.c
@@ -5843,17 +5843,17 @@ static int bnx2x_set_power_state(struct bnx2x_softc *sc, uint8_t state)
 		return 0;
 	}
 
-	pci_read(sc, (sc->devinfo.pcie_pm_cap_reg + PCIR_POWER_STATUS), &pmcsr,
+	pci_read(sc, (sc->devinfo.pcie_pm_cap_reg + RTE_PCI_PM_CTRL), &pmcsr,
 		 2);
 
 	switch (state) {
 	case PCI_PM_D0:
 		pci_write_word(sc,
 			       (sc->devinfo.pcie_pm_cap_reg +
-				PCIR_POWER_STATUS),
-			       ((pmcsr & ~PCIM_PSTAT_DMASK) | PCIM_PSTAT_PME));
+				RTE_PCI_PM_CTRL),
+			       ((pmcsr & ~RTE_PCI_PM_CTRL_STATE_MASK) | RTE_PCI_PM_CTRL_PME_STATUS));
 
-		if (pmcsr & PCIM_PSTAT_DMASK) {
+		if (pmcsr & RTE_PCI_PM_CTRL_STATE_MASK) {
 			/* delay required during transition out of D3hot */
 			DELAY(20000);
 		}
@@ -5866,16 +5866,17 @@ static int bnx2x_set_power_state(struct bnx2x_softc *sc, uint8_t state)
 			return 0;
 		}
 
-		pmcsr &= ~PCIM_PSTAT_DMASK;
-		pmcsr |= PCIM_PSTAT_D3;
+		pmcsr &= ~RTE_PCI_PM_CTRL_STATE_MASK;
+		/* D3 power state */
+		pmcsr |= 0x3;
 
 		if (sc->wol) {
-			pmcsr |= PCIM_PSTAT_PMEENABLE;
+			pmcsr |= RTE_PCI_PM_CTRL_PME_ENABLE;
 		}
 
 		pci_write_long(sc,
 			       (sc->devinfo.pcie_pm_cap_reg +
-				PCIR_POWER_STATUS), pmcsr);
+				RTE_PCI_PM_CTRL), pmcsr);
 
 		/*
 		 * No more memory access after this point until device is brought back
diff --git a/drivers/net/bnx2x/bnx2x.h b/drivers/net/bnx2x/bnx2x.h
index 60af75d336..1efa166316 100644
--- a/drivers/net/bnx2x/bnx2x.h
+++ b/drivers/net/bnx2x/bnx2x.h
@@ -41,11 +41,6 @@
 #define PCIR_EXPRESS_DEVICE_CTL        PCI_EXP_DEVCTL
 #define PCIM_EXP_CTL_MAX_PAYLOAD       PCI_EXP_DEVCTL_PAYLOAD
 #define PCIM_EXP_CTL_MAX_READ_REQUEST  PCI_EXP_DEVCTL_READRQ
-#define PCIR_POWER_STATUS              PCI_PM_CTRL
-#define PCIM_PSTAT_DMASK               PCI_PM_CTRL_STATE_MASK
-#define PCIM_PSTAT_PME                 PCI_PM_CTRL_PME_STATUS
-#define PCIM_PSTAT_D3                  0x3
-#define PCIM_PSTAT_PMEENABLE           PCI_PM_CTRL_PME_ENABLE
 #else
 #include <dev/pci/pcireg.h>
 #endif
diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
index 62bf87aa10..542d142dfb 100644
--- a/lib/pci/rte_pci.h
+++ b/lib/pci/rte_pci.h
@@ -57,6 +57,12 @@ extern "C" {
 #define RTE_PCI_CAP_ID_MSIX		0x11	/* MSI-X */
 #define RTE_PCI_CAP_SIZEOF		4
 
+/* Power Management Registers (RTE_PCI_CAP_ID_PM) */
+#define RTE_PCI_PM_CTRL			4	/* PM control and status register */
+#define RTE_PCI_PM_CTRL_STATE_MASK	0x0003	/* Current power state (D0 to D3) */
+#define RTE_PCI_PM_CTRL_PME_ENABLE	0x0100	/* PME pin enable */
+#define RTE_PCI_PM_CTRL_PME_STATUS	0x8000	/* PME pin status */
+
 /* MSI-X registers (RTE_PCI_CAP_ID_MSIX) */
 #define RTE_PCI_MSIX_FLAGS		2	/* Message Control */
 #define RTE_PCI_MSIX_FLAGS_QSIZE	0x07ff	/* Table size */
-- 
2.41.0


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

* [PATCH v2 10/15] pci: define some PCIe constants
  2023-08-21 11:35 ` [PATCH v2 00/15] " David Marchand
                     ` (8 preceding siblings ...)
  2023-08-21 11:35   ` [PATCH v2 09/15] pci: define some PM constants David Marchand
@ 2023-08-21 11:35   ` David Marchand
  2023-09-07 13:16     ` Xia, Chenbo
  2023-08-21 11:35   ` [PATCH v2 11/15] pci: define some extended capability constants David Marchand
                     ` (5 subsequent siblings)
  15 siblings, 1 reply; 98+ messages in thread
From: David Marchand @ 2023-08-21 11:35 UTC (permalink / raw)
  To: dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, bruce.richardson,
	Timothy McDaniel, Julien Aube, Gaetan Rivet

Define some PCI Express constants and use them in existing drivers.

Signed-off-by: David Marchand <david.marchand@redhat.com>
Acked-by: Bruce Richardson <bruce.richardson@intel.com>
---
 drivers/event/dlb2/pf/dlb2_main.c | 40 ++++++++++++-------------------
 drivers/net/bnx2x/bnx2x.c         | 16 ++++++-------
 drivers/net/bnx2x/bnx2x.h         | 35 ---------------------------
 lib/pci/rte_pci.h                 | 21 +++++++++++++---
 4 files changed, 41 insertions(+), 71 deletions(-)

diff --git a/drivers/event/dlb2/pf/dlb2_main.c b/drivers/event/dlb2/pf/dlb2_main.c
index 6dbaa2ff97..8d960edef6 100644
--- a/drivers/event/dlb2/pf/dlb2_main.c
+++ b/drivers/event/dlb2/pf/dlb2_main.c
@@ -27,16 +27,6 @@
 #define NO_OWNER_VF 0	/* PF ONLY! */
 #define NOT_VF_REQ false /* PF ONLY! */
 
-#define DLB2_PCI_LNKCTL 16
-#define DLB2_PCI_SLTCTL 24
-#define DLB2_PCI_RTCTL 28
-#define DLB2_PCI_EXP_DEVCTL2 40
-#define DLB2_PCI_LNKCTL2 48
-#define DLB2_PCI_SLTCTL2 56
-#define DLB2_PCI_EXP_DEVSTA 10
-#define DLB2_PCI_EXP_DEVSTA_TRPND 0x20
-#define DLB2_PCI_EXP_DEVCTL_BCR_FLR 0x8000
-
 #define DLB2_PCI_EXT_CAP_ID_PRI   0x13
 #define DLB2_PCI_EXT_CAP_ID_ACS   0xD
 
@@ -249,27 +239,27 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 	if (rte_pci_read_config(pdev, &dev_ctl_word, 2, off) != 2)
 		dev_ctl_word = 0;
 
-	off = pcie_cap_offset + DLB2_PCI_LNKCTL;
+	off = pcie_cap_offset + RTE_PCI_EXP_LNKCTL;
 	if (rte_pci_read_config(pdev, &lnk_word, 2, off) != 2)
 		lnk_word = 0;
 
-	off = pcie_cap_offset + DLB2_PCI_SLTCTL;
+	off = pcie_cap_offset + RTE_PCI_EXP_SLTCTL;
 	if (rte_pci_read_config(pdev, &slt_word, 2, off) != 2)
 		slt_word = 0;
 
-	off = pcie_cap_offset + DLB2_PCI_RTCTL;
+	off = pcie_cap_offset + RTE_PCI_EXP_RTCTL;
 	if (rte_pci_read_config(pdev, &rt_ctl_word, 2, off) != 2)
 		rt_ctl_word = 0;
 
-	off = pcie_cap_offset + DLB2_PCI_EXP_DEVCTL2;
+	off = pcie_cap_offset + RTE_PCI_EXP_DEVCTL2;
 	if (rte_pci_read_config(pdev, &dev_ctl2_word, 2, off) != 2)
 		dev_ctl2_word = 0;
 
-	off = pcie_cap_offset + DLB2_PCI_LNKCTL2;
+	off = pcie_cap_offset + RTE_PCI_EXP_LNKCTL2;
 	if (rte_pci_read_config(pdev, &lnk_word2, 2, off) != 2)
 		lnk_word2 = 0;
 
-	off = pcie_cap_offset + DLB2_PCI_SLTCTL2;
+	off = pcie_cap_offset + RTE_PCI_EXP_SLTCTL2;
 	if (rte_pci_read_config(pdev, &slt_word2, 2, off) != 2)
 		slt_word2 = 0;
 
@@ -296,7 +286,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 	for (wait_count = 0; wait_count < 4; wait_count++) {
 		int sleep_time;
 
-		off = pcie_cap_offset + DLB2_PCI_EXP_DEVSTA;
+		off = pcie_cap_offset + RTE_PCI_EXP_DEVSTA;
 		ret = rte_pci_read_config(pdev, &devsta_busy_word, 2, off);
 		if (ret != 2) {
 			DLB2_LOG_ERR("[%s()] failed to read the pci device status\n",
@@ -304,7 +294,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 		}
 
-		if (!(devsta_busy_word & DLB2_PCI_EXP_DEVSTA_TRPND))
+		if (!(devsta_busy_word & RTE_PCI_EXP_DEVSTA_TRPND))
 			break;
 
 		sleep_time = (1 << (wait_count)) * 100;
@@ -325,7 +315,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 		return ret;
 	}
 
-	devctl_word |= DLB2_PCI_EXP_DEVCTL_BCR_FLR;
+	devctl_word |= RTE_PCI_EXP_DEVCTL_BCR_FLR;
 
 	ret = rte_pci_write_config(pdev, &devctl_word, 2, off);
 	if (ret != 2) {
@@ -347,7 +337,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 		}
 
-		off = pcie_cap_offset + DLB2_PCI_LNKCTL;
+		off = pcie_cap_offset + RTE_PCI_EXP_LNKCTL;
 		ret = rte_pci_write_config(pdev, &lnk_word, 2, off);
 		if (ret != 2) {
 			DLB2_LOG_ERR("[%s()] failed to write the pcie config space at offset %d\n",
@@ -355,7 +345,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 		}
 
-		off = pcie_cap_offset + DLB2_PCI_SLTCTL;
+		off = pcie_cap_offset + RTE_PCI_EXP_SLTCTL;
 		ret = rte_pci_write_config(pdev, &slt_word, 2, off);
 		if (ret != 2) {
 			DLB2_LOG_ERR("[%s()] failed to write the pcie config space at offset %d\n",
@@ -363,7 +353,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 		}
 
-		off = pcie_cap_offset + DLB2_PCI_RTCTL;
+		off = pcie_cap_offset + RTE_PCI_EXP_RTCTL;
 		ret = rte_pci_write_config(pdev, &rt_ctl_word, 2, off);
 		if (ret != 2) {
 			DLB2_LOG_ERR("[%s()] failed to write the pcie config space at offset %d\n",
@@ -371,7 +361,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 		}
 
-		off = pcie_cap_offset + DLB2_PCI_EXP_DEVCTL2;
+		off = pcie_cap_offset + RTE_PCI_EXP_DEVCTL2;
 		ret = rte_pci_write_config(pdev, &dev_ctl2_word, 2, off);
 		if (ret != 2) {
 			DLB2_LOG_ERR("[%s()] failed to write the pcie config space at offset %d\n",
@@ -379,7 +369,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 		}
 
-		off = pcie_cap_offset + DLB2_PCI_LNKCTL2;
+		off = pcie_cap_offset + RTE_PCI_EXP_LNKCTL2;
 		ret = rte_pci_write_config(pdev, &lnk_word2, 2, off);
 		if (ret != 2) {
 			DLB2_LOG_ERR("[%s()] failed to write the pcie config space at offset %d\n",
@@ -387,7 +377,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 		}
 
-		off = pcie_cap_offset + DLB2_PCI_SLTCTL2;
+		off = pcie_cap_offset + RTE_PCI_EXP_SLTCTL2;
 		ret = rte_pci_write_config(pdev, &slt_word2, 2, off);
 		if (ret != 2) {
 			DLB2_LOG_ERR("[%s()] failed to write the pcie config space at offset %d\n",
diff --git a/drivers/net/bnx2x/bnx2x.c b/drivers/net/bnx2x/bnx2x.c
index faf061beba..cfd8e35aa3 100644
--- a/drivers/net/bnx2x/bnx2x.c
+++ b/drivers/net/bnx2x/bnx2x.c
@@ -7630,8 +7630,8 @@ static uint32_t bnx2x_pcie_capability_read(struct bnx2x_softc *sc, int reg)
 
 static uint8_t bnx2x_is_pcie_pending(struct bnx2x_softc *sc)
 {
-	return bnx2x_pcie_capability_read(sc, PCIR_EXPRESS_DEVICE_STA) &
-		PCIM_EXP_STA_TRANSACTION_PND;
+	return bnx2x_pcie_capability_read(sc, RTE_PCI_EXP_TYPE_RC_EC) &
+		RTE_PCI_EXP_DEVSTA_TRPND;
 }
 
 /*
@@ -7658,11 +7658,11 @@ static void bnx2x_probe_pci_caps(struct bnx2x_softc *sc)
 		sc->devinfo.pcie_pm_cap_reg = caps->addr;
 	}
 
-	link_status = bnx2x_pcie_capability_read(sc, PCIR_EXPRESS_LINK_STA);
+	link_status = bnx2x_pcie_capability_read(sc, RTE_PCI_EXP_LNKSTA);
 
-	sc->devinfo.pcie_link_speed = (link_status & PCIM_LINK_STA_SPEED);
+	sc->devinfo.pcie_link_speed = (link_status & RTE_PCI_EXP_LNKSTA_CLS);
 	sc->devinfo.pcie_link_width =
-	    ((link_status & PCIM_LINK_STA_WIDTH) >> 4);
+	    ((link_status & RTE_PCI_EXP_LNKSTA_NLW) >> 4);
 
 	PMD_DRV_LOG(DEBUG, sc, "PCIe link speed=%d width=%d",
 		    sc->devinfo.pcie_link_speed, sc->devinfo.pcie_link_width);
@@ -9979,10 +9979,10 @@ static void bnx2x_init_pxp(struct bnx2x_softc *sc)
 	uint16_t devctl;
 	int r_order, w_order;
 
-	devctl = bnx2x_pcie_capability_read(sc, PCIR_EXPRESS_DEVICE_CTL);
+	devctl = bnx2x_pcie_capability_read(sc, RTE_PCI_EXP_DEVCTL);
 
-	w_order = ((devctl & PCIM_EXP_CTL_MAX_PAYLOAD) >> 5);
-	r_order = ((devctl & PCIM_EXP_CTL_MAX_READ_REQUEST) >> 12);
+	w_order = ((devctl & RTE_PCI_EXP_DEVCTL_PAYLOAD) >> 5);
+	r_order = ((devctl & RTE_PCI_EXP_DEVCTL_READRQ) >> 12);
 
 	ecore_init_pxp_arb(sc, r_order, w_order);
 }
diff --git a/drivers/net/bnx2x/bnx2x.h b/drivers/net/bnx2x/bnx2x.h
index 1efa166316..35206b4758 100644
--- a/drivers/net/bnx2x/bnx2x.h
+++ b/drivers/net/bnx2x/bnx2x.h
@@ -30,45 +30,10 @@
 
 #include "elink.h"
 
-#ifndef RTE_EXEC_ENV_FREEBSD
-#include <linux/pci_regs.h>
-
-#define PCIR_EXPRESS_DEVICE_STA        PCI_EXP_TYPE_RC_EC
-#define PCIM_EXP_STA_TRANSACTION_PND   PCI_EXP_DEVSTA_TRPND
-#define PCIR_EXPRESS_LINK_STA          PCI_EXP_LNKSTA
-#define PCIM_LINK_STA_WIDTH            PCI_EXP_LNKSTA_NLW
-#define PCIM_LINK_STA_SPEED            PCI_EXP_LNKSTA_CLS
-#define PCIR_EXPRESS_DEVICE_CTL        PCI_EXP_DEVCTL
-#define PCIM_EXP_CTL_MAX_PAYLOAD       PCI_EXP_DEVCTL_PAYLOAD
-#define PCIM_EXP_CTL_MAX_READ_REQUEST  PCI_EXP_DEVCTL_READRQ
-#else
-#include <dev/pci/pcireg.h>
-#endif
-
 #define IFM_10G_CX4                    20 /* 10GBase CX4 copper */
 #define IFM_10G_TWINAX                 22 /* 10GBase Twinax copper */
 #define IFM_10G_T                      26 /* 10GBase-T - RJ45 */
 
-#ifndef RTE_EXEC_ENV_FREEBSD
-#define PCIR_EXPRESS_DEVICE_STA        PCI_EXP_TYPE_RC_EC
-#define PCIM_EXP_STA_TRANSACTION_PND   PCI_EXP_DEVSTA_TRPND
-#define PCIR_EXPRESS_LINK_STA          PCI_EXP_LNKSTA
-#define PCIM_LINK_STA_WIDTH            PCI_EXP_LNKSTA_NLW
-#define PCIM_LINK_STA_SPEED            PCI_EXP_LNKSTA_CLS
-#define PCIR_EXPRESS_DEVICE_CTL        PCI_EXP_DEVCTL
-#define PCIM_EXP_CTL_MAX_PAYLOAD       PCI_EXP_DEVCTL_PAYLOAD
-#define PCIM_EXP_CTL_MAX_READ_REQUEST  PCI_EXP_DEVCTL_READRQ
-#else
-#define PCIR_EXPRESS_DEVICE_STA	PCIER_DEVICE_STA
-#define PCIM_EXP_STA_TRANSACTION_PND   PCIEM_STA_TRANSACTION_PND
-#define PCIR_EXPRESS_LINK_STA          PCIER_LINK_STA
-#define PCIM_LINK_STA_WIDTH            PCIEM_LINK_STA_WIDTH
-#define PCIM_LINK_STA_SPEED            PCIEM_LINK_STA_SPEED
-#define PCIR_EXPRESS_DEVICE_CTL        PCIER_DEVICE_CTL
-#define PCIM_EXP_CTL_MAX_PAYLOAD       PCIEM_CTL_MAX_PAYLOAD
-#define PCIM_EXP_CTL_MAX_READ_REQUEST  PCIEM_CTL_MAX_READ_REQUEST
-#endif
-
 #ifndef ARRAY_SIZE
 #define ARRAY_SIZE(arr) RTE_DIM(arr)
 #endif
diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
index 542d142dfb..a82f073a7d 100644
--- a/lib/pci/rte_pci.h
+++ b/lib/pci/rte_pci.h
@@ -63,6 +63,24 @@ extern "C" {
 #define RTE_PCI_PM_CTRL_PME_ENABLE	0x0100	/* PME pin enable */
 #define RTE_PCI_PM_CTRL_PME_STATUS	0x8000	/* PME pin status */
 
+/* PCI Express capability registers (RTE_PCI_CAP_ID_EXP) */
+#define RTE_PCI_EXP_TYPE_RC_EC		0xa	/* Root Complex Event Collector */
+#define RTE_PCI_EXP_DEVCTL		0x08	/* Device Control */
+#define RTE_PCI_EXP_DEVCTL_PAYLOAD	0x00e0	/* Max_Payload_Size */
+#define RTE_PCI_EXP_DEVCTL_READRQ	0x7000	/* Max_Read_Request_Size */
+#define RTE_PCI_EXP_DEVCTL_BCR_FLR	0x8000	/* Bridge Configuration Retry / FLR */
+#define RTE_PCI_EXP_DEVSTA		0x0a	/* Device Status */
+#define RTE_PCI_EXP_DEVSTA_TRPND	0x0020	/* Transactions Pending */
+#define RTE_PCI_EXP_LNKCTL		0x10	/* Link Control */
+#define RTE_PCI_EXP_LNKSTA		0x12	/* Link Status */
+#define RTE_PCI_EXP_LNKSTA_CLS		0x000f	/* Current Link Speed */
+#define RTE_PCI_EXP_LNKSTA_NLW		0x03f0	/* Negotiated Link Width */
+#define RTE_PCI_EXP_SLTCTL		0x18	/* Slot Control */
+#define RTE_PCI_EXP_RTCTL		0x1c	/* Root Control */
+#define RTE_PCI_EXP_DEVCTL2		0x28	/* Device Control 2 */
+#define RTE_PCI_EXP_LNKCTL2		0x30	/* Link Control 2 */
+#define RTE_PCI_EXP_SLTCTL2		0x38	/* Slot Control 2 */
+
 /* MSI-X registers (RTE_PCI_CAP_ID_MSIX) */
 #define RTE_PCI_MSIX_FLAGS		2	/* Message Control */
 #define RTE_PCI_MSIX_FLAGS_QSIZE	0x07ff	/* Table size */
@@ -73,9 +91,6 @@ extern "C" {
 #define RTE_PCI_MSIX_TABLE_BIR		0x00000007 /* BAR index */
 #define RTE_PCI_MSIX_TABLE_OFFSET	0xfffffff8 /* Offset into specified BAR */
 
-/* PCI Express capability registers */
-#define RTE_PCI_EXP_DEVCTL	8	/* Device Control */
-
 /* Extended Capabilities (PCI-X 2.0 and Express) */
 #define RTE_PCI_EXT_CAP_ID(header)	(header & 0x0000ffff)
 #define RTE_PCI_EXT_CAP_NEXT(header)	((header >> 20) & 0xffc)
-- 
2.41.0


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

* [PATCH v2 11/15] pci: define some extended capability constants
  2023-08-21 11:35 ` [PATCH v2 00/15] " David Marchand
                     ` (9 preceding siblings ...)
  2023-08-21 11:35   ` [PATCH v2 10/15] pci: define some PCIe constants David Marchand
@ 2023-08-21 11:35   ` David Marchand
  2023-09-07 13:23     ` Xia, Chenbo
  2023-08-21 11:35   ` [PATCH v2 12/15] pci: define some ACS constants David Marchand
                     ` (4 subsequent siblings)
  15 siblings, 1 reply; 98+ messages in thread
From: David Marchand @ 2023-08-21 11:35 UTC (permalink / raw)
  To: dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, bruce.richardson,
	Timothy McDaniel, Gaetan Rivet

Define some PCI extended capability constants and use them in existing
drivers.

Signed-off-by: David Marchand <david.marchand@redhat.com>
Acked-by: Bruce Richardson <bruce.richardson@intel.com>
---
 drivers/event/dlb2/pf/dlb2_main.c | 7 ++-----
 lib/pci/rte_pci.h                 | 4 +++-
 2 files changed, 5 insertions(+), 6 deletions(-)

diff --git a/drivers/event/dlb2/pf/dlb2_main.c b/drivers/event/dlb2/pf/dlb2_main.c
index 8d960edef6..29e3001627 100644
--- a/drivers/event/dlb2/pf/dlb2_main.c
+++ b/drivers/event/dlb2/pf/dlb2_main.c
@@ -27,9 +27,6 @@
 #define NO_OWNER_VF 0	/* PF ONLY! */
 #define NOT_VF_REQ false /* PF ONLY! */
 
-#define DLB2_PCI_EXT_CAP_ID_PRI   0x13
-#define DLB2_PCI_EXT_CAP_ID_ACS   0xD
-
 #define DLB2_PCI_PRI_CTRL_ENABLE         0x1
 #define DLB2_PCI_PRI_ALLOC_REQ           0xC
 #define DLB2_PCI_PRI_CTRL                0x4
@@ -263,7 +260,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 	if (rte_pci_read_config(pdev, &slt_word2, 2, off) != 2)
 		slt_word2 = 0;
 
-	off = DLB2_PCI_EXT_CAP_ID_PRI;
+	off = RTE_PCI_EXT_CAP_ID_PRI;
 	pri_cap_offset = rte_pci_find_ext_capability(pdev, off);
 
 	if (pri_cap_offset >= 0) {
@@ -490,7 +487,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 		}
 	}
 
-	off = DLB2_PCI_EXT_CAP_ID_ACS;
+	off = RTE_PCI_EXT_CAP_ID_ACS;
 	acs_cap_offset = rte_pci_find_ext_capability(pdev, off);
 
 	if (acs_cap_offset >= 0) {
diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
index a82f073a7d..d2f7a96f17 100644
--- a/lib/pci/rte_pci.h
+++ b/lib/pci/rte_pci.h
@@ -97,9 +97,11 @@ extern "C" {
 
 #define RTE_PCI_EXT_CAP_ID_ERR		0x01	/* Advanced Error Reporting */
 #define RTE_PCI_EXT_CAP_ID_DSN		0x03	/* Device Serial Number */
+#define RTE_PCI_EXT_CAP_ID_ACS		0x0d	/* Access Control Services */
 #define RTE_PCI_EXT_CAP_ID_SRIOV	0x10	/* SR-IOV*/
+#define RTE_PCI_EXT_CAP_ID_PRI		0x13	/* Page Request Interface */
 
-/* Single Root I/O Virtualization */
+/* Single Root I/O Virtualization (RTE_PCI_EXT_CAP_ID_SRIOV) */
 #define RTE_PCI_SRIOV_CAP		0x04	/* SR-IOV Capabilities */
 #define RTE_PCI_SRIOV_CTRL		0x08	/* SR-IOV Control */
 #define RTE_PCI_SRIOV_INITIAL_VF	0x0c	/* Initial VFs */
-- 
2.41.0


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

* [PATCH v2 12/15] pci: define some ACS constants
  2023-08-21 11:35 ` [PATCH v2 00/15] " David Marchand
                     ` (10 preceding siblings ...)
  2023-08-21 11:35   ` [PATCH v2 11/15] pci: define some extended capability constants David Marchand
@ 2023-08-21 11:35   ` David Marchand
  2023-08-21 11:35   ` [PATCH v2 13/15] pci: define some PRI constants David Marchand
                     ` (3 subsequent siblings)
  15 siblings, 0 replies; 98+ messages in thread
From: David Marchand @ 2023-08-21 11:35 UTC (permalink / raw)
  To: dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, bruce.richardson,
	Timothy McDaniel, Gaetan Rivet

Define some PCI ACS extended feature constants and use them in existing
drivers.

Signed-off-by: David Marchand <david.marchand@redhat.com>
Acked-by: Bruce Richardson <bruce.richardson@intel.com>
---
 drivers/event/dlb2/pf/dlb2_main.c | 23 ++++++++---------------
 lib/pci/rte_pci.h                 |  9 +++++++++
 2 files changed, 17 insertions(+), 15 deletions(-)

diff --git a/drivers/event/dlb2/pf/dlb2_main.c b/drivers/event/dlb2/pf/dlb2_main.c
index 29e3001627..8e729d1964 100644
--- a/drivers/event/dlb2/pf/dlb2_main.c
+++ b/drivers/event/dlb2/pf/dlb2_main.c
@@ -33,13 +33,6 @@
 #define DLB2_PCI_ERR_ROOT_STATUS         0x30
 #define DLB2_PCI_ERR_COR_STATUS          0x10
 #define DLB2_PCI_ERR_UNCOR_STATUS        0x4
-#define DLB2_PCI_ACS_CAP                 0x4
-#define DLB2_PCI_ACS_CTRL                0x6
-#define DLB2_PCI_ACS_SV                  0x1
-#define DLB2_PCI_ACS_RR                  0x4
-#define DLB2_PCI_ACS_CR                  0x8
-#define DLB2_PCI_ACS_UF                  0x10
-#define DLB2_PCI_ACS_EC                  0x20
 
 static int
 dlb2_pf_init_driver_state(struct dlb2_dev *dlb2_dev)
@@ -492,16 +485,16 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 
 	if (acs_cap_offset >= 0) {
 		uint16_t acs_cap, acs_ctrl, acs_mask;
-		off = acs_cap_offset + DLB2_PCI_ACS_CAP;
+		off = acs_cap_offset + RTE_PCI_ACS_CAP;
 		if (rte_pci_read_config(pdev, &acs_cap, 2, off) != 2)
 			acs_cap = 0;
 
-		off = acs_cap_offset + DLB2_PCI_ACS_CTRL;
+		off = acs_cap_offset + RTE_PCI_ACS_CTRL;
 		if (rte_pci_read_config(pdev, &acs_ctrl, 2, off) != 2)
 			acs_ctrl = 0;
 
-		acs_mask = DLB2_PCI_ACS_SV | DLB2_PCI_ACS_RR;
-		acs_mask |= (DLB2_PCI_ACS_CR | DLB2_PCI_ACS_UF);
+		acs_mask = RTE_PCI_ACS_SV | RTE_PCI_ACS_RR;
+		acs_mask |= (RTE_PCI_ACS_CR | RTE_PCI_ACS_UF);
 		acs_ctrl |= (acs_cap & acs_mask);
 
 		ret = rte_pci_write_config(pdev, &acs_ctrl, 2, off);
@@ -511,15 +504,15 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 		}
 
-		off = acs_cap_offset + DLB2_PCI_ACS_CTRL;
+		off = acs_cap_offset + RTE_PCI_ACS_CTRL;
 		if (rte_pci_read_config(pdev, &acs_ctrl, 2, off) != 2)
 			acs_ctrl = 0;
 
-		acs_mask = DLB2_PCI_ACS_RR | DLB2_PCI_ACS_CR;
-		acs_mask |= DLB2_PCI_ACS_EC;
+		acs_mask = RTE_PCI_ACS_RR | RTE_PCI_ACS_CR;
+		acs_mask |= RTE_PCI_ACS_EC;
 		acs_ctrl &= ~acs_mask;
 
-		off = acs_cap_offset + DLB2_PCI_ACS_CTRL;
+		off = acs_cap_offset + RTE_PCI_ACS_CTRL;
 		ret = rte_pci_write_config(pdev, &acs_ctrl, 2, off);
 		if (ret != 2) {
 			DLB2_LOG_ERR("[%s()] failed to write the pcie config space at offset %d\n",
diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
index d2f7a96f17..a385285c94 100644
--- a/lib/pci/rte_pci.h
+++ b/lib/pci/rte_pci.h
@@ -101,6 +101,15 @@ extern "C" {
 #define RTE_PCI_EXT_CAP_ID_SRIOV	0x10	/* SR-IOV*/
 #define RTE_PCI_EXT_CAP_ID_PRI		0x13	/* Page Request Interface */
 
+/* Access Control Service (RTE_PCI_EXT_CAP_ID_ACS) */
+#define RTE_PCI_ACS_CAP			0x04	/* ACS Capability Register */
+#define RTE_PCI_ACS_CTRL		0x06	/* ACS Control Register */
+#define RTE_PCI_ACS_SV			0x0001	/* Source Validation */
+#define RTE_PCI_ACS_RR			0x0004	/* P2P Request Redirect */
+#define RTE_PCI_ACS_CR			0x0008	/* P2P Completion Redirect */
+#define RTE_PCI_ACS_UF			0x0010	/* Upstream Forwarding */
+#define RTE_PCI_ACS_EC			0x0020	/* P2P Egress Control */
+
 /* Single Root I/O Virtualization (RTE_PCI_EXT_CAP_ID_SRIOV) */
 #define RTE_PCI_SRIOV_CAP		0x04	/* SR-IOV Capabilities */
 #define RTE_PCI_SRIOV_CTRL		0x08	/* SR-IOV Control */
-- 
2.41.0


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

* [PATCH v2 13/15] pci: define some PRI constants
  2023-08-21 11:35 ` [PATCH v2 00/15] " David Marchand
                     ` (11 preceding siblings ...)
  2023-08-21 11:35   ` [PATCH v2 12/15] pci: define some ACS constants David Marchand
@ 2023-08-21 11:35   ` David Marchand
  2023-08-21 11:35   ` [PATCH v2 14/15] pci: define some AER constants David Marchand
                     ` (2 subsequent siblings)
  15 siblings, 0 replies; 98+ messages in thread
From: David Marchand @ 2023-08-21 11:35 UTC (permalink / raw)
  To: dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, bruce.richardson,
	Timothy McDaniel, Gaetan Rivet

Define some PCI PRI extended feature constants and use them in existing
drivers.

Signed-off-by: David Marchand <david.marchand@redhat.com>
Acked-by: Bruce Richardson <bruce.richardson@intel.com>
---
 drivers/event/dlb2/pf/dlb2_main.c | 11 ++++-------
 lib/pci/rte_pci.h                 |  5 +++++
 2 files changed, 9 insertions(+), 7 deletions(-)

diff --git a/drivers/event/dlb2/pf/dlb2_main.c b/drivers/event/dlb2/pf/dlb2_main.c
index 8e729d1964..187a356c24 100644
--- a/drivers/event/dlb2/pf/dlb2_main.c
+++ b/drivers/event/dlb2/pf/dlb2_main.c
@@ -27,9 +27,6 @@
 #define NO_OWNER_VF 0	/* PF ONLY! */
 #define NOT_VF_REQ false /* PF ONLY! */
 
-#define DLB2_PCI_PRI_CTRL_ENABLE         0x1
-#define DLB2_PCI_PRI_ALLOC_REQ           0xC
-#define DLB2_PCI_PRI_CTRL                0x4
 #define DLB2_PCI_ERR_ROOT_STATUS         0x30
 #define DLB2_PCI_ERR_COR_STATUS          0x10
 #define DLB2_PCI_ERR_UNCOR_STATUS        0x4
@@ -257,7 +254,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 	pri_cap_offset = rte_pci_find_ext_capability(pdev, off);
 
 	if (pri_cap_offset >= 0) {
-		off = pri_cap_offset + DLB2_PCI_PRI_ALLOC_REQ;
+		off = pri_cap_offset + RTE_PCI_PRI_ALLOC_REQ;
 		if (rte_pci_read_config(pdev, &pri_reqs_dword, 4, off) != 4)
 			pri_reqs_dword = 0;
 	}
@@ -377,9 +374,9 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 	}
 
 	if (pri_cap_offset >= 0) {
-		pri_ctrl_word = DLB2_PCI_PRI_CTRL_ENABLE;
+		pri_ctrl_word = RTE_PCI_PRI_CTRL_ENABLE;
 
-		off = pri_cap_offset + DLB2_PCI_PRI_ALLOC_REQ;
+		off = pri_cap_offset + RTE_PCI_PRI_ALLOC_REQ;
 		ret = rte_pci_write_config(pdev, &pri_reqs_dword, 4, off);
 		if (ret != 4) {
 			DLB2_LOG_ERR("[%s()] failed to write the pcie config space at offset %d\n",
@@ -387,7 +384,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 		}
 
-		off = pri_cap_offset + DLB2_PCI_PRI_CTRL;
+		off = pri_cap_offset + RTE_PCI_PRI_CTRL;
 		ret = rte_pci_write_config(pdev, &pri_ctrl_word, 2, off);
 		if (ret != 2) {
 			DLB2_LOG_ERR("[%s()] failed to write the pcie config space at offset %d\n",
diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
index a385285c94..b23671a2cf 100644
--- a/lib/pci/rte_pci.h
+++ b/lib/pci/rte_pci.h
@@ -122,6 +122,11 @@ extern "C" {
 #define RTE_PCI_SRIOV_VF_DID		0x1a	/* VF Device ID */
 #define RTE_PCI_SRIOV_SUP_PGSIZE	0x1c	/* Supported Page Sizes */
 
+/* Page Request Interface (RTE_PCI_EXT_CAP_ID_PRI) */
+#define RTE_PCI_PRI_CTRL		0x04	/* PRI control register */
+#define RTE_PCI_PRI_CTRL_ENABLE		0x0001	/* Enable */
+#define RTE_PCI_PRI_ALLOC_REQ		0x0c	/* PRI max reqs allowed */
+
 /** Formatting string for PCI device identifier: Ex: 0000:00:01.0 */
 #define PCI_PRI_FMT "%.4" PRIx32 ":%.2" PRIx8 ":%.2" PRIx8 ".%" PRIx8
 #define PCI_PRI_STR_SIZE sizeof("XXXXXXXX:XX:XX.X")
-- 
2.41.0


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

* [PATCH v2 14/15] pci: define some AER constants
  2023-08-21 11:35 ` [PATCH v2 00/15] " David Marchand
                     ` (12 preceding siblings ...)
  2023-08-21 11:35   ` [PATCH v2 13/15] pci: define some PRI constants David Marchand
@ 2023-08-21 11:35   ` David Marchand
  2023-08-21 11:35   ` [PATCH v2 15/15] devtools: forbid inclusion of Linux header for PCI David Marchand
  2023-08-22 15:30   ` [PATCH v2 00/15] Cleanup PCI(e) drivers Patrick Robb
  15 siblings, 0 replies; 98+ messages in thread
From: David Marchand @ 2023-08-21 11:35 UTC (permalink / raw)
  To: dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, bruce.richardson,
	Timothy McDaniel, Gaetan Rivet

Define some Advanced Error Reporting constants and use them in existing
drivers.

Signed-off-by: David Marchand <david.marchand@redhat.com>
Acked-by: Bruce Richardson <bruce.richardson@intel.com>
---
 drivers/event/dlb2/pf/dlb2_main.c | 10 +++-------
 lib/pci/rte_pci.h                 |  5 +++++
 2 files changed, 8 insertions(+), 7 deletions(-)

diff --git a/drivers/event/dlb2/pf/dlb2_main.c b/drivers/event/dlb2/pf/dlb2_main.c
index 187a356c24..aa03e4c311 100644
--- a/drivers/event/dlb2/pf/dlb2_main.c
+++ b/drivers/event/dlb2/pf/dlb2_main.c
@@ -27,10 +27,6 @@
 #define NO_OWNER_VF 0	/* PF ONLY! */
 #define NOT_VF_REQ false /* PF ONLY! */
 
-#define DLB2_PCI_ERR_ROOT_STATUS         0x30
-#define DLB2_PCI_ERR_COR_STATUS          0x10
-#define DLB2_PCI_ERR_UNCOR_STATUS        0x4
-
 static int
 dlb2_pf_init_driver_state(struct dlb2_dev *dlb2_dev)
 {
@@ -399,7 +395,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 	if (err_cap_offset >= 0) {
 		uint32_t tmp;
 
-		off = err_cap_offset + DLB2_PCI_ERR_ROOT_STATUS;
+		off = err_cap_offset + RTE_PCI_ERR_ROOT_STATUS;
 		if (rte_pci_read_config(pdev, &tmp, 4, off) != 4)
 			tmp = 0;
 
@@ -410,7 +406,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 		}
 
-		off = err_cap_offset + DLB2_PCI_ERR_COR_STATUS;
+		off = err_cap_offset + RTE_PCI_ERR_COR_STATUS;
 		if (rte_pci_read_config(pdev, &tmp, 4, off) != 4)
 			tmp = 0;
 
@@ -421,7 +417,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 		}
 
-		off = err_cap_offset + DLB2_PCI_ERR_UNCOR_STATUS;
+		off = err_cap_offset + RTE_PCI_ERR_UNCOR_STATUS;
 		if (rte_pci_read_config(pdev, &tmp, 4, off) != 4)
 			tmp = 0;
 
diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
index b23671a2cf..dbeefb315f 100644
--- a/lib/pci/rte_pci.h
+++ b/lib/pci/rte_pci.h
@@ -101,6 +101,11 @@ extern "C" {
 #define RTE_PCI_EXT_CAP_ID_SRIOV	0x10	/* SR-IOV*/
 #define RTE_PCI_EXT_CAP_ID_PRI		0x13	/* Page Request Interface */
 
+/* Advanced Error Reporting (RTE_PCI_EXT_CAP_ID_ERR) */
+#define RTE_PCI_ERR_UNCOR_STATUS	0x04	/* Uncorrectable Error Status */
+#define RTE_PCI_ERR_COR_STATUS		0x10	/* Correctable Error Status */
+#define RTE_PCI_ERR_ROOT_STATUS		0x30
+
 /* Access Control Service (RTE_PCI_EXT_CAP_ID_ACS) */
 #define RTE_PCI_ACS_CAP			0x04	/* ACS Capability Register */
 #define RTE_PCI_ACS_CTRL		0x06	/* ACS Control Register */
-- 
2.41.0


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

* [PATCH v2 15/15] devtools: forbid inclusion of Linux header for PCI
  2023-08-21 11:35 ` [PATCH v2 00/15] " David Marchand
                     ` (13 preceding siblings ...)
  2023-08-21 11:35   ` [PATCH v2 14/15] pci: define some AER constants David Marchand
@ 2023-08-21 11:35   ` David Marchand
  2023-08-21 16:24     ` Tyler Retzlaff
  2023-09-07 13:33     ` Xia, Chenbo
  2023-08-22 15:30   ` [PATCH v2 00/15] Cleanup PCI(e) drivers Patrick Robb
  15 siblings, 2 replies; 98+ messages in thread
From: David Marchand @ 2023-08-21 11:35 UTC (permalink / raw)
  To: dev; +Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, bruce.richardson

Refrain from including Linux-only pci_regs.h header.
Instead, prefer our own definitions from the pci library.

Signed-off-by: David Marchand <david.marchand@redhat.com>
Acked-by: Bruce Richardson <bruce.richardson@intel.com>
---
 devtools/checkpatches.sh | 8 ++++++++
 1 file changed, 8 insertions(+)

diff --git a/devtools/checkpatches.sh b/devtools/checkpatches.sh
index 43f5e36a18..5d3c5aaba5 100755
--- a/devtools/checkpatches.sh
+++ b/devtools/checkpatches.sh
@@ -127,6 +127,14 @@ check_forbidden_additions() { # <patch>
 		-f $(dirname $(readlink -f $0))/check-forbidden-tokens.awk \
 		"$1" || res=1
 
+	# forbid inclusion of Linux header for PCI constants
+	awk -v FOLDERS="lib drivers app examples" \
+		-v EXPRESSIONS='include.*linux/pci_regs\\.h' \
+		-v RET_ON_FAIL=1 \
+		-v MESSAGE='Using linux/pci_regs.h, prefer rte_pci.h' \
+		-f $(dirname $(readlink -f $0))/check-forbidden-tokens.awk \
+		"$1" || res=1
+
 	# forbid use of experimental build flag except in examples
 	awk -v FOLDERS='lib drivers app' \
 		-v EXPRESSIONS='-DALLOW_EXPERIMENTAL_API allow_experimental_apis' \
-- 
2.41.0


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

* Re: [PATCH v2 02/15] bus/pci: add const to some experimental API
  2023-08-21 11:35   ` [PATCH v2 02/15] bus/pci: add const to some experimental API David Marchand
@ 2023-08-21 16:14     ` Tyler Retzlaff
  2023-09-06 13:02     ` Xia, Chenbo
  1 sibling, 0 replies; 98+ messages in thread
From: Tyler Retzlaff @ 2023-08-21 16:14 UTC (permalink / raw)
  To: David Marchand
  Cc: dev, thomas, ferruh.yigit, chenbo.xia, nipun.gupta, bruce.richardson

On Mon, Aug 21, 2023 at 01:35:35PM +0200, David Marchand wrote:
> Those functions are fine with a const on the device pointer.
> 
> Signed-off-by: David Marchand <david.marchand@redhat.com>
> Acked-by: Bruce Richardson <bruce.richardson@intel.com>
> ---

Acked-by: Tyler Retzlaff <roretzla@linux.microsoft.com>


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

* Re: [PATCH v2 15/15] devtools: forbid inclusion of Linux header for PCI
  2023-08-21 11:35   ` [PATCH v2 15/15] devtools: forbid inclusion of Linux header for PCI David Marchand
@ 2023-08-21 16:24     ` Tyler Retzlaff
  2023-09-07 13:33     ` Xia, Chenbo
  1 sibling, 0 replies; 98+ messages in thread
From: Tyler Retzlaff @ 2023-08-21 16:24 UTC (permalink / raw)
  To: David Marchand
  Cc: dev, thomas, ferruh.yigit, chenbo.xia, nipun.gupta, bruce.richardson

On Mon, Aug 21, 2023 at 01:35:48PM +0200, David Marchand wrote:
> Refrain from including Linux-only pci_regs.h header.
> Instead, prefer our own definitions from the pci library.
> 
> Signed-off-by: David Marchand <david.marchand@redhat.com>
> Acked-by: Bruce Richardson <bruce.richardson@intel.com>
> ---

Acked-by: Tyler Retzlaff <roretzla@linux.microsoft.com>


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

* Re: [PATCH v2 00/15] Cleanup PCI(e) drivers
  2023-08-21 11:35 ` [PATCH v2 00/15] " David Marchand
                     ` (14 preceding siblings ...)
  2023-08-21 11:35   ` [PATCH v2 15/15] devtools: forbid inclusion of Linux header for PCI David Marchand
@ 2023-08-22 15:30   ` Patrick Robb
  15 siblings, 0 replies; 98+ messages in thread
From: Patrick Robb @ 2023-08-22 15:30 UTC (permalink / raw)
  To: David Marchand; +Cc: dev

[-- Attachment #1: Type: text/plain, Size: 197 bytes --]

Recheck-request: iol-unit-arm64-testing, iol-broadcom-Performance,
iol-compile-amd64-testing, iol-sample-apps-testing

This email is just a test of the new email based retesting request
framework.

[-- Attachment #2: Type: text/html, Size: 249 bytes --]

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

* Re: [PATCH 00/14] Cleanup PCI(e) drivers
  2023-08-03  7:50 [PATCH 00/14] Cleanup PCI(e) drivers David Marchand
                   ` (15 preceding siblings ...)
  2023-08-21 11:35 ` [PATCH v2 00/15] " David Marchand
@ 2023-08-22 16:09 ` Adam Hassick
  2023-08-22 16:48 ` Adam Hassick
                   ` (2 subsequent siblings)
  19 siblings, 0 replies; 98+ messages in thread
From: Adam Hassick @ 2023-08-22 16:09 UTC (permalink / raw)
  To: David Marchand; +Cc: dev

[-- Attachment #1: Type: text/plain, Size: 2552 bytes --]

Recheck-request: iol-sample-apps-testing

This is a test email of the retesting framework, please ignore. Testing the
behavior of replying to a superseded patch.

On Thu, Aug 3, 2023 at 3:50 AM David Marchand <david.marchand@redhat.com>
wrote:

> Rather than rely on Linux headers to find some PCI(e) standard constants
> or reinvent the same PCI capability helper, this series complements the
> pci library and the pci bus driver.
> PCI drivers can then use OS agnostic macros and helpers.
>
> WARNING: this is only compile tested.
>
> --
> David Marchand
>
> David Marchand (14):
>   drivers: remove duplicated PCI master control
>   bus/pci: add const to some experimental API
>   bus/pci: find PCI capability
>   pci: define some capability constants
>   pci: define some MSIX constants
>   pci: define some command constants
>   pci: define some BAR constants
>   pci: define some PM constants
>   pci: define some PCIe constants
>   pci: define some extended capability constants
>   pci: define some ACS constants
>   pci: define some PRI constants
>   pci: define some AER constants
>   devtools: forbid inclusion of Linux header for PCI
>
>  devtools/checkpatches.sh            |   8 ++
>  drivers/bus/pci/linux/pci_init.h    |  18 ----
>  drivers/bus/pci/linux/pci_uio.c     |  32 +-----
>  drivers/bus/pci/linux/pci_vfio.c    | 142 ++++++-------------------
>  drivers/bus/pci/pci_common.c        |  49 ++++++++-
>  drivers/bus/pci/rte_bus_pci.h       |  35 ++++++-
>  drivers/bus/pci/version.map         |   2 +
>  drivers/crypto/virtio/virtio_pci.c  |  67 ++++--------
>  drivers/event/dlb2/pf/dlb2_main.c   | 156 ++++++++--------------------
>  drivers/net/bnx2x/bnx2x.c           |  86 ++++++++-------
>  drivers/net/bnx2x/bnx2x.h           |  46 --------
>  drivers/net/cxgbe/base/adapter.h    |  31 +-----
>  drivers/net/gve/gve_ethdev.c        |  46 +-------
>  drivers/net/gve/gve_ethdev.h        |  14 +--
>  drivers/net/hns3/hns3_ethdev_vf.c   | 109 +++----------------
>  drivers/net/ngbe/base/ngbe_hw.c     |  20 +---
>  drivers/net/ngbe/base/ngbe_osdep.h  |   3 -
>  drivers/net/virtio/virtio_pci.c     | 131 ++++-------------------
>  drivers/vdpa/ifc/base/ifcvf_osdep.h |   4 +-
>  lib/pci/rte_pci.h                   |  77 +++++++++++++-
>  20 files changed, 346 insertions(+), 730 deletions(-)
>
> --
> 2.41.0
>
>

-- 
*Adam Hassick*
Senior Developer
UNH InterOperability Lab
ahassick@iol.unh.edu
iol.unh.edu <https://www.iol.unh.edu/>
+1 (603) 475-8248

[-- Attachment #2: Type: text/html, Size: 3844 bytes --]

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

* Re: [PATCH 00/14] Cleanup PCI(e) drivers
  2023-08-03  7:50 [PATCH 00/14] Cleanup PCI(e) drivers David Marchand
                   ` (16 preceding siblings ...)
  2023-08-22 16:09 ` [PATCH 00/14] " Adam Hassick
@ 2023-08-22 16:48 ` Adam Hassick
  2023-08-24 15:44 ` Adam Hassick
  2023-09-14 12:35 ` [PATCH v3 00/15] " David Marchand
  19 siblings, 0 replies; 98+ messages in thread
From: Adam Hassick @ 2023-08-22 16:48 UTC (permalink / raw)
  To: David Marchand; +Cc: dev

[-- Attachment #1: Type: text/plain, Size: 2496 bytes --]

Recheck-request: iol-sample-apps-testing,

This is a test email of the retesting framework, please ignore.

On Thu, Aug 3, 2023 at 3:50 AM David Marchand <david.marchand@redhat.com>
wrote:

> Rather than rely on Linux headers to find some PCI(e) standard constants
> or reinvent the same PCI capability helper, this series complements the
> pci library and the pci bus driver.
> PCI drivers can then use OS agnostic macros and helpers.
>
> WARNING: this is only compile tested.
>
> --
> David Marchand
>
> David Marchand (14):
>   drivers: remove duplicated PCI master control
>   bus/pci: add const to some experimental API
>   bus/pci: find PCI capability
>   pci: define some capability constants
>   pci: define some MSIX constants
>   pci: define some command constants
>   pci: define some BAR constants
>   pci: define some PM constants
>   pci: define some PCIe constants
>   pci: define some extended capability constants
>   pci: define some ACS constants
>   pci: define some PRI constants
>   pci: define some AER constants
>   devtools: forbid inclusion of Linux header for PCI
>
>  devtools/checkpatches.sh            |   8 ++
>  drivers/bus/pci/linux/pci_init.h    |  18 ----
>  drivers/bus/pci/linux/pci_uio.c     |  32 +-----
>  drivers/bus/pci/linux/pci_vfio.c    | 142 ++++++-------------------
>  drivers/bus/pci/pci_common.c        |  49 ++++++++-
>  drivers/bus/pci/rte_bus_pci.h       |  35 ++++++-
>  drivers/bus/pci/version.map         |   2 +
>  drivers/crypto/virtio/virtio_pci.c  |  67 ++++--------
>  drivers/event/dlb2/pf/dlb2_main.c   | 156 ++++++++--------------------
>  drivers/net/bnx2x/bnx2x.c           |  86 ++++++++-------
>  drivers/net/bnx2x/bnx2x.h           |  46 --------
>  drivers/net/cxgbe/base/adapter.h    |  31 +-----
>  drivers/net/gve/gve_ethdev.c        |  46 +-------
>  drivers/net/gve/gve_ethdev.h        |  14 +--
>  drivers/net/hns3/hns3_ethdev_vf.c   | 109 +++----------------
>  drivers/net/ngbe/base/ngbe_hw.c     |  20 +---
>  drivers/net/ngbe/base/ngbe_osdep.h  |   3 -
>  drivers/net/virtio/virtio_pci.c     | 131 ++++-------------------
>  drivers/vdpa/ifc/base/ifcvf_osdep.h |   4 +-
>  lib/pci/rte_pci.h                   |  77 +++++++++++++-
>  20 files changed, 346 insertions(+), 730 deletions(-)
>
> --
> 2.41.0
>
>

-- 
*Adam Hassick*
Senior Developer
UNH InterOperability Lab
ahassick@iol.unh.edu
iol.unh.edu <https://www.iol.unh.edu/>
+1 (603) 475-8248

[-- Attachment #2: Type: text/html, Size: 3785 bytes --]

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

* Re: [PATCH 06/14] pci: define some command constants
  2023-08-03  7:50 ` [PATCH 06/14] pci: define some command constants David Marchand
  2023-08-03  9:57   ` Bruce Richardson
@ 2023-08-22 19:23   ` Adam Hassick
  1 sibling, 0 replies; 98+ messages in thread
From: Adam Hassick @ 2023-08-22 19:23 UTC (permalink / raw)
  To: David Marchand; +Cc: dev

[-- Attachment #1: Type: text/plain, Size: 4336 bytes --]

Recheck-request: iol-sample-apps-testing,

This email is a test of the community lab's retesting system, please
ignore. Testing superseded reply on a patch.

On Thu, Aug 3, 2023 at 3:51 AM David Marchand <david.marchand@redhat.com>
wrote:

> Define some PCI command constants and use them in existing drivers.
>
> Signed-off-by: David Marchand <david.marchand@redhat.com>
> ---
>  drivers/bus/pci/linux/pci_vfio.c  | 8 ++++----
>  drivers/event/dlb2/pf/dlb2_main.c | 8 +++-----
>  lib/pci/rte_pci.h                 | 4 +++-
>  3 files changed, 10 insertions(+), 10 deletions(-)
>
> diff --git a/drivers/bus/pci/linux/pci_vfio.c
> b/drivers/bus/pci/linux/pci_vfio.c
> index 6d13cafdcf..f96b3ce7fb 100644
> --- a/drivers/bus/pci/linux/pci_vfio.c
> +++ b/drivers/bus/pci/linux/pci_vfio.c
> @@ -156,18 +156,18 @@ pci_vfio_enable_bus_memory(struct rte_pci_device
> *dev, int dev_fd)
>                 return -1;
>         }
>
> -       ret = pread64(dev_fd, &cmd, sizeof(cmd), offset + PCI_COMMAND);
> +       ret = pread64(dev_fd, &cmd, sizeof(cmd), offset + RTE_PCI_COMMAND);
>
>         if (ret != sizeof(cmd)) {
>                 RTE_LOG(ERR, EAL, "Cannot read command from PCI config
> space!\n");
>                 return -1;
>         }
>
> -       if (cmd & PCI_COMMAND_MEMORY)
> +       if (cmd & RTE_PCI_COMMAND_MEMORY)
>                 return 0;
>
> -       cmd |= PCI_COMMAND_MEMORY;
> -       ret = pwrite64(dev_fd, &cmd, sizeof(cmd), offset + PCI_COMMAND);
> +       cmd |= RTE_PCI_COMMAND_MEMORY;
> +       ret = pwrite64(dev_fd, &cmd, sizeof(cmd), offset +
> RTE_PCI_COMMAND);
>
>         if (ret != sizeof(cmd)) {
>                 RTE_LOG(ERR, EAL, "Cannot write command to PCI config
> space!\n");
> diff --git a/drivers/event/dlb2/pf/dlb2_main.c
> b/drivers/event/dlb2/pf/dlb2_main.c
> index c6606a9bee..6dbaa2ff97 100644
> --- a/drivers/event/dlb2/pf/dlb2_main.c
> +++ b/drivers/event/dlb2/pf/dlb2_main.c
> @@ -33,7 +33,6 @@
>  #define DLB2_PCI_EXP_DEVCTL2 40
>  #define DLB2_PCI_LNKCTL2 48
>  #define DLB2_PCI_SLTCTL2 56
> -#define DLB2_PCI_CMD 4
>  #define DLB2_PCI_EXP_DEVSTA 10
>  #define DLB2_PCI_EXP_DEVSTA_TRPND 0x20
>  #define DLB2_PCI_EXP_DEVCTL_BCR_FLR 0x8000
> @@ -47,7 +46,6 @@
>  #define DLB2_PCI_ERR_ROOT_STATUS         0x30
>  #define DLB2_PCI_ERR_COR_STATUS          0x10
>  #define DLB2_PCI_ERR_UNCOR_STATUS        0x4
> -#define DLB2_PCI_COMMAND_INTX_DISABLE    0x400
>  #define DLB2_PCI_ACS_CAP                 0x4
>  #define DLB2_PCI_ACS_CTRL                0x6
>  #define DLB2_PCI_ACS_SV                  0x1
> @@ -286,7 +284,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
>
>         /* clear the PCI command register before issuing the FLR */
>
> -       off = DLB2_PCI_CMD;
> +       off = RTE_PCI_COMMAND;
>         cmd = 0;
>         if (rte_pci_write_config(pdev, &cmd, 2, off) != 2) {
>                 DLB2_LOG_ERR("[%s()] failed to write the pci command\n",
> @@ -468,9 +466,9 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
>                 }
>         }
>
> -       off = DLB2_PCI_CMD;
> +       off = RTE_PCI_COMMAND;
>         if (rte_pci_read_config(pdev, &cmd, 2, off) == 2) {
> -               cmd &= ~DLB2_PCI_COMMAND_INTX_DISABLE;
> +               cmd &= ~RTE_PCI_COMMAND_INTX_DISABLE;
>                 if (rte_pci_write_config(pdev, &cmd, 2, off) != 2) {
>                         DLB2_LOG_ERR("[%s()] failed to write the pci
> command\n",
>                                __func__);
> diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
> index a055a28592..bf2b2639f4 100644
> --- a/lib/pci/rte_pci.h
> +++ b/lib/pci/rte_pci.h
> @@ -32,10 +32,12 @@ extern "C" {
>
>  #define RTE_PCI_VENDOR_ID      0x00    /* 16 bits */
>  #define RTE_PCI_DEVICE_ID      0x02    /* 16 bits */
> -#define RTE_PCI_COMMAND                0x04    /* 16 bits */
>
>  /* PCI Command Register */
> +#define RTE_PCI_COMMAND                0x04    /* 16 bits */
> +#define RTE_PCI_COMMAND_MEMORY 0x2     /* Enable response in Memory space
> */
>  #define RTE_PCI_COMMAND_MASTER 0x4     /* Bus Master Enable */
> +#define RTE_PCI_COMMAND_INTX_DISABLE 0x400 /* INTx Emulation Disable */
>
>  /* PCI Status Register */
>  #define RTE_PCI_STATUS         0x06    /* 16 bits */
> --
> 2.41.0
>
>

[-- Attachment #2: Type: text/html, Size: 5359 bytes --]

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

* Re: [PATCH 00/14] Cleanup PCI(e) drivers
  2023-08-03  7:50 [PATCH 00/14] Cleanup PCI(e) drivers David Marchand
                   ` (17 preceding siblings ...)
  2023-08-22 16:48 ` Adam Hassick
@ 2023-08-24 15:44 ` Adam Hassick
  2023-09-14 12:35 ` [PATCH v3 00/15] " David Marchand
  19 siblings, 0 replies; 98+ messages in thread
From: Adam Hassick @ 2023-08-24 15:44 UTC (permalink / raw)
  To: David Marchand; +Cc: dev

[-- Attachment #1: Type: text/plain, Size: 2349 bytes --]

Recheck-request: iol-sample-apps-testing

This is a test of the retesting system, please ignore this email.

On Thu, Aug 3, 2023 at 3:50 AM David Marchand <david.marchand@redhat.com>
wrote:

> Rather than rely on Linux headers to find some PCI(e) standard constants
> or reinvent the same PCI capability helper, this series complements the
> pci library and the pci bus driver.
> PCI drivers can then use OS agnostic macros and helpers.
>
> WARNING: this is only compile tested.
>
> --
> David Marchand
>
> David Marchand (14):
>   drivers: remove duplicated PCI master control
>   bus/pci: add const to some experimental API
>   bus/pci: find PCI capability
>   pci: define some capability constants
>   pci: define some MSIX constants
>   pci: define some command constants
>   pci: define some BAR constants
>   pci: define some PM constants
>   pci: define some PCIe constants
>   pci: define some extended capability constants
>   pci: define some ACS constants
>   pci: define some PRI constants
>   pci: define some AER constants
>   devtools: forbid inclusion of Linux header for PCI
>
>  devtools/checkpatches.sh            |   8 ++
>  drivers/bus/pci/linux/pci_init.h    |  18 ----
>  drivers/bus/pci/linux/pci_uio.c     |  32 +-----
>  drivers/bus/pci/linux/pci_vfio.c    | 142 ++++++-------------------
>  drivers/bus/pci/pci_common.c        |  49 ++++++++-
>  drivers/bus/pci/rte_bus_pci.h       |  35 ++++++-
>  drivers/bus/pci/version.map         |   2 +
>  drivers/crypto/virtio/virtio_pci.c  |  67 ++++--------
>  drivers/event/dlb2/pf/dlb2_main.c   | 156 ++++++++--------------------
>  drivers/net/bnx2x/bnx2x.c           |  86 ++++++++-------
>  drivers/net/bnx2x/bnx2x.h           |  46 --------
>  drivers/net/cxgbe/base/adapter.h    |  31 +-----
>  drivers/net/gve/gve_ethdev.c        |  46 +-------
>  drivers/net/gve/gve_ethdev.h        |  14 +--
>  drivers/net/hns3/hns3_ethdev_vf.c   | 109 +++----------------
>  drivers/net/ngbe/base/ngbe_hw.c     |  20 +---
>  drivers/net/ngbe/base/ngbe_osdep.h  |   3 -
>  drivers/net/virtio/virtio_pci.c     | 131 ++++-------------------
>  drivers/vdpa/ifc/base/ifcvf_osdep.h |   4 +-
>  lib/pci/rte_pci.h                   |  77 +++++++++++++-
>  20 files changed, 346 insertions(+), 730 deletions(-)
>
> --
> 2.41.0
>
>

[-- Attachment #2: Type: text/html, Size: 2901 bytes --]

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

* RE: [PATCH v2 01/15] drivers: remove duplicated PCI master control
  2023-08-21 11:35   ` [PATCH v2 01/15] drivers: remove duplicated PCI master control David Marchand
@ 2023-09-06 13:02     ` Xia, Chenbo
  0 siblings, 0 replies; 98+ messages in thread
From: Xia, Chenbo @ 2023-09-06 13:02 UTC (permalink / raw)
  To: David Marchand, dev
  Cc: thomas, ferruh.yigit, nipun.gupta, Richardson, Bruce, Burakov,
	Anatoly, Dongdong Liu, Yisen Zhuang, Jiawen Wu

> -----Original Message-----
> From: David Marchand <david.marchand@redhat.com>
> Sent: Monday, August 21, 2023 7:36 PM
> To: dev@dpdk.org
> Cc: thomas@monjalon.net; ferruh.yigit@amd.com; Xia, Chenbo
> <chenbo.xia@intel.com>; nipun.gupta@amd.com; Richardson, Bruce
> <bruce.richardson@intel.com>; Burakov, Anatoly <anatoly.burakov@intel.com>;
> Dongdong Liu <liudongdong3@huawei.com>; Yisen Zhuang
> <yisen.zhuang@huawei.com>; Jiawen Wu <jiawenwu@trustnetic.com>
> Subject: [PATCH v2 01/15] drivers: remove duplicated PCI master control
> 
> Use existing API to cleanup duplicated code.
> 
> Signed-off-by: David Marchand <david.marchand@redhat.com>
> Acked-by: Bruce Richardson <bruce.richardson@intel.com>
> ---
> --
> 2.41.0

Reviewed-by: Chenbo Xia <chenbo.xia@intel.com>

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

* RE: [PATCH v2 02/15] bus/pci: add const to some experimental API
  2023-08-21 11:35   ` [PATCH v2 02/15] bus/pci: add const to some experimental API David Marchand
  2023-08-21 16:14     ` Tyler Retzlaff
@ 2023-09-06 13:02     ` Xia, Chenbo
  1 sibling, 0 replies; 98+ messages in thread
From: Xia, Chenbo @ 2023-09-06 13:02 UTC (permalink / raw)
  To: David Marchand, dev; +Cc: thomas, ferruh.yigit, nipun.gupta, Richardson, Bruce

> -----Original Message-----
> From: David Marchand <david.marchand@redhat.com>
> Sent: Monday, August 21, 2023 7:36 PM
> To: dev@dpdk.org
> Cc: thomas@monjalon.net; ferruh.yigit@amd.com; Xia, Chenbo
> <chenbo.xia@intel.com>; nipun.gupta@amd.com; Richardson, Bruce
> <bruce.richardson@intel.com>
> Subject: [PATCH v2 02/15] bus/pci: add const to some experimental API
> 
> Those functions are fine with a const on the device pointer.
> 
> Signed-off-by: David Marchand <david.marchand@redhat.com>
> Acked-by: Bruce Richardson <bruce.richardson@intel.com>
> ---
>  drivers/bus/pci/pci_common.c  | 4 ++--
>  drivers/bus/pci/rte_bus_pci.h | 4 ++--
>  2 files changed, 4 insertions(+), 4 deletions(-)
> 
> diff --git a/drivers/bus/pci/pci_common.c b/drivers/bus/pci/pci_common.c
> index 52404ab0fe..382b0b8946 100644
> --- a/drivers/bus/pci/pci_common.c
> +++ b/drivers/bus/pci/pci_common.c
> @@ -814,7 +814,7 @@ rte_pci_get_iommu_class(void)
>  }
> 
>  off_t
> -rte_pci_find_ext_capability(struct rte_pci_device *dev, uint32_t cap)
> +rte_pci_find_ext_capability(const struct rte_pci_device *dev, uint32_t
> cap)
>  {
>  	off_t offset = RTE_PCI_CFG_SPACE_SIZE;
>  	uint32_t header;
> @@ -857,7 +857,7 @@ rte_pci_find_ext_capability(struct rte_pci_device *dev,
> uint32_t cap)
>  }
> 
>  int
> -rte_pci_set_bus_master(struct rte_pci_device *dev, bool enable)
> +rte_pci_set_bus_master(const struct rte_pci_device *dev, bool enable)
>  {
>  	uint16_t old_cmd, cmd;
> 
> diff --git a/drivers/bus/pci/rte_bus_pci.h b/drivers/bus/pci/rte_bus_pci.h
> index 9d59c4aef3..75d0030eae 100644
> --- a/drivers/bus/pci/rte_bus_pci.h
> +++ b/drivers/bus/pci/rte_bus_pci.h
> @@ -85,7 +85,7 @@ void rte_pci_dump(FILE *f);
>   *  = 0: Device does not support it.
>   */
>  __rte_experimental
> -off_t rte_pci_find_ext_capability(struct rte_pci_device *dev, uint32_t
> cap);
> +off_t rte_pci_find_ext_capability(const struct rte_pci_device *dev,
> uint32_t cap);
> 
>  /**
>   * Enables/Disables Bus Master for device's PCI command register.
> @@ -99,7 +99,7 @@ off_t rte_pci_find_ext_capability(struct rte_pci_device
> *dev, uint32_t cap);
>   *  0 on success, -1 on error in PCI config space read/write.
>   */
>  __rte_experimental
> -int rte_pci_set_bus_master(struct rte_pci_device *dev, bool enable);
> +int rte_pci_set_bus_master(const struct rte_pci_device *dev, bool enable);
> 
>  /**
>   * Read PCI config space.
> --
> 2.41.0

Reviewed-by: Chenbo Xia <chenbo.xia@intel.com> 

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

* RE: [PATCH v2 03/15] bus/pci: rework MSIX discovery with VFIO
  2023-08-21 11:35   ` [PATCH v2 03/15] bus/pci: rework MSIX discovery with VFIO David Marchand
@ 2023-09-06 13:03     ` Xia, Chenbo
  0 siblings, 0 replies; 98+ messages in thread
From: Xia, Chenbo @ 2023-09-06 13:03 UTC (permalink / raw)
  To: David Marchand, dev
  Cc: thomas, ferruh.yigit, nipun.gupta, Richardson, Bruce, Burakov, Anatoly

> -----Original Message-----
> From: David Marchand <david.marchand@redhat.com>
> Sent: Monday, August 21, 2023 7:36 PM
> To: dev@dpdk.org
> Cc: thomas@monjalon.net; ferruh.yigit@amd.com; Xia, Chenbo
> <chenbo.xia@intel.com>; nipun.gupta@amd.com; Richardson, Bruce
> <bruce.richardson@intel.com>; Burakov, Anatoly <anatoly.burakov@intel.com>
> Subject: [PATCH v2 03/15] bus/pci: rework MSIX discovery with VFIO
> 
> This is a preparatory step before using new helpers for finding PCI
> capabilities.
> In the code querying PCI capabilities for checking MSIX availability,
> replace direct calls to VFIO fd with the existing helpers for reading
> PCI configuration space: this requires setting VFIO fd in the PCI
> device object than was done before this change and removes the need to
> pass around this vfio_dev_fd variable.
> 
> Signed-off-by: David Marchand <david.marchand@redhat.com>
> ---
>  drivers/bus/pci/linux/pci_vfio.c | 27 ++++++++++-----------------
>  1 file changed, 10 insertions(+), 17 deletions(-)
> 
> diff --git a/drivers/bus/pci/linux/pci_vfio.c
> b/drivers/bus/pci/linux/pci_vfio.c
> index 8fa7fa458f..958f8b3b52 100644
> --- a/drivers/bus/pci/linux/pci_vfio.c
> +++ b/drivers/bus/pci/linux/pci_vfio.c
> @@ -107,23 +107,16 @@ pci_vfio_write_config(const struct rte_pci_device
> *dev,
> 
>  /* get PCI BAR number where MSI-X interrupts are */
>  static int
> -pci_vfio_get_msix_bar(const struct rte_pci_device *dev, int fd,
> +pci_vfio_get_msix_bar(const struct rte_pci_device *dev,
>  	struct pci_msix_table *msix_table)
>  {
>  	int ret;
>  	uint32_t reg;
>  	uint16_t flags;
>  	uint8_t cap_id, cap_offset;
> -	uint64_t size, offset;
> -
> -	if (pci_vfio_get_region(dev, VFIO_PCI_CONFIG_REGION_INDEX,
> -		&size, &offset) != 0) {
> -		RTE_LOG(ERR, EAL, "Cannot get offset of CONFIG region.\n");
> -		return -1;
> -	}
> 
>  	/* read PCI capability pointer from config space */
> -	ret = pread64(fd, &reg, sizeof(reg), offset + PCI_CAPABILITY_LIST);
> +	ret = rte_pci_read_config(dev, &reg, sizeof(reg),
> PCI_CAPABILITY_LIST);
>  	if (ret != sizeof(reg)) {
>  		RTE_LOG(ERR, EAL,
>  			"Cannot read capability pointer from PCI config
> space!\n");
> @@ -136,7 +129,7 @@ pci_vfio_get_msix_bar(const struct rte_pci_device *dev,
> int fd,
>  	while (cap_offset) {
> 
>  		/* read PCI capability ID */
> -		ret = pread64(fd, &reg, sizeof(reg), offset + cap_offset);
> +		ret = rte_pci_read_config(dev, &reg, sizeof(reg), cap_offset);
>  		if (ret != sizeof(reg)) {
>  			RTE_LOG(ERR, EAL,
>  				"Cannot read capability ID from PCI config
> space!\n");
> @@ -148,7 +141,7 @@ pci_vfio_get_msix_bar(const struct rte_pci_device *dev,
> int fd,
> 
>  		/* if we haven't reached MSI-X, check next capability */
>  		if (cap_id != PCI_CAP_ID_MSIX) {
> -			ret = pread64(fd, &reg, sizeof(reg), offset +
> cap_offset);
> +			ret = rte_pci_read_config(dev, &reg, sizeof(reg),
> cap_offset);
>  			if (ret != sizeof(reg)) {
>  				RTE_LOG(ERR, EAL,
>  					"Cannot read capability pointer from PCI
> config space!\n");
> @@ -163,14 +156,14 @@ pci_vfio_get_msix_bar(const struct rte_pci_device
> *dev, int fd,
>  		/* else, read table offset */
>  		else {
>  			/* table offset resides in the next 4 bytes */
> -			ret = pread64(fd, &reg, sizeof(reg), offset + cap_offset
> + 4);
> +			ret = rte_pci_read_config(dev, &reg, sizeof(reg),
> cap_offset + 4);
>  			if (ret != sizeof(reg)) {
>  				RTE_LOG(ERR, EAL,
>  					"Cannot read table offset from PCI config
> space!\n");
>  				return -1;
>  			}
> 
> -			ret = pread64(fd, &flags, sizeof(flags), offset +
> cap_offset + 2);
> +			ret = rte_pci_read_config(dev, &flags, sizeof(flags),
> cap_offset + 2);
>  			if (ret != sizeof(flags)) {
>  				RTE_LOG(ERR, EAL,
>  					"Cannot read table flags from PCI config
> space!\n");
> @@ -306,9 +299,6 @@ pci_vfio_setup_interrupts(struct rte_pci_device *dev,
> int vfio_dev_fd)
>  		if (rte_intr_fd_set(dev->intr_handle, fd))
>  			return -1;
> 
> -		if (rte_intr_dev_fd_set(dev->intr_handle, vfio_dev_fd))
> -			return -1;
> -
>  		switch (i) {
>  		case VFIO_PCI_MSIX_IRQ_INDEX:
>  			intr_mode = RTE_INTR_MODE_MSIX;
> @@ -838,6 +828,9 @@ pci_vfio_map_resource_primary(struct rte_pci_device
> *dev)
>  	if (ret)
>  		return ret;
> 
> +	if (rte_intr_dev_fd_set(dev->intr_handle, vfio_dev_fd))
> +		goto err_vfio_dev_fd;
> +
>  	/* allocate vfio_res and get region info */
>  	vfio_res = rte_zmalloc("VFIO_RES", sizeof(*vfio_res), 0);
>  	if (vfio_res == NULL) {
> @@ -869,7 +862,7 @@ pci_vfio_map_resource_primary(struct rte_pci_device
> *dev)
>  	/* get MSI-X BAR, if any (we have to know where it is because we
> can't
>  	 * easily mmap it when using VFIO)
>  	 */
> -	ret = pci_vfio_get_msix_bar(dev, vfio_dev_fd, &vfio_res->msix_table);
> +	ret = pci_vfio_get_msix_bar(dev, &vfio_res->msix_table);
>  	if (ret < 0) {
>  		RTE_LOG(ERR, EAL, "%s cannot get MSI-X BAR number!\n",
>  				pci_addr);
> --
> 2.41.0

Reviewed-by: Chenbo Xia <chenbo.xia@intel.com>

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

* RE: [PATCH v2 04/15] bus/pci: find PCI capability
  2023-08-21 11:35   ` [PATCH v2 04/15] bus/pci: find PCI capability David Marchand
@ 2023-09-07 12:43     ` Xia, Chenbo
  2023-09-14 12:29       ` David Marchand
  0 siblings, 1 reply; 98+ messages in thread
From: Xia, Chenbo @ 2023-09-07 12:43 UTC (permalink / raw)
  To: David Marchand, dev
  Cc: thomas, ferruh.yigit, nipun.gupta, Richardson, Bruce, Burakov,
	Anatoly, Jay Zhou, McDaniel, Timothy, Julien Aube,
	Rahul Lakkireddy, Guo, Junfeng, Jeroen de Borst, Rushil Gupta,
	Joshua Washington, Dongdong Liu, Yisen Zhuang, Maxime Coquelin,
	Gaetan Rivet

Hi David,

> -----Original Message-----
> From: David Marchand <david.marchand@redhat.com>
> Sent: Monday, August 21, 2023 7:36 PM
> To: dev@dpdk.org
> Cc: thomas@monjalon.net; ferruh.yigit@amd.com; Xia, Chenbo
> <chenbo.xia@intel.com>; nipun.gupta@amd.com; Richardson, Bruce
> <bruce.richardson@intel.com>; Burakov, Anatoly <anatoly.burakov@intel.com>;
> Jay Zhou <jianjay.zhou@huawei.com>; McDaniel, Timothy
> <timothy.mcdaniel@intel.com>; Julien Aube <julien_dpdk@jaube.fr>; Rahul
> Lakkireddy <rahul.lakkireddy@chelsio.com>; Guo, Junfeng
> <junfeng.guo@intel.com>; Jeroen de Borst <jeroendb@google.com>; Rushil
> Gupta <rushilg@google.com>; Joshua Washington <joshwash@google.com>;
> Dongdong Liu <liudongdong3@huawei.com>; Yisen Zhuang
> <yisen.zhuang@huawei.com>; Maxime Coquelin <maxime.coquelin@redhat.com>;
> Gaetan Rivet <grive@u256.net>
> Subject: [PATCH v2 04/15] bus/pci: find PCI capability
> 
> Introduce two helpers so that drivers stop reinventing the wheel when it
> comes to finding capabilities in a device PCI configuration space.
> Use it in existing drivers.
> 
> Note:
> - base/ drivers code is left untouched, only some wrappers in cxgbe
>   are touched,
> - bnx2x maintained a per device cache of capabilities, this code has been
>   reworked to only cache the capabilities used in this driver,
> 
> Signed-off-by: David Marchand <david.marchand@redhat.com>
> Acked-by: Bruce Richardson <bruce.richardson@intel.com>
> ---
> Changes since v1:
> - updated commitlog,
> - separated VFIO changes for using standard PCI helper in a separate
>   patch,
> - marked new experimental symbols with current version,
> - reordered defines in rte_pci.h,
> 
> ---
>  drivers/bus/pci/linux/pci_vfio.c   |  74 ++++--------------
>  drivers/bus/pci/pci_common.c       |  45 +++++++++++
>  drivers/bus/pci/rte_bus_pci.h      |  31 ++++++++
>  drivers/bus/pci/version.map        |   4 +
>  drivers/crypto/virtio/virtio_pci.c |  57 +++++---------
>  drivers/event/dlb2/pf/dlb2_main.c  |  42 +---------
>  drivers/net/bnx2x/bnx2x.c          |  41 +++++-----
>  drivers/net/cxgbe/base/adapter.h   |  28 +------
>  drivers/net/gve/gve_ethdev.c       |  46 ++---------
>  drivers/net/gve/gve_ethdev.h       |   4 -
>  drivers/net/hns3/hns3_ethdev_vf.c  |  79 +++----------------
>  drivers/net/virtio/virtio_pci.c    | 121 +++++------------------------
>  lib/pci/rte_pci.h                  |  11 +++
>  13 files changed, 186 insertions(+), 397 deletions(-)
> 
> diff --git a/drivers/bus/pci/linux/pci_vfio.c
> b/drivers/bus/pci/linux/pci_vfio.c
> index 958f8b3b52..614ed5d696 100644
> --- a/drivers/bus/pci/linux/pci_vfio.c
> +++ b/drivers/bus/pci/linux/pci_vfio.c
> @@ -110,74 +110,34 @@ static int
>  pci_vfio_get_msix_bar(const struct rte_pci_device *dev,
>  	struct pci_msix_table *msix_table)
>  {
> -	int ret;
> -	uint32_t reg;
> -	uint16_t flags;
> -	uint8_t cap_id, cap_offset;
> +	off_t cap_offset;
> 
> -	/* read PCI capability pointer from config space */
> -	ret = rte_pci_read_config(dev, &reg, sizeof(reg),
> PCI_CAPABILITY_LIST);
> -	if (ret != sizeof(reg)) {
> -		RTE_LOG(ERR, EAL,
> -			"Cannot read capability pointer from PCI config
> space!\n");
> +	cap_offset = rte_pci_find_capability(dev, PCI_CAP_ID_MSIX);

I notice in some cases we use rte_pci_has_capability_list() to check first,
then looking for specific cap, in other cases we don't use
rte_pci_has_capability_list(). Since we define this API, should we always do
the check?


> +	if (cap_offset < 0)
>  		return -1;
> -	}
> 
> -	/* we need first byte */
> -	cap_offset = reg & 0xFF;
> +	if (cap_offset != 0) {
> +		uint16_t flags;
> +		uint32_t reg;
> 
> -	while (cap_offset) {
> -
> -		/* read PCI capability ID */
> -		ret = rte_pci_read_config(dev, &reg, sizeof(reg), cap_offset);
> -		if (ret != sizeof(reg)) {
> +		/* table offset resides in the next 4 bytes */
> +		if (rte_pci_read_config(dev, &reg, sizeof(reg), cap_offset + 4)
> < 0) {
>  			RTE_LOG(ERR, EAL,
> -				"Cannot read capability ID from PCI config
> space!\n");
> +				"Cannot read MSIX table from PCI config space!\n");
>  			return -1;
>  		}
> 
> -		/* we need first byte */
> -		cap_id = reg & 0xFF;
> -
> -		/* if we haven't reached MSI-X, check next capability */
> -		if (cap_id != PCI_CAP_ID_MSIX) {
> -			ret = rte_pci_read_config(dev, &reg, sizeof(reg),
> cap_offset);
> -			if (ret != sizeof(reg)) {
> -				RTE_LOG(ERR, EAL,
> -					"Cannot read capability pointer from PCI
> config space!\n");
> -				return -1;
> -			}
> -
> -			/* we need second byte */
> -			cap_offset = (reg & 0xFF00) >> 8;
> -
> -			continue;
> +		if (rte_pci_read_config(dev, &flags, sizeof(flags), cap_offset
> + 2) < 0) {
> +			RTE_LOG(ERR, EAL,
> +				"Cannot read MSIX flags from PCI config space!\n");
> +			return -1;
>  		}
> -		/* else, read table offset */
> -		else {
> -			/* table offset resides in the next 4 bytes */
> -			ret = rte_pci_read_config(dev, &reg, sizeof(reg),
> cap_offset + 4);
> -			if (ret != sizeof(reg)) {
> -				RTE_LOG(ERR, EAL,
> -					"Cannot read table offset from PCI config
> space!\n");
> -				return -1;
> -			}
> -
> -			ret = rte_pci_read_config(dev, &flags, sizeof(flags),
> cap_offset + 2);
> -			if (ret != sizeof(flags)) {
> -				RTE_LOG(ERR, EAL,
> -					"Cannot read table flags from PCI config
> space!\n");
> -				return -1;
> -			}
> -
> -			msix_table->bar_index = reg & RTE_PCI_MSIX_TABLE_BIR;
> -			msix_table->offset = reg & RTE_PCI_MSIX_TABLE_OFFSET;
> -			msix_table->size =
> -				16 * (1 + (flags & RTE_PCI_MSIX_FLAGS_QSIZE));
> 
> -			return 0;
> -		}
> +		msix_table->bar_index = reg & RTE_PCI_MSIX_TABLE_BIR;
> +		msix_table->offset = reg & RTE_PCI_MSIX_TABLE_OFFSET;
> +		msix_table->size = 16 * (1 + (flags &
> RTE_PCI_MSIX_FLAGS_QSIZE));
>  	}
> +
>  	return 0;
>  }
> 
> diff --git a/drivers/bus/pci/pci_common.c b/drivers/bus/pci/pci_common.c
> index 382b0b8946..52272617eb 100644
> --- a/drivers/bus/pci/pci_common.c
> +++ b/drivers/bus/pci/pci_common.c
> @@ -813,6 +813,51 @@ rte_pci_get_iommu_class(void)
>  	return iova_mode;
>  }
> 
> +bool
> +rte_pci_has_capability_list(const struct rte_pci_device *dev)
> +{
> +	uint16_t status;
> +
> +	if (rte_pci_read_config(dev, &status, sizeof(status),
> RTE_PCI_STATUS) != sizeof(status))
> +		return false;
> +
> +	return (status & RTE_PCI_STATUS_CAP_LIST) != 0;
> +}
> +
> +off_t
> +rte_pci_find_capability(const struct rte_pci_device *dev, uint8_t cap)
> +{
> +	off_t offset;
> +	uint8_t pos;
> +	int ttl;
> +
> +	offset = RTE_PCI_CAPABILITY_LIST;
> +	ttl = (RTE_PCI_CFG_SPACE_SIZE - RTE_PCI_STD_HEADER_SIZEOF) /
> RTE_PCI_CAP_SIZEOF;
> +
> +	if (rte_pci_read_config(dev, &pos, sizeof(pos), offset) < 0)
> +		return -1;
> +
> +	while (pos && ttl--) {
> +		uint16_t ent;
> +		uint8_t id;
> +
> +		offset = pos;
> +		if (rte_pci_read_config(dev, &ent, sizeof(ent), offset) < 0)
> +			return -1;
> +
> +		id = ent & 0xff;
> +		if (id == 0xff)
> +			break;
> +
> +		if (id == cap)
> +			return offset;
> +
> +		pos = (ent >> 8);
> +	}
> +
> +	return 0;
> +}
> +
>  off_t
>  rte_pci_find_ext_capability(const struct rte_pci_device *dev, uint32_t
> cap)
>  {
> diff --git a/drivers/bus/pci/rte_bus_pci.h b/drivers/bus/pci/rte_bus_pci.h
> index 75d0030eae..1ed33dbf3d 100644
> --- a/drivers/bus/pci/rte_bus_pci.h
> +++ b/drivers/bus/pci/rte_bus_pci.h
> @@ -68,6 +68,37 @@ void rte_pci_unmap_device(struct rte_pci_device *dev);
>   */
>  void rte_pci_dump(FILE *f);
> 
> +/**
> + * Check whether this device has a PCI capability list.
> + *
> + *  @param dev
> + *    A pointer to rte_pci_device structure.
> + *
> + *  @return
> + *    true/false
> + */
> +__rte_experimental
> +bool rte_pci_has_capability_list(const struct rte_pci_device *dev);
> +
> +/**
> + * Find device's PCI capability.
> + *
> + *  @param dev
> + *    A pointer to rte_pci_device structure.
> + *
> + *  @param cap
> + *    Capability to be found, which can be any from
> + *    RTE_PCI_CAP_ID_*, defined in librte_pci.
> + *
> + *  @return
> + *  > 0: The offset of the next matching capability structure
> + *       within the device's PCI configuration space.
> + *  < 0: An error in PCI config space read.
> + *  = 0: Device does not support it.
> + */
> +__rte_experimental
> +off_t rte_pci_find_capability(const struct rte_pci_device *dev, uint8_t
> cap);
> +
>  /**
>   * Find device's extended PCI capability.
>   *
> diff --git a/drivers/bus/pci/version.map b/drivers/bus/pci/version.map
> index a0000f7938..2674f30235 100644
> --- a/drivers/bus/pci/version.map
> +++ b/drivers/bus/pci/version.map
> @@ -25,6 +25,10 @@ EXPERIMENTAL {
>  	# added in 23.07
>  	rte_pci_mmio_read;
>  	rte_pci_mmio_write;
> +
> +	# added in 23.11
> +	rte_pci_find_capability;
> +	rte_pci_has_capability_list;
>  };
> 
>  INTERNAL {
> diff --git a/drivers/crypto/virtio/virtio_pci.c
> b/drivers/crypto/virtio/virtio_pci.c
> index 95a43c8801..abc52b4701 100644
> --- a/drivers/crypto/virtio/virtio_pci.c
> +++ b/drivers/crypto/virtio/virtio_pci.c
> @@ -19,7 +19,6 @@
>   * we can't simply include that header here, as there is no such
>   * file for non-Linux platform.
>   */
> -#define PCI_CAPABILITY_LIST	0x34
>  #define PCI_CAP_ID_VNDR		0x09
>  #define PCI_CAP_ID_MSIX		0x11
> 
> @@ -343,8 +342,9 @@ get_cfg_addr(struct rte_pci_device *dev, struct
> virtio_pci_cap *cap)
>  static int
>  virtio_read_caps(struct rte_pci_device *dev, struct virtio_crypto_hw *hw)
>  {
> -	uint8_t pos;
>  	struct virtio_pci_cap cap;
> +	uint16_t flags;
> +	off_t pos;
>  	int ret;
> 
>  	if (rte_pci_map_device(dev)) {
> @@ -352,44 +352,26 @@ virtio_read_caps(struct rte_pci_device *dev, struct
> virtio_crypto_hw *hw)
>  		return -1;
>  	}
> 
> -	ret = rte_pci_read_config(dev, &pos, 1, PCI_CAPABILITY_LIST);
> -	if (ret < 0) {
> -		VIRTIO_CRYPTO_INIT_LOG_DBG("failed to read pci capability
> list");
> -		return -1;
> +	/*
> +	 * Transitional devices would also have this capability,
> +	 * that's why we also check if msix is enabled.
> +	 */
> +	pos = rte_pci_find_capability(dev, PCI_CAP_ID_MSIX);
> +	if (pos > 0 && rte_pci_read_config(dev, &flags, sizeof(flags),
> +			pos + 2) == sizeof(flags)) {
> +		if (flags & PCI_MSIX_ENABLE)
> +			hw->use_msix = VIRTIO_MSIX_ENABLED;
> +		else
> +			hw->use_msix = VIRTIO_MSIX_DISABLED;
> +	} else {
> +		hw->use_msix = VIRTIO_MSIX_NONE;
>  	}
> 
> -	while (pos) {
> -		ret = rte_pci_read_config(dev, &cap, sizeof(cap), pos);
> -		if (ret < 0) {
> -			VIRTIO_CRYPTO_INIT_LOG_ERR(
> -				"failed to read pci cap at pos: %x", pos);
> -			break;
> -		}
> -
> -		if (cap.cap_vndr == PCI_CAP_ID_MSIX) {
> -			/* Transitional devices would also have this capability,
> -			 * that's why we also check if msix is enabled.
> -			 * 1st byte is cap ID; 2nd byte is the position of next
> -			 * cap; next two bytes are the flags.
> -			 */
> -			uint16_t flags = ((uint16_t *)&cap)[1];
> -
> -			if (flags & PCI_MSIX_ENABLE)
> -				hw->use_msix = VIRTIO_MSIX_ENABLED;
> -			else
> -				hw->use_msix = VIRTIO_MSIX_DISABLED;
> -		}
> -
> -		if (cap.cap_vndr != PCI_CAP_ID_VNDR) {
> -			VIRTIO_CRYPTO_INIT_LOG_DBG(
> -				"[%2x] skipping non VNDR cap id: %02x",
> -				pos, cap.cap_vndr);
> -			goto next;
> -		}
> -
> +	pos = rte_pci_find_capability(dev, PCI_CAP_ID_VNDR);

The logic of vendor cap init seems incorrect. Virtio devices have multiple
Vendor cap (different cfg type). But now the logic seems to only init the first
one.

> +	if (pos > 0 && rte_pci_read_config(dev, &cap, sizeof(cap), pos) ==
> sizeof(cap)) {
>  		VIRTIO_CRYPTO_INIT_LOG_DBG(
>  			"[%2x] cfg type: %u, bar: %u, offset: %04x, len: %u",
> -			pos, cap.cfg_type, cap.bar, cap.offset, cap.length);
> +			(unsigned int)pos, cap.cfg_type, cap.bar, cap.offset,
> cap.length);
> 
>  		switch (cap.cfg_type) {
>  		case VIRTIO_PCI_CAP_COMMON_CFG:
> @@ -411,9 +393,6 @@ virtio_read_caps(struct rte_pci_device *dev, struct
> virtio_crypto_hw *hw)
>  			hw->isr = get_cfg_addr(dev, &cap);
>  			break;
>  		}
> -
> -next:
> -		pos = cap.cap_next;
>  	}

...

> diff --git a/drivers/net/virtio/virtio_pci.c
> b/drivers/net/virtio/virtio_pci.c
> index 29eb739b04..9fd9db3e03 100644
> --- a/drivers/net/virtio/virtio_pci.c
> +++ b/drivers/net/virtio/virtio_pci.c
> @@ -20,7 +20,6 @@
>   * we can't simply include that header here, as there is no such
>   * file for non-Linux platform.
>   */
> -#define PCI_CAPABILITY_LIST	0x34
>  #define PCI_CAP_ID_VNDR		0x09
>  #define PCI_CAP_ID_MSIX		0x11
> 
> @@ -38,46 +37,16 @@ struct virtio_pci_internal
> virtio_pci_internal[RTE_MAX_ETHPORTS];
>  static enum virtio_msix_status
>  vtpci_msix_detect(struct rte_pci_device *dev)
>  {
> -	uint8_t pos;
> -	int ret;
> +	uint16_t flags;
> +	off_t pos;
> 
> -	ret = rte_pci_read_config(dev, &pos, 1, PCI_CAPABILITY_LIST);
> -	if (ret != 1) {
> -		PMD_INIT_LOG(DEBUG,
> -			     "failed to read pci capability list, ret %d", ret);
> -		return VIRTIO_MSIX_NONE;
> -	}
> -
> -	while (pos) {
> -		uint8_t cap[2];
> -
> -		ret = rte_pci_read_config(dev, cap, sizeof(cap), pos);
> -		if (ret != sizeof(cap)) {
> -			PMD_INIT_LOG(DEBUG,
> -				     "failed to read pci cap at pos: %x ret %d",
> -				     pos, ret);
> -			break;
> -		}
> -
> -		if (cap[0] == PCI_CAP_ID_MSIX) {
> -			uint16_t flags;
> -
> -			ret = rte_pci_read_config(dev, &flags, sizeof(flags),
> -					pos + sizeof(cap));
> -			if (ret != sizeof(flags)) {
> -				PMD_INIT_LOG(DEBUG,
> -					     "failed to read pci cap at pos:"
> -					     " %x ret %d", pos + 2, ret);
> -				break;
> -			}
> -
> -			if (flags & PCI_MSIX_ENABLE)
> -				return VIRTIO_MSIX_ENABLED;
> -			else
> -				return VIRTIO_MSIX_DISABLED;
> -		}
> -
> -		pos = cap[1];
> +	pos = rte_pci_find_capability(dev, PCI_CAP_ID_MSIX);
> +	if (pos > 0 && rte_pci_read_config(dev, &flags, sizeof(flags),
> +			pos + 2) == sizeof(flags)) {
> +		if (flags & PCI_MSIX_ENABLE)
> +			return VIRTIO_MSIX_ENABLED;
> +		else
> +			return VIRTIO_MSIX_DISABLED;
>  	}
> 
>  	return VIRTIO_MSIX_NONE;
> @@ -623,8 +592,8 @@ static int
>  virtio_read_caps(struct rte_pci_device *pci_dev, struct virtio_hw *hw)
>  {
>  	struct virtio_pci_dev *dev = virtio_pci_get_dev(hw);
> -	uint8_t pos;
>  	struct virtio_pci_cap cap;
> +	off_t pos;
>  	int ret;
> 
>  	if (rte_pci_map_device(pci_dev)) {
> @@ -632,72 +601,25 @@ virtio_read_caps(struct rte_pci_device *pci_dev,
> struct virtio_hw *hw)
>  		return -1;
>  	}
> 
> -	ret = rte_pci_read_config(pci_dev, &pos, 1, PCI_CAPABILITY_LIST);
> -	if (ret != 1) {
> -		PMD_INIT_LOG(DEBUG,
> -			     "failed to read pci capability list, ret %d", ret);
> -		return -1;
> -	}
> -
> -	while (pos) {
> -		ret = rte_pci_read_config(pci_dev, &cap, 2, pos);
> -		if (ret != 2) {
> -			PMD_INIT_LOG(DEBUG,
> -				     "failed to read pci cap at pos: %x ret %d",
> -				     pos, ret);
> -			break;
> -		}
> -
> -		if (cap.cap_vndr == PCI_CAP_ID_MSIX) {
> -			/* Transitional devices would also have this capability,
> -			 * that's why we also check if msix is enabled.
> -			 * 1st byte is cap ID; 2nd byte is the position of next
> -			 * cap; next two bytes are the flags.
> -			 */
> -			uint16_t flags;
> -
> -			ret = rte_pci_read_config(pci_dev, &flags, sizeof(flags),
> -					pos + 2);
> -			if (ret != sizeof(flags)) {
> -				PMD_INIT_LOG(DEBUG,
> -					     "failed to read pci cap at pos:"
> -					     " %x ret %d", pos + 2, ret);
> -				break;
> -			}
> -
> -			if (flags & PCI_MSIX_ENABLE)
> -				dev->msix_status = VIRTIO_MSIX_ENABLED;
> -			else
> -				dev->msix_status = VIRTIO_MSIX_DISABLED;
> -		}
> -
> -		if (cap.cap_vndr != PCI_CAP_ID_VNDR) {
> -			PMD_INIT_LOG(DEBUG,
> -				"[%2x] skipping non VNDR cap id: %02x",
> -				pos, cap.cap_vndr);
> -			goto next;
> -		}
> -
> -		ret = rte_pci_read_config(pci_dev, &cap, sizeof(cap), pos);
> -		if (ret != sizeof(cap)) {
> -			PMD_INIT_LOG(DEBUG,
> -				     "failed to read pci cap at pos: %x ret %d",
> -				     pos, ret);
> -			break;
> -		}
> +	/*
> +	 * Transitional devices would also have this capability,
> +	 * that's why we also check if msix is enabled.
> +	 */
> +	dev->msix_status = vtpci_msix_detect(pci_dev);
> 
> +	pos = rte_pci_find_capability(pci_dev, PCI_CAP_ID_VNDR);
> +	if (pos > 0 && rte_pci_read_config(pci_dev, &cap, sizeof(cap), pos)
> == sizeof(cap)) {
>  		PMD_INIT_LOG(DEBUG,
>  			"[%2x] cfg type: %u, bar: %u, offset: %04x, len: %u",
> -			pos, cap.cfg_type, cap.bar, cap.offset, cap.length);
> +			(unsigned int)pos, cap.cfg_type, cap.bar, cap.offset,
> cap.length);
> 

Same comment about the vendor cap.

Thanks,
Chenbo

>  		switch (cap.cfg_type) {
>  		case VIRTIO_PCI_CAP_COMMON_CFG:
>  			dev->common_cfg = get_cfg_addr(pci_dev, &cap);
>  			break;
>  		case VIRTIO_PCI_CAP_NOTIFY_CFG:
> -			ret = rte_pci_read_config(pci_dev,
> -					&dev->notify_off_multiplier,
> -					4, pos + sizeof(cap));
> +			ret = rte_pci_read_config(pci_dev, &dev-
> >notify_off_multiplier,
> +				4, pos + sizeof(cap));
>  			if (ret != 4)
>  				PMD_INIT_LOG(DEBUG,
>  					"failed to read notify_off_multiplier,
> ret %d",
> @@ -712,9 +634,6 @@ virtio_read_caps(struct rte_pci_device *pci_dev,
> struct virtio_hw *hw)
>  			dev->isr = get_cfg_addr(pci_dev, &cap);
>  			break;
>  		}
> -
> -next:
> -		pos = cap.cap_next;
>  	}
> 
>  	if (dev->common_cfg == NULL || dev->notify_base == NULL ||
> diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
> index aab761b918..49fd5b1d02 100644
> --- a/lib/pci/rte_pci.h
> +++ b/lib/pci/rte_pci.h
> @@ -28,13 +28,24 @@ extern "C" {
>  #define RTE_PCI_CFG_SPACE_SIZE		256
>  #define RTE_PCI_CFG_SPACE_EXP_SIZE	4096
> 
> +#define RTE_PCI_STD_HEADER_SIZEOF	64
> +
> +/* Standard register offsets in the PCI configuration space */
>  #define RTE_PCI_VENDOR_ID	0x00	/* 16 bits */
>  #define RTE_PCI_DEVICE_ID	0x02	/* 16 bits */
>  #define RTE_PCI_COMMAND		0x04	/* 16 bits */
> +#define RTE_PCI_STATUS		0x06	/* 16 bits */
> +#define RTE_PCI_CAPABILITY_LIST	0x34	/* 32 bits */
> 
>  /* PCI Command Register */
>  #define RTE_PCI_COMMAND_MASTER	0x4	/* Bus Master Enable */
> 
> +/* PCI Status Register (RTE_PCI_STATUS) */
> +#define RTE_PCI_STATUS_CAP_LIST		0x10	/* Support Capability List
> */
> +
> +/* Capability registers (RTE_PCI_CAPABILITY_LIST) */
> +#define RTE_PCI_CAP_SIZEOF		4
> +
>  /* PCI Express capability registers */
>  #define RTE_PCI_EXP_DEVCTL	8	/* Device Control */
> 
> --
> 2.41.0


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

* RE: [PATCH v2 05/15] pci: define some capability constants
  2023-08-21 11:35   ` [PATCH v2 05/15] pci: define some capability constants David Marchand
@ 2023-09-07 13:15     ` Xia, Chenbo
  0 siblings, 0 replies; 98+ messages in thread
From: Xia, Chenbo @ 2023-09-07 13:15 UTC (permalink / raw)
  To: David Marchand, dev
  Cc: thomas, ferruh.yigit, nipun.gupta, Richardson, Bruce, Burakov,
	Anatoly, Jay Zhou, McDaniel, Timothy, Julien Aube,
	Rahul Lakkireddy, Guo, Junfeng, Jeroen de Borst, Rushil Gupta,
	Joshua Washington, Dongdong Liu, Yisen Zhuang, Maxime Coquelin,
	Wang, Xiao W, Gaetan Rivet

> -----Original Message-----
> From: David Marchand <david.marchand@redhat.com>
> Sent: Monday, August 21, 2023 7:36 PM
> To: dev@dpdk.org
> Cc: thomas@monjalon.net; ferruh.yigit@amd.com; Xia, Chenbo
> <chenbo.xia@intel.com>; nipun.gupta@amd.com; Richardson, Bruce
> <bruce.richardson@intel.com>; Burakov, Anatoly <anatoly.burakov@intel.com>;
> Jay Zhou <jianjay.zhou@huawei.com>; McDaniel, Timothy
> <timothy.mcdaniel@intel.com>; Julien Aube <julien_dpdk@jaube.fr>; Rahul
> Lakkireddy <rahul.lakkireddy@chelsio.com>; Guo, Junfeng
> <junfeng.guo@intel.com>; Jeroen de Borst <jeroendb@google.com>; Rushil
> Gupta <rushilg@google.com>; Joshua Washington <joshwash@google.com>;
> Dongdong Liu <liudongdong3@huawei.com>; Yisen Zhuang
> <yisen.zhuang@huawei.com>; Maxime Coquelin <maxime.coquelin@redhat.com>;
> Wang, Xiao W <xiao.w.wang@intel.com>; Gaetan Rivet <grive@u256.net>
> Subject: [PATCH v2 05/15] pci: define some capability constants
> 
> Define some PCI capability constants and use them in existing drivers.
> 
> Signed-off-by: David Marchand <david.marchand@redhat.com>
> Acked-by: Bruce Richardson <bruce.richardson@intel.com>
> ---
>  drivers/bus/pci/linux/pci_vfio.c    |  2 +-
>  drivers/crypto/virtio/virtio_pci.c  | 12 ++----------
>  drivers/event/dlb2/pf/dlb2_main.c   |  6 ++----
>  drivers/net/bnx2x/bnx2x.c           | 16 ++++++++--------
>  drivers/net/bnx2x/bnx2x.h           |  4 ----
>  drivers/net/cxgbe/base/adapter.h    |  3 +--
>  drivers/net/gve/gve_ethdev.c        |  2 +-
>  drivers/net/gve/gve_ethdev.h        |  2 +-
>  drivers/net/hns3/hns3_ethdev_vf.c   |  2 +-
>  drivers/net/virtio/virtio_pci.c     | 12 ++----------
>  drivers/vdpa/ifc/base/ifcvf_osdep.h |  4 +++-
>  lib/pci/rte_pci.h                   |  5 +++++
>  12 files changed, 27 insertions(+), 43 deletions(-)
> 
> diff --git a/drivers/bus/pci/linux/pci_vfio.c
> b/drivers/bus/pci/linux/pci_vfio.c
> index 614ed5d696..bfedbc1bed 100644
> --- a/drivers/bus/pci/linux/pci_vfio.c
> +++ b/drivers/bus/pci/linux/pci_vfio.c
> @@ -112,7 +112,7 @@ pci_vfio_get_msix_bar(const struct rte_pci_device *dev,
>  {
>  	off_t cap_offset;
> 
> -	cap_offset = rte_pci_find_capability(dev, PCI_CAP_ID_MSIX);
> +	cap_offset = rte_pci_find_capability(dev, RTE_PCI_CAP_ID_MSIX);
>  	if (cap_offset < 0)
>  		return -1;
> 
> diff --git a/drivers/crypto/virtio/virtio_pci.c
> b/drivers/crypto/virtio/virtio_pci.c
> index abc52b4701..9e340f2b0d 100644
> --- a/drivers/crypto/virtio/virtio_pci.c
> +++ b/drivers/crypto/virtio/virtio_pci.c
> @@ -14,14 +14,6 @@
>  #include "virtio_pci.h"
>  #include "virtqueue.h"
> 
> -/*
> - * Following macros are derived from linux/pci_regs.h, however,
> - * we can't simply include that header here, as there is no such
> - * file for non-Linux platform.
> - */
> -#define PCI_CAP_ID_VNDR		0x09
> -#define PCI_CAP_ID_MSIX		0x11
> -
>  /*
>   * The remaining space is defined by each driver as the per-driver
>   * configuration space.
> @@ -356,7 +348,7 @@ virtio_read_caps(struct rte_pci_device *dev, struct
> virtio_crypto_hw *hw)
>  	 * Transitional devices would also have this capability,
>  	 * that's why we also check if msix is enabled.
>  	 */
> -	pos = rte_pci_find_capability(dev, PCI_CAP_ID_MSIX);
> +	pos = rte_pci_find_capability(dev, RTE_PCI_CAP_ID_MSIX);
>  	if (pos > 0 && rte_pci_read_config(dev, &flags, sizeof(flags),
>  			pos + 2) == sizeof(flags)) {
>  		if (flags & PCI_MSIX_ENABLE)
> @@ -367,7 +359,7 @@ virtio_read_caps(struct rte_pci_device *dev, struct
> virtio_crypto_hw *hw)
>  		hw->use_msix = VIRTIO_MSIX_NONE;
>  	}
> 
> -	pos = rte_pci_find_capability(dev, PCI_CAP_ID_VNDR);
> +	pos = rte_pci_find_capability(dev, RTE_PCI_CAP_ID_VNDR);
>  	if (pos > 0 && rte_pci_read_config(dev, &cap, sizeof(cap), pos) ==
> sizeof(cap)) {
>  		VIRTIO_CRYPTO_INIT_LOG_DBG(
>  			"[%2x] cfg type: %u, bar: %u, offset: %04x, len: %u",
> diff --git a/drivers/event/dlb2/pf/dlb2_main.c
> b/drivers/event/dlb2/pf/dlb2_main.c
> index 40e5cb594f..1a229baee0 100644
> --- a/drivers/event/dlb2/pf/dlb2_main.c
> +++ b/drivers/event/dlb2/pf/dlb2_main.c
> @@ -38,8 +38,6 @@
>  #define DLB2_PCI_EXP_DEVSTA_TRPND 0x20
>  #define DLB2_PCI_EXP_DEVCTL_BCR_FLR 0x8000
> 
> -#define DLB2_PCI_CAP_ID_EXP       0x10
> -#define DLB2_PCI_CAP_ID_MSIX      0x11
>  #define DLB2_PCI_EXT_CAP_ID_PRI   0x13
>  #define DLB2_PCI_EXT_CAP_ID_ACS   0xD
> 
> @@ -244,7 +242,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
>  			return ret;
>  	}
> 
> -	pcie_cap_offset = rte_pci_find_capability(pdev, DLB2_PCI_CAP_ID_EXP);
> +	pcie_cap_offset = rte_pci_find_capability(pdev, RTE_PCI_CAP_ID_EXP);
> 
>  	if (pcie_cap_offset < 0) {
>  		DLB2_LOG_ERR("[%s()] failed to find the pcie capability\n",
> @@ -483,7 +481,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
>  		}
>  	}
> 
> -	msix_cap_offset = rte_pci_find_capability(pdev,
> DLB2_PCI_CAP_ID_MSIX);
> +	msix_cap_offset = rte_pci_find_capability(pdev, RTE_PCI_CAP_ID_MSIX);
>  	if (msix_cap_offset >= 0) {
>  		off = msix_cap_offset + DLB2_PCI_MSIX_FLAGS;
>  		if (rte_pci_read_config(pdev, &cmd, 2, off) == 2) {
> diff --git a/drivers/net/bnx2x/bnx2x.c b/drivers/net/bnx2x/bnx2x.c
> index 06f2949885..8a97de8806 100644
> --- a/drivers/net/bnx2x/bnx2x.c
> +++ b/drivers/net/bnx2x/bnx2x.c
> @@ -7613,7 +7613,7 @@ static uint32_t bnx2x_pcie_capability_read(struct
> bnx2x_softc *sc, int reg)
>  	struct bnx2x_pci_cap *caps;
> 
>  	/* ensure PCIe capability is enabled */
> -	caps = pci_find_cap(sc, PCIY_EXPRESS, BNX2X_PCI_CAP);
> +	caps = pci_find_cap(sc, RTE_PCI_CAP_ID_EXP, BNX2X_PCI_CAP);
>  	if (NULL != caps) {
>  		PMD_DRV_LOG(DEBUG, sc, "Found PCIe capability: "
>  			    "id=0x%04X type=0x%04X addr=0x%08X",
> @@ -7647,7 +7647,7 @@ static void bnx2x_probe_pci_caps(struct bnx2x_softc
> *sc)
>  	int reg = 0;
> 
>  	/* check if PCI Power Management is enabled */
> -	caps = pci_find_cap(sc, PCIY_PMG, BNX2X_PCI_CAP);
> +	caps = pci_find_cap(sc, RTE_PCI_CAP_ID_PM, BNX2X_PCI_CAP);
>  	if (NULL != caps) {
>  		PMD_DRV_LOG(DEBUG, sc, "Found PM capability: "
>  			    "id=0x%04X type=0x%04X addr=0x%08X",
> @@ -7669,7 +7669,7 @@ static void bnx2x_probe_pci_caps(struct bnx2x_softc
> *sc)
>  	sc->devinfo.pcie_cap_flags |= BNX2X_PCIE_CAPABLE_FLAG;
> 
>  	/* check if MSI capability is enabled */
> -	caps = pci_find_cap(sc, PCIY_MSI, BNX2X_PCI_CAP);
> +	caps = pci_find_cap(sc, RTE_PCI_CAP_ID_MSI, BNX2X_PCI_CAP);
>  	if (NULL != caps) {
>  		PMD_DRV_LOG(DEBUG, sc, "Found MSI capability at 0x%04x", reg);
> 
> @@ -7678,7 +7678,7 @@ static void bnx2x_probe_pci_caps(struct bnx2x_softc
> *sc)
>  	}
> 
>  	/* check if MSI-X capability is enabled */
> -	caps = pci_find_cap(sc, PCIY_MSIX, BNX2X_PCI_CAP);
> +	caps = pci_find_cap(sc, RTE_PCI_CAP_ID_MSIX, BNX2X_PCI_CAP);
>  	if (NULL != caps) {
>  		PMD_DRV_LOG(DEBUG, sc, "Found MSI-X capability at 0x%04x",
> reg);
> 
> @@ -9587,10 +9587,10 @@ static void bnx2x_init_multi_cos(struct
> bnx2x_softc *sc)
>  }
> 
>  static uint8_t bnx2x_pci_capabilities[] = {
> -	PCIY_EXPRESS,
> -	PCIY_PMG,
> -	PCIY_MSI,
> -	PCIY_MSIX,
> +	RTE_PCI_CAP_ID_EXP,
> +	RTE_PCI_CAP_ID_PM,
> +	RTE_PCI_CAP_ID_MSI,
> +	RTE_PCI_CAP_ID_MSIX,
>  };
> 
>  static int bnx2x_pci_get_caps(struct bnx2x_softc *sc)
> diff --git a/drivers/net/bnx2x/bnx2x.h b/drivers/net/bnx2x/bnx2x.h
> index 89414ac88a..07ef0567c2 100644
> --- a/drivers/net/bnx2x/bnx2x.h
> +++ b/drivers/net/bnx2x/bnx2x.h
> @@ -33,10 +33,6 @@
>  #ifndef RTE_EXEC_ENV_FREEBSD
>  #include <linux/pci_regs.h>
> 
> -#define PCIY_PMG                       PCI_CAP_ID_PM
> -#define PCIY_MSI                       PCI_CAP_ID_MSI
> -#define PCIY_EXPRESS                   PCI_CAP_ID_EXP
> -#define PCIY_MSIX                      PCI_CAP_ID_MSIX
>  #define PCIR_EXPRESS_DEVICE_STA        PCI_EXP_TYPE_RC_EC
>  #define PCIM_EXP_STA_TRANSACTION_PND   PCI_EXP_DEVSTA_TRPND
>  #define PCIR_EXPRESS_LINK_STA          PCI_EXP_LNKSTA
> diff --git a/drivers/net/cxgbe/base/adapter.h
> b/drivers/net/cxgbe/base/adapter.h
> index 00d7591ea4..7bee5cf3a8 100644
> --- a/drivers/net/cxgbe/base/adapter.h
> +++ b/drivers/net/cxgbe/base/adapter.h
> @@ -511,8 +511,7 @@ static inline void t4_write_reg64(struct adapter
> *adapter, u32 reg_addr,
>  	CXGBE_WRITE_REG64(adapter, reg_addr, val);
>  }
> 
> -/* Offset of first capability list entry */
> -#define PCI_CAP_ID_EXP          0x10    /* PCI Express */
> +#define PCI_CAP_ID_EXP          RTE_PCI_CAP_ID_EXP
>  #define PCI_EXP_DEVCTL          0x0008  /* Device control */
>  #define PCI_EXP_DEVCTL2         40      /* Device Control 2 */
>  #define PCI_EXP_DEVCTL_EXT_TAG  0x0100  /* Extended Tag Field Enable */
> diff --git a/drivers/net/gve/gve_ethdev.c b/drivers/net/gve/gve_ethdev.c
> index c276b9e68e..9ea5dbaeea 100644
> --- a/drivers/net/gve/gve_ethdev.c
> +++ b/drivers/net/gve/gve_ethdev.c
> @@ -609,7 +609,7 @@ gve_teardown_device_resources(struct gve_priv *priv)
>  static int
>  pci_dev_msix_vec_count(struct rte_pci_device *pdev)
>  {
> -	off_t msix_pos = rte_pci_find_capability(pdev, PCI_CAP_ID_MSIX);
> +	off_t msix_pos = rte_pci_find_capability(pdev, RTE_PCI_CAP_ID_MSIX);
>  	uint16_t control;
> 
>  	if (msix_pos > 0 && rte_pci_read_config(pdev, &control,
> sizeof(control),
> diff --git a/drivers/net/gve/gve_ethdev.h b/drivers/net/gve/gve_ethdev.h
> index 8759b1c76e..d604a75b7f 100644
> --- a/drivers/net/gve/gve_ethdev.h
> +++ b/drivers/net/gve/gve_ethdev.h
> @@ -8,6 +8,7 @@
>  #include <ethdev_driver.h>
>  #include <ethdev_pci.h>
>  #include <rte_ether.h>
> +#include <rte_pci.h>
> 
>  #include "base/gve.h"
> 
> @@ -19,7 +20,6 @@
>   * we can't simply include that header here, as there is no such
>   * file for non-Linux platform.
>   */
> -#define PCI_CAP_ID_MSIX		0x11	/* MSI-X */
>  #define PCI_MSIX_FLAGS		2	/* Message Control */
>  #define PCI_MSIX_FLAGS_QSIZE	0x07FF	/* Table size */
> 
> diff --git a/drivers/net/hns3/hns3_ethdev_vf.c
> b/drivers/net/hns3/hns3_ethdev_vf.c
> index b731850b01..eab5c55f5e 100644
> --- a/drivers/net/hns3/hns3_ethdev_vf.c
> +++ b/drivers/net/hns3/hns3_ethdev_vf.c
> @@ -61,7 +61,7 @@ hns3vf_enable_msix(const struct rte_pci_device *device,
> bool op)
>  		return 0;
>  	}
> 
> -	pos = rte_pci_find_capability(device, PCI_CAP_ID_MSIX);
> +	pos = rte_pci_find_capability(device, RTE_PCI_CAP_ID_MSIX);
>  	if (pos > 0) {
>  		ret = rte_pci_read_config(device, &control, sizeof(control),
>  			pos + PCI_MSIX_FLAGS);
> diff --git a/drivers/net/virtio/virtio_pci.c
> b/drivers/net/virtio/virtio_pci.c
> index 9fd9db3e03..81d5dd0a4a 100644
> --- a/drivers/net/virtio/virtio_pci.c
> +++ b/drivers/net/virtio/virtio_pci.c
> @@ -15,14 +15,6 @@
>  #include "virtio_logs.h"
>  #include "virtqueue.h"
> 
> -/*
> - * Following macros are derived from linux/pci_regs.h, however,
> - * we can't simply include that header here, as there is no such
> - * file for non-Linux platform.
> - */
> -#define PCI_CAP_ID_VNDR		0x09
> -#define PCI_CAP_ID_MSIX		0x11
> -
>  /*
>   * The remaining space is defined by each driver as the per-driver
>   * configuration space.
> @@ -40,7 +32,7 @@ vtpci_msix_detect(struct rte_pci_device *dev)
>  	uint16_t flags;
>  	off_t pos;
> 
> -	pos = rte_pci_find_capability(dev, PCI_CAP_ID_MSIX);
> +	pos = rte_pci_find_capability(dev, RTE_PCI_CAP_ID_MSIX);
>  	if (pos > 0 && rte_pci_read_config(dev, &flags, sizeof(flags),
>  			pos + 2) == sizeof(flags)) {
>  		if (flags & PCI_MSIX_ENABLE)
> @@ -607,7 +599,7 @@ virtio_read_caps(struct rte_pci_device *pci_dev,
> struct virtio_hw *hw)
>  	 */
>  	dev->msix_status = vtpci_msix_detect(pci_dev);
> 
> -	pos = rte_pci_find_capability(pci_dev, PCI_CAP_ID_VNDR);
> +	pos = rte_pci_find_capability(pci_dev, RTE_PCI_CAP_ID_VNDR);
>  	if (pos > 0 && rte_pci_read_config(pci_dev, &cap, sizeof(cap), pos)
> == sizeof(cap)) {
>  		PMD_INIT_LOG(DEBUG,
>  			"[%2x] cfg type: %u, bar: %u, offset: %04x, len: %u",
> diff --git a/drivers/vdpa/ifc/base/ifcvf_osdep.h
> b/drivers/vdpa/ifc/base/ifcvf_osdep.h
> index 6444d7f72c..dd2ff08f77 100644
> --- a/drivers/vdpa/ifc/base/ifcvf_osdep.h
> +++ b/drivers/vdpa/ifc/base/ifcvf_osdep.h
> @@ -6,7 +6,6 @@
>  #define _IFCVF_OSDEP_H_
> 
>  #include <stdint.h>
> -#include <linux/pci_regs.h>
> 
>  #include <rte_cycles.h>
>  #include <rte_pci.h>
> @@ -35,6 +34,9 @@ typedef struct rte_pci_device PCI_DEV;
>  #define PCI_READ_CONFIG_DWORD(dev, val, where) \
>  	rte_pci_read_config(dev, val, 4, where)
> 
> +#define PCI_CAPABILITY_LIST RTE_PCI_CAPABILITY_LIST
> +#define PCI_CAP_ID_VNDR RTE_PCI_CAP_ID_VNDR
> +
>  typedef uint8_t    u8;
>  typedef int8_t     s8;
>  typedef uint16_t   u16;
> diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
> index 49fd5b1d02..5a04a5a4b5 100644
> --- a/lib/pci/rte_pci.h
> +++ b/lib/pci/rte_pci.h
> @@ -44,6 +44,11 @@ extern "C" {
>  #define RTE_PCI_STATUS_CAP_LIST		0x10	/* Support Capability List
> */
> 
>  /* Capability registers (RTE_PCI_CAPABILITY_LIST) */
> +#define RTE_PCI_CAP_ID_PM		0x01	/* Power Management */
> +#define RTE_PCI_CAP_ID_MSI		0x05	/* Message Signalled Interrupts
> */
> +#define RTE_PCI_CAP_ID_VNDR		0x09	/* Vendor-Specific */
> +#define RTE_PCI_CAP_ID_EXP		0x10	/* PCI Express */
> +#define RTE_PCI_CAP_ID_MSIX		0x11	/* MSI-X */
>  #define RTE_PCI_CAP_SIZEOF		4
> 
>  /* PCI Express capability registers */
> --
> 2.41.0

Reviewed-by: Chenbo Xia <chenbo.xia@intel.com> 

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

* RE: [PATCH v2 06/15] pci: define some MSIX constants
  2023-08-21 11:35   ` [PATCH v2 06/15] pci: define some MSIX constants David Marchand
@ 2023-09-07 13:15     ` Xia, Chenbo
  0 siblings, 0 replies; 98+ messages in thread
From: Xia, Chenbo @ 2023-09-07 13:15 UTC (permalink / raw)
  To: David Marchand, dev
  Cc: thomas, ferruh.yigit, nipun.gupta, Richardson, Bruce, Burakov,
	Anatoly, Jay Zhou, McDaniel, Timothy, Julien Aube, Guo, Junfeng,
	Jeroen de Borst, Rushil Gupta, Joshua Washington, Dongdong Liu,
	Yisen Zhuang, Maxime Coquelin, Gaetan Rivet

> -----Original Message-----
> From: David Marchand <david.marchand@redhat.com>
> Sent: Monday, August 21, 2023 7:36 PM
> To: dev@dpdk.org
> Cc: thomas@monjalon.net; ferruh.yigit@amd.com; Xia, Chenbo
> <chenbo.xia@intel.com>; nipun.gupta@amd.com; Richardson, Bruce
> <bruce.richardson@intel.com>; Burakov, Anatoly <anatoly.burakov@intel.com>;
> Jay Zhou <jianjay.zhou@huawei.com>; McDaniel, Timothy
> <timothy.mcdaniel@intel.com>; Julien Aube <julien_dpdk@jaube.fr>; Guo,
> Junfeng <junfeng.guo@intel.com>; Jeroen de Borst <jeroendb@google.com>;
> Rushil Gupta <rushilg@google.com>; Joshua Washington <joshwash@google.com>;
> Dongdong Liu <liudongdong3@huawei.com>; Yisen Zhuang
> <yisen.zhuang@huawei.com>; Maxime Coquelin <maxime.coquelin@redhat.com>;
> Gaetan Rivet <grive@u256.net>
> Subject: [PATCH v2 06/15] pci: define some MSIX constants
> 
> Define some PCI MSIX constants and use them in existing drivers.
> 
> Signed-off-by: David Marchand <david.marchand@redhat.com>
> Acked-by: Bruce Richardson <bruce.richardson@intel.com>
> ---
>  drivers/bus/pci/linux/pci_init.h   | 18 ------------------
>  drivers/bus/pci/linux/pci_vfio.c   |  7 ++++---
>  drivers/crypto/virtio/virtio_pci.c |  6 ++----
>  drivers/event/dlb2/pf/dlb2_main.c  | 13 +++++--------
>  drivers/net/bnx2x/bnx2x.c          |  4 ++--
>  drivers/net/bnx2x/bnx2x.h          |  2 --
>  drivers/net/gve/gve_ethdev.c       |  4 ++--
>  drivers/net/gve/gve_ethdev.h       |  8 --------
>  drivers/net/hns3/hns3_ethdev_vf.c  |  9 ++++-----
>  drivers/net/virtio/virtio_pci.c    |  6 ++----
>  lib/pci/rte_pci.h                  | 10 ++++++++++
>  11 files changed, 31 insertions(+), 56 deletions(-)
> 
> diff --git a/drivers/bus/pci/linux/pci_init.h
> b/drivers/bus/pci/linux/pci_init.h
> index d842809ccd..a4d37c0d0a 100644
> --- a/drivers/bus/pci/linux/pci_init.h
> +++ b/drivers/bus/pci/linux/pci_init.h
> @@ -52,24 +52,6 @@ int pci_uio_ioport_unmap(struct rte_pci_ioport *p);
> 
>  #ifdef VFIO_PRESENT
> 
> -#ifdef PCI_MSIX_TABLE_BIR
> -#define RTE_PCI_MSIX_TABLE_BIR    PCI_MSIX_TABLE_BIR
> -#else
> -#define RTE_PCI_MSIX_TABLE_BIR    0x7
> -#endif
> -
> -#ifdef PCI_MSIX_TABLE_OFFSET
> -#define RTE_PCI_MSIX_TABLE_OFFSET PCI_MSIX_TABLE_OFFSET
> -#else
> -#define RTE_PCI_MSIX_TABLE_OFFSET 0xfffffff8
> -#endif
> -
> -#ifdef PCI_MSIX_FLAGS_QSIZE
> -#define RTE_PCI_MSIX_FLAGS_QSIZE  PCI_MSIX_FLAGS_QSIZE
> -#else
> -#define RTE_PCI_MSIX_FLAGS_QSIZE  0x07ff
> -#endif
> -
>  /* access config space */
>  int pci_vfio_read_config(const struct rte_pci_device *dev,
>  			 void *buf, size_t len, off_t offs);
> diff --git a/drivers/bus/pci/linux/pci_vfio.c
> b/drivers/bus/pci/linux/pci_vfio.c
> index bfedbc1bed..7881b7a946 100644
> --- a/drivers/bus/pci/linux/pci_vfio.c
> +++ b/drivers/bus/pci/linux/pci_vfio.c
> @@ -120,14 +120,15 @@ pci_vfio_get_msix_bar(const struct rte_pci_device
> *dev,
>  		uint16_t flags;
>  		uint32_t reg;
> 
> -		/* table offset resides in the next 4 bytes */
> -		if (rte_pci_read_config(dev, &reg, sizeof(reg), cap_offset + 4)
> < 0) {
> +		if (rte_pci_read_config(dev, &reg, sizeof(reg), cap_offset +
> +				RTE_PCI_MSIX_TABLE) < 0) {
>  			RTE_LOG(ERR, EAL,
>  				"Cannot read MSIX table from PCI config space!\n");
>  			return -1;
>  		}
> 
> -		if (rte_pci_read_config(dev, &flags, sizeof(flags), cap_offset
> + 2) < 0) {
> +		if (rte_pci_read_config(dev, &flags, sizeof(flags), cap_offset
> +
> +				RTE_PCI_MSIX_FLAGS) < 0) {
>  			RTE_LOG(ERR, EAL,
>  				"Cannot read MSIX flags from PCI config space!\n");
>  			return -1;
> diff --git a/drivers/crypto/virtio/virtio_pci.c
> b/drivers/crypto/virtio/virtio_pci.c
> index 9e340f2b0d..c9fb1087a9 100644
> --- a/drivers/crypto/virtio/virtio_pci.c
> +++ b/drivers/crypto/virtio/virtio_pci.c
> @@ -329,8 +329,6 @@ get_cfg_addr(struct rte_pci_device *dev, struct
> virtio_pci_cap *cap)
>  	return base + offset;
>  }
> 
> -#define PCI_MSIX_ENABLE 0x8000
> -
>  static int
>  virtio_read_caps(struct rte_pci_device *dev, struct virtio_crypto_hw *hw)
>  {
> @@ -350,8 +348,8 @@ virtio_read_caps(struct rte_pci_device *dev, struct
> virtio_crypto_hw *hw)
>  	 */
>  	pos = rte_pci_find_capability(dev, RTE_PCI_CAP_ID_MSIX);
>  	if (pos > 0 && rte_pci_read_config(dev, &flags, sizeof(flags),
> -			pos + 2) == sizeof(flags)) {
> -		if (flags & PCI_MSIX_ENABLE)
> +			pos + RTE_PCI_MSIX_FLAGS) == sizeof(flags)) {
> +		if (flags & RTE_PCI_MSIX_FLAGS_ENABLE)
>  			hw->use_msix = VIRTIO_MSIX_ENABLED;
>  		else
>  			hw->use_msix = VIRTIO_MSIX_DISABLED;
> diff --git a/drivers/event/dlb2/pf/dlb2_main.c
> b/drivers/event/dlb2/pf/dlb2_main.c
> index 1a229baee0..c6606a9bee 100644
> --- a/drivers/event/dlb2/pf/dlb2_main.c
> +++ b/drivers/event/dlb2/pf/dlb2_main.c
> @@ -44,9 +44,6 @@
>  #define DLB2_PCI_PRI_CTRL_ENABLE         0x1
>  #define DLB2_PCI_PRI_ALLOC_REQ           0xC
>  #define DLB2_PCI_PRI_CTRL                0x4
> -#define DLB2_PCI_MSIX_FLAGS              0x2
> -#define DLB2_PCI_MSIX_FLAGS_ENABLE       0x8000
> -#define DLB2_PCI_MSIX_FLAGS_MASKALL      0x4000
>  #define DLB2_PCI_ERR_ROOT_STATUS         0x30
>  #define DLB2_PCI_ERR_COR_STATUS          0x10
>  #define DLB2_PCI_ERR_UNCOR_STATUS        0x4
> @@ -483,10 +480,10 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
> 
>  	msix_cap_offset = rte_pci_find_capability(pdev, RTE_PCI_CAP_ID_MSIX);
>  	if (msix_cap_offset >= 0) {
> -		off = msix_cap_offset + DLB2_PCI_MSIX_FLAGS;
> +		off = msix_cap_offset + RTE_PCI_MSIX_FLAGS;
>  		if (rte_pci_read_config(pdev, &cmd, 2, off) == 2) {
> -			cmd |= DLB2_PCI_MSIX_FLAGS_ENABLE;
> -			cmd |= DLB2_PCI_MSIX_FLAGS_MASKALL;
> +			cmd |= RTE_PCI_MSIX_FLAGS_ENABLE;
> +			cmd |= RTE_PCI_MSIX_FLAGS_MASKALL;
>  			if (rte_pci_write_config(pdev, &cmd, 2, off) != 2) {
>  				DLB2_LOG_ERR("[%s()] failed to write msix flags\n",
>  				       __func__);
> @@ -494,9 +491,9 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
>  			}
>  		}
> 
> -		off = msix_cap_offset + DLB2_PCI_MSIX_FLAGS;
> +		off = msix_cap_offset + RTE_PCI_MSIX_FLAGS;
>  		if (rte_pci_read_config(pdev, &cmd, 2, off) == 2) {
> -			cmd &= ~DLB2_PCI_MSIX_FLAGS_MASKALL;
> +			cmd &= ~RTE_PCI_MSIX_FLAGS_MASKALL;
>  			if (rte_pci_write_config(pdev, &cmd, 2, off) != 2) {
>  				DLB2_LOG_ERR("[%s()] failed to write msix flags\n",
>  				       __func__);
> diff --git a/drivers/net/bnx2x/bnx2x.c b/drivers/net/bnx2x/bnx2x.c
> index 8a97de8806..e3f14400cc 100644
> --- a/drivers/net/bnx2x/bnx2x.c
> +++ b/drivers/net/bnx2x/bnx2x.c
> @@ -9766,9 +9766,9 @@ int bnx2x_attach(struct bnx2x_softc *sc)
>  	if (sc->devinfo.pcie_msix_cap_reg != 0) {
>  		uint32_t val;
>  		pci_read(sc,
> -			 (sc->devinfo.pcie_msix_cap_reg + PCIR_MSIX_CTRL), &val,
> +			 (sc->devinfo.pcie_msix_cap_reg + RTE_PCI_MSIX_FLAGS),
> &val,
>  			 2);
> -		sc->igu_sb_cnt = (val & PCIM_MSIXCTRL_TABLE_SIZE) + 1;
> +		sc->igu_sb_cnt = (val & RTE_PCI_MSIX_FLAGS_QSIZE) + 1;
>  	} else {
>  		sc->igu_sb_cnt = 1;
>  	}
> diff --git a/drivers/net/bnx2x/bnx2x.h b/drivers/net/bnx2x/bnx2x.h
> index 07ef0567c2..60af75d336 100644
> --- a/drivers/net/bnx2x/bnx2x.h
> +++ b/drivers/net/bnx2x/bnx2x.h
> @@ -46,8 +46,6 @@
>  #define PCIM_PSTAT_PME                 PCI_PM_CTRL_PME_STATUS
>  #define PCIM_PSTAT_D3                  0x3
>  #define PCIM_PSTAT_PMEENABLE           PCI_PM_CTRL_PME_ENABLE
> -#define PCIR_MSIX_CTRL                 PCI_MSIX_FLAGS
> -#define PCIM_MSIXCTRL_TABLE_SIZE       PCI_MSIX_FLAGS_QSIZE
>  #else
>  #include <dev/pci/pcireg.h>
>  #endif
> diff --git a/drivers/net/gve/gve_ethdev.c b/drivers/net/gve/gve_ethdev.c
> index 9ea5dbaeea..9b25f3036b 100644
> --- a/drivers/net/gve/gve_ethdev.c
> +++ b/drivers/net/gve/gve_ethdev.c
> @@ -613,8 +613,8 @@ pci_dev_msix_vec_count(struct rte_pci_device *pdev)
>  	uint16_t control;
> 
>  	if (msix_pos > 0 && rte_pci_read_config(pdev, &control,
> sizeof(control),
> -			msix_pos + PCI_MSIX_FLAGS) == sizeof(control))
> -		return (control & PCI_MSIX_FLAGS_QSIZE) + 1;
> +			msix_pos + RTE_PCI_MSIX_FLAGS) == sizeof(control))
> +		return (control & RTE_PCI_MSIX_FLAGS_QSIZE) + 1;
> 
>  	return 0;
>  }
> diff --git a/drivers/net/gve/gve_ethdev.h b/drivers/net/gve/gve_ethdev.h
> index d604a75b7f..c47b4d454d 100644
> --- a/drivers/net/gve/gve_ethdev.h
> +++ b/drivers/net/gve/gve_ethdev.h
> @@ -15,14 +15,6 @@
>  /* TODO: this is a workaround to ensure that Tx complq is enough */
>  #define DQO_TX_MULTIPLIER 4
> 
> -/*
> - * Following macros are derived from linux/pci_regs.h, however,
> - * we can't simply include that header here, as there is no such
> - * file for non-Linux platform.
> - */
> -#define PCI_MSIX_FLAGS		2	/* Message Control */
> -#define PCI_MSIX_FLAGS_QSIZE	0x07FF	/* Table size */
> -
>  #define GVE_DEFAULT_RX_FREE_THRESH  512
>  #define GVE_DEFAULT_TX_FREE_THRESH   32
>  #define GVE_DEFAULT_TX_RS_THRESH     32
> diff --git a/drivers/net/hns3/hns3_ethdev_vf.c
> b/drivers/net/hns3/hns3_ethdev_vf.c
> index eab5c55f5e..3729615159 100644
> --- a/drivers/net/hns3/hns3_ethdev_vf.c
> +++ b/drivers/net/hns3/hns3_ethdev_vf.c
> @@ -2,7 +2,6 @@
>   * Copyright(c) 2018-2021 HiSilicon Limited.
>   */
> 
> -#include <linux/pci_regs.h>
>  #include <rte_alarm.h>
>  #include <ethdev_pci.h>
>  #include <rte_io.h>
> @@ -64,18 +63,18 @@ hns3vf_enable_msix(const struct rte_pci_device *device,
> bool op)
>  	pos = rte_pci_find_capability(device, RTE_PCI_CAP_ID_MSIX);
>  	if (pos > 0) {
>  		ret = rte_pci_read_config(device, &control, sizeof(control),
> -			pos + PCI_MSIX_FLAGS);
> +			pos + RTE_PCI_MSIX_FLAGS);
>  		if (ret < 0) {
>  			PMD_INIT_LOG(ERR, "Failed to read MSIX flags");
>  			return -ENXIO;
>  		}
> 
>  		if (op)
> -			control |= PCI_MSIX_FLAGS_ENABLE;
> +			control |= RTE_PCI_MSIX_FLAGS_ENABLE;
>  		else
> -			control &= ~PCI_MSIX_FLAGS_ENABLE;
> +			control &= ~RTE_PCI_MSIX_FLAGS_ENABLE;
>  		ret = rte_pci_write_config(device, &control, sizeof(control),
> -			pos + PCI_MSIX_FLAGS);
> +			pos + RTE_PCI_MSIX_FLAGS);
>  		if (ret < 0) {
>  			PMD_INIT_LOG(ERR, "failed to write MSIX flags");
>  			return -ENXIO;
> diff --git a/drivers/net/virtio/virtio_pci.c
> b/drivers/net/virtio/virtio_pci.c
> index 81d5dd0a4a..cdffef267f 100644
> --- a/drivers/net/virtio/virtio_pci.c
> +++ b/drivers/net/virtio/virtio_pci.c
> @@ -24,8 +24,6 @@
> 
>  struct virtio_pci_internal virtio_pci_internal[RTE_MAX_ETHPORTS];
> 
> -#define PCI_MSIX_ENABLE 0x8000
> -
>  static enum virtio_msix_status
>  vtpci_msix_detect(struct rte_pci_device *dev)
>  {
> @@ -34,8 +32,8 @@ vtpci_msix_detect(struct rte_pci_device *dev)
> 
>  	pos = rte_pci_find_capability(dev, RTE_PCI_CAP_ID_MSIX);
>  	if (pos > 0 && rte_pci_read_config(dev, &flags, sizeof(flags),
> -			pos + 2) == sizeof(flags)) {
> -		if (flags & PCI_MSIX_ENABLE)
> +			pos + RTE_PCI_MSIX_FLAGS) == sizeof(flags)) {
> +		if (flags & RTE_PCI_MSIX_FLAGS_ENABLE)
>  			return VIRTIO_MSIX_ENABLED;
>  		else
>  			return VIRTIO_MSIX_DISABLED;
> diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
> index 5a04a5a4b5..41dc725cc4 100644
> --- a/lib/pci/rte_pci.h
> +++ b/lib/pci/rte_pci.h
> @@ -51,6 +51,16 @@ extern "C" {
>  #define RTE_PCI_CAP_ID_MSIX		0x11	/* MSI-X */
>  #define RTE_PCI_CAP_SIZEOF		4
> 
> +/* MSI-X registers (RTE_PCI_CAP_ID_MSIX) */
> +#define RTE_PCI_MSIX_FLAGS		2	/* Message Control */
> +#define RTE_PCI_MSIX_FLAGS_QSIZE	0x07ff	/* Table size */
> +#define RTE_PCI_MSIX_FLAGS_MASKALL	0x4000	/* Mask all vectors for
> this function */
> +#define RTE_PCI_MSIX_FLAGS_ENABLE	0x8000	/* MSI-X enable */
> +
> +#define RTE_PCI_MSIX_TABLE		4	/* Table offset */
> +#define RTE_PCI_MSIX_TABLE_BIR		0x00000007 /* BAR index */
> +#define RTE_PCI_MSIX_TABLE_OFFSET	0xfffffff8 /* Offset into specified
> BAR */
> +
>  /* PCI Express capability registers */
>  #define RTE_PCI_EXP_DEVCTL	8	/* Device Control */
> 
> --
> 2.41.0

Reviewed-by: Chenbo Xia <chenbo.xia@intel.com> 

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

* RE: [PATCH v2 07/15] pci: define some command constants
  2023-08-21 11:35   ` [PATCH v2 07/15] pci: define some command constants David Marchand
@ 2023-09-07 13:15     ` Xia, Chenbo
  0 siblings, 0 replies; 98+ messages in thread
From: Xia, Chenbo @ 2023-09-07 13:15 UTC (permalink / raw)
  To: David Marchand, dev
  Cc: thomas, ferruh.yigit, nipun.gupta, Richardson, Bruce, Burakov,
	Anatoly, McDaniel, Timothy, Gaetan Rivet

> -----Original Message-----
> From: David Marchand <david.marchand@redhat.com>
> Sent: Monday, August 21, 2023 7:36 PM
> To: dev@dpdk.org
> Cc: thomas@monjalon.net; ferruh.yigit@amd.com; Xia, Chenbo
> <chenbo.xia@intel.com>; nipun.gupta@amd.com; Richardson, Bruce
> <bruce.richardson@intel.com>; Burakov, Anatoly <anatoly.burakov@intel.com>;
> McDaniel, Timothy <timothy.mcdaniel@intel.com>; Gaetan Rivet
> <grive@u256.net>
> Subject: [PATCH v2 07/15] pci: define some command constants
> 
> Define some PCI command constants and use them in existing drivers.
> 
> Signed-off-by: David Marchand <david.marchand@redhat.com>
> Acked-by: Bruce Richardson <bruce.richardson@intel.com>
> ---
>  drivers/bus/pci/linux/pci_vfio.c  | 8 ++++----
>  drivers/event/dlb2/pf/dlb2_main.c | 8 +++-----
>  lib/pci/rte_pci.h                 | 6 ++++--
>  3 files changed, 11 insertions(+), 11 deletions(-)
> 
> diff --git a/drivers/bus/pci/linux/pci_vfio.c
> b/drivers/bus/pci/linux/pci_vfio.c
> index 7881b7a946..bf91492dd9 100644
> --- a/drivers/bus/pci/linux/pci_vfio.c
> +++ b/drivers/bus/pci/linux/pci_vfio.c
> @@ -156,18 +156,18 @@ pci_vfio_enable_bus_memory(struct rte_pci_device
> *dev, int dev_fd)
>  		return -1;
>  	}
> 
> -	ret = pread64(dev_fd, &cmd, sizeof(cmd), offset + PCI_COMMAND);
> +	ret = pread64(dev_fd, &cmd, sizeof(cmd), offset + RTE_PCI_COMMAND);
> 
>  	if (ret != sizeof(cmd)) {
>  		RTE_LOG(ERR, EAL, "Cannot read command from PCI config
> space!\n");
>  		return -1;
>  	}
> 
> -	if (cmd & PCI_COMMAND_MEMORY)
> +	if (cmd & RTE_PCI_COMMAND_MEMORY)
>  		return 0;
> 
> -	cmd |= PCI_COMMAND_MEMORY;
> -	ret = pwrite64(dev_fd, &cmd, sizeof(cmd), offset + PCI_COMMAND);
> +	cmd |= RTE_PCI_COMMAND_MEMORY;
> +	ret = pwrite64(dev_fd, &cmd, sizeof(cmd), offset + RTE_PCI_COMMAND);
> 
>  	if (ret != sizeof(cmd)) {
>  		RTE_LOG(ERR, EAL, "Cannot write command to PCI config
> space!\n");
> diff --git a/drivers/event/dlb2/pf/dlb2_main.c
> b/drivers/event/dlb2/pf/dlb2_main.c
> index c6606a9bee..6dbaa2ff97 100644
> --- a/drivers/event/dlb2/pf/dlb2_main.c
> +++ b/drivers/event/dlb2/pf/dlb2_main.c
> @@ -33,7 +33,6 @@
>  #define DLB2_PCI_EXP_DEVCTL2 40
>  #define DLB2_PCI_LNKCTL2 48
>  #define DLB2_PCI_SLTCTL2 56
> -#define DLB2_PCI_CMD 4
>  #define DLB2_PCI_EXP_DEVSTA 10
>  #define DLB2_PCI_EXP_DEVSTA_TRPND 0x20
>  #define DLB2_PCI_EXP_DEVCTL_BCR_FLR 0x8000
> @@ -47,7 +46,6 @@
>  #define DLB2_PCI_ERR_ROOT_STATUS         0x30
>  #define DLB2_PCI_ERR_COR_STATUS          0x10
>  #define DLB2_PCI_ERR_UNCOR_STATUS        0x4
> -#define DLB2_PCI_COMMAND_INTX_DISABLE    0x400
>  #define DLB2_PCI_ACS_CAP                 0x4
>  #define DLB2_PCI_ACS_CTRL                0x6
>  #define DLB2_PCI_ACS_SV                  0x1
> @@ -286,7 +284,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
> 
>  	/* clear the PCI command register before issuing the FLR */
> 
> -	off = DLB2_PCI_CMD;
> +	off = RTE_PCI_COMMAND;
>  	cmd = 0;
>  	if (rte_pci_write_config(pdev, &cmd, 2, off) != 2) {
>  		DLB2_LOG_ERR("[%s()] failed to write the pci command\n",
> @@ -468,9 +466,9 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
>  		}
>  	}
> 
> -	off = DLB2_PCI_CMD;
> +	off = RTE_PCI_COMMAND;
>  	if (rte_pci_read_config(pdev, &cmd, 2, off) == 2) {
> -		cmd &= ~DLB2_PCI_COMMAND_INTX_DISABLE;
> +		cmd &= ~RTE_PCI_COMMAND_INTX_DISABLE;
>  		if (rte_pci_write_config(pdev, &cmd, 2, off) != 2) {
>  			DLB2_LOG_ERR("[%s()] failed to write the pci command\n",
>  			       __func__);
> diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
> index 41dc725cc4..9eb8f85ceb 100644
> --- a/lib/pci/rte_pci.h
> +++ b/lib/pci/rte_pci.h
> @@ -37,8 +37,10 @@ extern "C" {
>  #define RTE_PCI_STATUS		0x06	/* 16 bits */
>  #define RTE_PCI_CAPABILITY_LIST	0x34	/* 32 bits */
> 
> -/* PCI Command Register */
> -#define RTE_PCI_COMMAND_MASTER	0x4	/* Bus Master Enable */
> +/* PCI Command Register (RTE_PCI_COMMAND) */
> +#define RTE_PCI_COMMAND_MEMORY		0x2	/* Enable response in
> Memory space */
> +#define RTE_PCI_COMMAND_MASTER		0x4	/* Bus Master Enable */
> +#define RTE_PCI_COMMAND_INTX_DISABLE	0x400	/* INTx Emulation Disable
> */
> 
>  /* PCI Status Register (RTE_PCI_STATUS) */
>  #define RTE_PCI_STATUS_CAP_LIST		0x10	/* Support Capability List
> */
> --
> 2.41.0

Reviewed-by: Chenbo Xia <chenbo.xia@intel.com> 

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

* RE: [PATCH v2 08/15] pci: define some BAR constants
  2023-08-21 11:35   ` [PATCH v2 08/15] pci: define some BAR constants David Marchand
@ 2023-09-07 13:16     ` Xia, Chenbo
  0 siblings, 0 replies; 98+ messages in thread
From: Xia, Chenbo @ 2023-09-07 13:16 UTC (permalink / raw)
  To: David Marchand, dev
  Cc: thomas, ferruh.yigit, nipun.gupta, Richardson, Bruce, Burakov,
	Anatoly, Gaetan Rivet

> -----Original Message-----
> From: David Marchand <david.marchand@redhat.com>
> Sent: Monday, August 21, 2023 7:36 PM
> To: dev@dpdk.org
> Cc: thomas@monjalon.net; ferruh.yigit@amd.com; Xia, Chenbo
> <chenbo.xia@intel.com>; nipun.gupta@amd.com; Richardson, Bruce
> <bruce.richardson@intel.com>; Burakov, Anatoly <anatoly.burakov@intel.com>;
> Gaetan Rivet <grive@u256.net>
> Subject: [PATCH v2 08/15] pci: define some BAR constants
> 
> Define some PCI BAR constants and use them in existing drivers.
> 
> Signed-off-by: David Marchand <david.marchand@redhat.com>
> Acked-by: Bruce Richardson <bruce.richardson@intel.com>
> ---
>  drivers/bus/pci/linux/pci_vfio.c | 7 +++----
>  lib/pci/rte_pci.h                | 4 ++++
>  2 files changed, 7 insertions(+), 4 deletions(-)
> 
> diff --git a/drivers/bus/pci/linux/pci_vfio.c
> b/drivers/bus/pci/linux/pci_vfio.c
> index bf91492dd9..3f3201daf2 100644
> --- a/drivers/bus/pci/linux/pci_vfio.c
> +++ b/drivers/bus/pci/linux/pci_vfio.c
> @@ -5,7 +5,6 @@
>  #include <unistd.h>
>  #include <string.h>
>  #include <fcntl.h>
> -#include <linux/pci_regs.h>
>  #include <sys/eventfd.h>
>  #include <sys/socket.h>
>  #include <sys/ioctl.h>
> @@ -427,14 +426,14 @@ pci_vfio_is_ioport_bar(const struct rte_pci_device
> *dev, int vfio_dev_fd,
>  	}
> 
>  	ret = pread64(vfio_dev_fd, &ioport_bar, sizeof(ioport_bar),
> -			  offset + PCI_BASE_ADDRESS_0 + bar_index * 4);
> +			  offset + RTE_PCI_BASE_ADDRESS_0 + bar_index * 4);
>  	if (ret != sizeof(ioport_bar)) {
>  		RTE_LOG(ERR, EAL, "Cannot read command (%x) from config
> space!\n",
> -			PCI_BASE_ADDRESS_0 + bar_index*4);
> +			RTE_PCI_BASE_ADDRESS_0 + bar_index*4);
>  		return -1;
>  	}
> 
> -	return (ioport_bar & PCI_BASE_ADDRESS_SPACE_IO) != 0;
> +	return (ioport_bar & RTE_PCI_BASE_ADDRESS_SPACE_IO) != 0;
>  }
> 
>  static int
> diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
> index 9eb8f85ceb..62bf87aa10 100644
> --- a/lib/pci/rte_pci.h
> +++ b/lib/pci/rte_pci.h
> @@ -35,6 +35,7 @@ extern "C" {
>  #define RTE_PCI_DEVICE_ID	0x02	/* 16 bits */
>  #define RTE_PCI_COMMAND		0x04	/* 16 bits */
>  #define RTE_PCI_STATUS		0x06	/* 16 bits */
> +#define RTE_PCI_BASE_ADDRESS_0	0x10	/* 32 bits */
>  #define RTE_PCI_CAPABILITY_LIST	0x34	/* 32 bits */
> 
>  /* PCI Command Register (RTE_PCI_COMMAND) */
> @@ -45,6 +46,9 @@ extern "C" {
>  /* PCI Status Register (RTE_PCI_STATUS) */
>  #define RTE_PCI_STATUS_CAP_LIST		0x10	/* Support Capability List
> */
> 
> +/* Base addresses (RTE_PCI_BASE_ADDRESS_*) */
> +#define RTE_PCI_BASE_ADDRESS_SPACE_IO	0x01
> +
>  /* Capability registers (RTE_PCI_CAPABILITY_LIST) */
>  #define RTE_PCI_CAP_ID_PM		0x01	/* Power Management */
>  #define RTE_PCI_CAP_ID_MSI		0x05	/* Message Signalled Interrupts
> */
> --
> 2.41.0

Reviewed-by: Chenbo Xia <chenbo.xia@intel.com> 

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

* RE: [PATCH v2 09/15] pci: define some PM constants
  2023-08-21 11:35   ` [PATCH v2 09/15] pci: define some PM constants David Marchand
@ 2023-09-07 13:16     ` Xia, Chenbo
  0 siblings, 0 replies; 98+ messages in thread
From: Xia, Chenbo @ 2023-09-07 13:16 UTC (permalink / raw)
  To: David Marchand, dev
  Cc: thomas, ferruh.yigit, nipun.gupta, Richardson, Bruce,
	Julien Aube, Gaetan Rivet

> -----Original Message-----
> From: David Marchand <david.marchand@redhat.com>
> Sent: Monday, August 21, 2023 7:36 PM
> To: dev@dpdk.org
> Cc: thomas@monjalon.net; ferruh.yigit@amd.com; Xia, Chenbo
> <chenbo.xia@intel.com>; nipun.gupta@amd.com; Richardson, Bruce
> <bruce.richardson@intel.com>; Julien Aube <julien_dpdk@jaube.fr>; Gaetan
> Rivet <grive@u256.net>
> Subject: [PATCH v2 09/15] pci: define some PM constants
> 
> Define some PCI Power Management constants and use them in existing
> drivers.
> 
> Signed-off-by: David Marchand <david.marchand@redhat.com>
> Acked-by: Bruce Richardson <bruce.richardson@intel.com>
> ---
>  drivers/net/bnx2x/bnx2x.c | 17 +++++++++--------
>  drivers/net/bnx2x/bnx2x.h |  5 -----
>  lib/pci/rte_pci.h         |  6 ++++++
>  3 files changed, 15 insertions(+), 13 deletions(-)
> 
> diff --git a/drivers/net/bnx2x/bnx2x.c b/drivers/net/bnx2x/bnx2x.c
> index e3f14400cc..faf061beba 100644
> --- a/drivers/net/bnx2x/bnx2x.c
> +++ b/drivers/net/bnx2x/bnx2x.c
> @@ -5843,17 +5843,17 @@ static int bnx2x_set_power_state(struct
> bnx2x_softc *sc, uint8_t state)
>  		return 0;
>  	}
> 
> -	pci_read(sc, (sc->devinfo.pcie_pm_cap_reg + PCIR_POWER_STATUS),
> &pmcsr,
> +	pci_read(sc, (sc->devinfo.pcie_pm_cap_reg + RTE_PCI_PM_CTRL), &pmcsr,
>  		 2);
> 
>  	switch (state) {
>  	case PCI_PM_D0:
>  		pci_write_word(sc,
>  			       (sc->devinfo.pcie_pm_cap_reg +
> -				PCIR_POWER_STATUS),
> -			       ((pmcsr & ~PCIM_PSTAT_DMASK) | PCIM_PSTAT_PME));
> +				RTE_PCI_PM_CTRL),
> +			       ((pmcsr & ~RTE_PCI_PM_CTRL_STATE_MASK) |
> RTE_PCI_PM_CTRL_PME_STATUS));
> 
> -		if (pmcsr & PCIM_PSTAT_DMASK) {
> +		if (pmcsr & RTE_PCI_PM_CTRL_STATE_MASK) {
>  			/* delay required during transition out of D3hot */
>  			DELAY(20000);
>  		}
> @@ -5866,16 +5866,17 @@ static int bnx2x_set_power_state(struct
> bnx2x_softc *sc, uint8_t state)
>  			return 0;
>  		}
> 
> -		pmcsr &= ~PCIM_PSTAT_DMASK;
> -		pmcsr |= PCIM_PSTAT_D3;
> +		pmcsr &= ~RTE_PCI_PM_CTRL_STATE_MASK;
> +		/* D3 power state */
> +		pmcsr |= 0x3;
> 
>  		if (sc->wol) {
> -			pmcsr |= PCIM_PSTAT_PMEENABLE;
> +			pmcsr |= RTE_PCI_PM_CTRL_PME_ENABLE;
>  		}
> 
>  		pci_write_long(sc,
>  			       (sc->devinfo.pcie_pm_cap_reg +
> -				PCIR_POWER_STATUS), pmcsr);
> +				RTE_PCI_PM_CTRL), pmcsr);
> 
>  		/*
>  		 * No more memory access after this point until device is
> brought back
> diff --git a/drivers/net/bnx2x/bnx2x.h b/drivers/net/bnx2x/bnx2x.h
> index 60af75d336..1efa166316 100644
> --- a/drivers/net/bnx2x/bnx2x.h
> +++ b/drivers/net/bnx2x/bnx2x.h
> @@ -41,11 +41,6 @@
>  #define PCIR_EXPRESS_DEVICE_CTL        PCI_EXP_DEVCTL
>  #define PCIM_EXP_CTL_MAX_PAYLOAD       PCI_EXP_DEVCTL_PAYLOAD
>  #define PCIM_EXP_CTL_MAX_READ_REQUEST  PCI_EXP_DEVCTL_READRQ
> -#define PCIR_POWER_STATUS              PCI_PM_CTRL
> -#define PCIM_PSTAT_DMASK               PCI_PM_CTRL_STATE_MASK
> -#define PCIM_PSTAT_PME                 PCI_PM_CTRL_PME_STATUS
> -#define PCIM_PSTAT_D3                  0x3
> -#define PCIM_PSTAT_PMEENABLE           PCI_PM_CTRL_PME_ENABLE
>  #else
>  #include <dev/pci/pcireg.h>
>  #endif
> diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
> index 62bf87aa10..542d142dfb 100644
> --- a/lib/pci/rte_pci.h
> +++ b/lib/pci/rte_pci.h
> @@ -57,6 +57,12 @@ extern "C" {
>  #define RTE_PCI_CAP_ID_MSIX		0x11	/* MSI-X */
>  #define RTE_PCI_CAP_SIZEOF		4
> 
> +/* Power Management Registers (RTE_PCI_CAP_ID_PM) */
> +#define RTE_PCI_PM_CTRL			4	/* PM control and status
> register */
> +#define RTE_PCI_PM_CTRL_STATE_MASK	0x0003	/* Current power state (D0
> to D3) */
> +#define RTE_PCI_PM_CTRL_PME_ENABLE	0x0100	/* PME pin enable */
> +#define RTE_PCI_PM_CTRL_PME_STATUS	0x8000	/* PME pin status */
> +
>  /* MSI-X registers (RTE_PCI_CAP_ID_MSIX) */
>  #define RTE_PCI_MSIX_FLAGS		2	/* Message Control */
>  #define RTE_PCI_MSIX_FLAGS_QSIZE	0x07ff	/* Table size */
> --
> 2.41.0

Reviewed-by: Chenbo Xia <chenbo.xia@intel.com> 

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

* RE: [PATCH v2 10/15] pci: define some PCIe constants
  2023-08-21 11:35   ` [PATCH v2 10/15] pci: define some PCIe constants David Marchand
@ 2023-09-07 13:16     ` Xia, Chenbo
  0 siblings, 0 replies; 98+ messages in thread
From: Xia, Chenbo @ 2023-09-07 13:16 UTC (permalink / raw)
  To: David Marchand, dev
  Cc: thomas, ferruh.yigit, nipun.gupta, Richardson, Bruce, McDaniel,
	Timothy, Julien Aube, Gaetan Rivet

> -----Original Message-----
> From: David Marchand <david.marchand@redhat.com>
> Sent: Monday, August 21, 2023 7:36 PM
> To: dev@dpdk.org
> Cc: thomas@monjalon.net; ferruh.yigit@amd.com; Xia, Chenbo
> <chenbo.xia@intel.com>; nipun.gupta@amd.com; Richardson, Bruce
> <bruce.richardson@intel.com>; McDaniel, Timothy
> <timothy.mcdaniel@intel.com>; Julien Aube <julien_dpdk@jaube.fr>; Gaetan
> Rivet <grive@u256.net>
> Subject: [PATCH v2 10/15] pci: define some PCIe constants
> 
> Define some PCI Express constants and use them in existing drivers.
> 
> Signed-off-by: David Marchand <david.marchand@redhat.com>
> Acked-by: Bruce Richardson <bruce.richardson@intel.com>
> ---
>  drivers/event/dlb2/pf/dlb2_main.c | 40 ++++++++++++-------------------
>  drivers/net/bnx2x/bnx2x.c         | 16 ++++++-------
>  drivers/net/bnx2x/bnx2x.h         | 35 ---------------------------
>  lib/pci/rte_pci.h                 | 21 +++++++++++++---
>  4 files changed, 41 insertions(+), 71 deletions(-)
> 
> diff --git a/drivers/event/dlb2/pf/dlb2_main.c
> b/drivers/event/dlb2/pf/dlb2_main.c
> index 6dbaa2ff97..8d960edef6 100644
> --- a/drivers/event/dlb2/pf/dlb2_main.c
> +++ b/drivers/event/dlb2/pf/dlb2_main.c
> @@ -27,16 +27,6 @@
>  #define NO_OWNER_VF 0	/* PF ONLY! */
>  #define NOT_VF_REQ false /* PF ONLY! */
> 
> -#define DLB2_PCI_LNKCTL 16
> -#define DLB2_PCI_SLTCTL 24
> -#define DLB2_PCI_RTCTL 28
> -#define DLB2_PCI_EXP_DEVCTL2 40
> -#define DLB2_PCI_LNKCTL2 48
> -#define DLB2_PCI_SLTCTL2 56
> -#define DLB2_PCI_EXP_DEVSTA 10
> -#define DLB2_PCI_EXP_DEVSTA_TRPND 0x20
> -#define DLB2_PCI_EXP_DEVCTL_BCR_FLR 0x8000
> -
>  #define DLB2_PCI_EXT_CAP_ID_PRI   0x13
>  #define DLB2_PCI_EXT_CAP_ID_ACS   0xD
> 
> @@ -249,27 +239,27 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
>  	if (rte_pci_read_config(pdev, &dev_ctl_word, 2, off) != 2)
>  		dev_ctl_word = 0;
> 
> -	off = pcie_cap_offset + DLB2_PCI_LNKCTL;
> +	off = pcie_cap_offset + RTE_PCI_EXP_LNKCTL;
>  	if (rte_pci_read_config(pdev, &lnk_word, 2, off) != 2)
>  		lnk_word = 0;
> 
> -	off = pcie_cap_offset + DLB2_PCI_SLTCTL;
> +	off = pcie_cap_offset + RTE_PCI_EXP_SLTCTL;
>  	if (rte_pci_read_config(pdev, &slt_word, 2, off) != 2)
>  		slt_word = 0;
> 
> -	off = pcie_cap_offset + DLB2_PCI_RTCTL;
> +	off = pcie_cap_offset + RTE_PCI_EXP_RTCTL;
>  	if (rte_pci_read_config(pdev, &rt_ctl_word, 2, off) != 2)
>  		rt_ctl_word = 0;
> 
> -	off = pcie_cap_offset + DLB2_PCI_EXP_DEVCTL2;
> +	off = pcie_cap_offset + RTE_PCI_EXP_DEVCTL2;
>  	if (rte_pci_read_config(pdev, &dev_ctl2_word, 2, off) != 2)
>  		dev_ctl2_word = 0;
> 
> -	off = pcie_cap_offset + DLB2_PCI_LNKCTL2;
> +	off = pcie_cap_offset + RTE_PCI_EXP_LNKCTL2;
>  	if (rte_pci_read_config(pdev, &lnk_word2, 2, off) != 2)
>  		lnk_word2 = 0;
> 
> -	off = pcie_cap_offset + DLB2_PCI_SLTCTL2;
> +	off = pcie_cap_offset + RTE_PCI_EXP_SLTCTL2;
>  	if (rte_pci_read_config(pdev, &slt_word2, 2, off) != 2)
>  		slt_word2 = 0;
> 
> @@ -296,7 +286,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
>  	for (wait_count = 0; wait_count < 4; wait_count++) {
>  		int sleep_time;
> 
> -		off = pcie_cap_offset + DLB2_PCI_EXP_DEVSTA;
> +		off = pcie_cap_offset + RTE_PCI_EXP_DEVSTA;
>  		ret = rte_pci_read_config(pdev, &devsta_busy_word, 2, off);
>  		if (ret != 2) {
>  			DLB2_LOG_ERR("[%s()] failed to read the pci device
> status\n",
> @@ -304,7 +294,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
>  			return ret;
>  		}
> 
> -		if (!(devsta_busy_word & DLB2_PCI_EXP_DEVSTA_TRPND))
> +		if (!(devsta_busy_word & RTE_PCI_EXP_DEVSTA_TRPND))
>  			break;
> 
>  		sleep_time = (1 << (wait_count)) * 100;
> @@ -325,7 +315,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
>  		return ret;
>  	}
> 
> -	devctl_word |= DLB2_PCI_EXP_DEVCTL_BCR_FLR;
> +	devctl_word |= RTE_PCI_EXP_DEVCTL_BCR_FLR;
> 
>  	ret = rte_pci_write_config(pdev, &devctl_word, 2, off);
>  	if (ret != 2) {
> @@ -347,7 +337,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
>  			return ret;
>  		}
> 
> -		off = pcie_cap_offset + DLB2_PCI_LNKCTL;
> +		off = pcie_cap_offset + RTE_PCI_EXP_LNKCTL;
>  		ret = rte_pci_write_config(pdev, &lnk_word, 2, off);
>  		if (ret != 2) {
>  			DLB2_LOG_ERR("[%s()] failed to write the pcie config
> space at offset %d\n",
> @@ -355,7 +345,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
>  			return ret;
>  		}
> 
> -		off = pcie_cap_offset + DLB2_PCI_SLTCTL;
> +		off = pcie_cap_offset + RTE_PCI_EXP_SLTCTL;
>  		ret = rte_pci_write_config(pdev, &slt_word, 2, off);
>  		if (ret != 2) {
>  			DLB2_LOG_ERR("[%s()] failed to write the pcie config
> space at offset %d\n",
> @@ -363,7 +353,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
>  			return ret;
>  		}
> 
> -		off = pcie_cap_offset + DLB2_PCI_RTCTL;
> +		off = pcie_cap_offset + RTE_PCI_EXP_RTCTL;
>  		ret = rte_pci_write_config(pdev, &rt_ctl_word, 2, off);
>  		if (ret != 2) {
>  			DLB2_LOG_ERR("[%s()] failed to write the pcie config
> space at offset %d\n",
> @@ -371,7 +361,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
>  			return ret;
>  		}
> 
> -		off = pcie_cap_offset + DLB2_PCI_EXP_DEVCTL2;
> +		off = pcie_cap_offset + RTE_PCI_EXP_DEVCTL2;
>  		ret = rte_pci_write_config(pdev, &dev_ctl2_word, 2, off);
>  		if (ret != 2) {
>  			DLB2_LOG_ERR("[%s()] failed to write the pcie config
> space at offset %d\n",
> @@ -379,7 +369,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
>  			return ret;
>  		}
> 
> -		off = pcie_cap_offset + DLB2_PCI_LNKCTL2;
> +		off = pcie_cap_offset + RTE_PCI_EXP_LNKCTL2;
>  		ret = rte_pci_write_config(pdev, &lnk_word2, 2, off);
>  		if (ret != 2) {
>  			DLB2_LOG_ERR("[%s()] failed to write the pcie config
> space at offset %d\n",
> @@ -387,7 +377,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
>  			return ret;
>  		}
> 
> -		off = pcie_cap_offset + DLB2_PCI_SLTCTL2;
> +		off = pcie_cap_offset + RTE_PCI_EXP_SLTCTL2;
>  		ret = rte_pci_write_config(pdev, &slt_word2, 2, off);
>  		if (ret != 2) {
>  			DLB2_LOG_ERR("[%s()] failed to write the pcie config
> space at offset %d\n",
> diff --git a/drivers/net/bnx2x/bnx2x.c b/drivers/net/bnx2x/bnx2x.c
> index faf061beba..cfd8e35aa3 100644
> --- a/drivers/net/bnx2x/bnx2x.c
> +++ b/drivers/net/bnx2x/bnx2x.c
> @@ -7630,8 +7630,8 @@ static uint32_t bnx2x_pcie_capability_read(struct
> bnx2x_softc *sc, int reg)
> 
>  static uint8_t bnx2x_is_pcie_pending(struct bnx2x_softc *sc)
>  {
> -	return bnx2x_pcie_capability_read(sc, PCIR_EXPRESS_DEVICE_STA) &
> -		PCIM_EXP_STA_TRANSACTION_PND;
> +	return bnx2x_pcie_capability_read(sc, RTE_PCI_EXP_TYPE_RC_EC) &
> +		RTE_PCI_EXP_DEVSTA_TRPND;
>  }
> 
>  /*
> @@ -7658,11 +7658,11 @@ static void bnx2x_probe_pci_caps(struct
> bnx2x_softc *sc)
>  		sc->devinfo.pcie_pm_cap_reg = caps->addr;
>  	}
> 
> -	link_status = bnx2x_pcie_capability_read(sc, PCIR_EXPRESS_LINK_STA);
> +	link_status = bnx2x_pcie_capability_read(sc, RTE_PCI_EXP_LNKSTA);
> 
> -	sc->devinfo.pcie_link_speed = (link_status & PCIM_LINK_STA_SPEED);
> +	sc->devinfo.pcie_link_speed = (link_status & RTE_PCI_EXP_LNKSTA_CLS);
>  	sc->devinfo.pcie_link_width =
> -	    ((link_status & PCIM_LINK_STA_WIDTH) >> 4);
> +	    ((link_status & RTE_PCI_EXP_LNKSTA_NLW) >> 4);
> 
>  	PMD_DRV_LOG(DEBUG, sc, "PCIe link speed=%d width=%d",
>  		    sc->devinfo.pcie_link_speed, sc->devinfo.pcie_link_width);
> @@ -9979,10 +9979,10 @@ static void bnx2x_init_pxp(struct bnx2x_softc *sc)
>  	uint16_t devctl;
>  	int r_order, w_order;
> 
> -	devctl = bnx2x_pcie_capability_read(sc, PCIR_EXPRESS_DEVICE_CTL);
> +	devctl = bnx2x_pcie_capability_read(sc, RTE_PCI_EXP_DEVCTL);
> 
> -	w_order = ((devctl & PCIM_EXP_CTL_MAX_PAYLOAD) >> 5);
> -	r_order = ((devctl & PCIM_EXP_CTL_MAX_READ_REQUEST) >> 12);
> +	w_order = ((devctl & RTE_PCI_EXP_DEVCTL_PAYLOAD) >> 5);
> +	r_order = ((devctl & RTE_PCI_EXP_DEVCTL_READRQ) >> 12);
> 
>  	ecore_init_pxp_arb(sc, r_order, w_order);
>  }
> diff --git a/drivers/net/bnx2x/bnx2x.h b/drivers/net/bnx2x/bnx2x.h
> index 1efa166316..35206b4758 100644
> --- a/drivers/net/bnx2x/bnx2x.h
> +++ b/drivers/net/bnx2x/bnx2x.h
> @@ -30,45 +30,10 @@
> 
>  #include "elink.h"
> 
> -#ifndef RTE_EXEC_ENV_FREEBSD
> -#include <linux/pci_regs.h>
> -
> -#define PCIR_EXPRESS_DEVICE_STA        PCI_EXP_TYPE_RC_EC
> -#define PCIM_EXP_STA_TRANSACTION_PND   PCI_EXP_DEVSTA_TRPND
> -#define PCIR_EXPRESS_LINK_STA          PCI_EXP_LNKSTA
> -#define PCIM_LINK_STA_WIDTH            PCI_EXP_LNKSTA_NLW
> -#define PCIM_LINK_STA_SPEED            PCI_EXP_LNKSTA_CLS
> -#define PCIR_EXPRESS_DEVICE_CTL        PCI_EXP_DEVCTL
> -#define PCIM_EXP_CTL_MAX_PAYLOAD       PCI_EXP_DEVCTL_PAYLOAD
> -#define PCIM_EXP_CTL_MAX_READ_REQUEST  PCI_EXP_DEVCTL_READRQ
> -#else
> -#include <dev/pci/pcireg.h>
> -#endif
> -
>  #define IFM_10G_CX4                    20 /* 10GBase CX4 copper */
>  #define IFM_10G_TWINAX                 22 /* 10GBase Twinax copper */
>  #define IFM_10G_T                      26 /* 10GBase-T - RJ45 */
> 
> -#ifndef RTE_EXEC_ENV_FREEBSD
> -#define PCIR_EXPRESS_DEVICE_STA        PCI_EXP_TYPE_RC_EC
> -#define PCIM_EXP_STA_TRANSACTION_PND   PCI_EXP_DEVSTA_TRPND
> -#define PCIR_EXPRESS_LINK_STA          PCI_EXP_LNKSTA
> -#define PCIM_LINK_STA_WIDTH            PCI_EXP_LNKSTA_NLW
> -#define PCIM_LINK_STA_SPEED            PCI_EXP_LNKSTA_CLS
> -#define PCIR_EXPRESS_DEVICE_CTL        PCI_EXP_DEVCTL
> -#define PCIM_EXP_CTL_MAX_PAYLOAD       PCI_EXP_DEVCTL_PAYLOAD
> -#define PCIM_EXP_CTL_MAX_READ_REQUEST  PCI_EXP_DEVCTL_READRQ
> -#else
> -#define PCIR_EXPRESS_DEVICE_STA	PCIER_DEVICE_STA
> -#define PCIM_EXP_STA_TRANSACTION_PND   PCIEM_STA_TRANSACTION_PND
> -#define PCIR_EXPRESS_LINK_STA          PCIER_LINK_STA
> -#define PCIM_LINK_STA_WIDTH            PCIEM_LINK_STA_WIDTH
> -#define PCIM_LINK_STA_SPEED            PCIEM_LINK_STA_SPEED
> -#define PCIR_EXPRESS_DEVICE_CTL        PCIER_DEVICE_CTL
> -#define PCIM_EXP_CTL_MAX_PAYLOAD       PCIEM_CTL_MAX_PAYLOAD
> -#define PCIM_EXP_CTL_MAX_READ_REQUEST  PCIEM_CTL_MAX_READ_REQUEST
> -#endif
> -
>  #ifndef ARRAY_SIZE
>  #define ARRAY_SIZE(arr) RTE_DIM(arr)
>  #endif
> diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
> index 542d142dfb..a82f073a7d 100644
> --- a/lib/pci/rte_pci.h
> +++ b/lib/pci/rte_pci.h
> @@ -63,6 +63,24 @@ extern "C" {
>  #define RTE_PCI_PM_CTRL_PME_ENABLE	0x0100	/* PME pin enable */
>  #define RTE_PCI_PM_CTRL_PME_STATUS	0x8000	/* PME pin status */
> 
> +/* PCI Express capability registers (RTE_PCI_CAP_ID_EXP) */
> +#define RTE_PCI_EXP_TYPE_RC_EC		0xa	/* Root Complex Event
> Collector */
> +#define RTE_PCI_EXP_DEVCTL		0x08	/* Device Control */
> +#define RTE_PCI_EXP_DEVCTL_PAYLOAD	0x00e0	/* Max_Payload_Size */
> +#define RTE_PCI_EXP_DEVCTL_READRQ	0x7000	/* Max_Read_Request_Size
> */
> +#define RTE_PCI_EXP_DEVCTL_BCR_FLR	0x8000	/* Bridge Configuration
> Retry / FLR */
> +#define RTE_PCI_EXP_DEVSTA		0x0a	/* Device Status */
> +#define RTE_PCI_EXP_DEVSTA_TRPND	0x0020	/* Transactions Pending */
> +#define RTE_PCI_EXP_LNKCTL		0x10	/* Link Control */
> +#define RTE_PCI_EXP_LNKSTA		0x12	/* Link Status */
> +#define RTE_PCI_EXP_LNKSTA_CLS		0x000f	/* Current Link
> Speed */
> +#define RTE_PCI_EXP_LNKSTA_NLW		0x03f0	/* Negotiated Link
> Width */
> +#define RTE_PCI_EXP_SLTCTL		0x18	/* Slot Control */
> +#define RTE_PCI_EXP_RTCTL		0x1c	/* Root Control */
> +#define RTE_PCI_EXP_DEVCTL2		0x28	/* Device Control 2 */
> +#define RTE_PCI_EXP_LNKCTL2		0x30	/* Link Control 2 */
> +#define RTE_PCI_EXP_SLTCTL2		0x38	/* Slot Control 2 */
> +
>  /* MSI-X registers (RTE_PCI_CAP_ID_MSIX) */
>  #define RTE_PCI_MSIX_FLAGS		2	/* Message Control */
>  #define RTE_PCI_MSIX_FLAGS_QSIZE	0x07ff	/* Table size */
> @@ -73,9 +91,6 @@ extern "C" {
>  #define RTE_PCI_MSIX_TABLE_BIR		0x00000007 /* BAR index */
>  #define RTE_PCI_MSIX_TABLE_OFFSET	0xfffffff8 /* Offset into specified
> BAR */
> 
> -/* PCI Express capability registers */
> -#define RTE_PCI_EXP_DEVCTL	8	/* Device Control */
> -
>  /* Extended Capabilities (PCI-X 2.0 and Express) */
>  #define RTE_PCI_EXT_CAP_ID(header)	(header & 0x0000ffff)
>  #define RTE_PCI_EXT_CAP_NEXT(header)	((header >> 20) & 0xffc)
> --
> 2.41.0

Reviewed-by: Chenbo Xia <chenbo.xia@intel.com> 

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

* RE: [PATCH v2 11/15] pci: define some extended capability constants
  2023-08-21 11:35   ` [PATCH v2 11/15] pci: define some extended capability constants David Marchand
@ 2023-09-07 13:23     ` Xia, Chenbo
  0 siblings, 0 replies; 98+ messages in thread
From: Xia, Chenbo @ 2023-09-07 13:23 UTC (permalink / raw)
  To: David Marchand, dev
  Cc: thomas, ferruh.yigit, nipun.gupta, Richardson, Bruce, McDaniel,
	Timothy, Gaetan Rivet

Hi David,

> -----Original Message-----
> From: David Marchand <david.marchand@redhat.com>
> Sent: Monday, August 21, 2023 7:36 PM
> To: dev@dpdk.org
> Cc: thomas@monjalon.net; ferruh.yigit@amd.com; Xia, Chenbo
> <chenbo.xia@intel.com>; nipun.gupta@amd.com; Richardson, Bruce
> <bruce.richardson@intel.com>; McDaniel, Timothy
> <timothy.mcdaniel@intel.com>; Gaetan Rivet <grive@u256.net>
> Subject: [PATCH v2 11/15] pci: define some extended capability constants
> 
> Define some PCI extended capability constants and use them in existing
> drivers.
> 
> Signed-off-by: David Marchand <david.marchand@redhat.com>
> Acked-by: Bruce Richardson <bruce.richardson@intel.com>
> ---
>  drivers/event/dlb2/pf/dlb2_main.c | 7 ++-----
>  lib/pci/rte_pci.h                 | 4 +++-
>  2 files changed, 5 insertions(+), 6 deletions(-)
> 
> diff --git a/drivers/event/dlb2/pf/dlb2_main.c
> b/drivers/event/dlb2/pf/dlb2_main.c
> index 8d960edef6..29e3001627 100644
> --- a/drivers/event/dlb2/pf/dlb2_main.c
> +++ b/drivers/event/dlb2/pf/dlb2_main.c
> @@ -27,9 +27,6 @@
>  #define NO_OWNER_VF 0	/* PF ONLY! */
>  #define NOT_VF_REQ false /* PF ONLY! */
> 
> -#define DLB2_PCI_EXT_CAP_ID_PRI   0x13
> -#define DLB2_PCI_EXT_CAP_ID_ACS   0xD
> -
>  #define DLB2_PCI_PRI_CTRL_ENABLE         0x1
>  #define DLB2_PCI_PRI_ALLOC_REQ           0xC
>  #define DLB2_PCI_PRI_CTRL                0x4
> @@ -263,7 +260,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
>  	if (rte_pci_read_config(pdev, &slt_word2, 2, off) != 2)
>  		slt_word2 = 0;
> 
> -	off = DLB2_PCI_EXT_CAP_ID_PRI;
> +	off = RTE_PCI_EXT_CAP_ID_PRI;
>  	pri_cap_offset = rte_pci_find_ext_capability(pdev, off);
> 
>  	if (pri_cap_offset >= 0) {
> @@ -490,7 +487,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
>  		}
>  	}
> 
> -	off = DLB2_PCI_EXT_CAP_ID_ACS;
> +	off = RTE_PCI_EXT_CAP_ID_ACS;
>  	acs_cap_offset = rte_pci_find_ext_capability(pdev, off);
> 
>  	if (acs_cap_offset >= 0) {
> diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
> index a82f073a7d..d2f7a96f17 100644
> --- a/lib/pci/rte_pci.h
> +++ b/lib/pci/rte_pci.h
> @@ -97,9 +97,11 @@ extern "C" {
> 
>  #define RTE_PCI_EXT_CAP_ID_ERR		0x01	/* Advanced Error
> Reporting */
>  #define RTE_PCI_EXT_CAP_ID_DSN		0x03	/* Device Serial Number */
> +#define RTE_PCI_EXT_CAP_ID_ACS		0x0d	/* Access Control Services
> */
>  #define RTE_PCI_EXT_CAP_ID_SRIOV	0x10	/* SR-IOV*/

Maybe we could also do the small clean-up: it should be one space after 'IOV' :)

With this fixed:

Reviewed-by: Chenbo Xia <chenbo.xia@intel.com>

> +#define RTE_PCI_EXT_CAP_ID_PRI		0x13	/* Page Request Interface
> */
> 
> -/* Single Root I/O Virtualization */
> +/* Single Root I/O Virtualization (RTE_PCI_EXT_CAP_ID_SRIOV) */
>  #define RTE_PCI_SRIOV_CAP		0x04	/* SR-IOV Capabilities */
>  #define RTE_PCI_SRIOV_CTRL		0x08	/* SR-IOV Control */
>  #define RTE_PCI_SRIOV_INITIAL_VF	0x0c	/* Initial VFs */
> --
> 2.41.0


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

* RE: [PATCH v2 15/15] devtools: forbid inclusion of Linux header for PCI
  2023-08-21 11:35   ` [PATCH v2 15/15] devtools: forbid inclusion of Linux header for PCI David Marchand
  2023-08-21 16:24     ` Tyler Retzlaff
@ 2023-09-07 13:33     ` Xia, Chenbo
  1 sibling, 0 replies; 98+ messages in thread
From: Xia, Chenbo @ 2023-09-07 13:33 UTC (permalink / raw)
  To: David Marchand, dev; +Cc: thomas, ferruh.yigit, nipun.gupta, Richardson, Bruce

> -----Original Message-----
> From: David Marchand <david.marchand@redhat.com>
> Sent: Monday, August 21, 2023 7:36 PM
> To: dev@dpdk.org
> Cc: thomas@monjalon.net; ferruh.yigit@amd.com; Xia, Chenbo
> <chenbo.xia@intel.com>; nipun.gupta@amd.com; Richardson, Bruce
> <bruce.richardson@intel.com>
> Subject: [PATCH v2 15/15] devtools: forbid inclusion of Linux header for
> PCI
> 
> Refrain from including Linux-only pci_regs.h header.
> Instead, prefer our own definitions from the pci library.
> 
> Signed-off-by: David Marchand <david.marchand@redhat.com>
> Acked-by: Bruce Richardson <bruce.richardson@intel.com>
> ---
>  devtools/checkpatches.sh | 8 ++++++++
>  1 file changed, 8 insertions(+)
> 
> diff --git a/devtools/checkpatches.sh b/devtools/checkpatches.sh
> index 43f5e36a18..5d3c5aaba5 100755
> --- a/devtools/checkpatches.sh
> +++ b/devtools/checkpatches.sh
> @@ -127,6 +127,14 @@ check_forbidden_additions() { # <patch>
>  		-f $(dirname $(readlink -f $0))/check-forbidden-tokens.awk \
>  		"$1" || res=1
> 
> +	# forbid inclusion of Linux header for PCI constants
> +	awk -v FOLDERS="lib drivers app examples" \
> +		-v EXPRESSIONS='include.*linux/pci_regs\\.h' \
> +		-v RET_ON_FAIL=1 \
> +		-v MESSAGE='Using linux/pci_regs.h, prefer rte_pci.h' \
> +		-f $(dirname $(readlink -f $0))/check-forbidden-tokens.awk \
> +		"$1" || res=1
> +
>  	# forbid use of experimental build flag except in examples
>  	awk -v FOLDERS='lib drivers app' \
>  		-v EXPRESSIONS='-DALLOW_EXPERIMENTAL_API
> allow_experimental_apis' \
> --
> 2.41.0

Reviewed-by: Chenbo Xia <chenbo.xia@intel.com> 

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

* Re: [PATCH v2 04/15] bus/pci: find PCI capability
  2023-09-07 12:43     ` Xia, Chenbo
@ 2023-09-14 12:29       ` David Marchand
  2023-09-19  2:19         ` Xia, Chenbo
  0 siblings, 1 reply; 98+ messages in thread
From: David Marchand @ 2023-09-14 12:29 UTC (permalink / raw)
  To: Xia, Chenbo, Maxime Coquelin
  Cc: dev, thomas, ferruh.yigit, nipun.gupta, Richardson, Bruce,
	Burakov, Anatoly, Jay Zhou, McDaniel, Timothy, Julien Aube,
	Rahul Lakkireddy, Guo, Junfeng, Jeroen de Borst, Rushil Gupta,
	Joshua Washington, Dongdong Liu, Yisen Zhuang, Gaetan Rivet

Hello Chenbo,

On Thu, Sep 7, 2023 at 2:43 PM Xia, Chenbo <chenbo.xia@intel.com> wrote:
> > Introduce two helpers so that drivers stop reinventing the wheel when it
> > comes to finding capabilities in a device PCI configuration space.
> > Use it in existing drivers.
> >
> > Note:
> > - base/ drivers code is left untouched, only some wrappers in cxgbe
> >   are touched,
> > - bnx2x maintained a per device cache of capabilities, this code has been
> >   reworked to only cache the capabilities used in this driver,
> >
> > Signed-off-by: David Marchand <david.marchand@redhat.com>
> > Acked-by: Bruce Richardson <bruce.richardson@intel.com>
> > ---
> > Changes since v1:
> > - updated commitlog,
> > - separated VFIO changes for using standard PCI helper in a separate
> >   patch,
> > - marked new experimental symbols with current version,
> > - reordered defines in rte_pci.h,
> >
> > ---
> >  drivers/bus/pci/linux/pci_vfio.c   |  74 ++++--------------
> >  drivers/bus/pci/pci_common.c       |  45 +++++++++++
> >  drivers/bus/pci/rte_bus_pci.h      |  31 ++++++++
> >  drivers/bus/pci/version.map        |   4 +
> >  drivers/crypto/virtio/virtio_pci.c |  57 +++++---------
> >  drivers/event/dlb2/pf/dlb2_main.c  |  42 +---------
> >  drivers/net/bnx2x/bnx2x.c          |  41 +++++-----
> >  drivers/net/cxgbe/base/adapter.h   |  28 +------
> >  drivers/net/gve/gve_ethdev.c       |  46 ++---------
> >  drivers/net/gve/gve_ethdev.h       |   4 -
> >  drivers/net/hns3/hns3_ethdev_vf.c  |  79 +++----------------
> >  drivers/net/virtio/virtio_pci.c    | 121 +++++------------------------
> >  lib/pci/rte_pci.h                  |  11 +++
> >  13 files changed, 186 insertions(+), 397 deletions(-)
> >
> > diff --git a/drivers/bus/pci/linux/pci_vfio.c
> > b/drivers/bus/pci/linux/pci_vfio.c
> > index 958f8b3b52..614ed5d696 100644
> > --- a/drivers/bus/pci/linux/pci_vfio.c
> > +++ b/drivers/bus/pci/linux/pci_vfio.c
> > @@ -110,74 +110,34 @@ static int
> >  pci_vfio_get_msix_bar(const struct rte_pci_device *dev,
> >       struct pci_msix_table *msix_table)
> >  {
> > -     int ret;
> > -     uint32_t reg;
> > -     uint16_t flags;
> > -     uint8_t cap_id, cap_offset;
> > +     off_t cap_offset;
> >
> > -     /* read PCI capability pointer from config space */
> > -     ret = rte_pci_read_config(dev, &reg, sizeof(reg),
> > PCI_CAPABILITY_LIST);
> > -     if (ret != sizeof(reg)) {
> > -             RTE_LOG(ERR, EAL,
> > -                     "Cannot read capability pointer from PCI config
> > space!\n");
> > +     cap_offset = rte_pci_find_capability(dev, PCI_CAP_ID_MSIX);
>
> I notice in some cases we use rte_pci_has_capability_list() to check first,
> then looking for specific cap, in other cases we don't use
> rte_pci_has_capability_list(). Since we define this API, should we always do
> the check?

Hum, I am not sure of what you suggest here.

I tried to do a 1:1 conversion of what existed.
Do you mean there are places where I missed converting some
rte_pci_read_config(PCI_CAPABILITY_LIST) to
rte_pci_has_capability_list()?
If so, could you point at them?

Or are you suggesting to have this check as part of rte_pci_find_capability() ?


I'll respin a v3 soon (to fix the nasty issue you pointed out below).
A v4 may be needed depending on your replies to above questions.


>
>
> > +     if (cap_offset < 0)
> >               return -1;
> > -     }
> >
> > -     /* we need first byte */
> > -     cap_offset = reg & 0xFF;
> > +     if (cap_offset != 0) {
> > +             uint16_t flags;
> > +             uint32_t reg;
> >
> > -     while (cap_offset) {
> > -
> > -             /* read PCI capability ID */
> > -             ret = rte_pci_read_config(dev, &reg, sizeof(reg), cap_offset);
> > -             if (ret != sizeof(reg)) {
> > +             /* table offset resides in the next 4 bytes */
> > +             if (rte_pci_read_config(dev, &reg, sizeof(reg), cap_offset + 4)
> > < 0) {
> >                       RTE_LOG(ERR, EAL,
> > -                             "Cannot read capability ID from PCI config
> > space!\n");
> > +                             "Cannot read MSIX table from PCI config space!\n");
> >                       return -1;
> >               }
> >
> > -             /* we need first byte */
> > -             cap_id = reg & 0xFF;
> > -
> > -             /* if we haven't reached MSI-X, check next capability */
> > -             if (cap_id != PCI_CAP_ID_MSIX) {
> > -                     ret = rte_pci_read_config(dev, &reg, sizeof(reg),
> > cap_offset);
> > -                     if (ret != sizeof(reg)) {
> > -                             RTE_LOG(ERR, EAL,
> > -                                     "Cannot read capability pointer from PCI
> > config space!\n");
> > -                             return -1;
> > -                     }
> > -
> > -                     /* we need second byte */
> > -                     cap_offset = (reg & 0xFF00) >> 8;
> > -
> > -                     continue;
> > +             if (rte_pci_read_config(dev, &flags, sizeof(flags), cap_offset
> > + 2) < 0) {
> > +                     RTE_LOG(ERR, EAL,
> > +                             "Cannot read MSIX flags from PCI config space!\n");
> > +                     return -1;
> >               }
> > -             /* else, read table offset */
> > -             else {
> > -                     /* table offset resides in the next 4 bytes */
> > -                     ret = rte_pci_read_config(dev, &reg, sizeof(reg),
> > cap_offset + 4);
> > -                     if (ret != sizeof(reg)) {
> > -                             RTE_LOG(ERR, EAL,
> > -                                     "Cannot read table offset from PCI config
> > space!\n");
> > -                             return -1;
> > -                     }
> > -
> > -                     ret = rte_pci_read_config(dev, &flags, sizeof(flags),
> > cap_offset + 2);
> > -                     if (ret != sizeof(flags)) {
> > -                             RTE_LOG(ERR, EAL,
> > -                                     "Cannot read table flags from PCI config
> > space!\n");
> > -                             return -1;
> > -                     }
> > -
> > -                     msix_table->bar_index = reg & RTE_PCI_MSIX_TABLE_BIR;
> > -                     msix_table->offset = reg & RTE_PCI_MSIX_TABLE_OFFSET;
> > -                     msix_table->size =
> > -                             16 * (1 + (flags & RTE_PCI_MSIX_FLAGS_QSIZE));
> >
> > -                     return 0;
> > -             }
> > +             msix_table->bar_index = reg & RTE_PCI_MSIX_TABLE_BIR;
> > +             msix_table->offset = reg & RTE_PCI_MSIX_TABLE_OFFSET;
> > +             msix_table->size = 16 * (1 + (flags &
> > RTE_PCI_MSIX_FLAGS_QSIZE));
> >       }
> > +
> >       return 0;
> >  }
> >
> > diff --git a/drivers/bus/pci/pci_common.c b/drivers/bus/pci/pci_common.c
> > index 382b0b8946..52272617eb 100644
> > --- a/drivers/bus/pci/pci_common.c
> > +++ b/drivers/bus/pci/pci_common.c
> > @@ -813,6 +813,51 @@ rte_pci_get_iommu_class(void)
> >       return iova_mode;
> >  }
> >
> > +bool
> > +rte_pci_has_capability_list(const struct rte_pci_device *dev)
> > +{
> > +     uint16_t status;
> > +
> > +     if (rte_pci_read_config(dev, &status, sizeof(status),
> > RTE_PCI_STATUS) != sizeof(status))
> > +             return false;
> > +
> > +     return (status & RTE_PCI_STATUS_CAP_LIST) != 0;
> > +}
> > +
> > +off_t
> > +rte_pci_find_capability(const struct rte_pci_device *dev, uint8_t cap)
> > +{
> > +     off_t offset;
> > +     uint8_t pos;
> > +     int ttl;
> > +
> > +     offset = RTE_PCI_CAPABILITY_LIST;
> > +     ttl = (RTE_PCI_CFG_SPACE_SIZE - RTE_PCI_STD_HEADER_SIZEOF) /
> > RTE_PCI_CAP_SIZEOF;
> > +
> > +     if (rte_pci_read_config(dev, &pos, sizeof(pos), offset) < 0)
> > +             return -1;
> > +
> > +     while (pos && ttl--) {
> > +             uint16_t ent;
> > +             uint8_t id;
> > +
> > +             offset = pos;
> > +             if (rte_pci_read_config(dev, &ent, sizeof(ent), offset) < 0)
> > +                     return -1;
> > +
> > +             id = ent & 0xff;
> > +             if (id == 0xff)
> > +                     break;
> > +
> > +             if (id == cap)
> > +                     return offset;
> > +
> > +             pos = (ent >> 8);
> > +     }
> > +
> > +     return 0;
> > +}
> > +
> >  off_t
> >  rte_pci_find_ext_capability(const struct rte_pci_device *dev, uint32_t
> > cap)
> >  {
> > diff --git a/drivers/bus/pci/rte_bus_pci.h b/drivers/bus/pci/rte_bus_pci.h
> > index 75d0030eae..1ed33dbf3d 100644
> > --- a/drivers/bus/pci/rte_bus_pci.h
> > +++ b/drivers/bus/pci/rte_bus_pci.h
> > @@ -68,6 +68,37 @@ void rte_pci_unmap_device(struct rte_pci_device *dev);
> >   */
> >  void rte_pci_dump(FILE *f);
> >
> > +/**
> > + * Check whether this device has a PCI capability list.
> > + *
> > + *  @param dev
> > + *    A pointer to rte_pci_device structure.
> > + *
> > + *  @return
> > + *    true/false
> > + */
> > +__rte_experimental
> > +bool rte_pci_has_capability_list(const struct rte_pci_device *dev);
> > +
> > +/**
> > + * Find device's PCI capability.
> > + *
> > + *  @param dev
> > + *    A pointer to rte_pci_device structure.
> > + *
> > + *  @param cap
> > + *    Capability to be found, which can be any from
> > + *    RTE_PCI_CAP_ID_*, defined in librte_pci.
> > + *
> > + *  @return
> > + *  > 0: The offset of the next matching capability structure
> > + *       within the device's PCI configuration space.
> > + *  < 0: An error in PCI config space read.
> > + *  = 0: Device does not support it.
> > + */
> > +__rte_experimental
> > +off_t rte_pci_find_capability(const struct rte_pci_device *dev, uint8_t
> > cap);
> > +
> >  /**
> >   * Find device's extended PCI capability.
> >   *
> > diff --git a/drivers/bus/pci/version.map b/drivers/bus/pci/version.map
> > index a0000f7938..2674f30235 100644
> > --- a/drivers/bus/pci/version.map
> > +++ b/drivers/bus/pci/version.map
> > @@ -25,6 +25,10 @@ EXPERIMENTAL {
> >       # added in 23.07
> >       rte_pci_mmio_read;
> >       rte_pci_mmio_write;
> > +
> > +     # added in 23.11
> > +     rte_pci_find_capability;
> > +     rte_pci_has_capability_list;
> >  };
> >
> >  INTERNAL {
> > diff --git a/drivers/crypto/virtio/virtio_pci.c
> > b/drivers/crypto/virtio/virtio_pci.c
> > index 95a43c8801..abc52b4701 100644
> > --- a/drivers/crypto/virtio/virtio_pci.c
> > +++ b/drivers/crypto/virtio/virtio_pci.c
> > @@ -19,7 +19,6 @@
> >   * we can't simply include that header here, as there is no such
> >   * file for non-Linux platform.
> >   */
> > -#define PCI_CAPABILITY_LIST  0x34
> >  #define PCI_CAP_ID_VNDR              0x09
> >  #define PCI_CAP_ID_MSIX              0x11
> >
> > @@ -343,8 +342,9 @@ get_cfg_addr(struct rte_pci_device *dev, struct
> > virtio_pci_cap *cap)
> >  static int
> >  virtio_read_caps(struct rte_pci_device *dev, struct virtio_crypto_hw *hw)
> >  {
> > -     uint8_t pos;
> >       struct virtio_pci_cap cap;
> > +     uint16_t flags;
> > +     off_t pos;
> >       int ret;
> >
> >       if (rte_pci_map_device(dev)) {
> > @@ -352,44 +352,26 @@ virtio_read_caps(struct rte_pci_device *dev, struct
> > virtio_crypto_hw *hw)
> >               return -1;
> >       }
> >
> > -     ret = rte_pci_read_config(dev, &pos, 1, PCI_CAPABILITY_LIST);
> > -     if (ret < 0) {
> > -             VIRTIO_CRYPTO_INIT_LOG_DBG("failed to read pci capability
> > list");
> > -             return -1;
> > +     /*
> > +      * Transitional devices would also have this capability,
> > +      * that's why we also check if msix is enabled.
> > +      */
> > +     pos = rte_pci_find_capability(dev, PCI_CAP_ID_MSIX);
> > +     if (pos > 0 && rte_pci_read_config(dev, &flags, sizeof(flags),
> > +                     pos + 2) == sizeof(flags)) {
> > +             if (flags & PCI_MSIX_ENABLE)
> > +                     hw->use_msix = VIRTIO_MSIX_ENABLED;
> > +             else
> > +                     hw->use_msix = VIRTIO_MSIX_DISABLED;
> > +     } else {
> > +             hw->use_msix = VIRTIO_MSIX_NONE;
> >       }
> >
> > -     while (pos) {
> > -             ret = rte_pci_read_config(dev, &cap, sizeof(cap), pos);
> > -             if (ret < 0) {
> > -                     VIRTIO_CRYPTO_INIT_LOG_ERR(
> > -                             "failed to read pci cap at pos: %x", pos);
> > -                     break;
> > -             }
> > -
> > -             if (cap.cap_vndr == PCI_CAP_ID_MSIX) {
> > -                     /* Transitional devices would also have this capability,
> > -                      * that's why we also check if msix is enabled.
> > -                      * 1st byte is cap ID; 2nd byte is the position of next
> > -                      * cap; next two bytes are the flags.
> > -                      */
> > -                     uint16_t flags = ((uint16_t *)&cap)[1];
> > -
> > -                     if (flags & PCI_MSIX_ENABLE)
> > -                             hw->use_msix = VIRTIO_MSIX_ENABLED;
> > -                     else
> > -                             hw->use_msix = VIRTIO_MSIX_DISABLED;
> > -             }
> > -
> > -             if (cap.cap_vndr != PCI_CAP_ID_VNDR) {
> > -                     VIRTIO_CRYPTO_INIT_LOG_DBG(
> > -                             "[%2x] skipping non VNDR cap id: %02x",
> > -                             pos, cap.cap_vndr);
> > -                     goto next;
> > -             }
> > -
> > +     pos = rte_pci_find_capability(dev, PCI_CAP_ID_VNDR);
>
> The logic of vendor cap init seems incorrect. Virtio devices have multiple
> Vendor cap (different cfg type). But now the logic seems to only init the first
> one.

Indeed, good catch!
It is sad that the CI did not catch this regression in virtio pmd init :-(.

I'll add a find_next_capability helper for v3.



>
> > +     if (pos > 0 && rte_pci_read_config(dev, &cap, sizeof(cap), pos) ==
> > sizeof(cap)) {
> >               VIRTIO_CRYPTO_INIT_LOG_DBG(
> >                       "[%2x] cfg type: %u, bar: %u, offset: %04x, len: %u",
> > -                     pos, cap.cfg_type, cap.bar, cap.offset, cap.length);
> > +                     (unsigned int)pos, cap.cfg_type, cap.bar, cap.offset,
> > cap.length);
> >
> >               switch (cap.cfg_type) {
> >               case VIRTIO_PCI_CAP_COMMON_CFG:
> > @@ -411,9 +393,6 @@ virtio_read_caps(struct rte_pci_device *dev, struct
> > virtio_crypto_hw *hw)
> >                       hw->isr = get_cfg_addr(dev, &cap);
> >                       break;
> >               }
> > -
> > -next:
> > -             pos = cap.cap_next;
> >       }
>
> ...


-- 
David Marchand


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

* [PATCH v3 00/15] Cleanup PCI(e) drivers
  2023-08-03  7:50 [PATCH 00/14] Cleanup PCI(e) drivers David Marchand
                   ` (18 preceding siblings ...)
  2023-08-24 15:44 ` Adam Hassick
@ 2023-09-14 12:35 ` David Marchand
  2023-09-14 12:36   ` [PATCH v3 01/15] drivers: remove duplicated PCI master control David Marchand
                     ` (16 more replies)
  19 siblings, 17 replies; 98+ messages in thread
From: David Marchand @ 2023-09-14 12:35 UTC (permalink / raw)
  To: dev; +Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, bruce.richardson

Rather than rely on Linux headers to find some PCI(e) standard constants
or reinvent the same PCI capability helper, this series complements the
pci library and the pci bus driver.
PCI drivers can then use OS agnostic macros and helpers.


-- 
David Marchand

Changes since v2:
- fixed vendor capability handling in virtio drivers (thanks Chenbo!),

Changes since v1:
- fix VFIO-backed drivers broken by v1 patch 3,
- enhanced rte_pci.h defines organisation,

David Marchand (15):
  drivers: remove duplicated PCI master control
  bus/pci: add const to some experimental API
  bus/pci: rework MSIX discovery with VFIO
  bus/pci: find PCI capability
  pci: define some capability constants
  pci: define some MSIX constants
  pci: define some command constants
  pci: define some BAR constants
  pci: define some PM constants
  pci: define some PCIe constants
  pci: define some extended capability constants
  pci: define some ACS constants
  pci: define some PRI constants
  pci: define some AER constants
  devtools: forbid inclusion of Linux header for PCI

 devtools/checkpatches.sh            |   8 ++
 drivers/bus/pci/linux/pci_init.h    |  18 ----
 drivers/bus/pci/linux/pci_uio.c     |  32 +-----
 drivers/bus/pci/linux/pci_vfio.c    | 148 ++++++--------------------
 drivers/bus/pci/pci_common.c        |  58 ++++++++++-
 drivers/bus/pci/rte_bus_pci.h       |  57 +++++++++-
 drivers/bus/pci/version.map         |   5 +
 drivers/crypto/virtio/virtio_pci.c  |  67 ++++--------
 drivers/event/dlb2/pf/dlb2_main.c   | 156 ++++++++--------------------
 drivers/net/bnx2x/bnx2x.c           |  86 ++++++++-------
 drivers/net/bnx2x/bnx2x.h           |  46 --------
 drivers/net/cxgbe/base/adapter.h    |  31 +-----
 drivers/net/gve/gve_ethdev.c        |  46 +-------
 drivers/net/gve/gve_ethdev.h        |  14 +--
 drivers/net/hns3/hns3_ethdev_vf.c   | 109 +++----------------
 drivers/net/ngbe/base/ngbe_hw.c     |  20 +---
 drivers/net/ngbe/base/ngbe_osdep.h  |   3 -
 drivers/net/virtio/virtio_pci.c     | 131 ++++-------------------
 drivers/vdpa/ifc/base/ifcvf_osdep.h |   4 +-
 lib/pci/rte_pci.h                   |  93 +++++++++++++++--
 20 files changed, 396 insertions(+), 736 deletions(-)

-- 
2.41.0


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

* [PATCH v3 01/15] drivers: remove duplicated PCI master control
  2023-09-14 12:35 ` [PATCH v3 00/15] " David Marchand
@ 2023-09-14 12:36   ` David Marchand
  2023-09-14 12:36   ` [PATCH v3 02/15] bus/pci: add const to some experimental API David Marchand
                     ` (15 subsequent siblings)
  16 siblings, 0 replies; 98+ messages in thread
From: David Marchand @ 2023-09-14 12:36 UTC (permalink / raw)
  To: dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, bruce.richardson,
	Anatoly Burakov, Dongdong Liu, Yisen Zhuang, Jiawen Wu

Use existing API to cleanup duplicated code.

Signed-off-by: David Marchand <david.marchand@redhat.com>
Acked-by: Bruce Richardson <bruce.richardson@intel.com>
Reviewed-by: Chenbo Xia <chenbo.xia@intel.com>
---
 drivers/bus/pci/linux/pci_uio.c    | 32 +----------------------
 drivers/bus/pci/linux/pci_vfio.c   | 41 ++----------------------------
 drivers/net/hns3/hns3_ethdev_vf.c  | 25 +-----------------
 drivers/net/ngbe/base/ngbe_hw.c    | 20 ++-------------
 drivers/net/ngbe/base/ngbe_osdep.h |  3 ---
 5 files changed, 6 insertions(+), 115 deletions(-)

diff --git a/drivers/bus/pci/linux/pci_uio.c b/drivers/bus/pci/linux/pci_uio.c
index 2bf16e9369..97d740dfe5 100644
--- a/drivers/bus/pci/linux/pci_uio.c
+++ b/drivers/bus/pci/linux/pci_uio.c
@@ -10,7 +10,6 @@
 #include <sys/stat.h>
 #include <sys/mman.h>
 #include <sys/sysmacros.h>
-#include <linux/pci_regs.h>
 
 #if defined(RTE_ARCH_X86)
 #include <sys/io.h>
@@ -77,35 +76,6 @@ pci_uio_mmio_write(const struct rte_pci_device *dev, int bar,
 	return len;
 }
 
-static int
-pci_uio_set_bus_master(int dev_fd)
-{
-	uint16_t reg;
-	int ret;
-
-	ret = pread(dev_fd, &reg, sizeof(reg), PCI_COMMAND);
-	if (ret != sizeof(reg)) {
-		RTE_LOG(ERR, EAL,
-			"Cannot read command from PCI config space!\n");
-		return -1;
-	}
-
-	/* return if bus mastering is already on */
-	if (reg & PCI_COMMAND_MASTER)
-		return 0;
-
-	reg |= PCI_COMMAND_MASTER;
-
-	ret = pwrite(dev_fd, &reg, sizeof(reg), PCI_COMMAND);
-	if (ret != sizeof(reg)) {
-		RTE_LOG(ERR, EAL,
-			"Cannot write command to PCI config space!\n");
-		return -1;
-	}
-
-	return 0;
-}
-
 static int
 pci_mknod_uio_dev(const char *sysfs_uio_path, unsigned uio_num)
 {
@@ -299,7 +269,7 @@ pci_uio_alloc_resource(struct rte_pci_device *dev,
 			goto error;
 
 		/* set bus master that is not done by uio_pci_generic */
-		if (pci_uio_set_bus_master(uio_cfg_fd)) {
+		if (rte_pci_set_bus_master(dev, true)) {
 			RTE_LOG(ERR, EAL, "Cannot set up bus mastering!\n");
 			goto error;
 		}
diff --git a/drivers/bus/pci/linux/pci_vfio.c b/drivers/bus/pci/linux/pci_vfio.c
index e634de8322..8fa7fa458f 100644
--- a/drivers/bus/pci/linux/pci_vfio.c
+++ b/drivers/bus/pci/linux/pci_vfio.c
@@ -223,42 +223,6 @@ pci_vfio_enable_bus_memory(struct rte_pci_device *dev, int dev_fd)
 	return 0;
 }
 
-/* set PCI bus mastering */
-static int
-pci_vfio_set_bus_master(const struct rte_pci_device *dev, int dev_fd, bool op)
-{
-	uint64_t size, offset;
-	uint16_t reg;
-	int ret;
-
-	if (pci_vfio_get_region(dev, VFIO_PCI_CONFIG_REGION_INDEX,
-		&size, &offset) != 0) {
-		RTE_LOG(ERR, EAL, "Cannot get offset of CONFIG region.\n");
-		return -1;
-	}
-
-	ret = pread64(dev_fd, &reg, sizeof(reg), offset + PCI_COMMAND);
-	if (ret != sizeof(reg)) {
-		RTE_LOG(ERR, EAL, "Cannot read command from PCI config space!\n");
-		return -1;
-	}
-
-	if (op)
-		/* set the master bit */
-		reg |= PCI_COMMAND_MASTER;
-	else
-		reg &= ~(PCI_COMMAND_MASTER);
-
-	ret = pwrite64(dev_fd, &reg, sizeof(reg), offset + PCI_COMMAND);
-
-	if (ret != sizeof(reg)) {
-		RTE_LOG(ERR, EAL, "Cannot write command to PCI config space!\n");
-		return -1;
-	}
-
-	return 0;
-}
-
 /* set up interrupt support (but not enable interrupts) */
 static int
 pci_vfio_setup_interrupts(struct rte_pci_device *dev, int vfio_dev_fd)
@@ -535,8 +499,7 @@ pci_rte_vfio_setup_device(struct rte_pci_device *dev, int vfio_dev_fd)
 		return -1;
 	}
 
-	/* set bus mastering for the device */
-	if (pci_vfio_set_bus_master(dev, vfio_dev_fd, true)) {
+	if (rte_pci_set_bus_master(dev, true)) {
 		RTE_LOG(ERR, EAL, "Cannot set up bus mastering!\n");
 		return -1;
 	}
@@ -1226,7 +1189,7 @@ pci_vfio_unmap_resource_primary(struct rte_pci_device *dev)
 	if (vfio_dev_fd < 0)
 		return -1;
 
-	if (pci_vfio_set_bus_master(dev, vfio_dev_fd, false)) {
+	if (rte_pci_set_bus_master(dev, false)) {
 		RTE_LOG(ERR, EAL, "%s cannot unset bus mastering for PCI device!\n",
 				pci_addr);
 		return -1;
diff --git a/drivers/net/hns3/hns3_ethdev_vf.c b/drivers/net/hns3/hns3_ethdev_vf.c
index 5aac62a41f..7b3c5dc168 100644
--- a/drivers/net/hns3/hns3_ethdev_vf.c
+++ b/drivers/net/hns3/hns3_ethdev_vf.c
@@ -49,29 +49,6 @@ static int hns3vf_remove_mc_mac_addr(struct hns3_hw *hw,
 static int hns3vf_dev_link_update(struct rte_eth_dev *eth_dev,
 				   __rte_unused int wait_to_complete);
 
-/* set PCI bus mastering */
-static int
-hns3vf_set_bus_master(const struct rte_pci_device *device, bool op)
-{
-	uint16_t reg;
-	int ret;
-
-	ret = rte_pci_read_config(device, &reg, sizeof(reg), PCI_COMMAND);
-	if (ret < 0) {
-		PMD_INIT_LOG(ERR, "Failed to read PCI offset 0x%x",
-			     PCI_COMMAND);
-		return ret;
-	}
-
-	if (op)
-		/* set the master bit */
-		reg |= PCI_COMMAND_MASTER;
-	else
-		reg &= ~(PCI_COMMAND_MASTER);
-
-	return rte_pci_write_config(device, &reg, sizeof(reg), PCI_COMMAND);
-}
-
 /**
  * hns3vf_find_pci_capability - lookup a capability in the PCI capability list
  * @cap: the capability
@@ -2140,7 +2117,7 @@ hns3vf_reinit_dev(struct hns3_adapter *hns)
 
 	if (hw->reset.level == HNS3_VF_FULL_RESET) {
 		rte_intr_disable(pci_dev->intr_handle);
-		ret = hns3vf_set_bus_master(pci_dev, true);
+		ret = rte_pci_set_bus_master(pci_dev, true);
 		if (ret < 0) {
 			hns3_err(hw, "failed to set pci bus, ret = %d", ret);
 			return ret;
diff --git a/drivers/net/ngbe/base/ngbe_hw.c b/drivers/net/ngbe/base/ngbe_hw.c
index 27243d85c8..22ccdb0b7d 100644
--- a/drivers/net/ngbe/base/ngbe_hw.c
+++ b/drivers/net/ngbe/base/ngbe_hw.c
@@ -1061,26 +1061,10 @@ s32 ngbe_set_pcie_master(struct ngbe_hw *hw, bool enable)
 {
 	struct rte_pci_device *pci_dev = (struct rte_pci_device *)hw->back;
 	s32 status = 0;
-	s32 ret = 0;
 	u32 i;
-	u16 reg;
 
-	ret = rte_pci_read_config(pci_dev, &reg,
-			sizeof(reg), PCI_COMMAND);
-	if (ret != sizeof(reg)) {
-		DEBUGOUT("Cannot read command from PCI config space!\n");
-		return -1;
-	}
-
-	if (enable)
-		reg |= PCI_COMMAND_MASTER;
-	else
-		reg &= ~PCI_COMMAND_MASTER;
-
-	ret = rte_pci_write_config(pci_dev, &reg,
-			sizeof(reg), PCI_COMMAND);
-	if (ret != sizeof(reg)) {
-		DEBUGOUT("Cannot write command to PCI config space!\n");
+	if (rte_pci_set_bus_master(pci_dev, enable) < 0) {
+		DEBUGOUT("Cannot configure PCI bus master\n");
 		return -1;
 	}
 
diff --git a/drivers/net/ngbe/base/ngbe_osdep.h b/drivers/net/ngbe/base/ngbe_osdep.h
index 8783fce4dd..30598a240a 100644
--- a/drivers/net/ngbe/base/ngbe_osdep.h
+++ b/drivers/net/ngbe/base/ngbe_osdep.h
@@ -181,7 +181,4 @@ static inline u64 REVERT_BIT_MASK64(u64 mask)
 #define ETH_P_8021Q      0x8100
 #define ETH_P_8021AD     0x88A8
 
-#define PCI_COMMAND		0x04
-#define  PCI_COMMAND_MASTER	0x4
-
 #endif /* _NGBE_OS_H_ */
-- 
2.41.0


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

* [PATCH v3 02/15] bus/pci: add const to some experimental API
  2023-09-14 12:35 ` [PATCH v3 00/15] " David Marchand
  2023-09-14 12:36   ` [PATCH v3 01/15] drivers: remove duplicated PCI master control David Marchand
@ 2023-09-14 12:36   ` David Marchand
  2023-09-14 12:36   ` [PATCH v3 03/15] bus/pci: rework MSIX discovery with VFIO David Marchand
                     ` (14 subsequent siblings)
  16 siblings, 0 replies; 98+ messages in thread
From: David Marchand @ 2023-09-14 12:36 UTC (permalink / raw)
  To: dev; +Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, bruce.richardson

Those functions are fine with a const on the device pointer.

Signed-off-by: David Marchand <david.marchand@redhat.com>
Acked-by: Bruce Richardson <bruce.richardson@intel.com>
Reviewed-by: Chenbo Xia <chenbo.xia@intel.com>
---
 drivers/bus/pci/pci_common.c  | 4 ++--
 drivers/bus/pci/rte_bus_pci.h | 4 ++--
 2 files changed, 4 insertions(+), 4 deletions(-)

diff --git a/drivers/bus/pci/pci_common.c b/drivers/bus/pci/pci_common.c
index 52404ab0fe..382b0b8946 100644
--- a/drivers/bus/pci/pci_common.c
+++ b/drivers/bus/pci/pci_common.c
@@ -814,7 +814,7 @@ rte_pci_get_iommu_class(void)
 }
 
 off_t
-rte_pci_find_ext_capability(struct rte_pci_device *dev, uint32_t cap)
+rte_pci_find_ext_capability(const struct rte_pci_device *dev, uint32_t cap)
 {
 	off_t offset = RTE_PCI_CFG_SPACE_SIZE;
 	uint32_t header;
@@ -857,7 +857,7 @@ rte_pci_find_ext_capability(struct rte_pci_device *dev, uint32_t cap)
 }
 
 int
-rte_pci_set_bus_master(struct rte_pci_device *dev, bool enable)
+rte_pci_set_bus_master(const struct rte_pci_device *dev, bool enable)
 {
 	uint16_t old_cmd, cmd;
 
diff --git a/drivers/bus/pci/rte_bus_pci.h b/drivers/bus/pci/rte_bus_pci.h
index 9d59c4aef3..75d0030eae 100644
--- a/drivers/bus/pci/rte_bus_pci.h
+++ b/drivers/bus/pci/rte_bus_pci.h
@@ -85,7 +85,7 @@ void rte_pci_dump(FILE *f);
  *  = 0: Device does not support it.
  */
 __rte_experimental
-off_t rte_pci_find_ext_capability(struct rte_pci_device *dev, uint32_t cap);
+off_t rte_pci_find_ext_capability(const struct rte_pci_device *dev, uint32_t cap);
 
 /**
  * Enables/Disables Bus Master for device's PCI command register.
@@ -99,7 +99,7 @@ off_t rte_pci_find_ext_capability(struct rte_pci_device *dev, uint32_t cap);
  *  0 on success, -1 on error in PCI config space read/write.
  */
 __rte_experimental
-int rte_pci_set_bus_master(struct rte_pci_device *dev, bool enable);
+int rte_pci_set_bus_master(const struct rte_pci_device *dev, bool enable);
 
 /**
  * Read PCI config space.
-- 
2.41.0


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

* [PATCH v3 03/15] bus/pci: rework MSIX discovery with VFIO
  2023-09-14 12:35 ` [PATCH v3 00/15] " David Marchand
  2023-09-14 12:36   ` [PATCH v3 01/15] drivers: remove duplicated PCI master control David Marchand
  2023-09-14 12:36   ` [PATCH v3 02/15] bus/pci: add const to some experimental API David Marchand
@ 2023-09-14 12:36   ` David Marchand
  2023-09-14 12:36   ` [PATCH v3 04/15] bus/pci: find PCI capability David Marchand
                     ` (13 subsequent siblings)
  16 siblings, 0 replies; 98+ messages in thread
From: David Marchand @ 2023-09-14 12:36 UTC (permalink / raw)
  To: dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, bruce.richardson,
	Anatoly Burakov

This is a preparatory step before using new helpers for finding PCI
capabilities.
In the code querying PCI capabilities for checking MSIX availability,
replace direct calls to VFIO fd with the existing helpers for reading
PCI configuration space: this requires setting VFIO fd in the PCI
device object than was done before this change and removes the need to
pass around this vfio_dev_fd variable.

Signed-off-by: David Marchand <david.marchand@redhat.com>
Reviewed-by: Chenbo Xia <chenbo.xia@intel.com>
---
 drivers/bus/pci/linux/pci_vfio.c | 27 ++++++++++-----------------
 1 file changed, 10 insertions(+), 17 deletions(-)

diff --git a/drivers/bus/pci/linux/pci_vfio.c b/drivers/bus/pci/linux/pci_vfio.c
index 8fa7fa458f..958f8b3b52 100644
--- a/drivers/bus/pci/linux/pci_vfio.c
+++ b/drivers/bus/pci/linux/pci_vfio.c
@@ -107,23 +107,16 @@ pci_vfio_write_config(const struct rte_pci_device *dev,
 
 /* get PCI BAR number where MSI-X interrupts are */
 static int
-pci_vfio_get_msix_bar(const struct rte_pci_device *dev, int fd,
+pci_vfio_get_msix_bar(const struct rte_pci_device *dev,
 	struct pci_msix_table *msix_table)
 {
 	int ret;
 	uint32_t reg;
 	uint16_t flags;
 	uint8_t cap_id, cap_offset;
-	uint64_t size, offset;
-
-	if (pci_vfio_get_region(dev, VFIO_PCI_CONFIG_REGION_INDEX,
-		&size, &offset) != 0) {
-		RTE_LOG(ERR, EAL, "Cannot get offset of CONFIG region.\n");
-		return -1;
-	}
 
 	/* read PCI capability pointer from config space */
-	ret = pread64(fd, &reg, sizeof(reg), offset + PCI_CAPABILITY_LIST);
+	ret = rte_pci_read_config(dev, &reg, sizeof(reg), PCI_CAPABILITY_LIST);
 	if (ret != sizeof(reg)) {
 		RTE_LOG(ERR, EAL,
 			"Cannot read capability pointer from PCI config space!\n");
@@ -136,7 +129,7 @@ pci_vfio_get_msix_bar(const struct rte_pci_device *dev, int fd,
 	while (cap_offset) {
 
 		/* read PCI capability ID */
-		ret = pread64(fd, &reg, sizeof(reg), offset + cap_offset);
+		ret = rte_pci_read_config(dev, &reg, sizeof(reg), cap_offset);
 		if (ret != sizeof(reg)) {
 			RTE_LOG(ERR, EAL,
 				"Cannot read capability ID from PCI config space!\n");
@@ -148,7 +141,7 @@ pci_vfio_get_msix_bar(const struct rte_pci_device *dev, int fd,
 
 		/* if we haven't reached MSI-X, check next capability */
 		if (cap_id != PCI_CAP_ID_MSIX) {
-			ret = pread64(fd, &reg, sizeof(reg), offset + cap_offset);
+			ret = rte_pci_read_config(dev, &reg, sizeof(reg), cap_offset);
 			if (ret != sizeof(reg)) {
 				RTE_LOG(ERR, EAL,
 					"Cannot read capability pointer from PCI config space!\n");
@@ -163,14 +156,14 @@ pci_vfio_get_msix_bar(const struct rte_pci_device *dev, int fd,
 		/* else, read table offset */
 		else {
 			/* table offset resides in the next 4 bytes */
-			ret = pread64(fd, &reg, sizeof(reg), offset + cap_offset + 4);
+			ret = rte_pci_read_config(dev, &reg, sizeof(reg), cap_offset + 4);
 			if (ret != sizeof(reg)) {
 				RTE_LOG(ERR, EAL,
 					"Cannot read table offset from PCI config space!\n");
 				return -1;
 			}
 
-			ret = pread64(fd, &flags, sizeof(flags), offset + cap_offset + 2);
+			ret = rte_pci_read_config(dev, &flags, sizeof(flags), cap_offset + 2);
 			if (ret != sizeof(flags)) {
 				RTE_LOG(ERR, EAL,
 					"Cannot read table flags from PCI config space!\n");
@@ -306,9 +299,6 @@ pci_vfio_setup_interrupts(struct rte_pci_device *dev, int vfio_dev_fd)
 		if (rte_intr_fd_set(dev->intr_handle, fd))
 			return -1;
 
-		if (rte_intr_dev_fd_set(dev->intr_handle, vfio_dev_fd))
-			return -1;
-
 		switch (i) {
 		case VFIO_PCI_MSIX_IRQ_INDEX:
 			intr_mode = RTE_INTR_MODE_MSIX;
@@ -838,6 +828,9 @@ pci_vfio_map_resource_primary(struct rte_pci_device *dev)
 	if (ret)
 		return ret;
 
+	if (rte_intr_dev_fd_set(dev->intr_handle, vfio_dev_fd))
+		goto err_vfio_dev_fd;
+
 	/* allocate vfio_res and get region info */
 	vfio_res = rte_zmalloc("VFIO_RES", sizeof(*vfio_res), 0);
 	if (vfio_res == NULL) {
@@ -869,7 +862,7 @@ pci_vfio_map_resource_primary(struct rte_pci_device *dev)
 	/* get MSI-X BAR, if any (we have to know where it is because we can't
 	 * easily mmap it when using VFIO)
 	 */
-	ret = pci_vfio_get_msix_bar(dev, vfio_dev_fd, &vfio_res->msix_table);
+	ret = pci_vfio_get_msix_bar(dev, &vfio_res->msix_table);
 	if (ret < 0) {
 		RTE_LOG(ERR, EAL, "%s cannot get MSI-X BAR number!\n",
 				pci_addr);
-- 
2.41.0


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

* [PATCH v3 04/15] bus/pci: find PCI capability
  2023-09-14 12:35 ` [PATCH v3 00/15] " David Marchand
                     ` (2 preceding siblings ...)
  2023-09-14 12:36   ` [PATCH v3 03/15] bus/pci: rework MSIX discovery with VFIO David Marchand
@ 2023-09-14 12:36   ` David Marchand
  2023-09-19  2:33     ` Xia, Chenbo
  2023-09-14 12:36   ` [PATCH v3 05/15] pci: define some capability constants David Marchand
                     ` (12 subsequent siblings)
  16 siblings, 1 reply; 98+ messages in thread
From: David Marchand @ 2023-09-14 12:36 UTC (permalink / raw)
  To: dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, bruce.richardson,
	Anatoly Burakov, Jay Zhou, Abdullah Sevincer, Julien Aube,
	Rahul Lakkireddy, Junfeng Guo, Jeroen de Borst, Rushil Gupta,
	Joshua Washington, Dongdong Liu, Yisen Zhuang, Maxime Coquelin,
	Gaetan Rivet

Introduce two helpers so that drivers stop reinventing the wheel when it
comes to finding capabilities in a device PCI configuration space.
Use it in existing drivers.

Note:
- base/ drivers code is left untouched, only some wrappers in cxgbe
  are touched,
- bnx2x maintained a per device cache of capabilities, this code has been
  reworked to only cache the capabilities used in this driver,

Acked-by: Bruce Richardson <bruce.richardson@intel.com>
Signed-off-by: David Marchand <david.marchand@redhat.com>
---
Changes since v2:
- added rte_pci_find_next_capability for vendor capa used with virtio,

Changes since v1:
- updated commitlog,
- separated VFIO changes for using standard PCI helper in a separate
  patch,
- marked new experimental symbols with current version,
- reordered defines in rte_pci.h,

---
 drivers/bus/pci/linux/pci_vfio.c   |  74 ++++--------------
 drivers/bus/pci/pci_common.c       |  54 +++++++++++++
 drivers/bus/pci/rte_bus_pci.h      |  53 +++++++++++++
 drivers/bus/pci/version.map        |   5 ++
 drivers/crypto/virtio/virtio_pci.c |  57 +++++---------
 drivers/event/dlb2/pf/dlb2_main.c  |  42 +---------
 drivers/net/bnx2x/bnx2x.c          |  41 +++++-----
 drivers/net/cxgbe/base/adapter.h   |  28 +------
 drivers/net/gve/gve_ethdev.c       |  46 ++---------
 drivers/net/gve/gve_ethdev.h       |   4 -
 drivers/net/hns3/hns3_ethdev_vf.c  |  79 +++----------------
 drivers/net/virtio/virtio_pci.c    | 121 ++++++-----------------------
 lib/pci/rte_pci.h                  |  12 +++
 13 files changed, 223 insertions(+), 393 deletions(-)

diff --git a/drivers/bus/pci/linux/pci_vfio.c b/drivers/bus/pci/linux/pci_vfio.c
index 958f8b3b52..614ed5d696 100644
--- a/drivers/bus/pci/linux/pci_vfio.c
+++ b/drivers/bus/pci/linux/pci_vfio.c
@@ -110,74 +110,34 @@ static int
 pci_vfio_get_msix_bar(const struct rte_pci_device *dev,
 	struct pci_msix_table *msix_table)
 {
-	int ret;
-	uint32_t reg;
-	uint16_t flags;
-	uint8_t cap_id, cap_offset;
+	off_t cap_offset;
 
-	/* read PCI capability pointer from config space */
-	ret = rte_pci_read_config(dev, &reg, sizeof(reg), PCI_CAPABILITY_LIST);
-	if (ret != sizeof(reg)) {
-		RTE_LOG(ERR, EAL,
-			"Cannot read capability pointer from PCI config space!\n");
+	cap_offset = rte_pci_find_capability(dev, PCI_CAP_ID_MSIX);
+	if (cap_offset < 0)
 		return -1;
-	}
 
-	/* we need first byte */
-	cap_offset = reg & 0xFF;
+	if (cap_offset != 0) {
+		uint16_t flags;
+		uint32_t reg;
 
-	while (cap_offset) {
-
-		/* read PCI capability ID */
-		ret = rte_pci_read_config(dev, &reg, sizeof(reg), cap_offset);
-		if (ret != sizeof(reg)) {
+		/* table offset resides in the next 4 bytes */
+		if (rte_pci_read_config(dev, &reg, sizeof(reg), cap_offset + 4) < 0) {
 			RTE_LOG(ERR, EAL,
-				"Cannot read capability ID from PCI config space!\n");
+				"Cannot read MSIX table from PCI config space!\n");
 			return -1;
 		}
 
-		/* we need first byte */
-		cap_id = reg & 0xFF;
-
-		/* if we haven't reached MSI-X, check next capability */
-		if (cap_id != PCI_CAP_ID_MSIX) {
-			ret = rte_pci_read_config(dev, &reg, sizeof(reg), cap_offset);
-			if (ret != sizeof(reg)) {
-				RTE_LOG(ERR, EAL,
-					"Cannot read capability pointer from PCI config space!\n");
-				return -1;
-			}
-
-			/* we need second byte */
-			cap_offset = (reg & 0xFF00) >> 8;
-
-			continue;
+		if (rte_pci_read_config(dev, &flags, sizeof(flags), cap_offset + 2) < 0) {
+			RTE_LOG(ERR, EAL,
+				"Cannot read MSIX flags from PCI config space!\n");
+			return -1;
 		}
-		/* else, read table offset */
-		else {
-			/* table offset resides in the next 4 bytes */
-			ret = rte_pci_read_config(dev, &reg, sizeof(reg), cap_offset + 4);
-			if (ret != sizeof(reg)) {
-				RTE_LOG(ERR, EAL,
-					"Cannot read table offset from PCI config space!\n");
-				return -1;
-			}
-
-			ret = rte_pci_read_config(dev, &flags, sizeof(flags), cap_offset + 2);
-			if (ret != sizeof(flags)) {
-				RTE_LOG(ERR, EAL,
-					"Cannot read table flags from PCI config space!\n");
-				return -1;
-			}
-
-			msix_table->bar_index = reg & RTE_PCI_MSIX_TABLE_BIR;
-			msix_table->offset = reg & RTE_PCI_MSIX_TABLE_OFFSET;
-			msix_table->size =
-				16 * (1 + (flags & RTE_PCI_MSIX_FLAGS_QSIZE));
 
-			return 0;
-		}
+		msix_table->bar_index = reg & RTE_PCI_MSIX_TABLE_BIR;
+		msix_table->offset = reg & RTE_PCI_MSIX_TABLE_OFFSET;
+		msix_table->size = 16 * (1 + (flags & RTE_PCI_MSIX_FLAGS_QSIZE));
 	}
+
 	return 0;
 }
 
diff --git a/drivers/bus/pci/pci_common.c b/drivers/bus/pci/pci_common.c
index 382b0b8946..f149963364 100644
--- a/drivers/bus/pci/pci_common.c
+++ b/drivers/bus/pci/pci_common.c
@@ -813,6 +813,60 @@ rte_pci_get_iommu_class(void)
 	return iova_mode;
 }
 
+bool
+rte_pci_has_capability_list(const struct rte_pci_device *dev)
+{
+	uint16_t status;
+
+	if (rte_pci_read_config(dev, &status, sizeof(status), RTE_PCI_STATUS) != sizeof(status))
+		return false;
+
+	return (status & RTE_PCI_STATUS_CAP_LIST) != 0;
+}
+
+off_t
+rte_pci_find_capability(const struct rte_pci_device *dev, uint8_t cap)
+{
+	return rte_pci_find_next_capability(dev, cap, 0);
+}
+
+off_t
+rte_pci_find_next_capability(const struct rte_pci_device *dev, uint8_t cap,
+	off_t offset)
+{
+	uint8_t pos;
+	int ttl;
+
+	if (offset == 0)
+		offset = RTE_PCI_CAPABILITY_LIST;
+	else
+		offset += RTE_PCI_CAP_NEXT;
+	ttl = (RTE_PCI_CFG_SPACE_SIZE - RTE_PCI_STD_HEADER_SIZEOF) / RTE_PCI_CAP_SIZEOF;
+
+	if (rte_pci_read_config(dev, &pos, sizeof(pos), offset) < 0)
+		return -1;
+
+	while (pos && ttl--) {
+		uint16_t ent;
+		uint8_t id;
+
+		offset = pos;
+		if (rte_pci_read_config(dev, &ent, sizeof(ent), offset) < 0)
+			return -1;
+
+		id = ent & 0xff;
+		if (id == 0xff)
+			break;
+
+		if (id == cap)
+			return offset;
+
+		pos = (ent >> 8);
+	}
+
+	return 0;
+}
+
 off_t
 rte_pci_find_ext_capability(const struct rte_pci_device *dev, uint32_t cap)
 {
diff --git a/drivers/bus/pci/rte_bus_pci.h b/drivers/bus/pci/rte_bus_pci.h
index 75d0030eae..e97b7eae5c 100644
--- a/drivers/bus/pci/rte_bus_pci.h
+++ b/drivers/bus/pci/rte_bus_pci.h
@@ -68,6 +68,59 @@ void rte_pci_unmap_device(struct rte_pci_device *dev);
  */
 void rte_pci_dump(FILE *f);
 
+/**
+ * Check whether this device has a PCI capability list.
+ *
+ *  @param dev
+ *    A pointer to rte_pci_device structure.
+ *
+ *  @return
+ *    true/false
+ */
+__rte_experimental
+bool rte_pci_has_capability_list(const struct rte_pci_device *dev);
+
+/**
+ * Find device's PCI capability.
+ *
+ *  @param dev
+ *    A pointer to rte_pci_device structure.
+ *
+ *  @param cap
+ *    Capability to be found, which can be any from
+ *    RTE_PCI_CAP_ID_*, defined in librte_pci.
+ *
+ *  @return
+ *  > 0: The offset of the next matching capability structure
+ *       within the device's PCI configuration space.
+ *  < 0: An error in PCI config space read.
+ *  = 0: Device does not support it.
+ */
+__rte_experimental
+off_t rte_pci_find_capability(const struct rte_pci_device *dev, uint8_t cap);
+
+/**
+ * Find device's PCI capability starting from a previous offset in PCI
+ * configuration space.
+ *
+ *  @param dev
+ *    A pointer to rte_pci_device structure.
+ *
+ *  @param cap
+ *    Capability to be found, which can be any from
+ *    RTE_PCI_CAP_ID_*, defined in librte_pci.
+ *  @param offset
+ *    offset from which the capability is looked for.
+ *
+ *  @return
+ *  > 0: The offset of the next matching capability structure
+ *       within the device's PCI configuration space.
+ *  < 0: An error in PCI config space read.
+ *  = 0: Device does not support it.
+ */
+__rte_experimental
+off_t rte_pci_find_next_capability(const struct rte_pci_device *dev, uint8_t cap, off_t offset);
+
 /**
  * Find device's extended PCI capability.
  *
diff --git a/drivers/bus/pci/version.map b/drivers/bus/pci/version.map
index a0000f7938..74c5b075d5 100644
--- a/drivers/bus/pci/version.map
+++ b/drivers/bus/pci/version.map
@@ -25,6 +25,11 @@ EXPERIMENTAL {
 	# added in 23.07
 	rte_pci_mmio_read;
 	rte_pci_mmio_write;
+
+	# added in 23.11
+	rte_pci_find_capability;
+	rte_pci_find_next_capability;
+	rte_pci_has_capability_list;
 };
 
 INTERNAL {
diff --git a/drivers/crypto/virtio/virtio_pci.c b/drivers/crypto/virtio/virtio_pci.c
index 95a43c8801..19afebdcad 100644
--- a/drivers/crypto/virtio/virtio_pci.c
+++ b/drivers/crypto/virtio/virtio_pci.c
@@ -19,7 +19,6 @@
  * we can't simply include that header here, as there is no such
  * file for non-Linux platform.
  */
-#define PCI_CAPABILITY_LIST	0x34
 #define PCI_CAP_ID_VNDR		0x09
 #define PCI_CAP_ID_MSIX		0x11
 
@@ -343,8 +342,9 @@ get_cfg_addr(struct rte_pci_device *dev, struct virtio_pci_cap *cap)
 static int
 virtio_read_caps(struct rte_pci_device *dev, struct virtio_crypto_hw *hw)
 {
-	uint8_t pos;
 	struct virtio_pci_cap cap;
+	uint16_t flags;
+	off_t pos;
 	int ret;
 
 	if (rte_pci_map_device(dev)) {
@@ -352,44 +352,28 @@ virtio_read_caps(struct rte_pci_device *dev, struct virtio_crypto_hw *hw)
 		return -1;
 	}
 
-	ret = rte_pci_read_config(dev, &pos, 1, PCI_CAPABILITY_LIST);
-	if (ret < 0) {
-		VIRTIO_CRYPTO_INIT_LOG_DBG("failed to read pci capability list");
-		return -1;
+	/*
+	 * Transitional devices would also have this capability,
+	 * that's why we also check if msix is enabled.
+	 */
+	pos = rte_pci_find_capability(dev, PCI_CAP_ID_MSIX);
+	if (pos > 0 && rte_pci_read_config(dev, &flags, sizeof(flags),
+			pos + 2) == sizeof(flags)) {
+		if (flags & PCI_MSIX_ENABLE)
+			hw->use_msix = VIRTIO_MSIX_ENABLED;
+		else
+			hw->use_msix = VIRTIO_MSIX_DISABLED;
+	} else {
+		hw->use_msix = VIRTIO_MSIX_NONE;
 	}
 
-	while (pos) {
-		ret = rte_pci_read_config(dev, &cap, sizeof(cap), pos);
-		if (ret < 0) {
-			VIRTIO_CRYPTO_INIT_LOG_ERR(
-				"failed to read pci cap at pos: %x", pos);
+	pos = rte_pci_find_capability(dev, PCI_CAP_ID_VNDR);
+	while (pos > 0) {
+		if (rte_pci_read_config(dev, &cap, sizeof(cap), pos) != sizeof(cap))
 			break;
-		}
-
-		if (cap.cap_vndr == PCI_CAP_ID_MSIX) {
-			/* Transitional devices would also have this capability,
-			 * that's why we also check if msix is enabled.
-			 * 1st byte is cap ID; 2nd byte is the position of next
-			 * cap; next two bytes are the flags.
-			 */
-			uint16_t flags = ((uint16_t *)&cap)[1];
-
-			if (flags & PCI_MSIX_ENABLE)
-				hw->use_msix = VIRTIO_MSIX_ENABLED;
-			else
-				hw->use_msix = VIRTIO_MSIX_DISABLED;
-		}
-
-		if (cap.cap_vndr != PCI_CAP_ID_VNDR) {
-			VIRTIO_CRYPTO_INIT_LOG_DBG(
-				"[%2x] skipping non VNDR cap id: %02x",
-				pos, cap.cap_vndr);
-			goto next;
-		}
-
 		VIRTIO_CRYPTO_INIT_LOG_DBG(
 			"[%2x] cfg type: %u, bar: %u, offset: %04x, len: %u",
-			pos, cap.cfg_type, cap.bar, cap.offset, cap.length);
+			(unsigned int)pos, cap.cfg_type, cap.bar, cap.offset, cap.length);
 
 		switch (cap.cfg_type) {
 		case VIRTIO_PCI_CAP_COMMON_CFG:
@@ -412,8 +396,7 @@ virtio_read_caps(struct rte_pci_device *dev, struct virtio_crypto_hw *hw)
 			break;
 		}
 
-next:
-		pos = cap.cap_next;
+		pos = rte_pci_find_next_capability(dev, PCI_CAP_ID_VNDR, pos);
 	}
 
 	if (hw->common_cfg == NULL || hw->notify_base == NULL ||
diff --git a/drivers/event/dlb2/pf/dlb2_main.c b/drivers/event/dlb2/pf/dlb2_main.c
index 717aa4fc08..40e5cb594f 100644
--- a/drivers/event/dlb2/pf/dlb2_main.c
+++ b/drivers/event/dlb2/pf/dlb2_main.c
@@ -27,10 +27,6 @@
 #define NO_OWNER_VF 0	/* PF ONLY! */
 #define NOT_VF_REQ false /* PF ONLY! */
 
-#define DLB2_PCI_CAP_POINTER 0x34
-#define DLB2_PCI_CAP_NEXT(hdr) (((hdr) >> 8) & 0xFC)
-#define DLB2_PCI_CAP_ID(hdr) ((hdr) & 0xFF)
-
 #define DLB2_PCI_LNKCTL 16
 #define DLB2_PCI_SLTCTL 24
 #define DLB2_PCI_RTCTL 28
@@ -65,35 +61,6 @@
 #define DLB2_PCI_ACS_UF                  0x10
 #define DLB2_PCI_ACS_EC                  0x20
 
-static int dlb2_pci_find_capability(struct rte_pci_device *pdev, uint32_t id)
-{
-	uint8_t pos;
-	int ret;
-	uint16_t hdr;
-
-	ret = rte_pci_read_config(pdev, &pos, 1, DLB2_PCI_CAP_POINTER);
-	pos &= 0xFC;
-
-	if (ret != 1)
-		return -1;
-
-	while (pos > 0x3F) {
-		ret = rte_pci_read_config(pdev, &hdr, 2, pos);
-		if (ret != 2)
-			return -1;
-
-		if (DLB2_PCI_CAP_ID(hdr) == id)
-			return pos;
-
-		if (DLB2_PCI_CAP_ID(hdr) == 0xFF)
-			return -1;
-
-		pos = DLB2_PCI_CAP_NEXT(hdr);
-	}
-
-	return -1;
-}
-
 static int
 dlb2_pf_init_driver_state(struct dlb2_dev *dlb2_dev)
 {
@@ -258,9 +225,9 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 	uint32_t pri_reqs_dword;
 	uint16_t pri_ctrl_word;
 
-	int pcie_cap_offset;
+	off_t pcie_cap_offset;
 	int pri_cap_offset;
-	int msix_cap_offset;
+	off_t msix_cap_offset;
 	int err_cap_offset;
 	int acs_cap_offset;
 	int wait_count;
@@ -277,7 +244,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 	}
 
-	pcie_cap_offset = dlb2_pci_find_capability(pdev, DLB2_PCI_CAP_ID_EXP);
+	pcie_cap_offset = rte_pci_find_capability(pdev, DLB2_PCI_CAP_ID_EXP);
 
 	if (pcie_cap_offset < 0) {
 		DLB2_LOG_ERR("[%s()] failed to find the pcie capability\n",
@@ -516,8 +483,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 		}
 	}
 
-	msix_cap_offset = dlb2_pci_find_capability(pdev,
-						   DLB2_PCI_CAP_ID_MSIX);
+	msix_cap_offset = rte_pci_find_capability(pdev, DLB2_PCI_CAP_ID_MSIX);
 	if (msix_cap_offset >= 0) {
 		off = msix_cap_offset + DLB2_PCI_MSIX_FLAGS;
 		if (rte_pci_read_config(pdev, &cmd, 2, off) == 2) {
diff --git a/drivers/net/bnx2x/bnx2x.c b/drivers/net/bnx2x/bnx2x.c
index 29c16bb207..06f2949885 100644
--- a/drivers/net/bnx2x/bnx2x.c
+++ b/drivers/net/bnx2x/bnx2x.c
@@ -9586,14 +9586,17 @@ static void bnx2x_init_multi_cos(struct bnx2x_softc *sc)
 	}
 }
 
+static uint8_t bnx2x_pci_capabilities[] = {
+	PCIY_EXPRESS,
+	PCIY_PMG,
+	PCIY_MSI,
+	PCIY_MSIX,
+};
+
 static int bnx2x_pci_get_caps(struct bnx2x_softc *sc)
 {
-	struct {
-		uint8_t id;
-		uint8_t next;
-	} pci_cap;
-	uint16_t status;
 	struct bnx2x_pci_cap *cap;
+	unsigned int i;
 
 	cap = sc->pci_caps = rte_zmalloc("caps", sizeof(struct bnx2x_pci_cap),
 					 RTE_CACHE_LINE_SIZE);
@@ -9602,29 +9605,21 @@ static int bnx2x_pci_get_caps(struct bnx2x_softc *sc)
 		return -ENOMEM;
 	}
 
-#ifndef RTE_EXEC_ENV_FREEBSD
-	pci_read(sc, PCI_STATUS, &status, 2);
-	if (!(status & PCI_STATUS_CAP_LIST)) {
-#else
-	pci_read(sc, PCIR_STATUS, &status, 2);
-	if (!(status & PCIM_STATUS_CAPPRESENT)) {
-#endif
+	if (!rte_pci_has_capability_list(sc->pci_dev)) {
 		PMD_DRV_LOG(NOTICE, sc, "PCIe capability reading failed");
 		return -1;
 	}
 
-#ifndef RTE_EXEC_ENV_FREEBSD
-	pci_read(sc, PCI_CAPABILITY_LIST, &pci_cap.next, 1);
-#else
-	pci_read(sc, PCIR_CAP_PTR, &pci_cap.next, 1);
-#endif
-	while (pci_cap.next) {
-		cap->addr = pci_cap.next & ~3;
-		pci_read(sc, pci_cap.next & ~3, &pci_cap, 2);
-		if (pci_cap.id == 0xff)
-			break;
-		cap->id = pci_cap.id;
+	for (i = 0; i < RTE_DIM(bnx2x_pci_capabilities); i++) {
+		off_t pos = rte_pci_find_capability(sc->pci_dev,
+			bnx2x_pci_capabilities[i]);
+
+		if (pos <= 0)
+			continue;
+
+		cap->id = bnx2x_pci_capabilities[i];
 		cap->type = BNX2X_PCI_CAP;
+		cap->addr = pos;
 		cap->next = rte_zmalloc("pci_cap",
 					sizeof(struct bnx2x_pci_cap),
 					RTE_CACHE_LINE_SIZE);
diff --git a/drivers/net/cxgbe/base/adapter.h b/drivers/net/cxgbe/base/adapter.h
index 8f2ffa0eeb..00d7591ea4 100644
--- a/drivers/net/cxgbe/base/adapter.h
+++ b/drivers/net/cxgbe/base/adapter.h
@@ -511,13 +511,8 @@ static inline void t4_write_reg64(struct adapter *adapter, u32 reg_addr,
 	CXGBE_WRITE_REG64(adapter, reg_addr, val);
 }
 
-#define PCI_STATUS              0x06    /* 16 bits */
-#define PCI_STATUS_CAP_LIST     0x10    /* Support Capability List */
-#define PCI_CAPABILITY_LIST     0x34
 /* Offset of first capability list entry */
 #define PCI_CAP_ID_EXP          0x10    /* PCI Express */
-#define PCI_CAP_LIST_ID         0       /* Capability ID */
-#define PCI_CAP_LIST_NEXT       1       /* Next capability in the list */
 #define PCI_EXP_DEVCTL          0x0008  /* Device control */
 #define PCI_EXP_DEVCTL2         40      /* Device Control 2 */
 #define PCI_EXP_DEVCTL_EXT_TAG  0x0100  /* Extended Tag Field Enable */
@@ -620,31 +615,12 @@ static inline void t4_os_pci_read_cfg(struct adapter *adapter, size_t addr,
  */
 static inline int t4_os_find_pci_capability(struct adapter *adapter, int cap)
 {
-	u16 status;
-	int ttl = 48;
-	u8 pos = 0;
-	u8 id = 0;
-
-	t4_os_pci_read_cfg2(adapter, PCI_STATUS, &status);
-	if (!(status & PCI_STATUS_CAP_LIST)) {
+	if (!rte_pci_has_capability_list(adapter->pdev)) {
 		dev_err(adapter, "PCIe capability reading failed\n");
 		return -1;
 	}
 
-	t4_os_pci_read_cfg(adapter, PCI_CAPABILITY_LIST, &pos);
-	while (ttl-- && pos >= 0x40) {
-		pos &= ~3;
-		t4_os_pci_read_cfg(adapter, (pos + PCI_CAP_LIST_ID), &id);
-
-		if (id == 0xff)
-			break;
-
-		if (id == cap)
-			return (int)pos;
-
-		t4_os_pci_read_cfg(adapter, (pos + PCI_CAP_LIST_NEXT), &pos);
-	}
-	return 0;
+	return rte_pci_find_capability(adapter->pdev, cap);
 }
 
 /**
diff --git a/drivers/net/gve/gve_ethdev.c b/drivers/net/gve/gve_ethdev.c
index aa75abe102..c276b9e68e 100644
--- a/drivers/net/gve/gve_ethdev.c
+++ b/drivers/net/gve/gve_ethdev.c
@@ -606,53 +606,17 @@ gve_teardown_device_resources(struct gve_priv *priv)
 	gve_clear_device_resources_ok(priv);
 }
 
-static uint8_t
-pci_dev_find_capability(struct rte_pci_device *pdev, int cap)
-{
-	uint8_t pos, id;
-	uint16_t ent;
-	int loops;
-	int ret;
-
-	ret = rte_pci_read_config(pdev, &pos, sizeof(pos), PCI_CAPABILITY_LIST);
-	if (ret != sizeof(pos))
-		return 0;
-
-	loops = (PCI_CFG_SPACE_SIZE - PCI_STD_HEADER_SIZEOF) / PCI_CAP_SIZEOF;
-
-	while (pos && loops--) {
-		ret = rte_pci_read_config(pdev, &ent, sizeof(ent), pos);
-		if (ret != sizeof(ent))
-			return 0;
-
-		id = ent & 0xff;
-		if (id == 0xff)
-			break;
-
-		if (id == cap)
-			return pos;
-
-		pos = (ent >> 8);
-	}
-
-	return 0;
-}
-
 static int
 pci_dev_msix_vec_count(struct rte_pci_device *pdev)
 {
-	uint8_t msix_cap = pci_dev_find_capability(pdev, PCI_CAP_ID_MSIX);
+	off_t msix_pos = rte_pci_find_capability(pdev, PCI_CAP_ID_MSIX);
 	uint16_t control;
-	int ret;
 
-	if (!msix_cap)
-		return 0;
-
-	ret = rte_pci_read_config(pdev, &control, sizeof(control), msix_cap + PCI_MSIX_FLAGS);
-	if (ret != sizeof(control))
-		return 0;
+	if (msix_pos > 0 && rte_pci_read_config(pdev, &control, sizeof(control),
+			msix_pos + PCI_MSIX_FLAGS) == sizeof(control))
+		return (control & PCI_MSIX_FLAGS_QSIZE) + 1;
 
-	return (control & PCI_MSIX_FLAGS_QSIZE) + 1;
+	return 0;
 }
 
 static int
diff --git a/drivers/net/gve/gve_ethdev.h b/drivers/net/gve/gve_ethdev.h
index c9bcfa553c..8759b1c76e 100644
--- a/drivers/net/gve/gve_ethdev.h
+++ b/drivers/net/gve/gve_ethdev.h
@@ -19,10 +19,6 @@
  * we can't simply include that header here, as there is no such
  * file for non-Linux platform.
  */
-#define PCI_CFG_SPACE_SIZE	256
-#define PCI_CAPABILITY_LIST	0x34	/* Offset of first capability list entry */
-#define PCI_STD_HEADER_SIZEOF	64
-#define PCI_CAP_SIZEOF		4
 #define PCI_CAP_ID_MSIX		0x11	/* MSI-X */
 #define PCI_MSIX_FLAGS		2	/* Message Control */
 #define PCI_MSIX_FLAGS_QSIZE	0x07FF	/* Table size */
diff --git a/drivers/net/hns3/hns3_ethdev_vf.c b/drivers/net/hns3/hns3_ethdev_vf.c
index 7b3c5dc168..b731850b01 100644
--- a/drivers/net/hns3/hns3_ethdev_vf.c
+++ b/drivers/net/hns3/hns3_ethdev_vf.c
@@ -49,80 +49,24 @@ static int hns3vf_remove_mc_mac_addr(struct hns3_hw *hw,
 static int hns3vf_dev_link_update(struct rte_eth_dev *eth_dev,
 				   __rte_unused int wait_to_complete);
 
-/**
- * hns3vf_find_pci_capability - lookup a capability in the PCI capability list
- * @cap: the capability
- *
- * Return the address of the given capability within the PCI capability list.
- */
 static int
-hns3vf_find_pci_capability(const struct rte_pci_device *device, int cap)
+hns3vf_enable_msix(const struct rte_pci_device *device, bool op)
 {
-#define MAX_PCIE_CAPABILITY 48
-	uint16_t status;
-	uint8_t pos;
-	uint8_t id;
-	int ttl;
+	uint16_t control;
+	off_t pos;
 	int ret;
 
-	ret = rte_pci_read_config(device, &status, sizeof(status), PCI_STATUS);
-	if (ret < 0) {
-		PMD_INIT_LOG(ERR, "Failed to read PCI offset 0x%x", PCI_STATUS);
-		return 0;
-	}
-
-	if (!(status & PCI_STATUS_CAP_LIST))
-		return 0;
-
-	ttl = MAX_PCIE_CAPABILITY;
-	ret = rte_pci_read_config(device, &pos, sizeof(pos),
-				  PCI_CAPABILITY_LIST);
-	if (ret < 0) {
-		PMD_INIT_LOG(ERR, "Failed to read PCI offset 0x%x",
-			     PCI_CAPABILITY_LIST);
+	if (!rte_pci_has_capability_list(device)) {
+		PMD_INIT_LOG(ERR, "Failed to read PCI capability list");
 		return 0;
 	}
 
-	while (ttl-- && pos >= PCI_STD_HEADER_SIZEOF) {
-		ret = rte_pci_read_config(device, &id, sizeof(id),
-					  (pos + PCI_CAP_LIST_ID));
-		if (ret < 0) {
-			PMD_INIT_LOG(ERR, "Failed to read PCI offset 0x%x",
-				     (pos + PCI_CAP_LIST_ID));
-			break;
-		}
-
-		if (id == 0xFF)
-			break;
-
-		if (id == cap)
-			return (int)pos;
-
-		ret = rte_pci_read_config(device, &pos, sizeof(pos),
-					  (pos + PCI_CAP_LIST_NEXT));
-		if (ret < 0) {
-			PMD_INIT_LOG(ERR, "Failed to read PCI offset 0x%x",
-				     (pos + PCI_CAP_LIST_NEXT));
-			break;
-		}
-	}
-	return 0;
-}
-
-static int
-hns3vf_enable_msix(const struct rte_pci_device *device, bool op)
-{
-	uint16_t control;
-	int pos;
-	int ret;
-
-	pos = hns3vf_find_pci_capability(device, PCI_CAP_ID_MSIX);
-	if (pos) {
+	pos = rte_pci_find_capability(device, PCI_CAP_ID_MSIX);
+	if (pos > 0) {
 		ret = rte_pci_read_config(device, &control, sizeof(control),
-					  (pos + PCI_MSIX_FLAGS));
+			pos + PCI_MSIX_FLAGS);
 		if (ret < 0) {
-			PMD_INIT_LOG(ERR, "Failed to read PCI offset 0x%x",
-				     (pos + PCI_MSIX_FLAGS));
+			PMD_INIT_LOG(ERR, "Failed to read MSIX flags");
 			return -ENXIO;
 		}
 
@@ -131,10 +75,9 @@ hns3vf_enable_msix(const struct rte_pci_device *device, bool op)
 		else
 			control &= ~PCI_MSIX_FLAGS_ENABLE;
 		ret = rte_pci_write_config(device, &control, sizeof(control),
-					   (pos + PCI_MSIX_FLAGS));
+			pos + PCI_MSIX_FLAGS);
 		if (ret < 0) {
-			PMD_INIT_LOG(ERR, "failed to write PCI offset 0x%x",
-				     (pos + PCI_MSIX_FLAGS));
+			PMD_INIT_LOG(ERR, "failed to write MSIX flags");
 			return -ENXIO;
 		}
 
diff --git a/drivers/net/virtio/virtio_pci.c b/drivers/net/virtio/virtio_pci.c
index 29eb739b04..4c2a1911d1 100644
--- a/drivers/net/virtio/virtio_pci.c
+++ b/drivers/net/virtio/virtio_pci.c
@@ -20,7 +20,6 @@
  * we can't simply include that header here, as there is no such
  * file for non-Linux platform.
  */
-#define PCI_CAPABILITY_LIST	0x34
 #define PCI_CAP_ID_VNDR		0x09
 #define PCI_CAP_ID_MSIX		0x11
 
@@ -38,46 +37,16 @@ struct virtio_pci_internal virtio_pci_internal[RTE_MAX_ETHPORTS];
 static enum virtio_msix_status
 vtpci_msix_detect(struct rte_pci_device *dev)
 {
-	uint8_t pos;
-	int ret;
-
-	ret = rte_pci_read_config(dev, &pos, 1, PCI_CAPABILITY_LIST);
-	if (ret != 1) {
-		PMD_INIT_LOG(DEBUG,
-			     "failed to read pci capability list, ret %d", ret);
-		return VIRTIO_MSIX_NONE;
-	}
-
-	while (pos) {
-		uint8_t cap[2];
-
-		ret = rte_pci_read_config(dev, cap, sizeof(cap), pos);
-		if (ret != sizeof(cap)) {
-			PMD_INIT_LOG(DEBUG,
-				     "failed to read pci cap at pos: %x ret %d",
-				     pos, ret);
-			break;
-		}
+	uint16_t flags;
+	off_t pos;
 
-		if (cap[0] == PCI_CAP_ID_MSIX) {
-			uint16_t flags;
-
-			ret = rte_pci_read_config(dev, &flags, sizeof(flags),
-					pos + sizeof(cap));
-			if (ret != sizeof(flags)) {
-				PMD_INIT_LOG(DEBUG,
-					     "failed to read pci cap at pos:"
-					     " %x ret %d", pos + 2, ret);
-				break;
-			}
-
-			if (flags & PCI_MSIX_ENABLE)
-				return VIRTIO_MSIX_ENABLED;
-			else
-				return VIRTIO_MSIX_DISABLED;
-		}
-
-		pos = cap[1];
+	pos = rte_pci_find_capability(dev, PCI_CAP_ID_MSIX);
+	if (pos > 0 && rte_pci_read_config(dev, &flags, sizeof(flags),
+			pos + 2) == sizeof(flags)) {
+		if (flags & PCI_MSIX_ENABLE)
+			return VIRTIO_MSIX_ENABLED;
+		else
+			return VIRTIO_MSIX_DISABLED;
 	}
 
 	return VIRTIO_MSIX_NONE;
@@ -623,8 +592,8 @@ static int
 virtio_read_caps(struct rte_pci_device *pci_dev, struct virtio_hw *hw)
 {
 	struct virtio_pci_dev *dev = virtio_pci_get_dev(hw);
-	uint8_t pos;
 	struct virtio_pci_cap cap;
+	off_t pos;
 	int ret;
 
 	if (rte_pci_map_device(pci_dev)) {
@@ -632,72 +601,27 @@ virtio_read_caps(struct rte_pci_device *pci_dev, struct virtio_hw *hw)
 		return -1;
 	}
 
-	ret = rte_pci_read_config(pci_dev, &pos, 1, PCI_CAPABILITY_LIST);
-	if (ret != 1) {
-		PMD_INIT_LOG(DEBUG,
-			     "failed to read pci capability list, ret %d", ret);
-		return -1;
-	}
-
-	while (pos) {
-		ret = rte_pci_read_config(pci_dev, &cap, 2, pos);
-		if (ret != 2) {
-			PMD_INIT_LOG(DEBUG,
-				     "failed to read pci cap at pos: %x ret %d",
-				     pos, ret);
-			break;
-		}
-
-		if (cap.cap_vndr == PCI_CAP_ID_MSIX) {
-			/* Transitional devices would also have this capability,
-			 * that's why we also check if msix is enabled.
-			 * 1st byte is cap ID; 2nd byte is the position of next
-			 * cap; next two bytes are the flags.
-			 */
-			uint16_t flags;
-
-			ret = rte_pci_read_config(pci_dev, &flags, sizeof(flags),
-					pos + 2);
-			if (ret != sizeof(flags)) {
-				PMD_INIT_LOG(DEBUG,
-					     "failed to read pci cap at pos:"
-					     " %x ret %d", pos + 2, ret);
-				break;
-			}
-
-			if (flags & PCI_MSIX_ENABLE)
-				dev->msix_status = VIRTIO_MSIX_ENABLED;
-			else
-				dev->msix_status = VIRTIO_MSIX_DISABLED;
-		}
-
-		if (cap.cap_vndr != PCI_CAP_ID_VNDR) {
-			PMD_INIT_LOG(DEBUG,
-				"[%2x] skipping non VNDR cap id: %02x",
-				pos, cap.cap_vndr);
-			goto next;
-		}
+	/*
+	 * Transitional devices would also have this capability,
+	 * that's why we also check if msix is enabled.
+	 */
+	dev->msix_status = vtpci_msix_detect(pci_dev);
 
-		ret = rte_pci_read_config(pci_dev, &cap, sizeof(cap), pos);
-		if (ret != sizeof(cap)) {
-			PMD_INIT_LOG(DEBUG,
-				     "failed to read pci cap at pos: %x ret %d",
-				     pos, ret);
+	pos = rte_pci_find_capability(pci_dev, PCI_CAP_ID_VNDR);
+	while (pos > 0) {
+		if (rte_pci_read_config(pci_dev, &cap, sizeof(cap), pos) != sizeof(cap))
 			break;
-		}
-
 		PMD_INIT_LOG(DEBUG,
 			"[%2x] cfg type: %u, bar: %u, offset: %04x, len: %u",
-			pos, cap.cfg_type, cap.bar, cap.offset, cap.length);
+			(unsigned int)pos, cap.cfg_type, cap.bar, cap.offset, cap.length);
 
 		switch (cap.cfg_type) {
 		case VIRTIO_PCI_CAP_COMMON_CFG:
 			dev->common_cfg = get_cfg_addr(pci_dev, &cap);
 			break;
 		case VIRTIO_PCI_CAP_NOTIFY_CFG:
-			ret = rte_pci_read_config(pci_dev,
-					&dev->notify_off_multiplier,
-					4, pos + sizeof(cap));
+			ret = rte_pci_read_config(pci_dev, &dev->notify_off_multiplier,
+				4, pos + sizeof(cap));
 			if (ret != 4)
 				PMD_INIT_LOG(DEBUG,
 					"failed to read notify_off_multiplier, ret %d",
@@ -713,8 +637,7 @@ virtio_read_caps(struct rte_pci_device *pci_dev, struct virtio_hw *hw)
 			break;
 		}
 
-next:
-		pos = cap.cap_next;
+		pos = rte_pci_find_next_capability(pci_dev, PCI_CAP_ID_VNDR, pos);
 	}
 
 	if (dev->common_cfg == NULL || dev->notify_base == NULL ||
diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
index aab761b918..a6a38462cb 100644
--- a/lib/pci/rte_pci.h
+++ b/lib/pci/rte_pci.h
@@ -28,13 +28,25 @@ extern "C" {
 #define RTE_PCI_CFG_SPACE_SIZE		256
 #define RTE_PCI_CFG_SPACE_EXP_SIZE	4096
 
+#define RTE_PCI_STD_HEADER_SIZEOF	64
+
+/* Standard register offsets in the PCI configuration space */
 #define RTE_PCI_VENDOR_ID	0x00	/* 16 bits */
 #define RTE_PCI_DEVICE_ID	0x02	/* 16 bits */
 #define RTE_PCI_COMMAND		0x04	/* 16 bits */
+#define RTE_PCI_STATUS		0x06	/* 16 bits */
+#define RTE_PCI_CAPABILITY_LIST	0x34	/* 32 bits */
 
 /* PCI Command Register */
 #define RTE_PCI_COMMAND_MASTER	0x4	/* Bus Master Enable */
 
+/* PCI Status Register (RTE_PCI_STATUS) */
+#define RTE_PCI_STATUS_CAP_LIST		0x10	/* Support Capability List */
+
+/* Capability registers (RTE_PCI_CAPABILITY_LIST) */
+#define RTE_PCI_CAP_SIZEOF		4
+#define RTE_PCI_CAP_NEXT		1
+
 /* PCI Express capability registers */
 #define RTE_PCI_EXP_DEVCTL	8	/* Device Control */
 
-- 
2.41.0


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

* [PATCH v3 05/15] pci: define some capability constants
  2023-09-14 12:35 ` [PATCH v3 00/15] " David Marchand
                     ` (3 preceding siblings ...)
  2023-09-14 12:36   ` [PATCH v3 04/15] bus/pci: find PCI capability David Marchand
@ 2023-09-14 12:36   ` David Marchand
  2023-09-15 16:27     ` Sevincer, Abdullah
  2023-09-14 12:36   ` [PATCH v3 06/15] pci: define some MSIX constants David Marchand
                     ` (11 subsequent siblings)
  16 siblings, 1 reply; 98+ messages in thread
From: David Marchand @ 2023-09-14 12:36 UTC (permalink / raw)
  To: dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, bruce.richardson,
	Anatoly Burakov, Jay Zhou, Abdullah Sevincer, Julien Aube,
	Rahul Lakkireddy, Junfeng Guo, Jeroen de Borst, Rushil Gupta,
	Joshua Washington, Dongdong Liu, Yisen Zhuang, Maxime Coquelin,
	Xiao Wang, Gaetan Rivet

Define some PCI capability constants and use them in existing drivers.

Acked-by: Bruce Richardson <bruce.richardson@intel.com>
Reviewed-by: Chenbo Xia <chenbo.xia@intel.com>
Signed-off-by: David Marchand <david.marchand@redhat.com>
---
Changes since v2:
- adjusted virtio drivers after changes in previous patch,

---
 drivers/bus/pci/linux/pci_vfio.c    |  2 +-
 drivers/crypto/virtio/virtio_pci.c  | 14 +++-----------
 drivers/event/dlb2/pf/dlb2_main.c   |  6 ++----
 drivers/net/bnx2x/bnx2x.c           | 16 ++++++++--------
 drivers/net/bnx2x/bnx2x.h           |  4 ----
 drivers/net/cxgbe/base/adapter.h    |  3 +--
 drivers/net/gve/gve_ethdev.c        |  2 +-
 drivers/net/gve/gve_ethdev.h        |  2 +-
 drivers/net/hns3/hns3_ethdev_vf.c   |  2 +-
 drivers/net/virtio/virtio_pci.c     | 14 +++-----------
 drivers/vdpa/ifc/base/ifcvf_osdep.h |  4 +++-
 lib/pci/rte_pci.h                   |  5 +++++
 12 files changed, 29 insertions(+), 45 deletions(-)

diff --git a/drivers/bus/pci/linux/pci_vfio.c b/drivers/bus/pci/linux/pci_vfio.c
index 614ed5d696..bfedbc1bed 100644
--- a/drivers/bus/pci/linux/pci_vfio.c
+++ b/drivers/bus/pci/linux/pci_vfio.c
@@ -112,7 +112,7 @@ pci_vfio_get_msix_bar(const struct rte_pci_device *dev,
 {
 	off_t cap_offset;
 
-	cap_offset = rte_pci_find_capability(dev, PCI_CAP_ID_MSIX);
+	cap_offset = rte_pci_find_capability(dev, RTE_PCI_CAP_ID_MSIX);
 	if (cap_offset < 0)
 		return -1;
 
diff --git a/drivers/crypto/virtio/virtio_pci.c b/drivers/crypto/virtio/virtio_pci.c
index 19afebdcad..8f4c6bddbe 100644
--- a/drivers/crypto/virtio/virtio_pci.c
+++ b/drivers/crypto/virtio/virtio_pci.c
@@ -14,14 +14,6 @@
 #include "virtio_pci.h"
 #include "virtqueue.h"
 
-/*
- * Following macros are derived from linux/pci_regs.h, however,
- * we can't simply include that header here, as there is no such
- * file for non-Linux platform.
- */
-#define PCI_CAP_ID_VNDR		0x09
-#define PCI_CAP_ID_MSIX		0x11
-
 /*
  * The remaining space is defined by each driver as the per-driver
  * configuration space.
@@ -356,7 +348,7 @@ virtio_read_caps(struct rte_pci_device *dev, struct virtio_crypto_hw *hw)
 	 * Transitional devices would also have this capability,
 	 * that's why we also check if msix is enabled.
 	 */
-	pos = rte_pci_find_capability(dev, PCI_CAP_ID_MSIX);
+	pos = rte_pci_find_capability(dev, RTE_PCI_CAP_ID_MSIX);
 	if (pos > 0 && rte_pci_read_config(dev, &flags, sizeof(flags),
 			pos + 2) == sizeof(flags)) {
 		if (flags & PCI_MSIX_ENABLE)
@@ -367,7 +359,7 @@ virtio_read_caps(struct rte_pci_device *dev, struct virtio_crypto_hw *hw)
 		hw->use_msix = VIRTIO_MSIX_NONE;
 	}
 
-	pos = rte_pci_find_capability(dev, PCI_CAP_ID_VNDR);
+	pos = rte_pci_find_capability(dev, RTE_PCI_CAP_ID_VNDR);
 	while (pos > 0) {
 		if (rte_pci_read_config(dev, &cap, sizeof(cap), pos) != sizeof(cap))
 			break;
@@ -396,7 +388,7 @@ virtio_read_caps(struct rte_pci_device *dev, struct virtio_crypto_hw *hw)
 			break;
 		}
 
-		pos = rte_pci_find_next_capability(dev, PCI_CAP_ID_VNDR, pos);
+		pos = rte_pci_find_next_capability(dev, RTE_PCI_CAP_ID_VNDR, pos);
 	}
 
 	if (hw->common_cfg == NULL || hw->notify_base == NULL ||
diff --git a/drivers/event/dlb2/pf/dlb2_main.c b/drivers/event/dlb2/pf/dlb2_main.c
index 40e5cb594f..1a229baee0 100644
--- a/drivers/event/dlb2/pf/dlb2_main.c
+++ b/drivers/event/dlb2/pf/dlb2_main.c
@@ -38,8 +38,6 @@
 #define DLB2_PCI_EXP_DEVSTA_TRPND 0x20
 #define DLB2_PCI_EXP_DEVCTL_BCR_FLR 0x8000
 
-#define DLB2_PCI_CAP_ID_EXP       0x10
-#define DLB2_PCI_CAP_ID_MSIX      0x11
 #define DLB2_PCI_EXT_CAP_ID_PRI   0x13
 #define DLB2_PCI_EXT_CAP_ID_ACS   0xD
 
@@ -244,7 +242,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 	}
 
-	pcie_cap_offset = rte_pci_find_capability(pdev, DLB2_PCI_CAP_ID_EXP);
+	pcie_cap_offset = rte_pci_find_capability(pdev, RTE_PCI_CAP_ID_EXP);
 
 	if (pcie_cap_offset < 0) {
 		DLB2_LOG_ERR("[%s()] failed to find the pcie capability\n",
@@ -483,7 +481,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 		}
 	}
 
-	msix_cap_offset = rte_pci_find_capability(pdev, DLB2_PCI_CAP_ID_MSIX);
+	msix_cap_offset = rte_pci_find_capability(pdev, RTE_PCI_CAP_ID_MSIX);
 	if (msix_cap_offset >= 0) {
 		off = msix_cap_offset + DLB2_PCI_MSIX_FLAGS;
 		if (rte_pci_read_config(pdev, &cmd, 2, off) == 2) {
diff --git a/drivers/net/bnx2x/bnx2x.c b/drivers/net/bnx2x/bnx2x.c
index 06f2949885..8a97de8806 100644
--- a/drivers/net/bnx2x/bnx2x.c
+++ b/drivers/net/bnx2x/bnx2x.c
@@ -7613,7 +7613,7 @@ static uint32_t bnx2x_pcie_capability_read(struct bnx2x_softc *sc, int reg)
 	struct bnx2x_pci_cap *caps;
 
 	/* ensure PCIe capability is enabled */
-	caps = pci_find_cap(sc, PCIY_EXPRESS, BNX2X_PCI_CAP);
+	caps = pci_find_cap(sc, RTE_PCI_CAP_ID_EXP, BNX2X_PCI_CAP);
 	if (NULL != caps) {
 		PMD_DRV_LOG(DEBUG, sc, "Found PCIe capability: "
 			    "id=0x%04X type=0x%04X addr=0x%08X",
@@ -7647,7 +7647,7 @@ static void bnx2x_probe_pci_caps(struct bnx2x_softc *sc)
 	int reg = 0;
 
 	/* check if PCI Power Management is enabled */
-	caps = pci_find_cap(sc, PCIY_PMG, BNX2X_PCI_CAP);
+	caps = pci_find_cap(sc, RTE_PCI_CAP_ID_PM, BNX2X_PCI_CAP);
 	if (NULL != caps) {
 		PMD_DRV_LOG(DEBUG, sc, "Found PM capability: "
 			    "id=0x%04X type=0x%04X addr=0x%08X",
@@ -7669,7 +7669,7 @@ static void bnx2x_probe_pci_caps(struct bnx2x_softc *sc)
 	sc->devinfo.pcie_cap_flags |= BNX2X_PCIE_CAPABLE_FLAG;
 
 	/* check if MSI capability is enabled */
-	caps = pci_find_cap(sc, PCIY_MSI, BNX2X_PCI_CAP);
+	caps = pci_find_cap(sc, RTE_PCI_CAP_ID_MSI, BNX2X_PCI_CAP);
 	if (NULL != caps) {
 		PMD_DRV_LOG(DEBUG, sc, "Found MSI capability at 0x%04x", reg);
 
@@ -7678,7 +7678,7 @@ static void bnx2x_probe_pci_caps(struct bnx2x_softc *sc)
 	}
 
 	/* check if MSI-X capability is enabled */
-	caps = pci_find_cap(sc, PCIY_MSIX, BNX2X_PCI_CAP);
+	caps = pci_find_cap(sc, RTE_PCI_CAP_ID_MSIX, BNX2X_PCI_CAP);
 	if (NULL != caps) {
 		PMD_DRV_LOG(DEBUG, sc, "Found MSI-X capability at 0x%04x", reg);
 
@@ -9587,10 +9587,10 @@ static void bnx2x_init_multi_cos(struct bnx2x_softc *sc)
 }
 
 static uint8_t bnx2x_pci_capabilities[] = {
-	PCIY_EXPRESS,
-	PCIY_PMG,
-	PCIY_MSI,
-	PCIY_MSIX,
+	RTE_PCI_CAP_ID_EXP,
+	RTE_PCI_CAP_ID_PM,
+	RTE_PCI_CAP_ID_MSI,
+	RTE_PCI_CAP_ID_MSIX,
 };
 
 static int bnx2x_pci_get_caps(struct bnx2x_softc *sc)
diff --git a/drivers/net/bnx2x/bnx2x.h b/drivers/net/bnx2x/bnx2x.h
index 89414ac88a..07ef0567c2 100644
--- a/drivers/net/bnx2x/bnx2x.h
+++ b/drivers/net/bnx2x/bnx2x.h
@@ -33,10 +33,6 @@
 #ifndef RTE_EXEC_ENV_FREEBSD
 #include <linux/pci_regs.h>
 
-#define PCIY_PMG                       PCI_CAP_ID_PM
-#define PCIY_MSI                       PCI_CAP_ID_MSI
-#define PCIY_EXPRESS                   PCI_CAP_ID_EXP
-#define PCIY_MSIX                      PCI_CAP_ID_MSIX
 #define PCIR_EXPRESS_DEVICE_STA        PCI_EXP_TYPE_RC_EC
 #define PCIM_EXP_STA_TRANSACTION_PND   PCI_EXP_DEVSTA_TRPND
 #define PCIR_EXPRESS_LINK_STA          PCI_EXP_LNKSTA
diff --git a/drivers/net/cxgbe/base/adapter.h b/drivers/net/cxgbe/base/adapter.h
index 00d7591ea4..7bee5cf3a8 100644
--- a/drivers/net/cxgbe/base/adapter.h
+++ b/drivers/net/cxgbe/base/adapter.h
@@ -511,8 +511,7 @@ static inline void t4_write_reg64(struct adapter *adapter, u32 reg_addr,
 	CXGBE_WRITE_REG64(adapter, reg_addr, val);
 }
 
-/* Offset of first capability list entry */
-#define PCI_CAP_ID_EXP          0x10    /* PCI Express */
+#define PCI_CAP_ID_EXP          RTE_PCI_CAP_ID_EXP
 #define PCI_EXP_DEVCTL          0x0008  /* Device control */
 #define PCI_EXP_DEVCTL2         40      /* Device Control 2 */
 #define PCI_EXP_DEVCTL_EXT_TAG  0x0100  /* Extended Tag Field Enable */
diff --git a/drivers/net/gve/gve_ethdev.c b/drivers/net/gve/gve_ethdev.c
index c276b9e68e..9ea5dbaeea 100644
--- a/drivers/net/gve/gve_ethdev.c
+++ b/drivers/net/gve/gve_ethdev.c
@@ -609,7 +609,7 @@ gve_teardown_device_resources(struct gve_priv *priv)
 static int
 pci_dev_msix_vec_count(struct rte_pci_device *pdev)
 {
-	off_t msix_pos = rte_pci_find_capability(pdev, PCI_CAP_ID_MSIX);
+	off_t msix_pos = rte_pci_find_capability(pdev, RTE_PCI_CAP_ID_MSIX);
 	uint16_t control;
 
 	if (msix_pos > 0 && rte_pci_read_config(pdev, &control, sizeof(control),
diff --git a/drivers/net/gve/gve_ethdev.h b/drivers/net/gve/gve_ethdev.h
index 8759b1c76e..d604a75b7f 100644
--- a/drivers/net/gve/gve_ethdev.h
+++ b/drivers/net/gve/gve_ethdev.h
@@ -8,6 +8,7 @@
 #include <ethdev_driver.h>
 #include <ethdev_pci.h>
 #include <rte_ether.h>
+#include <rte_pci.h>
 
 #include "base/gve.h"
 
@@ -19,7 +20,6 @@
  * we can't simply include that header here, as there is no such
  * file for non-Linux platform.
  */
-#define PCI_CAP_ID_MSIX		0x11	/* MSI-X */
 #define PCI_MSIX_FLAGS		2	/* Message Control */
 #define PCI_MSIX_FLAGS_QSIZE	0x07FF	/* Table size */
 
diff --git a/drivers/net/hns3/hns3_ethdev_vf.c b/drivers/net/hns3/hns3_ethdev_vf.c
index b731850b01..eab5c55f5e 100644
--- a/drivers/net/hns3/hns3_ethdev_vf.c
+++ b/drivers/net/hns3/hns3_ethdev_vf.c
@@ -61,7 +61,7 @@ hns3vf_enable_msix(const struct rte_pci_device *device, bool op)
 		return 0;
 	}
 
-	pos = rte_pci_find_capability(device, PCI_CAP_ID_MSIX);
+	pos = rte_pci_find_capability(device, RTE_PCI_CAP_ID_MSIX);
 	if (pos > 0) {
 		ret = rte_pci_read_config(device, &control, sizeof(control),
 			pos + PCI_MSIX_FLAGS);
diff --git a/drivers/net/virtio/virtio_pci.c b/drivers/net/virtio/virtio_pci.c
index 4c2a1911d1..ffdacecd6d 100644
--- a/drivers/net/virtio/virtio_pci.c
+++ b/drivers/net/virtio/virtio_pci.c
@@ -15,14 +15,6 @@
 #include "virtio_logs.h"
 #include "virtqueue.h"
 
-/*
- * Following macros are derived from linux/pci_regs.h, however,
- * we can't simply include that header here, as there is no such
- * file for non-Linux platform.
- */
-#define PCI_CAP_ID_VNDR		0x09
-#define PCI_CAP_ID_MSIX		0x11
-
 /*
  * The remaining space is defined by each driver as the per-driver
  * configuration space.
@@ -40,7 +32,7 @@ vtpci_msix_detect(struct rte_pci_device *dev)
 	uint16_t flags;
 	off_t pos;
 
-	pos = rte_pci_find_capability(dev, PCI_CAP_ID_MSIX);
+	pos = rte_pci_find_capability(dev, RTE_PCI_CAP_ID_MSIX);
 	if (pos > 0 && rte_pci_read_config(dev, &flags, sizeof(flags),
 			pos + 2) == sizeof(flags)) {
 		if (flags & PCI_MSIX_ENABLE)
@@ -607,7 +599,7 @@ virtio_read_caps(struct rte_pci_device *pci_dev, struct virtio_hw *hw)
 	 */
 	dev->msix_status = vtpci_msix_detect(pci_dev);
 
-	pos = rte_pci_find_capability(pci_dev, PCI_CAP_ID_VNDR);
+	pos = rte_pci_find_capability(pci_dev, RTE_PCI_CAP_ID_VNDR);
 	while (pos > 0) {
 		if (rte_pci_read_config(pci_dev, &cap, sizeof(cap), pos) != sizeof(cap))
 			break;
@@ -637,7 +629,7 @@ virtio_read_caps(struct rte_pci_device *pci_dev, struct virtio_hw *hw)
 			break;
 		}
 
-		pos = rte_pci_find_next_capability(pci_dev, PCI_CAP_ID_VNDR, pos);
+		pos = rte_pci_find_next_capability(pci_dev, RTE_PCI_CAP_ID_VNDR, pos);
 	}
 
 	if (dev->common_cfg == NULL || dev->notify_base == NULL ||
diff --git a/drivers/vdpa/ifc/base/ifcvf_osdep.h b/drivers/vdpa/ifc/base/ifcvf_osdep.h
index 6444d7f72c..dd2ff08f77 100644
--- a/drivers/vdpa/ifc/base/ifcvf_osdep.h
+++ b/drivers/vdpa/ifc/base/ifcvf_osdep.h
@@ -6,7 +6,6 @@
 #define _IFCVF_OSDEP_H_
 
 #include <stdint.h>
-#include <linux/pci_regs.h>
 
 #include <rte_cycles.h>
 #include <rte_pci.h>
@@ -35,6 +34,9 @@ typedef struct rte_pci_device PCI_DEV;
 #define PCI_READ_CONFIG_DWORD(dev, val, where) \
 	rte_pci_read_config(dev, val, 4, where)
 
+#define PCI_CAPABILITY_LIST RTE_PCI_CAPABILITY_LIST
+#define PCI_CAP_ID_VNDR RTE_PCI_CAP_ID_VNDR
+
 typedef uint8_t    u8;
 typedef int8_t     s8;
 typedef uint16_t   u16;
diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
index a6a38462cb..8e030caef2 100644
--- a/lib/pci/rte_pci.h
+++ b/lib/pci/rte_pci.h
@@ -44,6 +44,11 @@ extern "C" {
 #define RTE_PCI_STATUS_CAP_LIST		0x10	/* Support Capability List */
 
 /* Capability registers (RTE_PCI_CAPABILITY_LIST) */
+#define RTE_PCI_CAP_ID_PM		0x01	/* Power Management */
+#define RTE_PCI_CAP_ID_MSI		0x05	/* Message Signalled Interrupts */
+#define RTE_PCI_CAP_ID_VNDR		0x09	/* Vendor-Specific */
+#define RTE_PCI_CAP_ID_EXP		0x10	/* PCI Express */
+#define RTE_PCI_CAP_ID_MSIX		0x11	/* MSI-X */
 #define RTE_PCI_CAP_SIZEOF		4
 #define RTE_PCI_CAP_NEXT		1
 
-- 
2.41.0


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

* [PATCH v3 06/15] pci: define some MSIX constants
  2023-09-14 12:35 ` [PATCH v3 00/15] " David Marchand
                     ` (4 preceding siblings ...)
  2023-09-14 12:36   ` [PATCH v3 05/15] pci: define some capability constants David Marchand
@ 2023-09-14 12:36   ` David Marchand
  2023-09-14 12:36   ` [PATCH v3 07/15] pci: define some command constants David Marchand
                     ` (10 subsequent siblings)
  16 siblings, 0 replies; 98+ messages in thread
From: David Marchand @ 2023-09-14 12:36 UTC (permalink / raw)
  To: dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, bruce.richardson,
	Anatoly Burakov, Jay Zhou, Abdullah Sevincer, Julien Aube,
	Junfeng Guo, Jeroen de Borst, Rushil Gupta, Joshua Washington,
	Dongdong Liu, Yisen Zhuang, Maxime Coquelin, Gaetan Rivet

Define some PCI MSIX constants and use them in existing drivers.

Signed-off-by: David Marchand <david.marchand@redhat.com>
Acked-by: Bruce Richardson <bruce.richardson@intel.com>
Reviewed-by: Chenbo Xia <chenbo.xia@intel.com>
---
 drivers/bus/pci/linux/pci_init.h   | 18 ------------------
 drivers/bus/pci/linux/pci_vfio.c   |  7 ++++---
 drivers/crypto/virtio/virtio_pci.c |  6 ++----
 drivers/event/dlb2/pf/dlb2_main.c  | 13 +++++--------
 drivers/net/bnx2x/bnx2x.c          |  4 ++--
 drivers/net/bnx2x/bnx2x.h          |  2 --
 drivers/net/gve/gve_ethdev.c       |  4 ++--
 drivers/net/gve/gve_ethdev.h       |  8 --------
 drivers/net/hns3/hns3_ethdev_vf.c  |  9 ++++-----
 drivers/net/virtio/virtio_pci.c    |  6 ++----
 lib/pci/rte_pci.h                  | 10 ++++++++++
 11 files changed, 31 insertions(+), 56 deletions(-)

diff --git a/drivers/bus/pci/linux/pci_init.h b/drivers/bus/pci/linux/pci_init.h
index d842809ccd..a4d37c0d0a 100644
--- a/drivers/bus/pci/linux/pci_init.h
+++ b/drivers/bus/pci/linux/pci_init.h
@@ -52,24 +52,6 @@ int pci_uio_ioport_unmap(struct rte_pci_ioport *p);
 
 #ifdef VFIO_PRESENT
 
-#ifdef PCI_MSIX_TABLE_BIR
-#define RTE_PCI_MSIX_TABLE_BIR    PCI_MSIX_TABLE_BIR
-#else
-#define RTE_PCI_MSIX_TABLE_BIR    0x7
-#endif
-
-#ifdef PCI_MSIX_TABLE_OFFSET
-#define RTE_PCI_MSIX_TABLE_OFFSET PCI_MSIX_TABLE_OFFSET
-#else
-#define RTE_PCI_MSIX_TABLE_OFFSET 0xfffffff8
-#endif
-
-#ifdef PCI_MSIX_FLAGS_QSIZE
-#define RTE_PCI_MSIX_FLAGS_QSIZE  PCI_MSIX_FLAGS_QSIZE
-#else
-#define RTE_PCI_MSIX_FLAGS_QSIZE  0x07ff
-#endif
-
 /* access config space */
 int pci_vfio_read_config(const struct rte_pci_device *dev,
 			 void *buf, size_t len, off_t offs);
diff --git a/drivers/bus/pci/linux/pci_vfio.c b/drivers/bus/pci/linux/pci_vfio.c
index bfedbc1bed..7881b7a946 100644
--- a/drivers/bus/pci/linux/pci_vfio.c
+++ b/drivers/bus/pci/linux/pci_vfio.c
@@ -120,14 +120,15 @@ pci_vfio_get_msix_bar(const struct rte_pci_device *dev,
 		uint16_t flags;
 		uint32_t reg;
 
-		/* table offset resides in the next 4 bytes */
-		if (rte_pci_read_config(dev, &reg, sizeof(reg), cap_offset + 4) < 0) {
+		if (rte_pci_read_config(dev, &reg, sizeof(reg), cap_offset +
+				RTE_PCI_MSIX_TABLE) < 0) {
 			RTE_LOG(ERR, EAL,
 				"Cannot read MSIX table from PCI config space!\n");
 			return -1;
 		}
 
-		if (rte_pci_read_config(dev, &flags, sizeof(flags), cap_offset + 2) < 0) {
+		if (rte_pci_read_config(dev, &flags, sizeof(flags), cap_offset +
+				RTE_PCI_MSIX_FLAGS) < 0) {
 			RTE_LOG(ERR, EAL,
 				"Cannot read MSIX flags from PCI config space!\n");
 			return -1;
diff --git a/drivers/crypto/virtio/virtio_pci.c b/drivers/crypto/virtio/virtio_pci.c
index 8f4c6bddbe..eca8a2a69d 100644
--- a/drivers/crypto/virtio/virtio_pci.c
+++ b/drivers/crypto/virtio/virtio_pci.c
@@ -329,8 +329,6 @@ get_cfg_addr(struct rte_pci_device *dev, struct virtio_pci_cap *cap)
 	return base + offset;
 }
 
-#define PCI_MSIX_ENABLE 0x8000
-
 static int
 virtio_read_caps(struct rte_pci_device *dev, struct virtio_crypto_hw *hw)
 {
@@ -350,8 +348,8 @@ virtio_read_caps(struct rte_pci_device *dev, struct virtio_crypto_hw *hw)
 	 */
 	pos = rte_pci_find_capability(dev, RTE_PCI_CAP_ID_MSIX);
 	if (pos > 0 && rte_pci_read_config(dev, &flags, sizeof(flags),
-			pos + 2) == sizeof(flags)) {
-		if (flags & PCI_MSIX_ENABLE)
+			pos + RTE_PCI_MSIX_FLAGS) == sizeof(flags)) {
+		if (flags & RTE_PCI_MSIX_FLAGS_ENABLE)
 			hw->use_msix = VIRTIO_MSIX_ENABLED;
 		else
 			hw->use_msix = VIRTIO_MSIX_DISABLED;
diff --git a/drivers/event/dlb2/pf/dlb2_main.c b/drivers/event/dlb2/pf/dlb2_main.c
index 1a229baee0..c6606a9bee 100644
--- a/drivers/event/dlb2/pf/dlb2_main.c
+++ b/drivers/event/dlb2/pf/dlb2_main.c
@@ -44,9 +44,6 @@
 #define DLB2_PCI_PRI_CTRL_ENABLE         0x1
 #define DLB2_PCI_PRI_ALLOC_REQ           0xC
 #define DLB2_PCI_PRI_CTRL                0x4
-#define DLB2_PCI_MSIX_FLAGS              0x2
-#define DLB2_PCI_MSIX_FLAGS_ENABLE       0x8000
-#define DLB2_PCI_MSIX_FLAGS_MASKALL      0x4000
 #define DLB2_PCI_ERR_ROOT_STATUS         0x30
 #define DLB2_PCI_ERR_COR_STATUS          0x10
 #define DLB2_PCI_ERR_UNCOR_STATUS        0x4
@@ -483,10 +480,10 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 
 	msix_cap_offset = rte_pci_find_capability(pdev, RTE_PCI_CAP_ID_MSIX);
 	if (msix_cap_offset >= 0) {
-		off = msix_cap_offset + DLB2_PCI_MSIX_FLAGS;
+		off = msix_cap_offset + RTE_PCI_MSIX_FLAGS;
 		if (rte_pci_read_config(pdev, &cmd, 2, off) == 2) {
-			cmd |= DLB2_PCI_MSIX_FLAGS_ENABLE;
-			cmd |= DLB2_PCI_MSIX_FLAGS_MASKALL;
+			cmd |= RTE_PCI_MSIX_FLAGS_ENABLE;
+			cmd |= RTE_PCI_MSIX_FLAGS_MASKALL;
 			if (rte_pci_write_config(pdev, &cmd, 2, off) != 2) {
 				DLB2_LOG_ERR("[%s()] failed to write msix flags\n",
 				       __func__);
@@ -494,9 +491,9 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			}
 		}
 
-		off = msix_cap_offset + DLB2_PCI_MSIX_FLAGS;
+		off = msix_cap_offset + RTE_PCI_MSIX_FLAGS;
 		if (rte_pci_read_config(pdev, &cmd, 2, off) == 2) {
-			cmd &= ~DLB2_PCI_MSIX_FLAGS_MASKALL;
+			cmd &= ~RTE_PCI_MSIX_FLAGS_MASKALL;
 			if (rte_pci_write_config(pdev, &cmd, 2, off) != 2) {
 				DLB2_LOG_ERR("[%s()] failed to write msix flags\n",
 				       __func__);
diff --git a/drivers/net/bnx2x/bnx2x.c b/drivers/net/bnx2x/bnx2x.c
index 8a97de8806..e3f14400cc 100644
--- a/drivers/net/bnx2x/bnx2x.c
+++ b/drivers/net/bnx2x/bnx2x.c
@@ -9766,9 +9766,9 @@ int bnx2x_attach(struct bnx2x_softc *sc)
 	if (sc->devinfo.pcie_msix_cap_reg != 0) {
 		uint32_t val;
 		pci_read(sc,
-			 (sc->devinfo.pcie_msix_cap_reg + PCIR_MSIX_CTRL), &val,
+			 (sc->devinfo.pcie_msix_cap_reg + RTE_PCI_MSIX_FLAGS), &val,
 			 2);
-		sc->igu_sb_cnt = (val & PCIM_MSIXCTRL_TABLE_SIZE) + 1;
+		sc->igu_sb_cnt = (val & RTE_PCI_MSIX_FLAGS_QSIZE) + 1;
 	} else {
 		sc->igu_sb_cnt = 1;
 	}
diff --git a/drivers/net/bnx2x/bnx2x.h b/drivers/net/bnx2x/bnx2x.h
index 07ef0567c2..60af75d336 100644
--- a/drivers/net/bnx2x/bnx2x.h
+++ b/drivers/net/bnx2x/bnx2x.h
@@ -46,8 +46,6 @@
 #define PCIM_PSTAT_PME                 PCI_PM_CTRL_PME_STATUS
 #define PCIM_PSTAT_D3                  0x3
 #define PCIM_PSTAT_PMEENABLE           PCI_PM_CTRL_PME_ENABLE
-#define PCIR_MSIX_CTRL                 PCI_MSIX_FLAGS
-#define PCIM_MSIXCTRL_TABLE_SIZE       PCI_MSIX_FLAGS_QSIZE
 #else
 #include <dev/pci/pcireg.h>
 #endif
diff --git a/drivers/net/gve/gve_ethdev.c b/drivers/net/gve/gve_ethdev.c
index 9ea5dbaeea..9b25f3036b 100644
--- a/drivers/net/gve/gve_ethdev.c
+++ b/drivers/net/gve/gve_ethdev.c
@@ -613,8 +613,8 @@ pci_dev_msix_vec_count(struct rte_pci_device *pdev)
 	uint16_t control;
 
 	if (msix_pos > 0 && rte_pci_read_config(pdev, &control, sizeof(control),
-			msix_pos + PCI_MSIX_FLAGS) == sizeof(control))
-		return (control & PCI_MSIX_FLAGS_QSIZE) + 1;
+			msix_pos + RTE_PCI_MSIX_FLAGS) == sizeof(control))
+		return (control & RTE_PCI_MSIX_FLAGS_QSIZE) + 1;
 
 	return 0;
 }
diff --git a/drivers/net/gve/gve_ethdev.h b/drivers/net/gve/gve_ethdev.h
index d604a75b7f..c47b4d454d 100644
--- a/drivers/net/gve/gve_ethdev.h
+++ b/drivers/net/gve/gve_ethdev.h
@@ -15,14 +15,6 @@
 /* TODO: this is a workaround to ensure that Tx complq is enough */
 #define DQO_TX_MULTIPLIER 4
 
-/*
- * Following macros are derived from linux/pci_regs.h, however,
- * we can't simply include that header here, as there is no such
- * file for non-Linux platform.
- */
-#define PCI_MSIX_FLAGS		2	/* Message Control */
-#define PCI_MSIX_FLAGS_QSIZE	0x07FF	/* Table size */
-
 #define GVE_DEFAULT_RX_FREE_THRESH  512
 #define GVE_DEFAULT_TX_FREE_THRESH   32
 #define GVE_DEFAULT_TX_RS_THRESH     32
diff --git a/drivers/net/hns3/hns3_ethdev_vf.c b/drivers/net/hns3/hns3_ethdev_vf.c
index eab5c55f5e..3729615159 100644
--- a/drivers/net/hns3/hns3_ethdev_vf.c
+++ b/drivers/net/hns3/hns3_ethdev_vf.c
@@ -2,7 +2,6 @@
  * Copyright(c) 2018-2021 HiSilicon Limited.
  */
 
-#include <linux/pci_regs.h>
 #include <rte_alarm.h>
 #include <ethdev_pci.h>
 #include <rte_io.h>
@@ -64,18 +63,18 @@ hns3vf_enable_msix(const struct rte_pci_device *device, bool op)
 	pos = rte_pci_find_capability(device, RTE_PCI_CAP_ID_MSIX);
 	if (pos > 0) {
 		ret = rte_pci_read_config(device, &control, sizeof(control),
-			pos + PCI_MSIX_FLAGS);
+			pos + RTE_PCI_MSIX_FLAGS);
 		if (ret < 0) {
 			PMD_INIT_LOG(ERR, "Failed to read MSIX flags");
 			return -ENXIO;
 		}
 
 		if (op)
-			control |= PCI_MSIX_FLAGS_ENABLE;
+			control |= RTE_PCI_MSIX_FLAGS_ENABLE;
 		else
-			control &= ~PCI_MSIX_FLAGS_ENABLE;
+			control &= ~RTE_PCI_MSIX_FLAGS_ENABLE;
 		ret = rte_pci_write_config(device, &control, sizeof(control),
-			pos + PCI_MSIX_FLAGS);
+			pos + RTE_PCI_MSIX_FLAGS);
 		if (ret < 0) {
 			PMD_INIT_LOG(ERR, "failed to write MSIX flags");
 			return -ENXIO;
diff --git a/drivers/net/virtio/virtio_pci.c b/drivers/net/virtio/virtio_pci.c
index ffdacecd6d..90bbb53502 100644
--- a/drivers/net/virtio/virtio_pci.c
+++ b/drivers/net/virtio/virtio_pci.c
@@ -24,8 +24,6 @@
 
 struct virtio_pci_internal virtio_pci_internal[RTE_MAX_ETHPORTS];
 
-#define PCI_MSIX_ENABLE 0x8000
-
 static enum virtio_msix_status
 vtpci_msix_detect(struct rte_pci_device *dev)
 {
@@ -34,8 +32,8 @@ vtpci_msix_detect(struct rte_pci_device *dev)
 
 	pos = rte_pci_find_capability(dev, RTE_PCI_CAP_ID_MSIX);
 	if (pos > 0 && rte_pci_read_config(dev, &flags, sizeof(flags),
-			pos + 2) == sizeof(flags)) {
-		if (flags & PCI_MSIX_ENABLE)
+			pos + RTE_PCI_MSIX_FLAGS) == sizeof(flags)) {
+		if (flags & RTE_PCI_MSIX_FLAGS_ENABLE)
 			return VIRTIO_MSIX_ENABLED;
 		else
 			return VIRTIO_MSIX_DISABLED;
diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
index 8e030caef2..650dbb7645 100644
--- a/lib/pci/rte_pci.h
+++ b/lib/pci/rte_pci.h
@@ -52,6 +52,16 @@ extern "C" {
 #define RTE_PCI_CAP_SIZEOF		4
 #define RTE_PCI_CAP_NEXT		1
 
+/* MSI-X registers (RTE_PCI_CAP_ID_MSIX) */
+#define RTE_PCI_MSIX_FLAGS		2	/* Message Control */
+#define RTE_PCI_MSIX_FLAGS_QSIZE	0x07ff	/* Table size */
+#define RTE_PCI_MSIX_FLAGS_MASKALL	0x4000	/* Mask all vectors for this function */
+#define RTE_PCI_MSIX_FLAGS_ENABLE	0x8000	/* MSI-X enable */
+
+#define RTE_PCI_MSIX_TABLE		4	/* Table offset */
+#define RTE_PCI_MSIX_TABLE_BIR		0x00000007 /* BAR index */
+#define RTE_PCI_MSIX_TABLE_OFFSET	0xfffffff8 /* Offset into specified BAR */
+
 /* PCI Express capability registers */
 #define RTE_PCI_EXP_DEVCTL	8	/* Device Control */
 
-- 
2.41.0


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

* [PATCH v3 07/15] pci: define some command constants
  2023-09-14 12:35 ` [PATCH v3 00/15] " David Marchand
                     ` (5 preceding siblings ...)
  2023-09-14 12:36   ` [PATCH v3 06/15] pci: define some MSIX constants David Marchand
@ 2023-09-14 12:36   ` David Marchand
  2023-09-14 12:36   ` [PATCH v3 08/15] pci: define some BAR constants David Marchand
                     ` (9 subsequent siblings)
  16 siblings, 0 replies; 98+ messages in thread
From: David Marchand @ 2023-09-14 12:36 UTC (permalink / raw)
  To: dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, bruce.richardson,
	Anatoly Burakov, Abdullah Sevincer, Gaetan Rivet

Define some PCI command constants and use them in existing drivers.

Signed-off-by: David Marchand <david.marchand@redhat.com>
Acked-by: Bruce Richardson <bruce.richardson@intel.com>
Reviewed-by: Chenbo Xia <chenbo.xia@intel.com>
---
 drivers/bus/pci/linux/pci_vfio.c  | 8 ++++----
 drivers/event/dlb2/pf/dlb2_main.c | 8 +++-----
 lib/pci/rte_pci.h                 | 6 ++++--
 3 files changed, 11 insertions(+), 11 deletions(-)

diff --git a/drivers/bus/pci/linux/pci_vfio.c b/drivers/bus/pci/linux/pci_vfio.c
index 7881b7a946..bf91492dd9 100644
--- a/drivers/bus/pci/linux/pci_vfio.c
+++ b/drivers/bus/pci/linux/pci_vfio.c
@@ -156,18 +156,18 @@ pci_vfio_enable_bus_memory(struct rte_pci_device *dev, int dev_fd)
 		return -1;
 	}
 
-	ret = pread64(dev_fd, &cmd, sizeof(cmd), offset + PCI_COMMAND);
+	ret = pread64(dev_fd, &cmd, sizeof(cmd), offset + RTE_PCI_COMMAND);
 
 	if (ret != sizeof(cmd)) {
 		RTE_LOG(ERR, EAL, "Cannot read command from PCI config space!\n");
 		return -1;
 	}
 
-	if (cmd & PCI_COMMAND_MEMORY)
+	if (cmd & RTE_PCI_COMMAND_MEMORY)
 		return 0;
 
-	cmd |= PCI_COMMAND_MEMORY;
-	ret = pwrite64(dev_fd, &cmd, sizeof(cmd), offset + PCI_COMMAND);
+	cmd |= RTE_PCI_COMMAND_MEMORY;
+	ret = pwrite64(dev_fd, &cmd, sizeof(cmd), offset + RTE_PCI_COMMAND);
 
 	if (ret != sizeof(cmd)) {
 		RTE_LOG(ERR, EAL, "Cannot write command to PCI config space!\n");
diff --git a/drivers/event/dlb2/pf/dlb2_main.c b/drivers/event/dlb2/pf/dlb2_main.c
index c6606a9bee..6dbaa2ff97 100644
--- a/drivers/event/dlb2/pf/dlb2_main.c
+++ b/drivers/event/dlb2/pf/dlb2_main.c
@@ -33,7 +33,6 @@
 #define DLB2_PCI_EXP_DEVCTL2 40
 #define DLB2_PCI_LNKCTL2 48
 #define DLB2_PCI_SLTCTL2 56
-#define DLB2_PCI_CMD 4
 #define DLB2_PCI_EXP_DEVSTA 10
 #define DLB2_PCI_EXP_DEVSTA_TRPND 0x20
 #define DLB2_PCI_EXP_DEVCTL_BCR_FLR 0x8000
@@ -47,7 +46,6 @@
 #define DLB2_PCI_ERR_ROOT_STATUS         0x30
 #define DLB2_PCI_ERR_COR_STATUS          0x10
 #define DLB2_PCI_ERR_UNCOR_STATUS        0x4
-#define DLB2_PCI_COMMAND_INTX_DISABLE    0x400
 #define DLB2_PCI_ACS_CAP                 0x4
 #define DLB2_PCI_ACS_CTRL                0x6
 #define DLB2_PCI_ACS_SV                  0x1
@@ -286,7 +284,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 
 	/* clear the PCI command register before issuing the FLR */
 
-	off = DLB2_PCI_CMD;
+	off = RTE_PCI_COMMAND;
 	cmd = 0;
 	if (rte_pci_write_config(pdev, &cmd, 2, off) != 2) {
 		DLB2_LOG_ERR("[%s()] failed to write the pci command\n",
@@ -468,9 +466,9 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 		}
 	}
 
-	off = DLB2_PCI_CMD;
+	off = RTE_PCI_COMMAND;
 	if (rte_pci_read_config(pdev, &cmd, 2, off) == 2) {
-		cmd &= ~DLB2_PCI_COMMAND_INTX_DISABLE;
+		cmd &= ~RTE_PCI_COMMAND_INTX_DISABLE;
 		if (rte_pci_write_config(pdev, &cmd, 2, off) != 2) {
 			DLB2_LOG_ERR("[%s()] failed to write the pci command\n",
 			       __func__);
diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
index 650dbb7645..8bf60b9fb7 100644
--- a/lib/pci/rte_pci.h
+++ b/lib/pci/rte_pci.h
@@ -37,8 +37,10 @@ extern "C" {
 #define RTE_PCI_STATUS		0x06	/* 16 bits */
 #define RTE_PCI_CAPABILITY_LIST	0x34	/* 32 bits */
 
-/* PCI Command Register */
-#define RTE_PCI_COMMAND_MASTER	0x4	/* Bus Master Enable */
+/* PCI Command Register (RTE_PCI_COMMAND) */
+#define RTE_PCI_COMMAND_MEMORY		0x2	/* Enable response in Memory space */
+#define RTE_PCI_COMMAND_MASTER		0x4	/* Bus Master Enable */
+#define RTE_PCI_COMMAND_INTX_DISABLE	0x400	/* INTx Emulation Disable */
 
 /* PCI Status Register (RTE_PCI_STATUS) */
 #define RTE_PCI_STATUS_CAP_LIST		0x10	/* Support Capability List */
-- 
2.41.0


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

* [PATCH v3 08/15] pci: define some BAR constants
  2023-09-14 12:35 ` [PATCH v3 00/15] " David Marchand
                     ` (6 preceding siblings ...)
  2023-09-14 12:36   ` [PATCH v3 07/15] pci: define some command constants David Marchand
@ 2023-09-14 12:36   ` David Marchand
  2023-09-14 12:36   ` [PATCH v3 09/15] pci: define some PM constants David Marchand
                     ` (8 subsequent siblings)
  16 siblings, 0 replies; 98+ messages in thread
From: David Marchand @ 2023-09-14 12:36 UTC (permalink / raw)
  To: dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, bruce.richardson,
	Anatoly Burakov, Gaetan Rivet

Define some PCI BAR constants and use them in existing drivers.

Signed-off-by: David Marchand <david.marchand@redhat.com>
Acked-by: Bruce Richardson <bruce.richardson@intel.com>
Reviewed-by: Chenbo Xia <chenbo.xia@intel.com>
---
 drivers/bus/pci/linux/pci_vfio.c | 7 +++----
 lib/pci/rte_pci.h                | 4 ++++
 2 files changed, 7 insertions(+), 4 deletions(-)

diff --git a/drivers/bus/pci/linux/pci_vfio.c b/drivers/bus/pci/linux/pci_vfio.c
index bf91492dd9..3f3201daf2 100644
--- a/drivers/bus/pci/linux/pci_vfio.c
+++ b/drivers/bus/pci/linux/pci_vfio.c
@@ -5,7 +5,6 @@
 #include <unistd.h>
 #include <string.h>
 #include <fcntl.h>
-#include <linux/pci_regs.h>
 #include <sys/eventfd.h>
 #include <sys/socket.h>
 #include <sys/ioctl.h>
@@ -427,14 +426,14 @@ pci_vfio_is_ioport_bar(const struct rte_pci_device *dev, int vfio_dev_fd,
 	}
 
 	ret = pread64(vfio_dev_fd, &ioport_bar, sizeof(ioport_bar),
-			  offset + PCI_BASE_ADDRESS_0 + bar_index * 4);
+			  offset + RTE_PCI_BASE_ADDRESS_0 + bar_index * 4);
 	if (ret != sizeof(ioport_bar)) {
 		RTE_LOG(ERR, EAL, "Cannot read command (%x) from config space!\n",
-			PCI_BASE_ADDRESS_0 + bar_index*4);
+			RTE_PCI_BASE_ADDRESS_0 + bar_index*4);
 		return -1;
 	}
 
-	return (ioport_bar & PCI_BASE_ADDRESS_SPACE_IO) != 0;
+	return (ioport_bar & RTE_PCI_BASE_ADDRESS_SPACE_IO) != 0;
 }
 
 static int
diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
index 8bf60b9fb7..12866be5d5 100644
--- a/lib/pci/rte_pci.h
+++ b/lib/pci/rte_pci.h
@@ -35,6 +35,7 @@ extern "C" {
 #define RTE_PCI_DEVICE_ID	0x02	/* 16 bits */
 #define RTE_PCI_COMMAND		0x04	/* 16 bits */
 #define RTE_PCI_STATUS		0x06	/* 16 bits */
+#define RTE_PCI_BASE_ADDRESS_0	0x10	/* 32 bits */
 #define RTE_PCI_CAPABILITY_LIST	0x34	/* 32 bits */
 
 /* PCI Command Register (RTE_PCI_COMMAND) */
@@ -45,6 +46,9 @@ extern "C" {
 /* PCI Status Register (RTE_PCI_STATUS) */
 #define RTE_PCI_STATUS_CAP_LIST		0x10	/* Support Capability List */
 
+/* Base addresses (RTE_PCI_BASE_ADDRESS_*) */
+#define RTE_PCI_BASE_ADDRESS_SPACE_IO	0x01
+
 /* Capability registers (RTE_PCI_CAPABILITY_LIST) */
 #define RTE_PCI_CAP_ID_PM		0x01	/* Power Management */
 #define RTE_PCI_CAP_ID_MSI		0x05	/* Message Signalled Interrupts */
-- 
2.41.0


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

* [PATCH v3 09/15] pci: define some PM constants
  2023-09-14 12:35 ` [PATCH v3 00/15] " David Marchand
                     ` (7 preceding siblings ...)
  2023-09-14 12:36   ` [PATCH v3 08/15] pci: define some BAR constants David Marchand
@ 2023-09-14 12:36   ` David Marchand
  2023-09-14 12:36   ` [PATCH v3 10/15] pci: define some PCIe constants David Marchand
                     ` (7 subsequent siblings)
  16 siblings, 0 replies; 98+ messages in thread
From: David Marchand @ 2023-09-14 12:36 UTC (permalink / raw)
  To: dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, bruce.richardson,
	Julien Aube, Gaetan Rivet

Define some PCI Power Management constants and use them in existing
drivers.

Signed-off-by: David Marchand <david.marchand@redhat.com>
Acked-by: Bruce Richardson <bruce.richardson@intel.com>
Reviewed-by: Chenbo Xia <chenbo.xia@intel.com>
---
 drivers/net/bnx2x/bnx2x.c | 17 +++++++++--------
 drivers/net/bnx2x/bnx2x.h |  5 -----
 lib/pci/rte_pci.h         |  6 ++++++
 3 files changed, 15 insertions(+), 13 deletions(-)

diff --git a/drivers/net/bnx2x/bnx2x.c b/drivers/net/bnx2x/bnx2x.c
index e3f14400cc..faf061beba 100644
--- a/drivers/net/bnx2x/bnx2x.c
+++ b/drivers/net/bnx2x/bnx2x.c
@@ -5843,17 +5843,17 @@ static int bnx2x_set_power_state(struct bnx2x_softc *sc, uint8_t state)
 		return 0;
 	}
 
-	pci_read(sc, (sc->devinfo.pcie_pm_cap_reg + PCIR_POWER_STATUS), &pmcsr,
+	pci_read(sc, (sc->devinfo.pcie_pm_cap_reg + RTE_PCI_PM_CTRL), &pmcsr,
 		 2);
 
 	switch (state) {
 	case PCI_PM_D0:
 		pci_write_word(sc,
 			       (sc->devinfo.pcie_pm_cap_reg +
-				PCIR_POWER_STATUS),
-			       ((pmcsr & ~PCIM_PSTAT_DMASK) | PCIM_PSTAT_PME));
+				RTE_PCI_PM_CTRL),
+			       ((pmcsr & ~RTE_PCI_PM_CTRL_STATE_MASK) | RTE_PCI_PM_CTRL_PME_STATUS));
 
-		if (pmcsr & PCIM_PSTAT_DMASK) {
+		if (pmcsr & RTE_PCI_PM_CTRL_STATE_MASK) {
 			/* delay required during transition out of D3hot */
 			DELAY(20000);
 		}
@@ -5866,16 +5866,17 @@ static int bnx2x_set_power_state(struct bnx2x_softc *sc, uint8_t state)
 			return 0;
 		}
 
-		pmcsr &= ~PCIM_PSTAT_DMASK;
-		pmcsr |= PCIM_PSTAT_D3;
+		pmcsr &= ~RTE_PCI_PM_CTRL_STATE_MASK;
+		/* D3 power state */
+		pmcsr |= 0x3;
 
 		if (sc->wol) {
-			pmcsr |= PCIM_PSTAT_PMEENABLE;
+			pmcsr |= RTE_PCI_PM_CTRL_PME_ENABLE;
 		}
 
 		pci_write_long(sc,
 			       (sc->devinfo.pcie_pm_cap_reg +
-				PCIR_POWER_STATUS), pmcsr);
+				RTE_PCI_PM_CTRL), pmcsr);
 
 		/*
 		 * No more memory access after this point until device is brought back
diff --git a/drivers/net/bnx2x/bnx2x.h b/drivers/net/bnx2x/bnx2x.h
index 60af75d336..1efa166316 100644
--- a/drivers/net/bnx2x/bnx2x.h
+++ b/drivers/net/bnx2x/bnx2x.h
@@ -41,11 +41,6 @@
 #define PCIR_EXPRESS_DEVICE_CTL        PCI_EXP_DEVCTL
 #define PCIM_EXP_CTL_MAX_PAYLOAD       PCI_EXP_DEVCTL_PAYLOAD
 #define PCIM_EXP_CTL_MAX_READ_REQUEST  PCI_EXP_DEVCTL_READRQ
-#define PCIR_POWER_STATUS              PCI_PM_CTRL
-#define PCIM_PSTAT_DMASK               PCI_PM_CTRL_STATE_MASK
-#define PCIM_PSTAT_PME                 PCI_PM_CTRL_PME_STATUS
-#define PCIM_PSTAT_D3                  0x3
-#define PCIM_PSTAT_PMEENABLE           PCI_PM_CTRL_PME_ENABLE
 #else
 #include <dev/pci/pcireg.h>
 #endif
diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
index 12866be5d5..90d734f0ad 100644
--- a/lib/pci/rte_pci.h
+++ b/lib/pci/rte_pci.h
@@ -58,6 +58,12 @@ extern "C" {
 #define RTE_PCI_CAP_SIZEOF		4
 #define RTE_PCI_CAP_NEXT		1
 
+/* Power Management Registers (RTE_PCI_CAP_ID_PM) */
+#define RTE_PCI_PM_CTRL			4	/* PM control and status register */
+#define RTE_PCI_PM_CTRL_STATE_MASK	0x0003	/* Current power state (D0 to D3) */
+#define RTE_PCI_PM_CTRL_PME_ENABLE	0x0100	/* PME pin enable */
+#define RTE_PCI_PM_CTRL_PME_STATUS	0x8000	/* PME pin status */
+
 /* MSI-X registers (RTE_PCI_CAP_ID_MSIX) */
 #define RTE_PCI_MSIX_FLAGS		2	/* Message Control */
 #define RTE_PCI_MSIX_FLAGS_QSIZE	0x07ff	/* Table size */
-- 
2.41.0


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

* [PATCH v3 10/15] pci: define some PCIe constants
  2023-09-14 12:35 ` [PATCH v3 00/15] " David Marchand
                     ` (8 preceding siblings ...)
  2023-09-14 12:36   ` [PATCH v3 09/15] pci: define some PM constants David Marchand
@ 2023-09-14 12:36   ` David Marchand
  2023-09-15 16:26     ` Sevincer, Abdullah
  2023-09-14 12:36   ` [PATCH v3 11/15] pci: define some extended capability constants David Marchand
                     ` (6 subsequent siblings)
  16 siblings, 1 reply; 98+ messages in thread
From: David Marchand @ 2023-09-14 12:36 UTC (permalink / raw)
  To: dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, bruce.richardson,
	Abdullah Sevincer, Julien Aube, Gaetan Rivet

Define some PCI Express constants and use them in existing drivers.

Signed-off-by: David Marchand <david.marchand@redhat.com>
Acked-by: Bruce Richardson <bruce.richardson@intel.com>
Reviewed-by: Chenbo Xia <chenbo.xia@intel.com>
---
 drivers/event/dlb2/pf/dlb2_main.c | 40 ++++++++++++-------------------
 drivers/net/bnx2x/bnx2x.c         | 16 ++++++-------
 drivers/net/bnx2x/bnx2x.h         | 35 ---------------------------
 lib/pci/rte_pci.h                 | 21 +++++++++++++---
 4 files changed, 41 insertions(+), 71 deletions(-)

diff --git a/drivers/event/dlb2/pf/dlb2_main.c b/drivers/event/dlb2/pf/dlb2_main.c
index 6dbaa2ff97..8d960edef6 100644
--- a/drivers/event/dlb2/pf/dlb2_main.c
+++ b/drivers/event/dlb2/pf/dlb2_main.c
@@ -27,16 +27,6 @@
 #define NO_OWNER_VF 0	/* PF ONLY! */
 #define NOT_VF_REQ false /* PF ONLY! */
 
-#define DLB2_PCI_LNKCTL 16
-#define DLB2_PCI_SLTCTL 24
-#define DLB2_PCI_RTCTL 28
-#define DLB2_PCI_EXP_DEVCTL2 40
-#define DLB2_PCI_LNKCTL2 48
-#define DLB2_PCI_SLTCTL2 56
-#define DLB2_PCI_EXP_DEVSTA 10
-#define DLB2_PCI_EXP_DEVSTA_TRPND 0x20
-#define DLB2_PCI_EXP_DEVCTL_BCR_FLR 0x8000
-
 #define DLB2_PCI_EXT_CAP_ID_PRI   0x13
 #define DLB2_PCI_EXT_CAP_ID_ACS   0xD
 
@@ -249,27 +239,27 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 	if (rte_pci_read_config(pdev, &dev_ctl_word, 2, off) != 2)
 		dev_ctl_word = 0;
 
-	off = pcie_cap_offset + DLB2_PCI_LNKCTL;
+	off = pcie_cap_offset + RTE_PCI_EXP_LNKCTL;
 	if (rte_pci_read_config(pdev, &lnk_word, 2, off) != 2)
 		lnk_word = 0;
 
-	off = pcie_cap_offset + DLB2_PCI_SLTCTL;
+	off = pcie_cap_offset + RTE_PCI_EXP_SLTCTL;
 	if (rte_pci_read_config(pdev, &slt_word, 2, off) != 2)
 		slt_word = 0;
 
-	off = pcie_cap_offset + DLB2_PCI_RTCTL;
+	off = pcie_cap_offset + RTE_PCI_EXP_RTCTL;
 	if (rte_pci_read_config(pdev, &rt_ctl_word, 2, off) != 2)
 		rt_ctl_word = 0;
 
-	off = pcie_cap_offset + DLB2_PCI_EXP_DEVCTL2;
+	off = pcie_cap_offset + RTE_PCI_EXP_DEVCTL2;
 	if (rte_pci_read_config(pdev, &dev_ctl2_word, 2, off) != 2)
 		dev_ctl2_word = 0;
 
-	off = pcie_cap_offset + DLB2_PCI_LNKCTL2;
+	off = pcie_cap_offset + RTE_PCI_EXP_LNKCTL2;
 	if (rte_pci_read_config(pdev, &lnk_word2, 2, off) != 2)
 		lnk_word2 = 0;
 
-	off = pcie_cap_offset + DLB2_PCI_SLTCTL2;
+	off = pcie_cap_offset + RTE_PCI_EXP_SLTCTL2;
 	if (rte_pci_read_config(pdev, &slt_word2, 2, off) != 2)
 		slt_word2 = 0;
 
@@ -296,7 +286,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 	for (wait_count = 0; wait_count < 4; wait_count++) {
 		int sleep_time;
 
-		off = pcie_cap_offset + DLB2_PCI_EXP_DEVSTA;
+		off = pcie_cap_offset + RTE_PCI_EXP_DEVSTA;
 		ret = rte_pci_read_config(pdev, &devsta_busy_word, 2, off);
 		if (ret != 2) {
 			DLB2_LOG_ERR("[%s()] failed to read the pci device status\n",
@@ -304,7 +294,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 		}
 
-		if (!(devsta_busy_word & DLB2_PCI_EXP_DEVSTA_TRPND))
+		if (!(devsta_busy_word & RTE_PCI_EXP_DEVSTA_TRPND))
 			break;
 
 		sleep_time = (1 << (wait_count)) * 100;
@@ -325,7 +315,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 		return ret;
 	}
 
-	devctl_word |= DLB2_PCI_EXP_DEVCTL_BCR_FLR;
+	devctl_word |= RTE_PCI_EXP_DEVCTL_BCR_FLR;
 
 	ret = rte_pci_write_config(pdev, &devctl_word, 2, off);
 	if (ret != 2) {
@@ -347,7 +337,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 		}
 
-		off = pcie_cap_offset + DLB2_PCI_LNKCTL;
+		off = pcie_cap_offset + RTE_PCI_EXP_LNKCTL;
 		ret = rte_pci_write_config(pdev, &lnk_word, 2, off);
 		if (ret != 2) {
 			DLB2_LOG_ERR("[%s()] failed to write the pcie config space at offset %d\n",
@@ -355,7 +345,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 		}
 
-		off = pcie_cap_offset + DLB2_PCI_SLTCTL;
+		off = pcie_cap_offset + RTE_PCI_EXP_SLTCTL;
 		ret = rte_pci_write_config(pdev, &slt_word, 2, off);
 		if (ret != 2) {
 			DLB2_LOG_ERR("[%s()] failed to write the pcie config space at offset %d\n",
@@ -363,7 +353,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 		}
 
-		off = pcie_cap_offset + DLB2_PCI_RTCTL;
+		off = pcie_cap_offset + RTE_PCI_EXP_RTCTL;
 		ret = rte_pci_write_config(pdev, &rt_ctl_word, 2, off);
 		if (ret != 2) {
 			DLB2_LOG_ERR("[%s()] failed to write the pcie config space at offset %d\n",
@@ -371,7 +361,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 		}
 
-		off = pcie_cap_offset + DLB2_PCI_EXP_DEVCTL2;
+		off = pcie_cap_offset + RTE_PCI_EXP_DEVCTL2;
 		ret = rte_pci_write_config(pdev, &dev_ctl2_word, 2, off);
 		if (ret != 2) {
 			DLB2_LOG_ERR("[%s()] failed to write the pcie config space at offset %d\n",
@@ -379,7 +369,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 		}
 
-		off = pcie_cap_offset + DLB2_PCI_LNKCTL2;
+		off = pcie_cap_offset + RTE_PCI_EXP_LNKCTL2;
 		ret = rte_pci_write_config(pdev, &lnk_word2, 2, off);
 		if (ret != 2) {
 			DLB2_LOG_ERR("[%s()] failed to write the pcie config space at offset %d\n",
@@ -387,7 +377,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 		}
 
-		off = pcie_cap_offset + DLB2_PCI_SLTCTL2;
+		off = pcie_cap_offset + RTE_PCI_EXP_SLTCTL2;
 		ret = rte_pci_write_config(pdev, &slt_word2, 2, off);
 		if (ret != 2) {
 			DLB2_LOG_ERR("[%s()] failed to write the pcie config space at offset %d\n",
diff --git a/drivers/net/bnx2x/bnx2x.c b/drivers/net/bnx2x/bnx2x.c
index faf061beba..cfd8e35aa3 100644
--- a/drivers/net/bnx2x/bnx2x.c
+++ b/drivers/net/bnx2x/bnx2x.c
@@ -7630,8 +7630,8 @@ static uint32_t bnx2x_pcie_capability_read(struct bnx2x_softc *sc, int reg)
 
 static uint8_t bnx2x_is_pcie_pending(struct bnx2x_softc *sc)
 {
-	return bnx2x_pcie_capability_read(sc, PCIR_EXPRESS_DEVICE_STA) &
-		PCIM_EXP_STA_TRANSACTION_PND;
+	return bnx2x_pcie_capability_read(sc, RTE_PCI_EXP_TYPE_RC_EC) &
+		RTE_PCI_EXP_DEVSTA_TRPND;
 }
 
 /*
@@ -7658,11 +7658,11 @@ static void bnx2x_probe_pci_caps(struct bnx2x_softc *sc)
 		sc->devinfo.pcie_pm_cap_reg = caps->addr;
 	}
 
-	link_status = bnx2x_pcie_capability_read(sc, PCIR_EXPRESS_LINK_STA);
+	link_status = bnx2x_pcie_capability_read(sc, RTE_PCI_EXP_LNKSTA);
 
-	sc->devinfo.pcie_link_speed = (link_status & PCIM_LINK_STA_SPEED);
+	sc->devinfo.pcie_link_speed = (link_status & RTE_PCI_EXP_LNKSTA_CLS);
 	sc->devinfo.pcie_link_width =
-	    ((link_status & PCIM_LINK_STA_WIDTH) >> 4);
+	    ((link_status & RTE_PCI_EXP_LNKSTA_NLW) >> 4);
 
 	PMD_DRV_LOG(DEBUG, sc, "PCIe link speed=%d width=%d",
 		    sc->devinfo.pcie_link_speed, sc->devinfo.pcie_link_width);
@@ -9979,10 +9979,10 @@ static void bnx2x_init_pxp(struct bnx2x_softc *sc)
 	uint16_t devctl;
 	int r_order, w_order;
 
-	devctl = bnx2x_pcie_capability_read(sc, PCIR_EXPRESS_DEVICE_CTL);
+	devctl = bnx2x_pcie_capability_read(sc, RTE_PCI_EXP_DEVCTL);
 
-	w_order = ((devctl & PCIM_EXP_CTL_MAX_PAYLOAD) >> 5);
-	r_order = ((devctl & PCIM_EXP_CTL_MAX_READ_REQUEST) >> 12);
+	w_order = ((devctl & RTE_PCI_EXP_DEVCTL_PAYLOAD) >> 5);
+	r_order = ((devctl & RTE_PCI_EXP_DEVCTL_READRQ) >> 12);
 
 	ecore_init_pxp_arb(sc, r_order, w_order);
 }
diff --git a/drivers/net/bnx2x/bnx2x.h b/drivers/net/bnx2x/bnx2x.h
index 1efa166316..35206b4758 100644
--- a/drivers/net/bnx2x/bnx2x.h
+++ b/drivers/net/bnx2x/bnx2x.h
@@ -30,45 +30,10 @@
 
 #include "elink.h"
 
-#ifndef RTE_EXEC_ENV_FREEBSD
-#include <linux/pci_regs.h>
-
-#define PCIR_EXPRESS_DEVICE_STA        PCI_EXP_TYPE_RC_EC
-#define PCIM_EXP_STA_TRANSACTION_PND   PCI_EXP_DEVSTA_TRPND
-#define PCIR_EXPRESS_LINK_STA          PCI_EXP_LNKSTA
-#define PCIM_LINK_STA_WIDTH            PCI_EXP_LNKSTA_NLW
-#define PCIM_LINK_STA_SPEED            PCI_EXP_LNKSTA_CLS
-#define PCIR_EXPRESS_DEVICE_CTL        PCI_EXP_DEVCTL
-#define PCIM_EXP_CTL_MAX_PAYLOAD       PCI_EXP_DEVCTL_PAYLOAD
-#define PCIM_EXP_CTL_MAX_READ_REQUEST  PCI_EXP_DEVCTL_READRQ
-#else
-#include <dev/pci/pcireg.h>
-#endif
-
 #define IFM_10G_CX4                    20 /* 10GBase CX4 copper */
 #define IFM_10G_TWINAX                 22 /* 10GBase Twinax copper */
 #define IFM_10G_T                      26 /* 10GBase-T - RJ45 */
 
-#ifndef RTE_EXEC_ENV_FREEBSD
-#define PCIR_EXPRESS_DEVICE_STA        PCI_EXP_TYPE_RC_EC
-#define PCIM_EXP_STA_TRANSACTION_PND   PCI_EXP_DEVSTA_TRPND
-#define PCIR_EXPRESS_LINK_STA          PCI_EXP_LNKSTA
-#define PCIM_LINK_STA_WIDTH            PCI_EXP_LNKSTA_NLW
-#define PCIM_LINK_STA_SPEED            PCI_EXP_LNKSTA_CLS
-#define PCIR_EXPRESS_DEVICE_CTL        PCI_EXP_DEVCTL
-#define PCIM_EXP_CTL_MAX_PAYLOAD       PCI_EXP_DEVCTL_PAYLOAD
-#define PCIM_EXP_CTL_MAX_READ_REQUEST  PCI_EXP_DEVCTL_READRQ
-#else
-#define PCIR_EXPRESS_DEVICE_STA	PCIER_DEVICE_STA
-#define PCIM_EXP_STA_TRANSACTION_PND   PCIEM_STA_TRANSACTION_PND
-#define PCIR_EXPRESS_LINK_STA          PCIER_LINK_STA
-#define PCIM_LINK_STA_WIDTH            PCIEM_LINK_STA_WIDTH
-#define PCIM_LINK_STA_SPEED            PCIEM_LINK_STA_SPEED
-#define PCIR_EXPRESS_DEVICE_CTL        PCIER_DEVICE_CTL
-#define PCIM_EXP_CTL_MAX_PAYLOAD       PCIEM_CTL_MAX_PAYLOAD
-#define PCIM_EXP_CTL_MAX_READ_REQUEST  PCIEM_CTL_MAX_READ_REQUEST
-#endif
-
 #ifndef ARRAY_SIZE
 #define ARRAY_SIZE(arr) RTE_DIM(arr)
 #endif
diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
index 90d734f0ad..00ce390c1c 100644
--- a/lib/pci/rte_pci.h
+++ b/lib/pci/rte_pci.h
@@ -64,6 +64,24 @@ extern "C" {
 #define RTE_PCI_PM_CTRL_PME_ENABLE	0x0100	/* PME pin enable */
 #define RTE_PCI_PM_CTRL_PME_STATUS	0x8000	/* PME pin status */
 
+/* PCI Express capability registers (RTE_PCI_CAP_ID_EXP) */
+#define RTE_PCI_EXP_TYPE_RC_EC		0xa	/* Root Complex Event Collector */
+#define RTE_PCI_EXP_DEVCTL		0x08	/* Device Control */
+#define RTE_PCI_EXP_DEVCTL_PAYLOAD	0x00e0	/* Max_Payload_Size */
+#define RTE_PCI_EXP_DEVCTL_READRQ	0x7000	/* Max_Read_Request_Size */
+#define RTE_PCI_EXP_DEVCTL_BCR_FLR	0x8000	/* Bridge Configuration Retry / FLR */
+#define RTE_PCI_EXP_DEVSTA		0x0a	/* Device Status */
+#define RTE_PCI_EXP_DEVSTA_TRPND	0x0020	/* Transactions Pending */
+#define RTE_PCI_EXP_LNKCTL		0x10	/* Link Control */
+#define RTE_PCI_EXP_LNKSTA		0x12	/* Link Status */
+#define RTE_PCI_EXP_LNKSTA_CLS		0x000f	/* Current Link Speed */
+#define RTE_PCI_EXP_LNKSTA_NLW		0x03f0	/* Negotiated Link Width */
+#define RTE_PCI_EXP_SLTCTL		0x18	/* Slot Control */
+#define RTE_PCI_EXP_RTCTL		0x1c	/* Root Control */
+#define RTE_PCI_EXP_DEVCTL2		0x28	/* Device Control 2 */
+#define RTE_PCI_EXP_LNKCTL2		0x30	/* Link Control 2 */
+#define RTE_PCI_EXP_SLTCTL2		0x38	/* Slot Control 2 */
+
 /* MSI-X registers (RTE_PCI_CAP_ID_MSIX) */
 #define RTE_PCI_MSIX_FLAGS		2	/* Message Control */
 #define RTE_PCI_MSIX_FLAGS_QSIZE	0x07ff	/* Table size */
@@ -74,9 +92,6 @@ extern "C" {
 #define RTE_PCI_MSIX_TABLE_BIR		0x00000007 /* BAR index */
 #define RTE_PCI_MSIX_TABLE_OFFSET	0xfffffff8 /* Offset into specified BAR */
 
-/* PCI Express capability registers */
-#define RTE_PCI_EXP_DEVCTL	8	/* Device Control */
-
 /* Extended Capabilities (PCI-X 2.0 and Express) */
 #define RTE_PCI_EXT_CAP_ID(header)	(header & 0x0000ffff)
 #define RTE_PCI_EXT_CAP_NEXT(header)	((header >> 20) & 0xffc)
-- 
2.41.0


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

* [PATCH v3 11/15] pci: define some extended capability constants
  2023-09-14 12:35 ` [PATCH v3 00/15] " David Marchand
                     ` (9 preceding siblings ...)
  2023-09-14 12:36   ` [PATCH v3 10/15] pci: define some PCIe constants David Marchand
@ 2023-09-14 12:36   ` David Marchand
  2023-09-15 16:27     ` Sevincer, Abdullah
  2023-09-14 12:36   ` [PATCH v3 12/15] pci: define some ACS constants David Marchand
                     ` (5 subsequent siblings)
  16 siblings, 1 reply; 98+ messages in thread
From: David Marchand @ 2023-09-14 12:36 UTC (permalink / raw)
  To: dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, bruce.richardson,
	Abdullah Sevincer, Gaetan Rivet

Define some PCI extended capability constants and use them in existing
drivers.

Acked-by: Bruce Richardson <bruce.richardson@intel.com>
Reviewed-by: Chenbo Xia <chenbo.xia@intel.com>
Signed-off-by: David Marchand <david.marchand@redhat.com>
---
Changes since v2:
- fixed existing SRIOV comment,

---
 drivers/event/dlb2/pf/dlb2_main.c | 7 ++-----
 lib/pci/rte_pci.h                 | 6 ++++--
 2 files changed, 6 insertions(+), 7 deletions(-)

diff --git a/drivers/event/dlb2/pf/dlb2_main.c b/drivers/event/dlb2/pf/dlb2_main.c
index 8d960edef6..29e3001627 100644
--- a/drivers/event/dlb2/pf/dlb2_main.c
+++ b/drivers/event/dlb2/pf/dlb2_main.c
@@ -27,9 +27,6 @@
 #define NO_OWNER_VF 0	/* PF ONLY! */
 #define NOT_VF_REQ false /* PF ONLY! */
 
-#define DLB2_PCI_EXT_CAP_ID_PRI   0x13
-#define DLB2_PCI_EXT_CAP_ID_ACS   0xD
-
 #define DLB2_PCI_PRI_CTRL_ENABLE         0x1
 #define DLB2_PCI_PRI_ALLOC_REQ           0xC
 #define DLB2_PCI_PRI_CTRL                0x4
@@ -263,7 +260,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 	if (rte_pci_read_config(pdev, &slt_word2, 2, off) != 2)
 		slt_word2 = 0;
 
-	off = DLB2_PCI_EXT_CAP_ID_PRI;
+	off = RTE_PCI_EXT_CAP_ID_PRI;
 	pri_cap_offset = rte_pci_find_ext_capability(pdev, off);
 
 	if (pri_cap_offset >= 0) {
@@ -490,7 +487,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 		}
 	}
 
-	off = DLB2_PCI_EXT_CAP_ID_ACS;
+	off = RTE_PCI_EXT_CAP_ID_ACS;
 	acs_cap_offset = rte_pci_find_ext_capability(pdev, off);
 
 	if (acs_cap_offset >= 0) {
diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
index 00ce390c1c..1fdca91f8b 100644
--- a/lib/pci/rte_pci.h
+++ b/lib/pci/rte_pci.h
@@ -98,9 +98,11 @@ extern "C" {
 
 #define RTE_PCI_EXT_CAP_ID_ERR		0x01	/* Advanced Error Reporting */
 #define RTE_PCI_EXT_CAP_ID_DSN		0x03	/* Device Serial Number */
-#define RTE_PCI_EXT_CAP_ID_SRIOV	0x10	/* SR-IOV*/
+#define RTE_PCI_EXT_CAP_ID_ACS		0x0d	/* Access Control Services */
+#define RTE_PCI_EXT_CAP_ID_SRIOV	0x10	/* SR-IOV */
+#define RTE_PCI_EXT_CAP_ID_PRI		0x13	/* Page Request Interface */
 
-/* Single Root I/O Virtualization */
+/* Single Root I/O Virtualization (RTE_PCI_EXT_CAP_ID_SRIOV) */
 #define RTE_PCI_SRIOV_CAP		0x04	/* SR-IOV Capabilities */
 #define RTE_PCI_SRIOV_CTRL		0x08	/* SR-IOV Control */
 #define RTE_PCI_SRIOV_INITIAL_VF	0x0c	/* Initial VFs */
-- 
2.41.0


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

* [PATCH v3 12/15] pci: define some ACS constants
  2023-09-14 12:35 ` [PATCH v3 00/15] " David Marchand
                     ` (10 preceding siblings ...)
  2023-09-14 12:36   ` [PATCH v3 11/15] pci: define some extended capability constants David Marchand
@ 2023-09-14 12:36   ` David Marchand
  2023-09-15 16:25     ` Sevincer, Abdullah
  2023-09-19  2:35     ` Xia, Chenbo
  2023-09-14 12:36   ` [PATCH v3 13/15] pci: define some PRI constants David Marchand
                     ` (4 subsequent siblings)
  16 siblings, 2 replies; 98+ messages in thread
From: David Marchand @ 2023-09-14 12:36 UTC (permalink / raw)
  To: dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, bruce.richardson,
	Abdullah Sevincer, Gaetan Rivet

Define some PCI ACS extended feature constants and use them in existing
drivers.

Signed-off-by: David Marchand <david.marchand@redhat.com>
Acked-by: Bruce Richardson <bruce.richardson@intel.com>
---
 drivers/event/dlb2/pf/dlb2_main.c | 23 ++++++++---------------
 lib/pci/rte_pci.h                 |  9 +++++++++
 2 files changed, 17 insertions(+), 15 deletions(-)

diff --git a/drivers/event/dlb2/pf/dlb2_main.c b/drivers/event/dlb2/pf/dlb2_main.c
index 29e3001627..8e729d1964 100644
--- a/drivers/event/dlb2/pf/dlb2_main.c
+++ b/drivers/event/dlb2/pf/dlb2_main.c
@@ -33,13 +33,6 @@
 #define DLB2_PCI_ERR_ROOT_STATUS         0x30
 #define DLB2_PCI_ERR_COR_STATUS          0x10
 #define DLB2_PCI_ERR_UNCOR_STATUS        0x4
-#define DLB2_PCI_ACS_CAP                 0x4
-#define DLB2_PCI_ACS_CTRL                0x6
-#define DLB2_PCI_ACS_SV                  0x1
-#define DLB2_PCI_ACS_RR                  0x4
-#define DLB2_PCI_ACS_CR                  0x8
-#define DLB2_PCI_ACS_UF                  0x10
-#define DLB2_PCI_ACS_EC                  0x20
 
 static int
 dlb2_pf_init_driver_state(struct dlb2_dev *dlb2_dev)
@@ -492,16 +485,16 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 
 	if (acs_cap_offset >= 0) {
 		uint16_t acs_cap, acs_ctrl, acs_mask;
-		off = acs_cap_offset + DLB2_PCI_ACS_CAP;
+		off = acs_cap_offset + RTE_PCI_ACS_CAP;
 		if (rte_pci_read_config(pdev, &acs_cap, 2, off) != 2)
 			acs_cap = 0;
 
-		off = acs_cap_offset + DLB2_PCI_ACS_CTRL;
+		off = acs_cap_offset + RTE_PCI_ACS_CTRL;
 		if (rte_pci_read_config(pdev, &acs_ctrl, 2, off) != 2)
 			acs_ctrl = 0;
 
-		acs_mask = DLB2_PCI_ACS_SV | DLB2_PCI_ACS_RR;
-		acs_mask |= (DLB2_PCI_ACS_CR | DLB2_PCI_ACS_UF);
+		acs_mask = RTE_PCI_ACS_SV | RTE_PCI_ACS_RR;
+		acs_mask |= (RTE_PCI_ACS_CR | RTE_PCI_ACS_UF);
 		acs_ctrl |= (acs_cap & acs_mask);
 
 		ret = rte_pci_write_config(pdev, &acs_ctrl, 2, off);
@@ -511,15 +504,15 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 		}
 
-		off = acs_cap_offset + DLB2_PCI_ACS_CTRL;
+		off = acs_cap_offset + RTE_PCI_ACS_CTRL;
 		if (rte_pci_read_config(pdev, &acs_ctrl, 2, off) != 2)
 			acs_ctrl = 0;
 
-		acs_mask = DLB2_PCI_ACS_RR | DLB2_PCI_ACS_CR;
-		acs_mask |= DLB2_PCI_ACS_EC;
+		acs_mask = RTE_PCI_ACS_RR | RTE_PCI_ACS_CR;
+		acs_mask |= RTE_PCI_ACS_EC;
 		acs_ctrl &= ~acs_mask;
 
-		off = acs_cap_offset + DLB2_PCI_ACS_CTRL;
+		off = acs_cap_offset + RTE_PCI_ACS_CTRL;
 		ret = rte_pci_write_config(pdev, &acs_ctrl, 2, off);
 		if (ret != 2) {
 			DLB2_LOG_ERR("[%s()] failed to write the pcie config space at offset %d\n",
diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
index 1fdca91f8b..a6c52a232d 100644
--- a/lib/pci/rte_pci.h
+++ b/lib/pci/rte_pci.h
@@ -102,6 +102,15 @@ extern "C" {
 #define RTE_PCI_EXT_CAP_ID_SRIOV	0x10	/* SR-IOV */
 #define RTE_PCI_EXT_CAP_ID_PRI		0x13	/* Page Request Interface */
 
+/* Access Control Service (RTE_PCI_EXT_CAP_ID_ACS) */
+#define RTE_PCI_ACS_CAP			0x04	/* ACS Capability Register */
+#define RTE_PCI_ACS_CTRL		0x06	/* ACS Control Register */
+#define RTE_PCI_ACS_SV			0x0001	/* Source Validation */
+#define RTE_PCI_ACS_RR			0x0004	/* P2P Request Redirect */
+#define RTE_PCI_ACS_CR			0x0008	/* P2P Completion Redirect */
+#define RTE_PCI_ACS_UF			0x0010	/* Upstream Forwarding */
+#define RTE_PCI_ACS_EC			0x0020	/* P2P Egress Control */
+
 /* Single Root I/O Virtualization (RTE_PCI_EXT_CAP_ID_SRIOV) */
 #define RTE_PCI_SRIOV_CAP		0x04	/* SR-IOV Capabilities */
 #define RTE_PCI_SRIOV_CTRL		0x08	/* SR-IOV Control */
-- 
2.41.0


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

* [PATCH v3 13/15] pci: define some PRI constants
  2023-09-14 12:35 ` [PATCH v3 00/15] " David Marchand
                     ` (11 preceding siblings ...)
  2023-09-14 12:36   ` [PATCH v3 12/15] pci: define some ACS constants David Marchand
@ 2023-09-14 12:36   ` David Marchand
  2023-09-15 16:21     ` Sevincer, Abdullah
  2023-09-19  2:36     ` Xia, Chenbo
  2023-09-14 12:36   ` [PATCH v3 14/15] pci: define some AER constants David Marchand
                     ` (3 subsequent siblings)
  16 siblings, 2 replies; 98+ messages in thread
From: David Marchand @ 2023-09-14 12:36 UTC (permalink / raw)
  To: dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, bruce.richardson,
	Abdullah Sevincer, Gaetan Rivet

Define some PCI PRI extended feature constants and use them in existing
drivers.

Signed-off-by: David Marchand <david.marchand@redhat.com>
Acked-by: Bruce Richardson <bruce.richardson@intel.com>
---
 drivers/event/dlb2/pf/dlb2_main.c | 11 ++++-------
 lib/pci/rte_pci.h                 |  5 +++++
 2 files changed, 9 insertions(+), 7 deletions(-)

diff --git a/drivers/event/dlb2/pf/dlb2_main.c b/drivers/event/dlb2/pf/dlb2_main.c
index 8e729d1964..187a356c24 100644
--- a/drivers/event/dlb2/pf/dlb2_main.c
+++ b/drivers/event/dlb2/pf/dlb2_main.c
@@ -27,9 +27,6 @@
 #define NO_OWNER_VF 0	/* PF ONLY! */
 #define NOT_VF_REQ false /* PF ONLY! */
 
-#define DLB2_PCI_PRI_CTRL_ENABLE         0x1
-#define DLB2_PCI_PRI_ALLOC_REQ           0xC
-#define DLB2_PCI_PRI_CTRL                0x4
 #define DLB2_PCI_ERR_ROOT_STATUS         0x30
 #define DLB2_PCI_ERR_COR_STATUS          0x10
 #define DLB2_PCI_ERR_UNCOR_STATUS        0x4
@@ -257,7 +254,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 	pri_cap_offset = rte_pci_find_ext_capability(pdev, off);
 
 	if (pri_cap_offset >= 0) {
-		off = pri_cap_offset + DLB2_PCI_PRI_ALLOC_REQ;
+		off = pri_cap_offset + RTE_PCI_PRI_ALLOC_REQ;
 		if (rte_pci_read_config(pdev, &pri_reqs_dword, 4, off) != 4)
 			pri_reqs_dword = 0;
 	}
@@ -377,9 +374,9 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 	}
 
 	if (pri_cap_offset >= 0) {
-		pri_ctrl_word = DLB2_PCI_PRI_CTRL_ENABLE;
+		pri_ctrl_word = RTE_PCI_PRI_CTRL_ENABLE;
 
-		off = pri_cap_offset + DLB2_PCI_PRI_ALLOC_REQ;
+		off = pri_cap_offset + RTE_PCI_PRI_ALLOC_REQ;
 		ret = rte_pci_write_config(pdev, &pri_reqs_dword, 4, off);
 		if (ret != 4) {
 			DLB2_LOG_ERR("[%s()] failed to write the pcie config space at offset %d\n",
@@ -387,7 +384,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 		}
 
-		off = pri_cap_offset + DLB2_PCI_PRI_CTRL;
+		off = pri_cap_offset + RTE_PCI_PRI_CTRL;
 		ret = rte_pci_write_config(pdev, &pri_ctrl_word, 2, off);
 		if (ret != 2) {
 			DLB2_LOG_ERR("[%s()] failed to write the pcie config space at offset %d\n",
diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
index a6c52a232d..6bbcad20f2 100644
--- a/lib/pci/rte_pci.h
+++ b/lib/pci/rte_pci.h
@@ -123,6 +123,11 @@ extern "C" {
 #define RTE_PCI_SRIOV_VF_DID		0x1a	/* VF Device ID */
 #define RTE_PCI_SRIOV_SUP_PGSIZE	0x1c	/* Supported Page Sizes */
 
+/* Page Request Interface (RTE_PCI_EXT_CAP_ID_PRI) */
+#define RTE_PCI_PRI_CTRL		0x04	/* PRI control register */
+#define RTE_PCI_PRI_CTRL_ENABLE		0x0001	/* Enable */
+#define RTE_PCI_PRI_ALLOC_REQ		0x0c	/* PRI max reqs allowed */
+
 /** Formatting string for PCI device identifier: Ex: 0000:00:01.0 */
 #define PCI_PRI_FMT "%.4" PRIx32 ":%.2" PRIx8 ":%.2" PRIx8 ".%" PRIx8
 #define PCI_PRI_STR_SIZE sizeof("XXXXXXXX:XX:XX.X")
-- 
2.41.0


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

* [PATCH v3 14/15] pci: define some AER constants
  2023-09-14 12:35 ` [PATCH v3 00/15] " David Marchand
                     ` (12 preceding siblings ...)
  2023-09-14 12:36   ` [PATCH v3 13/15] pci: define some PRI constants David Marchand
@ 2023-09-14 12:36   ` David Marchand
  2023-09-15 16:26     ` Sevincer, Abdullah
  2023-09-19  2:36     ` Xia, Chenbo
  2023-09-14 12:36   ` [PATCH v3 15/15] devtools: forbid inclusion of Linux header for PCI David Marchand
                     ` (2 subsequent siblings)
  16 siblings, 2 replies; 98+ messages in thread
From: David Marchand @ 2023-09-14 12:36 UTC (permalink / raw)
  To: dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, bruce.richardson,
	Abdullah Sevincer, Gaetan Rivet

Define some Advanced Error Reporting constants and use them in existing
drivers.

Signed-off-by: David Marchand <david.marchand@redhat.com>
Acked-by: Bruce Richardson <bruce.richardson@intel.com>
---
 drivers/event/dlb2/pf/dlb2_main.c | 10 +++-------
 lib/pci/rte_pci.h                 |  5 +++++
 2 files changed, 8 insertions(+), 7 deletions(-)

diff --git a/drivers/event/dlb2/pf/dlb2_main.c b/drivers/event/dlb2/pf/dlb2_main.c
index 187a356c24..aa03e4c311 100644
--- a/drivers/event/dlb2/pf/dlb2_main.c
+++ b/drivers/event/dlb2/pf/dlb2_main.c
@@ -27,10 +27,6 @@
 #define NO_OWNER_VF 0	/* PF ONLY! */
 #define NOT_VF_REQ false /* PF ONLY! */
 
-#define DLB2_PCI_ERR_ROOT_STATUS         0x30
-#define DLB2_PCI_ERR_COR_STATUS          0x10
-#define DLB2_PCI_ERR_UNCOR_STATUS        0x4
-
 static int
 dlb2_pf_init_driver_state(struct dlb2_dev *dlb2_dev)
 {
@@ -399,7 +395,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 	if (err_cap_offset >= 0) {
 		uint32_t tmp;
 
-		off = err_cap_offset + DLB2_PCI_ERR_ROOT_STATUS;
+		off = err_cap_offset + RTE_PCI_ERR_ROOT_STATUS;
 		if (rte_pci_read_config(pdev, &tmp, 4, off) != 4)
 			tmp = 0;
 
@@ -410,7 +406,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 		}
 
-		off = err_cap_offset + DLB2_PCI_ERR_COR_STATUS;
+		off = err_cap_offset + RTE_PCI_ERR_COR_STATUS;
 		if (rte_pci_read_config(pdev, &tmp, 4, off) != 4)
 			tmp = 0;
 
@@ -421,7 +417,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
 			return ret;
 		}
 
-		off = err_cap_offset + DLB2_PCI_ERR_UNCOR_STATUS;
+		off = err_cap_offset + RTE_PCI_ERR_UNCOR_STATUS;
 		if (rte_pci_read_config(pdev, &tmp, 4, off) != 4)
 			tmp = 0;
 
diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
index 6bbcad20f2..69e932d910 100644
--- a/lib/pci/rte_pci.h
+++ b/lib/pci/rte_pci.h
@@ -102,6 +102,11 @@ extern "C" {
 #define RTE_PCI_EXT_CAP_ID_SRIOV	0x10	/* SR-IOV */
 #define RTE_PCI_EXT_CAP_ID_PRI		0x13	/* Page Request Interface */
 
+/* Advanced Error Reporting (RTE_PCI_EXT_CAP_ID_ERR) */
+#define RTE_PCI_ERR_UNCOR_STATUS	0x04	/* Uncorrectable Error Status */
+#define RTE_PCI_ERR_COR_STATUS		0x10	/* Correctable Error Status */
+#define RTE_PCI_ERR_ROOT_STATUS		0x30
+
 /* Access Control Service (RTE_PCI_EXT_CAP_ID_ACS) */
 #define RTE_PCI_ACS_CAP			0x04	/* ACS Capability Register */
 #define RTE_PCI_ACS_CTRL		0x06	/* ACS Control Register */
-- 
2.41.0


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

* [PATCH v3 15/15] devtools: forbid inclusion of Linux header for PCI
  2023-09-14 12:35 ` [PATCH v3 00/15] " David Marchand
                     ` (13 preceding siblings ...)
  2023-09-14 12:36   ` [PATCH v3 14/15] pci: define some AER constants David Marchand
@ 2023-09-14 12:36   ` David Marchand
  2023-09-15 15:14   ` [PATCH v3 00/15] Cleanup PCI(e) drivers Stephen Hemminger
  2023-09-19 12:41   ` David Marchand
  16 siblings, 0 replies; 98+ messages in thread
From: David Marchand @ 2023-09-14 12:36 UTC (permalink / raw)
  To: dev; +Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, bruce.richardson

Refrain from including Linux-only pci_regs.h header.
Instead, prefer our own definitions from the pci library.

Signed-off-by: David Marchand <david.marchand@redhat.com>
Acked-by: Bruce Richardson <bruce.richardson@intel.com>
Reviewed-by: Chenbo Xia <chenbo.xia@intel.com>
---
 devtools/checkpatches.sh | 8 ++++++++
 1 file changed, 8 insertions(+)

diff --git a/devtools/checkpatches.sh b/devtools/checkpatches.sh
index 55fabc5458..3a2a772573 100755
--- a/devtools/checkpatches.sh
+++ b/devtools/checkpatches.sh
@@ -135,6 +135,14 @@ check_forbidden_additions() { # <patch>
 		-f $(dirname $(readlink -f $0))/check-forbidden-tokens.awk \
 		"$1" || res=1
 
+	# forbid inclusion of Linux header for PCI constants
+	awk -v FOLDERS="lib drivers app examples" \
+		-v EXPRESSIONS='include.*linux/pci_regs\\.h' \
+		-v RET_ON_FAIL=1 \
+		-v MESSAGE='Using linux/pci_regs.h, prefer rte_pci.h' \
+		-f $(dirname $(readlink -f $0))/check-forbidden-tokens.awk \
+		"$1" || res=1
+
 	# forbid use of experimental build flag except in examples
 	awk -v FOLDERS='lib drivers app' \
 		-v EXPRESSIONS='-DALLOW_EXPERIMENTAL_API allow_experimental_apis' \
-- 
2.41.0


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

* Re: [PATCH v3 00/15] Cleanup PCI(e) drivers
  2023-09-14 12:35 ` [PATCH v3 00/15] " David Marchand
                     ` (14 preceding siblings ...)
  2023-09-14 12:36   ` [PATCH v3 15/15] devtools: forbid inclusion of Linux header for PCI David Marchand
@ 2023-09-15 15:14   ` Stephen Hemminger
  2023-09-19 12:41   ` David Marchand
  16 siblings, 0 replies; 98+ messages in thread
From: Stephen Hemminger @ 2023-09-15 15:14 UTC (permalink / raw)
  To: David Marchand
  Cc: dev, thomas, ferruh.yigit, chenbo.xia, nipun.gupta, bruce.richardson

On Thu, 14 Sep 2023 14:35:59 +0200
David Marchand <david.marchand@redhat.com> wrote:

> Rather than rely on Linux headers to find some PCI(e) standard constants
> or reinvent the same PCI capability helper, this series complements the
> pci library and the pci bus driver.
> PCI drivers can then use OS agnostic macros and helpers.
> 
> 

Series-Acked-by: Stephen Hemminger <stephen@networkplumber.org>

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

* RE: [PATCH v3 13/15] pci: define some PRI constants
  2023-09-14 12:36   ` [PATCH v3 13/15] pci: define some PRI constants David Marchand
@ 2023-09-15 16:21     ` Sevincer, Abdullah
  2023-09-19  2:36     ` Xia, Chenbo
  1 sibling, 0 replies; 98+ messages in thread
From: Sevincer, Abdullah @ 2023-09-15 16:21 UTC (permalink / raw)
  To: David Marchand, dev
  Cc: thomas, ferruh.yigit, Xia, Chenbo, nipun.gupta, Richardson,
	Bruce, Gaetan Rivet

Acked-by: Abdullah Sevincer <abdullah.sevincer@intel.com>



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

* RE: [PATCH v3 12/15] pci: define some ACS constants
  2023-09-14 12:36   ` [PATCH v3 12/15] pci: define some ACS constants David Marchand
@ 2023-09-15 16:25     ` Sevincer, Abdullah
  2023-09-19  2:35     ` Xia, Chenbo
  1 sibling, 0 replies; 98+ messages in thread
From: Sevincer, Abdullah @ 2023-09-15 16:25 UTC (permalink / raw)
  To: David Marchand, dev
  Cc: thomas, ferruh.yigit, Xia, Chenbo, nipun.gupta, Richardson,
	Bruce, Gaetan Rivet

Acked-by: Abdullah Sevincer <abdullah.sevincer@intel.com>

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

* RE: [PATCH v3 14/15] pci: define some AER constants
  2023-09-14 12:36   ` [PATCH v3 14/15] pci: define some AER constants David Marchand
@ 2023-09-15 16:26     ` Sevincer, Abdullah
  2023-09-19  2:36     ` Xia, Chenbo
  1 sibling, 0 replies; 98+ messages in thread
From: Sevincer, Abdullah @ 2023-09-15 16:26 UTC (permalink / raw)
  To: David Marchand, dev
  Cc: thomas, ferruh.yigit, Xia, Chenbo, nipun.gupta, Richardson,
	Bruce, Gaetan Rivet

Acked-by: Abdullah Sevincer <abdullah.sevincer@intel.com>

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

* RE: [PATCH v3 10/15] pci: define some PCIe constants
  2023-09-14 12:36   ` [PATCH v3 10/15] pci: define some PCIe constants David Marchand
@ 2023-09-15 16:26     ` Sevincer, Abdullah
  0 siblings, 0 replies; 98+ messages in thread
From: Sevincer, Abdullah @ 2023-09-15 16:26 UTC (permalink / raw)
  To: David Marchand, dev
  Cc: thomas, ferruh.yigit, Xia, Chenbo, nipun.gupta, Richardson,
	Bruce, Julien Aube, Gaetan Rivet

Acked-by: Abdullah Sevincer <abdullah.sevincer@intel.com>

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

* RE: [PATCH v3 11/15] pci: define some extended capability constants
  2023-09-14 12:36   ` [PATCH v3 11/15] pci: define some extended capability constants David Marchand
@ 2023-09-15 16:27     ` Sevincer, Abdullah
  0 siblings, 0 replies; 98+ messages in thread
From: Sevincer, Abdullah @ 2023-09-15 16:27 UTC (permalink / raw)
  To: David Marchand, dev
  Cc: thomas, ferruh.yigit, Xia, Chenbo, nipun.gupta, Richardson,
	Bruce, Gaetan Rivet

Acked-by: Abdullah Sevincer <abdullah.sevincer@intel.com>

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

* RE: [PATCH v3 05/15] pci: define some capability constants
  2023-09-14 12:36   ` [PATCH v3 05/15] pci: define some capability constants David Marchand
@ 2023-09-15 16:27     ` Sevincer, Abdullah
  0 siblings, 0 replies; 98+ messages in thread
From: Sevincer, Abdullah @ 2023-09-15 16:27 UTC (permalink / raw)
  To: David Marchand, dev
  Cc: thomas, ferruh.yigit, Xia, Chenbo, nipun.gupta, Richardson,
	Bruce, Burakov, Anatoly, Jay Zhou, Julien Aube, Rahul Lakkireddy,
	Guo, Junfeng, Jeroen de Borst, Rushil Gupta, Joshua Washington,
	Dongdong Liu, Yisen Zhuang, Maxime Coquelin, Wang, Xiao W,
	Gaetan Rivet

Acked-by: Abdullah Sevincer <abdullah.sevincer@intel.com>

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

* RE: [PATCH v2 04/15] bus/pci: find PCI capability
  2023-09-14 12:29       ` David Marchand
@ 2023-09-19  2:19         ` Xia, Chenbo
  2023-09-19  9:00           ` David Marchand
  0 siblings, 1 reply; 98+ messages in thread
From: Xia, Chenbo @ 2023-09-19  2:19 UTC (permalink / raw)
  To: David Marchand, Maxime Coquelin
  Cc: dev, thomas, ferruh.yigit, nipun.gupta, Richardson, Bruce,
	Burakov, Anatoly, Jay Zhou, McDaniel, Timothy, Julien Aube,
	Rahul Lakkireddy, Guo, Junfeng, Jeroen de Borst, Rushil Gupta,
	Joshua Washington, Dongdong Liu, Yisen Zhuang, Gaetan Rivet

Hi David,

> -----Original Message-----
> From: David Marchand <david.marchand@redhat.com>
> Sent: Thursday, September 14, 2023 8:29 PM
> To: Xia, Chenbo <chenbo.xia@intel.com>; Maxime Coquelin
> <maxime.coquelin@redhat.com>
> Cc: dev@dpdk.org; thomas@monjalon.net; ferruh.yigit@amd.com;
> nipun.gupta@amd.com; Richardson, Bruce <bruce.richardson@intel.com>;
> Burakov, Anatoly <anatoly.burakov@intel.com>; Jay Zhou
> <jianjay.zhou@huawei.com>; McDaniel, Timothy <timothy.mcdaniel@intel.com>;
> Julien Aube <julien_dpdk@jaube.fr>; Rahul Lakkireddy
> <rahul.lakkireddy@chelsio.com>; Guo, Junfeng <junfeng.guo@intel.com>;
> Jeroen de Borst <jeroendb@google.com>; Rushil Gupta <rushilg@google.com>;
> Joshua Washington <joshwash@google.com>; Dongdong Liu
> <liudongdong3@huawei.com>; Yisen Zhuang <yisen.zhuang@huawei.com>; Gaetan
> Rivet <grive@u256.net>
> Subject: Re: [PATCH v2 04/15] bus/pci: find PCI capability
> 
> Hello Chenbo,
> 
> On Thu, Sep 7, 2023 at 2:43 PM Xia, Chenbo <chenbo.xia@intel.com> wrote:
> > > Introduce two helpers so that drivers stop reinventing the wheel when
> it
> > > comes to finding capabilities in a device PCI configuration space.
> > > Use it in existing drivers.
> > >
> > > Note:
> > > - base/ drivers code is left untouched, only some wrappers in cxgbe
> > >   are touched,
> > > - bnx2x maintained a per device cache of capabilities, this code has
> been
> > >   reworked to only cache the capabilities used in this driver,
> > >
> > > Signed-off-by: David Marchand <david.marchand@redhat.com>
> > > Acked-by: Bruce Richardson <bruce.richardson@intel.com>
> > > ---
> > > Changes since v1:
> > > - updated commitlog,
> > > - separated VFIO changes for using standard PCI helper in a separate
> > >   patch,
> > > - marked new experimental symbols with current version,
> > > - reordered defines in rte_pci.h,
> > >
> > > ---
> > >  drivers/bus/pci/linux/pci_vfio.c   |  74 ++++--------------
> > >  drivers/bus/pci/pci_common.c       |  45 +++++++++++
> > >  drivers/bus/pci/rte_bus_pci.h      |  31 ++++++++
> > >  drivers/bus/pci/version.map        |   4 +
> > >  drivers/crypto/virtio/virtio_pci.c |  57 +++++---------
> > >  drivers/event/dlb2/pf/dlb2_main.c  |  42 +---------
> > >  drivers/net/bnx2x/bnx2x.c          |  41 +++++-----
> > >  drivers/net/cxgbe/base/adapter.h   |  28 +------
> > >  drivers/net/gve/gve_ethdev.c       |  46 ++---------
> > >  drivers/net/gve/gve_ethdev.h       |   4 -
> > >  drivers/net/hns3/hns3_ethdev_vf.c  |  79 +++----------------
> > >  drivers/net/virtio/virtio_pci.c    | 121 +++++-----------------------
> -
> > >  lib/pci/rte_pci.h                  |  11 +++
> > >  13 files changed, 186 insertions(+), 397 deletions(-)
> > >
> > > diff --git a/drivers/bus/pci/linux/pci_vfio.c
> > > b/drivers/bus/pci/linux/pci_vfio.c
> > > index 958f8b3b52..614ed5d696 100644
> > > --- a/drivers/bus/pci/linux/pci_vfio.c
> > > +++ b/drivers/bus/pci/linux/pci_vfio.c
> > > @@ -110,74 +110,34 @@ static int
> > >  pci_vfio_get_msix_bar(const struct rte_pci_device *dev,
> > >       struct pci_msix_table *msix_table)
> > >  {
> > > -     int ret;
> > > -     uint32_t reg;
> > > -     uint16_t flags;
> > > -     uint8_t cap_id, cap_offset;
> > > +     off_t cap_offset;
> > >
> > > -     /* read PCI capability pointer from config space */
> > > -     ret = rte_pci_read_config(dev, &reg, sizeof(reg),
> > > PCI_CAPABILITY_LIST);
> > > -     if (ret != sizeof(reg)) {
> > > -             RTE_LOG(ERR, EAL,
> > > -                     "Cannot read capability pointer from PCI config
> > > space!\n");
> > > +     cap_offset = rte_pci_find_capability(dev, PCI_CAP_ID_MSIX);
> >
> > I notice in some cases we use rte_pci_has_capability_list() to check
> first,
> > then looking for specific cap, in other cases we don't use
> > rte_pci_has_capability_list(). Since we define this API, should we
> always do
> > the check?
> 
> Hum, I am not sure of what you suggest here.
> 
> I tried to do a 1:1 conversion of what existed.
> Do you mean there are places where I missed converting some
> rte_pci_read_config(PCI_CAPABILITY_LIST) to
> rte_pci_has_capability_list()?
> If so, could you point at them?
> 
> Or are you suggesting to have this check as part of
> rte_pci_find_capability() ?

Your conversion is correct. I was saying about the usage of
rte_pci_has_capability_list/rte_pci_find_capability, logically should we
always call rte_pci_has_capability_list first before find capability?

I don't have strong opinion on this. You can choose to keep the same or
call rte_pci_has_capability_list more.

Thanks!
Chenbo

> 
> 
> I'll respin a v3 soon (to fix the nasty issue you pointed out below).
> A v4 may be needed depending on your replies to above questions.
> 
> 
> >
> >
> > > +     if (cap_offset < 0)
> > >               return -1;
> > > -     }
> > >
> > > -     /* we need first byte */
> > > -     cap_offset = reg & 0xFF;
> > > +     if (cap_offset != 0) {
> > > +             uint16_t flags;
> > > +             uint32_t reg;
> > >
> > > -     while (cap_offset) {
> > > -
> > > -             /* read PCI capability ID */
> > > -             ret = rte_pci_read_config(dev, &reg, sizeof(reg),
> cap_offset);
> > > -             if (ret != sizeof(reg)) {
> > > +             /* table offset resides in the next 4 bytes */
> > > +             if (rte_pci_read_config(dev, &reg, sizeof(reg),
> cap_offset + 4)
> > > < 0) {
> > >                       RTE_LOG(ERR, EAL,
> > > -                             "Cannot read capability ID from PCI
> config
> > > space!\n");
> > > +                             "Cannot read MSIX table from PCI config
> space!\n");
> > >                       return -1;
> > >               }
> > >
> > > -             /* we need first byte */
> > > -             cap_id = reg & 0xFF;
> > > -
> > > -             /* if we haven't reached MSI-X, check next capability */
> > > -             if (cap_id != PCI_CAP_ID_MSIX) {
> > > -                     ret = rte_pci_read_config(dev, &reg, sizeof(reg),
> > > cap_offset);
> > > -                     if (ret != sizeof(reg)) {
> > > -                             RTE_LOG(ERR, EAL,
> > > -                                     "Cannot read capability pointer
> from PCI
> > > config space!\n");
> > > -                             return -1;
> > > -                     }
> > > -
> > > -                     /* we need second byte */
> > > -                     cap_offset = (reg & 0xFF00) >> 8;
> > > -
> > > -                     continue;
> > > +             if (rte_pci_read_config(dev, &flags, sizeof(flags),
> cap_offset
> > > + 2) < 0) {
> > > +                     RTE_LOG(ERR, EAL,
> > > +                             "Cannot read MSIX flags from PCI config
> space!\n");
> > > +                     return -1;
> > >               }
> > > -             /* else, read table offset */
> > > -             else {
> > > -                     /* table offset resides in the next 4 bytes */
> > > -                     ret = rte_pci_read_config(dev, &reg, sizeof(reg),
> > > cap_offset + 4);
> > > -                     if (ret != sizeof(reg)) {
> > > -                             RTE_LOG(ERR, EAL,
> > > -                                     "Cannot read table offset from
> PCI config
> > > space!\n");
> > > -                             return -1;
> > > -                     }
> > > -
> > > -                     ret = rte_pci_read_config(dev, &flags,
> sizeof(flags),
> > > cap_offset + 2);
> > > -                     if (ret != sizeof(flags)) {
> > > -                             RTE_LOG(ERR, EAL,
> > > -                                     "Cannot read table flags from
> PCI config
> > > space!\n");
> > > -                             return -1;
> > > -                     }
> > > -
> > > -                     msix_table->bar_index = reg &
> RTE_PCI_MSIX_TABLE_BIR;
> > > -                     msix_table->offset = reg &
> RTE_PCI_MSIX_TABLE_OFFSET;
> > > -                     msix_table->size =
> > > -                             16 * (1 + (flags &
> RTE_PCI_MSIX_FLAGS_QSIZE));
> > >
> > > -                     return 0;
> > > -             }
> > > +             msix_table->bar_index = reg & RTE_PCI_MSIX_TABLE_BIR;
> > > +             msix_table->offset = reg & RTE_PCI_MSIX_TABLE_OFFSET;
> > > +             msix_table->size = 16 * (1 + (flags &
> > > RTE_PCI_MSIX_FLAGS_QSIZE));
> > >       }
> > > +
> > >       return 0;
> > >  }
> > >
> > > diff --git a/drivers/bus/pci/pci_common.c
> b/drivers/bus/pci/pci_common.c
> > > index 382b0b8946..52272617eb 100644
> > > --- a/drivers/bus/pci/pci_common.c
> > > +++ b/drivers/bus/pci/pci_common.c
> > > @@ -813,6 +813,51 @@ rte_pci_get_iommu_class(void)
> > >       return iova_mode;
> > >  }
> > >
> > > +bool
> > > +rte_pci_has_capability_list(const struct rte_pci_device *dev)
> > > +{
> > > +     uint16_t status;
> > > +
> > > +     if (rte_pci_read_config(dev, &status, sizeof(status),
> > > RTE_PCI_STATUS) != sizeof(status))
> > > +             return false;
> > > +
> > > +     return (status & RTE_PCI_STATUS_CAP_LIST) != 0;
> > > +}
> > > +
> > > +off_t
> > > +rte_pci_find_capability(const struct rte_pci_device *dev, uint8_t cap)
> > > +{
> > > +     off_t offset;
> > > +     uint8_t pos;
> > > +     int ttl;
> > > +
> > > +     offset = RTE_PCI_CAPABILITY_LIST;
> > > +     ttl = (RTE_PCI_CFG_SPACE_SIZE - RTE_PCI_STD_HEADER_SIZEOF) /
> > > RTE_PCI_CAP_SIZEOF;
> > > +
> > > +     if (rte_pci_read_config(dev, &pos, sizeof(pos), offset) < 0)
> > > +             return -1;
> > > +
> > > +     while (pos && ttl--) {
> > > +             uint16_t ent;
> > > +             uint8_t id;
> > > +
> > > +             offset = pos;
> > > +             if (rte_pci_read_config(dev, &ent, sizeof(ent), offset)
> < 0)
> > > +                     return -1;
> > > +
> > > +             id = ent & 0xff;
> > > +             if (id == 0xff)
> > > +                     break;
> > > +
> > > +             if (id == cap)
> > > +                     return offset;
> > > +
> > > +             pos = (ent >> 8);
> > > +     }
> > > +
> > > +     return 0;
> > > +}
> > > +
> > >  off_t
> > >  rte_pci_find_ext_capability(const struct rte_pci_device *dev,
> uint32_t
> > > cap)
> > >  {
> > > diff --git a/drivers/bus/pci/rte_bus_pci.h
> b/drivers/bus/pci/rte_bus_pci.h
> > > index 75d0030eae..1ed33dbf3d 100644
> > > --- a/drivers/bus/pci/rte_bus_pci.h
> > > +++ b/drivers/bus/pci/rte_bus_pci.h
> > > @@ -68,6 +68,37 @@ void rte_pci_unmap_device(struct rte_pci_device
> *dev);
> > >   */
> > >  void rte_pci_dump(FILE *f);
> > >
> > > +/**
> > > + * Check whether this device has a PCI capability list.
> > > + *
> > > + *  @param dev
> > > + *    A pointer to rte_pci_device structure.
> > > + *
> > > + *  @return
> > > + *    true/false
> > > + */
> > > +__rte_experimental
> > > +bool rte_pci_has_capability_list(const struct rte_pci_device *dev);
> > > +
> > > +/**
> > > + * Find device's PCI capability.
> > > + *
> > > + *  @param dev
> > > + *    A pointer to rte_pci_device structure.
> > > + *
> > > + *  @param cap
> > > + *    Capability to be found, which can be any from
> > > + *    RTE_PCI_CAP_ID_*, defined in librte_pci.
> > > + *
> > > + *  @return
> > > + *  > 0: The offset of the next matching capability structure
> > > + *       within the device's PCI configuration space.
> > > + *  < 0: An error in PCI config space read.
> > > + *  = 0: Device does not support it.
> > > + */
> > > +__rte_experimental
> > > +off_t rte_pci_find_capability(const struct rte_pci_device *dev,
> uint8_t
> > > cap);
> > > +
> > >  /**
> > >   * Find device's extended PCI capability.
> > >   *
> > > diff --git a/drivers/bus/pci/version.map b/drivers/bus/pci/version.map
> > > index a0000f7938..2674f30235 100644
> > > --- a/drivers/bus/pci/version.map
> > > +++ b/drivers/bus/pci/version.map
> > > @@ -25,6 +25,10 @@ EXPERIMENTAL {
> > >       # added in 23.07
> > >       rte_pci_mmio_read;
> > >       rte_pci_mmio_write;
> > > +
> > > +     # added in 23.11
> > > +     rte_pci_find_capability;
> > > +     rte_pci_has_capability_list;
> > >  };
> > >
> > >  INTERNAL {
> > > diff --git a/drivers/crypto/virtio/virtio_pci.c
> > > b/drivers/crypto/virtio/virtio_pci.c
> > > index 95a43c8801..abc52b4701 100644
> > > --- a/drivers/crypto/virtio/virtio_pci.c
> > > +++ b/drivers/crypto/virtio/virtio_pci.c
> > > @@ -19,7 +19,6 @@
> > >   * we can't simply include that header here, as there is no such
> > >   * file for non-Linux platform.
> > >   */
> > > -#define PCI_CAPABILITY_LIST  0x34
> > >  #define PCI_CAP_ID_VNDR              0x09
> > >  #define PCI_CAP_ID_MSIX              0x11
> > >
> > > @@ -343,8 +342,9 @@ get_cfg_addr(struct rte_pci_device *dev, struct
> > > virtio_pci_cap *cap)
> > >  static int
> > >  virtio_read_caps(struct rte_pci_device *dev, struct virtio_crypto_hw
> *hw)
> > >  {
> > > -     uint8_t pos;
> > >       struct virtio_pci_cap cap;
> > > +     uint16_t flags;
> > > +     off_t pos;
> > >       int ret;
> > >
> > >       if (rte_pci_map_device(dev)) {
> > > @@ -352,44 +352,26 @@ virtio_read_caps(struct rte_pci_device *dev,
> struct
> > > virtio_crypto_hw *hw)
> > >               return -1;
> > >       }
> > >
> > > -     ret = rte_pci_read_config(dev, &pos, 1, PCI_CAPABILITY_LIST);
> > > -     if (ret < 0) {
> > > -             VIRTIO_CRYPTO_INIT_LOG_DBG("failed to read pci
> capability
> > > list");
> > > -             return -1;
> > > +     /*
> > > +      * Transitional devices would also have this capability,
> > > +      * that's why we also check if msix is enabled.
> > > +      */
> > > +     pos = rte_pci_find_capability(dev, PCI_CAP_ID_MSIX);
> > > +     if (pos > 0 && rte_pci_read_config(dev, &flags, sizeof(flags),
> > > +                     pos + 2) == sizeof(flags)) {
> > > +             if (flags & PCI_MSIX_ENABLE)
> > > +                     hw->use_msix = VIRTIO_MSIX_ENABLED;
> > > +             else
> > > +                     hw->use_msix = VIRTIO_MSIX_DISABLED;
> > > +     } else {
> > > +             hw->use_msix = VIRTIO_MSIX_NONE;
> > >       }
> > >
> > > -     while (pos) {
> > > -             ret = rte_pci_read_config(dev, &cap, sizeof(cap), pos);
> > > -             if (ret < 0) {
> > > -                     VIRTIO_CRYPTO_INIT_LOG_ERR(
> > > -                             "failed to read pci cap at pos: %x",
> pos);
> > > -                     break;
> > > -             }
> > > -
> > > -             if (cap.cap_vndr == PCI_CAP_ID_MSIX) {
> > > -                     /* Transitional devices would also have this
> capability,
> > > -                      * that's why we also check if msix is enabled.
> > > -                      * 1st byte is cap ID; 2nd byte is the position
> of next
> > > -                      * cap; next two bytes are the flags.
> > > -                      */
> > > -                     uint16_t flags = ((uint16_t *)&cap)[1];
> > > -
> > > -                     if (flags & PCI_MSIX_ENABLE)
> > > -                             hw->use_msix = VIRTIO_MSIX_ENABLED;
> > > -                     else
> > > -                             hw->use_msix = VIRTIO_MSIX_DISABLED;
> > > -             }
> > > -
> > > -             if (cap.cap_vndr != PCI_CAP_ID_VNDR) {
> > > -                     VIRTIO_CRYPTO_INIT_LOG_DBG(
> > > -                             "[%2x] skipping non VNDR cap id: %02x",
> > > -                             pos, cap.cap_vndr);
> > > -                     goto next;
> > > -             }
> > > -
> > > +     pos = rte_pci_find_capability(dev, PCI_CAP_ID_VNDR);
> >
> > The logic of vendor cap init seems incorrect. Virtio devices have
> multiple
> > Vendor cap (different cfg type). But now the logic seems to only init
> the first
> > one.
> 
> Indeed, good catch!
> It is sad that the CI did not catch this regression in virtio pmd init :-(.
> 
> I'll add a find_next_capability helper for v3.
> 
> 
> 
> >
> > > +     if (pos > 0 && rte_pci_read_config(dev, &cap, sizeof(cap), pos)
> ==
> > > sizeof(cap)) {
> > >               VIRTIO_CRYPTO_INIT_LOG_DBG(
> > >                       "[%2x] cfg type: %u, bar: %u, offset: %04x,
> len: %u",
> > > -                     pos, cap.cfg_type, cap.bar, cap.offset,
> cap.length);
> > > +                     (unsigned int)pos, cap.cfg_type, cap.bar,
> cap.offset,
> > > cap.length);
> > >
> > >               switch (cap.cfg_type) {
> > >               case VIRTIO_PCI_CAP_COMMON_CFG:
> > > @@ -411,9 +393,6 @@ virtio_read_caps(struct rte_pci_device *dev,
> struct
> > > virtio_crypto_hw *hw)
> > >                       hw->isr = get_cfg_addr(dev, &cap);
> > >                       break;
> > >               }
> > > -
> > > -next:
> > > -             pos = cap.cap_next;
> > >       }
> >
> > ...
> 
> 
> --
> David Marchand


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

* RE: [PATCH v3 04/15] bus/pci: find PCI capability
  2023-09-14 12:36   ` [PATCH v3 04/15] bus/pci: find PCI capability David Marchand
@ 2023-09-19  2:33     ` Xia, Chenbo
  0 siblings, 0 replies; 98+ messages in thread
From: Xia, Chenbo @ 2023-09-19  2:33 UTC (permalink / raw)
  To: David Marchand, dev
  Cc: thomas, ferruh.yigit, nipun.gupta, Richardson, Bruce, Burakov,
	Anatoly, Jay Zhou, Sevincer, Abdullah, Julien Aube,
	Rahul Lakkireddy, Guo, Junfeng, Jeroen de Borst, Rushil Gupta,
	Joshua Washington, Dongdong Liu, Yisen Zhuang, Maxime Coquelin,
	Gaetan Rivet

> -----Original Message-----
> From: David Marchand <david.marchand@redhat.com>
> Sent: Thursday, September 14, 2023 8:36 PM
> To: dev@dpdk.org
> Cc: thomas@monjalon.net; ferruh.yigit@amd.com; Xia, Chenbo
> <chenbo.xia@intel.com>; nipun.gupta@amd.com; Richardson, Bruce
> <bruce.richardson@intel.com>; Burakov, Anatoly <anatoly.burakov@intel.com>;
> Jay Zhou <jianjay.zhou@huawei.com>; Sevincer, Abdullah
> <abdullah.sevincer@intel.com>; Julien Aube <julien_dpdk@jaube.fr>; Rahul
> Lakkireddy <rahul.lakkireddy@chelsio.com>; Guo, Junfeng
> <junfeng.guo@intel.com>; Jeroen de Borst <jeroendb@google.com>; Rushil
> Gupta <rushilg@google.com>; Joshua Washington <joshwash@google.com>;
> Dongdong Liu <liudongdong3@huawei.com>; Yisen Zhuang
> <yisen.zhuang@huawei.com>; Maxime Coquelin <maxime.coquelin@redhat.com>;
> Gaetan Rivet <grive@u256.net>
> Subject: [PATCH v3 04/15] bus/pci: find PCI capability
> 
> Introduce two helpers so that drivers stop reinventing the wheel when it
> comes to finding capabilities in a device PCI configuration space.
> Use it in existing drivers.
> 
> Note:
> - base/ drivers code is left untouched, only some wrappers in cxgbe
>   are touched,
> - bnx2x maintained a per device cache of capabilities, this code has been
>   reworked to only cache the capabilities used in this driver,
> 
> Acked-by: Bruce Richardson <bruce.richardson@intel.com>
> Signed-off-by: David Marchand <david.marchand@redhat.com>
> ---
> Changes since v2:
> - added rte_pci_find_next_capability for vendor capa used with virtio,
> 
> Changes since v1:
> - updated commitlog,
> - separated VFIO changes for using standard PCI helper in a separate
>   patch,
> - marked new experimental symbols with current version,
> - reordered defines in rte_pci.h,
> 
> ---
>  drivers/bus/pci/linux/pci_vfio.c   |  74 ++++--------------
>  drivers/bus/pci/pci_common.c       |  54 +++++++++++++
>  drivers/bus/pci/rte_bus_pci.h      |  53 +++++++++++++
>  drivers/bus/pci/version.map        |   5 ++
>  drivers/crypto/virtio/virtio_pci.c |  57 +++++---------
>  drivers/event/dlb2/pf/dlb2_main.c  |  42 +---------
>  drivers/net/bnx2x/bnx2x.c          |  41 +++++-----
>  drivers/net/cxgbe/base/adapter.h   |  28 +------
>  drivers/net/gve/gve_ethdev.c       |  46 ++---------
>  drivers/net/gve/gve_ethdev.h       |   4 -
>  drivers/net/hns3/hns3_ethdev_vf.c  |  79 +++----------------
>  drivers/net/virtio/virtio_pci.c    | 121 ++++++-----------------------
>  lib/pci/rte_pci.h                  |  12 +++
>  13 files changed, 223 insertions(+), 393 deletions(-)
> 

Reviewed-by: Chenbo Xia <chenbo.xia@intel.com> 

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

* RE: [PATCH v3 12/15] pci: define some ACS constants
  2023-09-14 12:36   ` [PATCH v3 12/15] pci: define some ACS constants David Marchand
  2023-09-15 16:25     ` Sevincer, Abdullah
@ 2023-09-19  2:35     ` Xia, Chenbo
  1 sibling, 0 replies; 98+ messages in thread
From: Xia, Chenbo @ 2023-09-19  2:35 UTC (permalink / raw)
  To: David Marchand, dev
  Cc: thomas, ferruh.yigit, nipun.gupta, Richardson, Bruce, Sevincer,
	Abdullah, Gaetan Rivet

> -----Original Message-----
> From: David Marchand <david.marchand@redhat.com>
> Sent: Thursday, September 14, 2023 8:36 PM
> To: dev@dpdk.org
> Cc: thomas@monjalon.net; ferruh.yigit@amd.com; Xia, Chenbo
> <chenbo.xia@intel.com>; nipun.gupta@amd.com; Richardson, Bruce
> <bruce.richardson@intel.com>; Sevincer, Abdullah
> <abdullah.sevincer@intel.com>; Gaetan Rivet <grive@u256.net>
> Subject: [PATCH v3 12/15] pci: define some ACS constants
> 
> Define some PCI ACS extended feature constants and use them in existing
> drivers.
> 
> Signed-off-by: David Marchand <david.marchand@redhat.com>
> Acked-by: Bruce Richardson <bruce.richardson@intel.com>
> ---
>  drivers/event/dlb2/pf/dlb2_main.c | 23 ++++++++---------------
>  lib/pci/rte_pci.h                 |  9 +++++++++
>  2 files changed, 17 insertions(+), 15 deletions(-)
> 
> diff --git a/drivers/event/dlb2/pf/dlb2_main.c
> b/drivers/event/dlb2/pf/dlb2_main.c
> index 29e3001627..8e729d1964 100644
> --- a/drivers/event/dlb2/pf/dlb2_main.c
> +++ b/drivers/event/dlb2/pf/dlb2_main.c
> @@ -33,13 +33,6 @@
>  #define DLB2_PCI_ERR_ROOT_STATUS         0x30
>  #define DLB2_PCI_ERR_COR_STATUS          0x10
>  #define DLB2_PCI_ERR_UNCOR_STATUS        0x4
> -#define DLB2_PCI_ACS_CAP                 0x4
> -#define DLB2_PCI_ACS_CTRL                0x6
> -#define DLB2_PCI_ACS_SV                  0x1
> -#define DLB2_PCI_ACS_RR                  0x4
> -#define DLB2_PCI_ACS_CR                  0x8
> -#define DLB2_PCI_ACS_UF                  0x10
> -#define DLB2_PCI_ACS_EC                  0x20
> 
>  static int
>  dlb2_pf_init_driver_state(struct dlb2_dev *dlb2_dev)
> @@ -492,16 +485,16 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
> 
>  	if (acs_cap_offset >= 0) {
>  		uint16_t acs_cap, acs_ctrl, acs_mask;
> -		off = acs_cap_offset + DLB2_PCI_ACS_CAP;
> +		off = acs_cap_offset + RTE_PCI_ACS_CAP;
>  		if (rte_pci_read_config(pdev, &acs_cap, 2, off) != 2)
>  			acs_cap = 0;
> 
> -		off = acs_cap_offset + DLB2_PCI_ACS_CTRL;
> +		off = acs_cap_offset + RTE_PCI_ACS_CTRL;
>  		if (rte_pci_read_config(pdev, &acs_ctrl, 2, off) != 2)
>  			acs_ctrl = 0;
> 
> -		acs_mask = DLB2_PCI_ACS_SV | DLB2_PCI_ACS_RR;
> -		acs_mask |= (DLB2_PCI_ACS_CR | DLB2_PCI_ACS_UF);
> +		acs_mask = RTE_PCI_ACS_SV | RTE_PCI_ACS_RR;
> +		acs_mask |= (RTE_PCI_ACS_CR | RTE_PCI_ACS_UF);
>  		acs_ctrl |= (acs_cap & acs_mask);
> 
>  		ret = rte_pci_write_config(pdev, &acs_ctrl, 2, off);
> @@ -511,15 +504,15 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
>  			return ret;
>  		}
> 
> -		off = acs_cap_offset + DLB2_PCI_ACS_CTRL;
> +		off = acs_cap_offset + RTE_PCI_ACS_CTRL;
>  		if (rte_pci_read_config(pdev, &acs_ctrl, 2, off) != 2)
>  			acs_ctrl = 0;
> 
> -		acs_mask = DLB2_PCI_ACS_RR | DLB2_PCI_ACS_CR;
> -		acs_mask |= DLB2_PCI_ACS_EC;
> +		acs_mask = RTE_PCI_ACS_RR | RTE_PCI_ACS_CR;
> +		acs_mask |= RTE_PCI_ACS_EC;
>  		acs_ctrl &= ~acs_mask;
> 
> -		off = acs_cap_offset + DLB2_PCI_ACS_CTRL;
> +		off = acs_cap_offset + RTE_PCI_ACS_CTRL;
>  		ret = rte_pci_write_config(pdev, &acs_ctrl, 2, off);
>  		if (ret != 2) {
>  			DLB2_LOG_ERR("[%s()] failed to write the pcie config
> space at offset %d\n",
> diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
> index 1fdca91f8b..a6c52a232d 100644
> --- a/lib/pci/rte_pci.h
> +++ b/lib/pci/rte_pci.h
> @@ -102,6 +102,15 @@ extern "C" {
>  #define RTE_PCI_EXT_CAP_ID_SRIOV	0x10	/* SR-IOV */
>  #define RTE_PCI_EXT_CAP_ID_PRI		0x13	/* Page Request Interface
> */
> 
> +/* Access Control Service (RTE_PCI_EXT_CAP_ID_ACS) */
> +#define RTE_PCI_ACS_CAP			0x04	/* ACS Capability Register
> */
> +#define RTE_PCI_ACS_CTRL		0x06	/* ACS Control Register */
> +#define RTE_PCI_ACS_SV			0x0001	/* Source Validation */
> +#define RTE_PCI_ACS_RR			0x0004	/* P2P Request Redirect */
> +#define RTE_PCI_ACS_CR			0x0008	/* P2P Completion Redirect
> */
> +#define RTE_PCI_ACS_UF			0x0010	/* Upstream Forwarding */
> +#define RTE_PCI_ACS_EC			0x0020	/* P2P Egress Control */
> +
>  /* Single Root I/O Virtualization (RTE_PCI_EXT_CAP_ID_SRIOV) */
>  #define RTE_PCI_SRIOV_CAP		0x04	/* SR-IOV Capabilities */
>  #define RTE_PCI_SRIOV_CTRL		0x08	/* SR-IOV Control */
> --
> 2.41.0

Reviewed-by: Chenbo Xia <chenbo.xia@intel.com> 

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

* RE: [PATCH v3 13/15] pci: define some PRI constants
  2023-09-14 12:36   ` [PATCH v3 13/15] pci: define some PRI constants David Marchand
  2023-09-15 16:21     ` Sevincer, Abdullah
@ 2023-09-19  2:36     ` Xia, Chenbo
  1 sibling, 0 replies; 98+ messages in thread
From: Xia, Chenbo @ 2023-09-19  2:36 UTC (permalink / raw)
  To: David Marchand, dev
  Cc: thomas, ferruh.yigit, nipun.gupta, Richardson, Bruce, Sevincer,
	Abdullah, Gaetan Rivet

> -----Original Message-----
> From: David Marchand <david.marchand@redhat.com>
> Sent: Thursday, September 14, 2023 8:36 PM
> To: dev@dpdk.org
> Cc: thomas@monjalon.net; ferruh.yigit@amd.com; Xia, Chenbo
> <chenbo.xia@intel.com>; nipun.gupta@amd.com; Richardson, Bruce
> <bruce.richardson@intel.com>; Sevincer, Abdullah
> <abdullah.sevincer@intel.com>; Gaetan Rivet <grive@u256.net>
> Subject: [PATCH v3 13/15] pci: define some PRI constants
> 
> Define some PCI PRI extended feature constants and use them in existing
> drivers.
> 
> Signed-off-by: David Marchand <david.marchand@redhat.com>
> Acked-by: Bruce Richardson <bruce.richardson@intel.com>
> ---
>  drivers/event/dlb2/pf/dlb2_main.c | 11 ++++-------
>  lib/pci/rte_pci.h                 |  5 +++++
>  2 files changed, 9 insertions(+), 7 deletions(-)
> 
> diff --git a/drivers/event/dlb2/pf/dlb2_main.c
> b/drivers/event/dlb2/pf/dlb2_main.c
> index 8e729d1964..187a356c24 100644
> --- a/drivers/event/dlb2/pf/dlb2_main.c
> +++ b/drivers/event/dlb2/pf/dlb2_main.c
> @@ -27,9 +27,6 @@
>  #define NO_OWNER_VF 0	/* PF ONLY! */
>  #define NOT_VF_REQ false /* PF ONLY! */
> 
> -#define DLB2_PCI_PRI_CTRL_ENABLE         0x1
> -#define DLB2_PCI_PRI_ALLOC_REQ           0xC
> -#define DLB2_PCI_PRI_CTRL                0x4
>  #define DLB2_PCI_ERR_ROOT_STATUS         0x30
>  #define DLB2_PCI_ERR_COR_STATUS          0x10
>  #define DLB2_PCI_ERR_UNCOR_STATUS        0x4
> @@ -257,7 +254,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
>  	pri_cap_offset = rte_pci_find_ext_capability(pdev, off);
> 
>  	if (pri_cap_offset >= 0) {
> -		off = pri_cap_offset + DLB2_PCI_PRI_ALLOC_REQ;
> +		off = pri_cap_offset + RTE_PCI_PRI_ALLOC_REQ;
>  		if (rte_pci_read_config(pdev, &pri_reqs_dword, 4, off) != 4)
>  			pri_reqs_dword = 0;
>  	}
> @@ -377,9 +374,9 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
>  	}
> 
>  	if (pri_cap_offset >= 0) {
> -		pri_ctrl_word = DLB2_PCI_PRI_CTRL_ENABLE;
> +		pri_ctrl_word = RTE_PCI_PRI_CTRL_ENABLE;
> 
> -		off = pri_cap_offset + DLB2_PCI_PRI_ALLOC_REQ;
> +		off = pri_cap_offset + RTE_PCI_PRI_ALLOC_REQ;
>  		ret = rte_pci_write_config(pdev, &pri_reqs_dword, 4, off);
>  		if (ret != 4) {
>  			DLB2_LOG_ERR("[%s()] failed to write the pcie config
> space at offset %d\n",
> @@ -387,7 +384,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
>  			return ret;
>  		}
> 
> -		off = pri_cap_offset + DLB2_PCI_PRI_CTRL;
> +		off = pri_cap_offset + RTE_PCI_PRI_CTRL;
>  		ret = rte_pci_write_config(pdev, &pri_ctrl_word, 2, off);
>  		if (ret != 2) {
>  			DLB2_LOG_ERR("[%s()] failed to write the pcie config
> space at offset %d\n",
> diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
> index a6c52a232d..6bbcad20f2 100644
> --- a/lib/pci/rte_pci.h
> +++ b/lib/pci/rte_pci.h
> @@ -123,6 +123,11 @@ extern "C" {
>  #define RTE_PCI_SRIOV_VF_DID		0x1a	/* VF Device ID */
>  #define RTE_PCI_SRIOV_SUP_PGSIZE	0x1c	/* Supported Page Sizes */
> 
> +/* Page Request Interface (RTE_PCI_EXT_CAP_ID_PRI) */
> +#define RTE_PCI_PRI_CTRL		0x04	/* PRI control register */
> +#define RTE_PCI_PRI_CTRL_ENABLE		0x0001	/* Enable */
> +#define RTE_PCI_PRI_ALLOC_REQ		0x0c	/* PRI max reqs allowed */
> +
>  /** Formatting string for PCI device identifier: Ex: 0000:00:01.0 */
>  #define PCI_PRI_FMT "%.4" PRIx32 ":%.2" PRIx8 ":%.2" PRIx8 ".%" PRIx8
>  #define PCI_PRI_STR_SIZE sizeof("XXXXXXXX:XX:XX.X")
> --
> 2.41.0

Reviewed-by: Chenbo Xia <chenbo.xia@intel.com> 

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

* RE: [PATCH v3 14/15] pci: define some AER constants
  2023-09-14 12:36   ` [PATCH v3 14/15] pci: define some AER constants David Marchand
  2023-09-15 16:26     ` Sevincer, Abdullah
@ 2023-09-19  2:36     ` Xia, Chenbo
  1 sibling, 0 replies; 98+ messages in thread
From: Xia, Chenbo @ 2023-09-19  2:36 UTC (permalink / raw)
  To: David Marchand, dev
  Cc: thomas, ferruh.yigit, nipun.gupta, Richardson, Bruce, Sevincer,
	Abdullah, Gaetan Rivet

> -----Original Message-----
> From: David Marchand <david.marchand@redhat.com>
> Sent: Thursday, September 14, 2023 8:36 PM
> To: dev@dpdk.org
> Cc: thomas@monjalon.net; ferruh.yigit@amd.com; Xia, Chenbo
> <chenbo.xia@intel.com>; nipun.gupta@amd.com; Richardson, Bruce
> <bruce.richardson@intel.com>; Sevincer, Abdullah
> <abdullah.sevincer@intel.com>; Gaetan Rivet <grive@u256.net>
> Subject: [PATCH v3 14/15] pci: define some AER constants
> 
> Define some Advanced Error Reporting constants and use them in existing
> drivers.
> 
> Signed-off-by: David Marchand <david.marchand@redhat.com>
> Acked-by: Bruce Richardson <bruce.richardson@intel.com>
> ---
>  drivers/event/dlb2/pf/dlb2_main.c | 10 +++-------
>  lib/pci/rte_pci.h                 |  5 +++++
>  2 files changed, 8 insertions(+), 7 deletions(-)
> 
> diff --git a/drivers/event/dlb2/pf/dlb2_main.c
> b/drivers/event/dlb2/pf/dlb2_main.c
> index 187a356c24..aa03e4c311 100644
> --- a/drivers/event/dlb2/pf/dlb2_main.c
> +++ b/drivers/event/dlb2/pf/dlb2_main.c
> @@ -27,10 +27,6 @@
>  #define NO_OWNER_VF 0	/* PF ONLY! */
>  #define NOT_VF_REQ false /* PF ONLY! */
> 
> -#define DLB2_PCI_ERR_ROOT_STATUS         0x30
> -#define DLB2_PCI_ERR_COR_STATUS          0x10
> -#define DLB2_PCI_ERR_UNCOR_STATUS        0x4
> -
>  static int
>  dlb2_pf_init_driver_state(struct dlb2_dev *dlb2_dev)
>  {
> @@ -399,7 +395,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
>  	if (err_cap_offset >= 0) {
>  		uint32_t tmp;
> 
> -		off = err_cap_offset + DLB2_PCI_ERR_ROOT_STATUS;
> +		off = err_cap_offset + RTE_PCI_ERR_ROOT_STATUS;
>  		if (rte_pci_read_config(pdev, &tmp, 4, off) != 4)
>  			tmp = 0;
> 
> @@ -410,7 +406,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
>  			return ret;
>  		}
> 
> -		off = err_cap_offset + DLB2_PCI_ERR_COR_STATUS;
> +		off = err_cap_offset + RTE_PCI_ERR_COR_STATUS;
>  		if (rte_pci_read_config(pdev, &tmp, 4, off) != 4)
>  			tmp = 0;
> 
> @@ -421,7 +417,7 @@ dlb2_pf_reset(struct dlb2_dev *dlb2_dev)
>  			return ret;
>  		}
> 
> -		off = err_cap_offset + DLB2_PCI_ERR_UNCOR_STATUS;
> +		off = err_cap_offset + RTE_PCI_ERR_UNCOR_STATUS;
>  		if (rte_pci_read_config(pdev, &tmp, 4, off) != 4)
>  			tmp = 0;
> 
> diff --git a/lib/pci/rte_pci.h b/lib/pci/rte_pci.h
> index 6bbcad20f2..69e932d910 100644
> --- a/lib/pci/rte_pci.h
> +++ b/lib/pci/rte_pci.h
> @@ -102,6 +102,11 @@ extern "C" {
>  #define RTE_PCI_EXT_CAP_ID_SRIOV	0x10	/* SR-IOV */
>  #define RTE_PCI_EXT_CAP_ID_PRI		0x13	/* Page Request Interface
> */
> 
> +/* Advanced Error Reporting (RTE_PCI_EXT_CAP_ID_ERR) */
> +#define RTE_PCI_ERR_UNCOR_STATUS	0x04	/* Uncorrectable Error Status */
> +#define RTE_PCI_ERR_COR_STATUS		0x10	/* Correctable Error
> Status */
> +#define RTE_PCI_ERR_ROOT_STATUS		0x30
> +
>  /* Access Control Service (RTE_PCI_EXT_CAP_ID_ACS) */
>  #define RTE_PCI_ACS_CAP			0x04	/* ACS Capability Register
> */
>  #define RTE_PCI_ACS_CTRL		0x06	/* ACS Control Register */
> --
> 2.41.0

Reviewed-by: Chenbo Xia <chenbo.xia@intel.com> 

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

* Re: [PATCH v2 04/15] bus/pci: find PCI capability
  2023-09-19  2:19         ` Xia, Chenbo
@ 2023-09-19  9:00           ` David Marchand
  0 siblings, 0 replies; 98+ messages in thread
From: David Marchand @ 2023-09-19  9:00 UTC (permalink / raw)
  To: Xia, Chenbo
  Cc: Maxime Coquelin, dev, thomas, ferruh.yigit, nipun.gupta,
	Richardson, Bruce, Burakov, Anatoly, Jay Zhou, McDaniel, Timothy,
	Julien Aube, Rahul Lakkireddy, Guo, Junfeng, Jeroen de Borst,
	Rushil Gupta, Joshua Washington, Dongdong Liu, Yisen Zhuang,
	Gaetan Rivet

On Tue, Sep 19, 2023 at 4:19 AM Xia, Chenbo <chenbo.xia@intel.com> wrote:
>
> Hi David,
>
> > -----Original Message-----
> > From: David Marchand <david.marchand@redhat.com>
> > Sent: Thursday, September 14, 2023 8:29 PM
> > To: Xia, Chenbo <chenbo.xia@intel.com>; Maxime Coquelin
> > <maxime.coquelin@redhat.com>
> > Cc: dev@dpdk.org; thomas@monjalon.net; ferruh.yigit@amd.com;
> > nipun.gupta@amd.com; Richardson, Bruce <bruce.richardson@intel.com>;
> > Burakov, Anatoly <anatoly.burakov@intel.com>; Jay Zhou
> > <jianjay.zhou@huawei.com>; McDaniel, Timothy <timothy.mcdaniel@intel.com>;
> > Julien Aube <julien_dpdk@jaube.fr>; Rahul Lakkireddy
> > <rahul.lakkireddy@chelsio.com>; Guo, Junfeng <junfeng.guo@intel.com>;
> > Jeroen de Borst <jeroendb@google.com>; Rushil Gupta <rushilg@google.com>;
> > Joshua Washington <joshwash@google.com>; Dongdong Liu
> > <liudongdong3@huawei.com>; Yisen Zhuang <yisen.zhuang@huawei.com>; Gaetan
> > Rivet <grive@u256.net>
> > Subject: Re: [PATCH v2 04/15] bus/pci: find PCI capability
> >
> > Hello Chenbo,
> >
> > On Thu, Sep 7, 2023 at 2:43 PM Xia, Chenbo <chenbo.xia@intel.com> wrote:
> > > > Introduce two helpers so that drivers stop reinventing the wheel when
> > it
> > > > comes to finding capabilities in a device PCI configuration space.
> > > > Use it in existing drivers.
> > > >
> > > > Note:
> > > > - base/ drivers code is left untouched, only some wrappers in cxgbe
> > > >   are touched,
> > > > - bnx2x maintained a per device cache of capabilities, this code has
> > been
> > > >   reworked to only cache the capabilities used in this driver,
> > > >
> > > > Signed-off-by: David Marchand <david.marchand@redhat.com>
> > > > Acked-by: Bruce Richardson <bruce.richardson@intel.com>
> > > > ---
> > > > Changes since v1:
> > > > - updated commitlog,
> > > > - separated VFIO changes for using standard PCI helper in a separate
> > > >   patch,
> > > > - marked new experimental symbols with current version,
> > > > - reordered defines in rte_pci.h,
> > > >
> > > > ---
> > > >  drivers/bus/pci/linux/pci_vfio.c   |  74 ++++--------------
> > > >  drivers/bus/pci/pci_common.c       |  45 +++++++++++
> > > >  drivers/bus/pci/rte_bus_pci.h      |  31 ++++++++
> > > >  drivers/bus/pci/version.map        |   4 +
> > > >  drivers/crypto/virtio/virtio_pci.c |  57 +++++---------
> > > >  drivers/event/dlb2/pf/dlb2_main.c  |  42 +---------
> > > >  drivers/net/bnx2x/bnx2x.c          |  41 +++++-----
> > > >  drivers/net/cxgbe/base/adapter.h   |  28 +------
> > > >  drivers/net/gve/gve_ethdev.c       |  46 ++---------
> > > >  drivers/net/gve/gve_ethdev.h       |   4 -
> > > >  drivers/net/hns3/hns3_ethdev_vf.c  |  79 +++----------------
> > > >  drivers/net/virtio/virtio_pci.c    | 121 +++++-----------------------
> > -
> > > >  lib/pci/rte_pci.h                  |  11 +++
> > > >  13 files changed, 186 insertions(+), 397 deletions(-)
> > > >
> > > > diff --git a/drivers/bus/pci/linux/pci_vfio.c
> > > > b/drivers/bus/pci/linux/pci_vfio.c
> > > > index 958f8b3b52..614ed5d696 100644
> > > > --- a/drivers/bus/pci/linux/pci_vfio.c
> > > > +++ b/drivers/bus/pci/linux/pci_vfio.c
> > > > @@ -110,74 +110,34 @@ static int
> > > >  pci_vfio_get_msix_bar(const struct rte_pci_device *dev,
> > > >       struct pci_msix_table *msix_table)
> > > >  {
> > > > -     int ret;
> > > > -     uint32_t reg;
> > > > -     uint16_t flags;
> > > > -     uint8_t cap_id, cap_offset;
> > > > +     off_t cap_offset;
> > > >
> > > > -     /* read PCI capability pointer from config space */
> > > > -     ret = rte_pci_read_config(dev, &reg, sizeof(reg),
> > > > PCI_CAPABILITY_LIST);
> > > > -     if (ret != sizeof(reg)) {
> > > > -             RTE_LOG(ERR, EAL,
> > > > -                     "Cannot read capability pointer from PCI config
> > > > space!\n");
> > > > +     cap_offset = rte_pci_find_capability(dev, PCI_CAP_ID_MSIX);
> > >
> > > I notice in some cases we use rte_pci_has_capability_list() to check
> > first,
> > > then looking for specific cap, in other cases we don't use
> > > rte_pci_has_capability_list(). Since we define this API, should we
> > always do
> > > the check?
> >
> > Hum, I am not sure of what you suggest here.
> >
> > I tried to do a 1:1 conversion of what existed.
> > Do you mean there are places where I missed converting some
> > rte_pci_read_config(PCI_CAPABILITY_LIST) to
> > rte_pci_has_capability_list()?
> > If so, could you point at them?
> >
> > Or are you suggesting to have this check as part of
> > rte_pci_find_capability() ?
>
> Your conversion is correct. I was saying about the usage of
> rte_pci_has_capability_list/rte_pci_find_capability, logically should we
> always call rte_pci_has_capability_list first before find capability?
>
> I don't have strong opinion on this. You can choose to keep the same or
> call rte_pci_has_capability_list more.

I prefer to keep it as is (the series is already big enough).
We can still add more checks in the future.

Thanks Chenbo.


-- 
David Marchand


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

* Re: [PATCH v3 00/15] Cleanup PCI(e) drivers
  2023-09-14 12:35 ` [PATCH v3 00/15] " David Marchand
                     ` (15 preceding siblings ...)
  2023-09-15 15:14   ` [PATCH v3 00/15] Cleanup PCI(e) drivers Stephen Hemminger
@ 2023-09-19 12:41   ` David Marchand
  16 siblings, 0 replies; 98+ messages in thread
From: David Marchand @ 2023-09-19 12:41 UTC (permalink / raw)
  To: David Marchand
  Cc: dev, thomas, ferruh.yigit, chenbo.xia, nipun.gupta,
	bruce.richardson, Stephen Hemminger, Sevincer, Abdullah,
	Tyler Retzlaff

On Thu, Sep 14, 2023 at 2:36 PM David Marchand
<david.marchand@redhat.com> wrote:
>
> Rather than rely on Linux headers to find some PCI(e) standard constants
> or reinvent the same PCI capability helper, this series complements the
> pci library and the pci bus driver.
> PCI drivers can then use OS agnostic macros and helpers.

Thanks to all reviewers.
Series applied.


-- 
David Marchand


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

* Re: [PATCH 01/14] drivers: remove duplicated PCI master control
  2023-08-03  7:50 ` [PATCH 01/14] drivers: remove duplicated PCI master control David Marchand
  2023-08-03  9:45   ` Bruce Richardson
@ 2023-10-07  2:53   ` fengchengwen
  1 sibling, 0 replies; 98+ messages in thread
From: fengchengwen @ 2023-10-07  2:53 UTC (permalink / raw)
  To: David Marchand, dev
  Cc: thomas, ferruh.yigit, chenbo.xia, nipun.gupta, Anatoly Burakov,
	Dongdong Liu, Yisen Zhuang, Jiawen Wu

Acked-by: Chengwen Feng <fengchengwen@huawei.com>

On 2023/8/3 15:50, David Marchand wrote:
> Use existing API to cleanup duplicated code.
> 
> Signed-off-by: David Marchand <david.marchand@redhat.com>
> ---
>  drivers/bus/pci/linux/pci_uio.c    | 32 +----------------------
>  drivers/bus/pci/linux/pci_vfio.c   | 41 ++----------------------------
>  drivers/net/hns3/hns3_ethdev_vf.c  | 25 +-----------------
>  drivers/net/ngbe/base/ngbe_hw.c    | 20 ++-------------
>  drivers/net/ngbe/base/ngbe_osdep.h |  3 ---
>  5 files changed, 6 insertions(+), 115 deletions(-)
> 

...

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

end of thread, other threads:[~2023-10-07  2:53 UTC | newest]

Thread overview: 98+ messages (download: mbox.gz / follow: Atom feed)
-- links below jump to the message on this page --
2023-08-03  7:50 [PATCH 00/14] Cleanup PCI(e) drivers David Marchand
2023-08-03  7:50 ` [PATCH 01/14] drivers: remove duplicated PCI master control David Marchand
2023-08-03  9:45   ` Bruce Richardson
2023-10-07  2:53   ` fengchengwen
2023-08-03  7:50 ` [PATCH 02/14] bus/pci: add const to some experimental API David Marchand
2023-08-03  9:46   ` Bruce Richardson
2023-08-03 11:50     ` David Marchand
2023-08-03  7:50 ` [PATCH 03/14] bus/pci: find PCI capability David Marchand
2023-08-03  9:49   ` Bruce Richardson
2023-08-03  9:52     ` Bruce Richardson
2023-08-03 11:49       ` David Marchand
2023-08-03  7:50 ` [PATCH 04/14] pci: define some capability constants David Marchand
2023-08-03  9:51   ` Bruce Richardson
2023-08-03  7:50 ` [PATCH 05/14] pci: define some MSIX constants David Marchand
2023-08-03  9:53   ` Bruce Richardson
2023-08-03  7:50 ` [PATCH 06/14] pci: define some command constants David Marchand
2023-08-03  9:57   ` Bruce Richardson
2023-08-03 11:51     ` David Marchand
2023-08-08  9:20       ` David Marchand
2023-08-08 10:08         ` Bruce Richardson
2023-08-22 19:23   ` Adam Hassick
2023-08-03  7:50 ` [PATCH 07/14] pci: define some BAR constants David Marchand
2023-08-03  9:58   ` Bruce Richardson
2023-08-03  7:50 ` [PATCH 08/14] pci: define some PM constants David Marchand
2023-08-03  9:59   ` Bruce Richardson
2023-08-03  7:50 ` [PATCH 09/14] pci: define some PCIe constants David Marchand
2023-08-03 10:01   ` Bruce Richardson
2023-08-03  7:50 ` [PATCH 10/14] pci: define some extended capability constants David Marchand
2023-08-03  7:50 ` [PATCH 11/14] pci: define some ACS constants David Marchand
2023-08-03  7:50 ` [PATCH 12/14] pci: define some PRI constants David Marchand
2023-08-03  7:50 ` [PATCH 13/14] pci: define some AER constants David Marchand
2023-08-03  7:50 ` [PATCH 14/14] devtools: forbid inclusion of Linux header for PCI David Marchand
2023-08-03 10:03 ` [PATCH 00/14] Cleanup PCI(e) drivers Bruce Richardson
2023-08-21 11:35 ` [PATCH v2 00/15] " David Marchand
2023-08-21 11:35   ` [PATCH v2 01/15] drivers: remove duplicated PCI master control David Marchand
2023-09-06 13:02     ` Xia, Chenbo
2023-08-21 11:35   ` [PATCH v2 02/15] bus/pci: add const to some experimental API David Marchand
2023-08-21 16:14     ` Tyler Retzlaff
2023-09-06 13:02     ` Xia, Chenbo
2023-08-21 11:35   ` [PATCH v2 03/15] bus/pci: rework MSIX discovery with VFIO David Marchand
2023-09-06 13:03     ` Xia, Chenbo
2023-08-21 11:35   ` [PATCH v2 04/15] bus/pci: find PCI capability David Marchand
2023-09-07 12:43     ` Xia, Chenbo
2023-09-14 12:29       ` David Marchand
2023-09-19  2:19         ` Xia, Chenbo
2023-09-19  9:00           ` David Marchand
2023-08-21 11:35   ` [PATCH v2 05/15] pci: define some capability constants David Marchand
2023-09-07 13:15     ` Xia, Chenbo
2023-08-21 11:35   ` [PATCH v2 06/15] pci: define some MSIX constants David Marchand
2023-09-07 13:15     ` Xia, Chenbo
2023-08-21 11:35   ` [PATCH v2 07/15] pci: define some command constants David Marchand
2023-09-07 13:15     ` Xia, Chenbo
2023-08-21 11:35   ` [PATCH v2 08/15] pci: define some BAR constants David Marchand
2023-09-07 13:16     ` Xia, Chenbo
2023-08-21 11:35   ` [PATCH v2 09/15] pci: define some PM constants David Marchand
2023-09-07 13:16     ` Xia, Chenbo
2023-08-21 11:35   ` [PATCH v2 10/15] pci: define some PCIe constants David Marchand
2023-09-07 13:16     ` Xia, Chenbo
2023-08-21 11:35   ` [PATCH v2 11/15] pci: define some extended capability constants David Marchand
2023-09-07 13:23     ` Xia, Chenbo
2023-08-21 11:35   ` [PATCH v2 12/15] pci: define some ACS constants David Marchand
2023-08-21 11:35   ` [PATCH v2 13/15] pci: define some PRI constants David Marchand
2023-08-21 11:35   ` [PATCH v2 14/15] pci: define some AER constants David Marchand
2023-08-21 11:35   ` [PATCH v2 15/15] devtools: forbid inclusion of Linux header for PCI David Marchand
2023-08-21 16:24     ` Tyler Retzlaff
2023-09-07 13:33     ` Xia, Chenbo
2023-08-22 15:30   ` [PATCH v2 00/15] Cleanup PCI(e) drivers Patrick Robb
2023-08-22 16:09 ` [PATCH 00/14] " Adam Hassick
2023-08-22 16:48 ` Adam Hassick
2023-08-24 15:44 ` Adam Hassick
2023-09-14 12:35 ` [PATCH v3 00/15] " David Marchand
2023-09-14 12:36   ` [PATCH v3 01/15] drivers: remove duplicated PCI master control David Marchand
2023-09-14 12:36   ` [PATCH v3 02/15] bus/pci: add const to some experimental API David Marchand
2023-09-14 12:36   ` [PATCH v3 03/15] bus/pci: rework MSIX discovery with VFIO David Marchand
2023-09-14 12:36   ` [PATCH v3 04/15] bus/pci: find PCI capability David Marchand
2023-09-19  2:33     ` Xia, Chenbo
2023-09-14 12:36   ` [PATCH v3 05/15] pci: define some capability constants David Marchand
2023-09-15 16:27     ` Sevincer, Abdullah
2023-09-14 12:36   ` [PATCH v3 06/15] pci: define some MSIX constants David Marchand
2023-09-14 12:36   ` [PATCH v3 07/15] pci: define some command constants David Marchand
2023-09-14 12:36   ` [PATCH v3 08/15] pci: define some BAR constants David Marchand
2023-09-14 12:36   ` [PATCH v3 09/15] pci: define some PM constants David Marchand
2023-09-14 12:36   ` [PATCH v3 10/15] pci: define some PCIe constants David Marchand
2023-09-15 16:26     ` Sevincer, Abdullah
2023-09-14 12:36   ` [PATCH v3 11/15] pci: define some extended capability constants David Marchand
2023-09-15 16:27     ` Sevincer, Abdullah
2023-09-14 12:36   ` [PATCH v3 12/15] pci: define some ACS constants David Marchand
2023-09-15 16:25     ` Sevincer, Abdullah
2023-09-19  2:35     ` Xia, Chenbo
2023-09-14 12:36   ` [PATCH v3 13/15] pci: define some PRI constants David Marchand
2023-09-15 16:21     ` Sevincer, Abdullah
2023-09-19  2:36     ` Xia, Chenbo
2023-09-14 12:36   ` [PATCH v3 14/15] pci: define some AER constants David Marchand
2023-09-15 16:26     ` Sevincer, Abdullah
2023-09-19  2:36     ` Xia, Chenbo
2023-09-14 12:36   ` [PATCH v3 15/15] devtools: forbid inclusion of Linux header for PCI David Marchand
2023-09-15 15:14   ` [PATCH v3 00/15] Cleanup PCI(e) drivers Stephen Hemminger
2023-09-19 12:41   ` David Marchand

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).