public inbox for devel@edk2.groups.io
 help / color / mirror / Atom feed
* [edk2-platforms][PATCH v2 0/4] Platform/RPi4: Add PCIe and xHCI support
@ 2019-12-13 17:07 Pete Batard
  2019-12-13 17:07 ` [edk2-platforms][PATCH v2 1/4] Silicon/Bcm27xx: Add PCIe constants to Bcm2711.h Pete Batard
                   ` (4 more replies)
  0 siblings, 5 replies; 8+ messages in thread
From: Pete Batard @ 2019-12-13 17:07 UTC (permalink / raw)
  To: devel; +Cc: ard.biesheuvel, leif.lindholm, philmd, lintonrjeremy

Changes from v1 (https://edk2.groups.io/g/devel/message/52160 - 52164):

* Ensure that read/write accesses are serialized in PciSegmentLib.
* Flesh out commit messages.
* Minor comments and code updates for whitespaces & capitalization.

Jeremy Linton (4):
  Silicon/Bcm27xx: Add PCIe constants to Bcm2711.h
  Silicon/Bcm27xx: Add segment library to handle nonstandard ECAM
  Silicon/Bcm27xx: Add PCIe host bridge config library
  Platform/RPi4: Build the PCIe and xHCI drivers into the firmware

 Platform/RaspberryPi/RPi4/RPi4.dsc                                                            |   29 +-
 Platform/RaspberryPi/RPi4/RPi4.fdf                                                            |   10 +-
 Platform/RaspberryPi/RPi4/Readme.md                                                           |   23 +-
 Silicon/Broadcom/Bcm27xx/Bcm27xx.dec                                                          |    4 +
 Silicon/Broadcom/Bcm27xx/Include/IndustryStandard/Bcm2711.h                                   |   71 +
 Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciHostBridgeLib/Bcm2711PciHostBridgeLib.c            |  193 +++
 Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciHostBridgeLib/Bcm2711PciHostBridgeLib.inf          |   51 +
 Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciHostBridgeLib/Bcm2711PciHostBridgeLibConstructor.c |  235 ++++
 Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciSegmentLib/PciSegmentLib.c                         | 1445 ++++++++++++++++++++
 Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciSegmentLib/PciSegmentLib.inf                       |   35 +
 10 files changed, 2078 insertions(+), 18 deletions(-)
 create mode 100644 Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciHostBridgeLib/Bcm2711PciHostBridgeLib.c
 create mode 100644 Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciHostBridgeLib/Bcm2711PciHostBridgeLib.inf
 create mode 100644 Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciHostBridgeLib/Bcm2711PciHostBridgeLibConstructor.c
 create mode 100644 Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciSegmentLib/PciSegmentLib.c
 create mode 100644 Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciSegmentLib/PciSegmentLib.inf

-- 
2.21.0.windows.1


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

* [edk2-platforms][PATCH v2 1/4] Silicon/Bcm27xx: Add PCIe constants to Bcm2711.h
  2019-12-13 17:07 [edk2-platforms][PATCH v2 0/4] Platform/RPi4: Add PCIe and xHCI support Pete Batard
@ 2019-12-13 17:07 ` Pete Batard
  2019-12-13 17:07 ` [edk2-platforms][PATCH v2 2/4] Silicon/Bcm27xx: Add segment library to handle nonstandard ECAM Pete Batard
                   ` (3 subsequent siblings)
  4 siblings, 0 replies; 8+ messages in thread
From: Pete Batard @ 2019-12-13 17:07 UTC (permalink / raw)
  To: devel; +Cc: ard.biesheuvel, leif.lindholm, philmd, lintonrjeremy

From: Jeremy Linton <lintonrjeremy@gmail.com>

This populates all of the define's we need for PCIe accesses.
Four new PCDs are also introduced for the register and MMIO platform
constants.

Signed-off-by: Pete Batard <pete@akeo.ie>
---
 Silicon/Broadcom/Bcm27xx/Bcm27xx.dec                        |  4 ++
 Silicon/Broadcom/Bcm27xx/Include/IndustryStandard/Bcm2711.h | 71 ++++++++++++++++++++
 2 files changed, 75 insertions(+)

diff --git a/Silicon/Broadcom/Bcm27xx/Bcm27xx.dec b/Silicon/Broadcom/Bcm27xx/Bcm27xx.dec
index 815302f6d209..cd6f86670d9f 100644
--- a/Silicon/Broadcom/Bcm27xx/Bcm27xx.dec
+++ b/Silicon/Broadcom/Bcm27xx/Bcm27xx.dec
@@ -20,3 +20,7 @@ [Guids]
 
 [PcdsFixedAtBuild.common]
   gBcm27xxTokenSpaceGuid.PcdBcm27xxRegistersAddress|0x0|UINT32|0x00000001
+  gBcm27xxTokenSpaceGuid.PcdBcm27xxPciRegBase|0x0|UINT32|0x00000002
+  gBcm27xxTokenSpaceGuid.PcdBcm27xxPciBusMmioAdr|0x0|UINT64|0x00000003
+  gBcm27xxTokenSpaceGuid.PcdBcm27xxPciBusMmioLen|0x0|UINT32|0x00000004
+  gBcm27xxTokenSpaceGuid.PcdBcm27xxPciCpuMmioAdr|0x0|UINT64|0x00000005
diff --git a/Silicon/Broadcom/Bcm27xx/Include/IndustryStandard/Bcm2711.h b/Silicon/Broadcom/Bcm27xx/Include/IndustryStandard/Bcm2711.h
index 356458024e84..a1609ce9b517 100644
--- a/Silicon/Broadcom/Bcm27xx/Include/IndustryStandard/Bcm2711.h
+++ b/Silicon/Broadcom/Bcm27xx/Include/IndustryStandard/Bcm2711.h
@@ -1,5 +1,6 @@
 /** @file
  *
+ *  Copyright (c) 2019, Jeremy Linton
  *  Copyright (c) 2019, Pete Batard <pete@akeo.ie>.
  *
  *  SPDX-License-Identifier: BSD-2-Clause-Patent
@@ -12,4 +13,74 @@
 #define BCM2711_SOC_REGISTERS               (FixedPcdGet64 (PcdBcm27xxRegistersAddress))
 #define BCM2711_SOC_REGISTER_LENGTH         0x02000000
 
+/* Generic PCI addresses */
+#define PCIE_TOP_OF_MEM_WIN                                 (FixedPcdGet64 (PcdBcm27xxPciBusMmioAdr))
+#define PCIE_CPU_MMIO_WINDOW                                (FixedPcdGet64 (PcdBcm27xxPciCpuMmioAdr))
+#define PCIE_BRIDGE_MMIO_LEN                                (FixedPcdGet32 (PcdBcm27xxPciBusMmioLen))
+
+/* PCI root bridge control registers location */
+#define PCIE_REG_BASE                                       (FixedPcdGet32 (PcdBcm27xxPciRegBase))
+#define PCIE_REG_LIMIT                                      0x9310
+
+/* PCI root bridge control registers */
+#define BRCM_PCIE_CAP_REGS                                  0x00ac      /* Offset to ecam like range for root port */
+#define PCIE_RC_CFG_VENDOR_VENDOR_SPECIFIC_REG1             0x0188
+#define BRCM_PCIE_CLASS                                     0x043c
+#define PCIE_MISC_MISC_CTRL                                 0x4008
+#define PCIE_MISC_CPU_2_PCIE_MEM_WIN0_LO                    0x400c
+#define PCIE_MISC_CPU_2_PCIE_MEM_WIN0_HI                    0x4010
+#define PCIE_MISC_RC_BAR1_CONFIG_LO                         0x402c
+#define PCIE_MISC_RC_BAR2_CONFIG_LO                         0x4034
+#define PCIE_MISC_RC_BAR2_CONFIG_HI                         0x4038
+#define PCIE_MISC_RC_BAR3_CONFIG_LO                         0x403c
+#define PCIE_MISC_PCIE_STATUS                               0x4068
+#define PCIE_MISC_REVISION                                  0x406c
+#define PCIE_MISC_CPU_2_PCIE_MEM_WIN0_BASE_LIMIT            0x4070
+#define PCIE_MISC_CPU_2_PCIE_MEM_WIN0_BASE_HI               0x4080
+#define PCIE_MISC_CPU_2_PCIE_MEM_WIN0_LIMIT_HI              0x4084
+#define PCIE_MISC_HARD_PCIE_HARD_DEBUG                      0x4204
+
+#define PCIE_INTR2_CPU_STATUS                               0x4300
+#define PCIE_INTR2_CPU_SET                                  0x4304
+#define PCIE_INTR2_CPU_CLR                                  0x4308
+#define PCIE_INTR2_CPU_MASK_STATUS                          0x430c
+#define PCIE_INTR2_CPU_MASK_SET                             0x4310
+#define PCIE_INTR2_CPU_MASK_CLR                             0x4314
+
+#define PCIE_RGR1_SW_INIT_1                                 0x9210
+#define PCIE_EXT_CFG_INDEX                                  0x9000
+/* A small window pointing at the ECAM of the device selected by CFG_INDEX */
+#define PCIE_EXT_CFG_DATA                                   0x8000
+
+#define PCIE_RC_CFG_VENDOR_VENDOR_SPECIFIC_REG1_ENDIAN_MODE_BAR2_MASK 0xc
+#define PCIE_RC_CFG_PRIV1_ID_VAL3_CLASS_CODE_MASK           0xffffff
+
+#define PCIE_MISC_MISC_CTRL_SCB_ACCESS_EN_MASK              0x1000
+#define PCIE_MISC_MISC_CTRL_CFG_READ_UR_MODE_MASK           0x2000
+#define PCIE_MISC_MISC_CTRL_MAX_BURST_SIZE_MASK             0x300000
+#define PCIE_MISC_MISC_CTRL_SCB0_SIZE_MASK                  0xf8000000
+#define PCIE_MISC_MISC_CTRL_SCB1_SIZE_MASK                  0x7c00000
+#define PCIE_MISC_MISC_CTRL_SCB2_SIZE_MASK                  0x1f
+#define PCIE_MISC_RC_BAR2_CONFIG_LO_SIZE_MASK               0x1f
+
+#define PCIE_RGR1_SW_INIT_1_INIT_MASK                       0x2
+#define PCIE_RGR1_SW_INIT_1_PERST_MASK                      0x1
+
+#define PCIE_MISC_HARD_PCIE_HARD_DEBUG_SERDES_IDDQ_MASK     0x08000000
+
+#define PCIE_MISC_HARD_PCIE_HARD_DEBUG_CLKREQ_DEBUG_ENABLE_MASK 0x2
+
+#define PCIE_MISC_CPU_2_PCIE_MEM_WIN0_BASE_LIMIT_LIMIT_MASK 0xfff00000
+#define PCIE_MISC_CPU_2_PCIE_MEM_WIN0_BASE_LIMIT_BASE_MASK  0xfff0
+#define PCIE_MISC_CPU_2_PCIE_MEM_WIN0_BASE_HI_BASE_MASK     0xff
+#define PCIE_MISC_CPU_2_PCIE_MEM_WIN0_LIMIT_HI_LIMIT_MASK   0xff
+#define PCIE_MISC_CPU_2_PCIE_MEM_WIN0_MASK_BITS             0xc
+
+
+#define PCIE_MISC_REVISION_MAJMIN_MASK                      0xffff
+
+#define BURST_SIZE_128                                      0
+#define BURST_SIZE_256                                      1
+#define BURST_SIZE_512                                      2
+
 #endif /* BCM2711_H__ */
-- 
2.21.0.windows.1


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

* [edk2-platforms][PATCH v2 2/4] Silicon/Bcm27xx: Add segment library to handle nonstandard ECAM
  2019-12-13 17:07 [edk2-platforms][PATCH v2 0/4] Platform/RPi4: Add PCIe and xHCI support Pete Batard
  2019-12-13 17:07 ` [edk2-platforms][PATCH v2 1/4] Silicon/Bcm27xx: Add PCIe constants to Bcm2711.h Pete Batard
@ 2019-12-13 17:07 ` Pete Batard
  2019-12-13 17:07 ` [edk2-platforms][PATCH v2 3/4] Silicon/Bcm27xx: Add PCIe host bridge config library Pete Batard
                   ` (2 subsequent siblings)
  4 siblings, 0 replies; 8+ messages in thread
From: Pete Batard @ 2019-12-13 17:07 UTC (permalink / raw)
  To: devel; +Cc: ard.biesheuvel, leif.lindholm, philmd, lintonrjeremy

From: Jeremy Linton <lintonrjeremy@gmail.com>

This SoC uses a nonstantard ECAM with requires the provision of a custom
segment library. Basically, with the Bcm2711, the root port is the first
bytes of the register space (offset 0) and individual devices are selected
by computing their BDF index and writing that into the CFG_INDEX register
before ECAM data can then be read/written at CFG_DATA.

We also ensure that read/write accesses are serialized through the use of
a lock, as some of the library calls cannot run concurrently.

Signed-off-by: Pete Batard <pete@akeo.ie>
---
 Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciSegmentLib/PciSegmentLib.c   | 1445 ++++++++++++++++++++
 Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciSegmentLib/PciSegmentLib.inf |   35 +
 2 files changed, 1480 insertions(+)

diff --git a/Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciSegmentLib/PciSegmentLib.c b/Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciSegmentLib/PciSegmentLib.c
new file mode 100644
index 000000000000..11a3ef2645d7
--- /dev/null
+++ b/Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciSegmentLib/PciSegmentLib.c
@@ -0,0 +1,1445 @@
+/** @file
+ *
+ * PCI Segment Library for Bcm2711 (RPi4) SoC
+ *
+ * Copyright (c) 2019, Jeremy Linton
+ * Copyright (c) 2017, Linaro, Ltd. All rights reserved.<BR>
+ * Copyright (c) 2007 - 2012, Intel Corporation. All rights reserved.<BR>
+ *
+ * SPDX-License-Identifier: BSD-2-Clause-Patent
+ *
+ **/
+
+#include <Base.h>
+#include <Uefi.h>
+#include <Library/BaseLib.h>
+#include <Library/DebugLib.h>
+#include <Library/IoLib.h>
+#include <Library/PcdLib.h>
+#include <Library/PciSegmentLib.h>
+#include <Library/UefiLib.h>
+#include <IndustryStandard/Bcm2711.h>
+
+typedef enum {
+  PciCfgWidthUint8 = 0,
+  PciCfgWidthUint16,
+  PciCfgWidthUint32,
+  PciCfgWidthMax
+} PCI_CFG_WIDTH;
+
+/*
+ * This PCIe config space is unusual...
+ * The root port is the first bytes of the register space (offset 0)
+ * The individual devices are then selected by computing their BDF index
+ * and writing that into the CFG_INDEX register (offset 0x9000)
+ * the "ECAM" data is then read/writeable at CFG_DATA (offset 0x8000)
+ */
+
+#define EFI_PCI_ADDR_BUS(bus) ((bus>>20) & 0xFF)    /* Note PCI_SEGMENT_LIB_ADDRESS */
+#define EFI_PCI_ADDR_DEV(dev) ((dev>>15) & 0x1F)
+#define EFI_PCI_ADDR_FUN(fun) ((fun>>12) & 0x07)
+
+/**
+  Assert the validity of a PCI Segment address.
+  A valid PCI Segment address should not contain 1's in bits 28..31 and 48..63
+
+  @param  A The address to validate.
+  @param  M Additional bits to assert to be zero.
+
+**/
+#define ASSERT_INVALID_PCI_SEGMENT_ADDRESS(A,M) \
+  ASSERT (((A) & (0xffff0000f0000000ULL | (M))) == 0)
+
+/**
+  Given the nature of how we access PCI devices, we ensure that
+  read/write accesses are serialized through the use of a lock.
+**/
+EFI_LOCK mPciSegmentReadWriteLock = EFI_INITIALIZE_LOCK_VARIABLE (TPL_HIGH_LEVEL);
+
+/**
+  Internal worker function to obtain config space base address.
+
+  @param  Address The address that encodes the PCI Bus, Device, Function and
+                  Register.
+
+  @return The value read from the PCI configuration register.
+
+**/
+
+STATIC
+UINT64
+PciSegmentLibGetConfigBase (
+  IN  UINT64                      Address
+  )
+{
+  STATIC UINT64 LastAccess = 0;     /* Avoid repeat CFG_INDEX updates */
+  UINT64        Base;
+  UINT64        Offset;
+
+  Base = PCIE_REG_BASE;
+  Offset = Address & 0xFFF;         /* Pick off the 4k register offset */
+  Address &= 0xFFFFF000;            /* Clear the offset leave only the BDF */
+
+  /* The root port is at the base of the PCIe register space */
+  if (Address != 0) {
+    /* The current device is at CFG_DATA */
+    Base += PCIE_EXT_CFG_DATA;
+    if (LastAccess != Address) {
+      UINT32 dev = EFI_PCI_ADDR_DEV (Address);
+      /*
+       * Scan things out directly rather than translating the "bus" to a device, etc..
+       * only we need to limit each bus to a single device.
+       */
+      if (dev < 1) {
+          MmioWrite32 (PCIE_REG_BASE + PCIE_EXT_CFG_INDEX, Address);
+          LastAccess = Address;
+      } else {
+          LastAccess = 0;
+          return 0xFFFFFFFF;
+      }
+    }
+  }
+  return Base + Offset;
+}
+
+/**
+  Internal worker function to read a PCI configuration register.
+
+  @param  Address The address that encodes the PCI Bus, Device, Function and
+                  Register.
+  @param  Width   The width of data to read
+
+  @return The value read from the PCI configuration register.
+
+**/
+STATIC
+UINT32
+PciSegmentLibReadWorker (
+  IN  UINT64                      Address,
+  IN  PCI_CFG_WIDTH               Width
+  )
+{
+  UINT64    Base;
+  UINT64    Ret = 0;
+
+  EfiAcquireLock (&mPciSegmentReadWriteLock);
+  Base = PciSegmentLibGetConfigBase (Address);
+
+  if (Base == 0xFFFFFFFF) {
+    EfiReleaseLock (&mPciSegmentReadWriteLock);
+    return Base;
+  }
+
+  switch (Width) {
+  case PciCfgWidthUint8:
+    Ret = MmioRead8 (Base);
+    break;
+  case PciCfgWidthUint16:
+    Ret = MmioRead16 (Base);
+    break;
+  case PciCfgWidthUint32:
+    Ret = MmioRead32 (Base);
+    break;
+  default:
+    ASSERT (FALSE);
+  }
+  EfiReleaseLock (&mPciSegmentReadWriteLock);
+  return Ret;
+}
+
+/**
+  Internal worker function to writes a PCI configuration register.
+
+  @param  Address The address that encodes the PCI Bus, Device, Function and
+                  Register.
+  @param  Width   The width of data to write
+  @param  Data    The value to write.
+
+  @return The value written to the PCI configuration register.
+
+**/
+STATIC
+UINT32
+PciSegmentLibWriteWorker (
+  IN  UINT64                      Address,
+  IN  PCI_CFG_WIDTH               Width,
+  IN  UINT32                      Data
+  )
+{
+  UINT64    Base;
+
+  EfiAcquireLock (&mPciSegmentReadWriteLock);
+  Base = PciSegmentLibGetConfigBase (Address);
+
+  switch (Width) {
+  case PciCfgWidthUint8:
+    MmioWrite8 (Base, Data);
+    break;
+  case PciCfgWidthUint16:
+    MmioWrite16 (Base, Data);
+    break;
+  case PciCfgWidthUint32:
+    MmioWrite32 (Base, Data);
+    break;
+  default:
+    ASSERT (FALSE);
+  }
+  EfiReleaseLock (&mPciSegmentReadWriteLock);
+  return Data;
+}
+
+/**
+  Register a PCI device so PCI configuration registers may be accessed after
+  SetVirtualAddressMap().
+
+  If any reserved bits in Address are set, then ASSERT().
+
+  @param  Address The address that encodes the PCI Bus, Device, Function and
+                  Register.
+
+  @retval RETURN_SUCCESS           The PCI device was registered for runtime access.
+  @retval RETURN_UNSUPPORTED       An attempt was made to call this function
+                                   after ExitBootServices().
+  @retval RETURN_UNSUPPORTED       The resources required to access the PCI device
+                                   at runtime could not be mapped.
+  @retval RETURN_OUT_OF_RESOURCES  There are not enough resources available to
+                                   complete the registration.
+
+**/
+RETURN_STATUS
+EFIAPI
+PciSegmentRegisterForRuntimeAccess (
+  IN UINTN  Address
+  )
+{
+  ASSERT_INVALID_PCI_SEGMENT_ADDRESS (Address, 0);
+  return RETURN_UNSUPPORTED;
+}
+
+/**
+  Reads an 8-bit PCI configuration register.
+
+  Reads and returns the 8-bit PCI configuration register specified by Address.
+  This function must guarantee that all PCI read and write operations are serialized.
+
+  If any reserved bits in Address are set, then ASSERT().
+
+  @param  Address   The address that encodes the PCI Segment, Bus, Device, Function,
+                    and Register.
+
+  @return The 8-bit PCI configuration register specified by Address.
+
+**/
+UINT8
+EFIAPI
+PciSegmentRead8 (
+  IN UINT64                    Address
+  )
+{
+  ASSERT_INVALID_PCI_SEGMENT_ADDRESS (Address, 0);
+
+  return (UINT8) PciSegmentLibReadWorker (Address, PciCfgWidthUint8);
+}
+
+/**
+  Writes an 8-bit PCI configuration register.
+
+  Writes the 8-bit PCI configuration register specified by Address with the value specified by Value.
+  Value is returned.  This function must guarantee that all PCI read and write operations are serialized.
+
+  If any reserved bits in Address are set, then ASSERT().
+
+  @param  Address     The address that encodes the PCI Segment, Bus, Device, Function, and Register.
+  @param  Value       The value to write.
+
+  @return The value written to the PCI configuration register.
+
+**/
+UINT8
+EFIAPI
+PciSegmentWrite8 (
+  IN UINT64                    Address,
+  IN UINT8                     Value
+  )
+{
+  ASSERT_INVALID_PCI_SEGMENT_ADDRESS (Address, 0);
+
+  return (UINT8) PciSegmentLibWriteWorker (Address, PciCfgWidthUint8, Value);
+}
+
+/**
+  Performs a bitwise OR of an 8-bit PCI configuration register with an 8-bit value.
+
+  Reads the 8-bit PCI configuration register specified by Address,
+  performs a bitwise OR between the read result and the value specified by OrData,
+  and writes the result to the 8-bit PCI configuration register specified by Address.
+  The value written to the PCI configuration register is returned.
+  This function must guarantee that all PCI read and write operations are serialized.
+
+  If any reserved bits in Address are set, then ASSERT().
+
+  @param  Address   The address that encodes the PCI Segment, Bus, Device, Function, and Register.
+  @param  OrData    The value to OR with the PCI configuration register.
+
+  @return The value written to the PCI configuration register.
+
+**/
+UINT8
+EFIAPI
+PciSegmentOr8 (
+  IN UINT64                    Address,
+  IN UINT8                     OrData
+  )
+{
+  return PciSegmentWrite8 (Address, (UINT8) (PciSegmentRead8 (Address) | OrData));
+}
+
+/**
+  Performs a bitwise AND of an 8-bit PCI configuration register with an 8-bit value.
+
+  Reads the 8-bit PCI configuration register specified by Address,
+  performs a bitwise AND between the read result and the value specified by AndData,
+  and writes the result to the 8-bit PCI configuration register specified by Address.
+  The value written to the PCI configuration register is returned.
+  This function must guarantee that all PCI read and write operations are serialized.
+  If any reserved bits in Address are set, then ASSERT().
+
+  @param  Address   The address that encodes the PCI Segment, Bus, Device, Function, and Register.
+  @param  AndData   The value to AND with the PCI configuration register.
+
+  @return The value written to the PCI configuration register.
+
+**/
+UINT8
+EFIAPI
+PciSegmentAnd8 (
+  IN UINT64                    Address,
+  IN UINT8                     AndData
+  )
+{
+  return PciSegmentWrite8 (Address, (UINT8) (PciSegmentRead8 (Address) & AndData));
+}
+
+/**
+  Performs a bitwise AND of an 8-bit PCI configuration register with an 8-bit value,
+  followed a  bitwise OR with another 8-bit value.
+
+  Reads the 8-bit PCI configuration register specified by Address,
+  performs a bitwise AND between the read result and the value specified by AndData,
+  performs a bitwise OR between the result of the AND operation and the value specified by OrData,
+  and writes the result to the 8-bit PCI configuration register specified by Address.
+  The value written to the PCI configuration register is returned.
+  This function must guarantee that all PCI read and write operations are serialized.
+
+  If any reserved bits in Address are set, then ASSERT().
+
+  @param  Address   The address that encodes the PCI Segment, Bus, Device, Function, and Register.
+  @param  AndData    The value to AND with the PCI configuration register.
+  @param  OrData    The value to OR with the PCI configuration register.
+
+  @return The value written to the PCI configuration register.
+
+**/
+UINT8
+EFIAPI
+PciSegmentAndThenOr8 (
+  IN UINT64                    Address,
+  IN UINT8                     AndData,
+  IN UINT8                     OrData
+  )
+{
+  return PciSegmentWrite8 (Address, (UINT8) ((PciSegmentRead8 (Address) & AndData) | OrData));
+}
+
+/**
+  Reads a bit field of a PCI configuration register.
+
+  Reads the bit field in an 8-bit PCI configuration register. The bit field is
+  specified by the StartBit and the EndBit. The value of the bit field is
+  returned.
+
+  If any reserved bits in Address are set, then ASSERT().
+  If StartBit is greater than 7, then ASSERT().
+  If EndBit is greater than 7, then ASSERT().
+  If EndBit is less than StartBit, then ASSERT().
+
+  @param  Address   The PCI configuration register to read.
+  @param  StartBit  The ordinal of the least significant bit in the bit field.
+                    Range 0..7.
+  @param  EndBit    The ordinal of the most significant bit in the bit field.
+                    Range 0..7.
+
+  @return The value of the bit field read from the PCI configuration register.
+
+**/
+UINT8
+EFIAPI
+PciSegmentBitFieldRead8 (
+  IN UINT64                    Address,
+  IN UINTN                     StartBit,
+  IN UINTN                     EndBit
+  )
+{
+  return BitFieldRead8 (PciSegmentRead8 (Address), StartBit, EndBit);
+}
+
+/**
+  Writes a bit field to a PCI configuration register.
+
+  Writes Value to the bit field of the PCI configuration register. The bit
+  field is specified by the StartBit and the EndBit. All other bits in the
+  destination PCI configuration register are preserved. The new value of the
+  8-bit register is returned.
+
+  If any reserved bits in Address are set, then ASSERT().
+  If StartBit is greater than 7, then ASSERT().
+  If EndBit is greater than 7, then ASSERT().
+  If EndBit is less than StartBit, then ASSERT().
+  If Value is larger than the bitmask value range specified by StartBit and EndBit, then ASSERT().
+
+  @param  Address   The PCI configuration register to write.
+  @param  StartBit  The ordinal of the least significant bit in the bit field.
+                    Range 0..7.
+  @param  EndBit    The ordinal of the most significant bit in the bit field.
+                    Range 0..7.
+  @param  Value     The new value of the bit field.
+
+  @return The value written back to the PCI configuration register.
+
+**/
+UINT8
+EFIAPI
+PciSegmentBitFieldWrite8 (
+  IN UINT64                    Address,
+  IN UINTN                     StartBit,
+  IN UINTN                     EndBit,
+  IN UINT8                     Value
+  )
+{
+  return PciSegmentWrite8 (
+           Address,
+           BitFieldWrite8 (PciSegmentRead8 (Address), StartBit, EndBit, Value)
+           );
+}
+
+/**
+  Reads a bit field in an 8-bit PCI configuration, performs a bitwise OR, and
+  writes the result back to the bit field in the 8-bit port.
+
+  Reads the 8-bit PCI configuration register specified by Address, performs a
+  bitwise OR between the read result and the value specified by
+  OrData, and writes the result to the 8-bit PCI configuration register
+  specified by Address. The value written to the PCI configuration register is
+  returned. This function must guarantee that all PCI read and write operations
+  are serialized. Extra left bits in OrData are stripped.
+
+  If any reserved bits in Address are set, then ASSERT().
+  If StartBit is greater than 7, then ASSERT().
+  If EndBit is greater than 7, then ASSERT().
+  If EndBit is less than StartBit, then ASSERT().
+  If OrData is larger than the bitmask value range specified by StartBit and EndBit, then ASSERT().
+
+  @param  Address   The PCI configuration register to write.
+  @param  StartBit  The ordinal of the least significant bit in the bit field.
+                    Range 0..7.
+  @param  EndBit    The ordinal of the most significant bit in the bit field.
+                    Range 0..7.
+  @param  OrData    The value to OR with the PCI configuration register.
+
+  @return The value written back to the PCI configuration register.
+
+**/
+UINT8
+EFIAPI
+PciSegmentBitFieldOr8 (
+  IN UINT64                    Address,
+  IN UINTN                     StartBit,
+  IN UINTN                     EndBit,
+  IN UINT8                     OrData
+  )
+{
+  return PciSegmentWrite8 (
+           Address,
+           BitFieldOr8 (PciSegmentRead8 (Address), StartBit, EndBit, OrData)
+           );
+}
+
+/**
+  Reads a bit field in an 8-bit PCI configuration register, performs a bitwise
+  AND, and writes the result back to the bit field in the 8-bit register.
+
+  Reads the 8-bit PCI configuration register specified by Address, performs a
+  bitwise AND between the read result and the value specified by AndData, and
+  writes the result to the 8-bit PCI configuration register specified by
+  Address. The value written to the PCI configuration register is returned.
+  This function must guarantee that all PCI read and write operations are
+  serialized. Extra left bits in AndData are stripped.
+
+  If any reserved bits in Address are set, then ASSERT().
+  If StartBit is greater than 7, then ASSERT().
+  If EndBit is greater than 7, then ASSERT().
+  If EndBit is less than StartBit, then ASSERT().
+  If AndData is larger than the bitmask value range specified by StartBit and EndBit, then ASSERT().
+
+  @param  Address   The PCI configuration register to write.
+  @param  StartBit  The ordinal of the least significant bit in the bit field.
+                    Range 0..7.
+  @param  EndBit    The ordinal of the most significant bit in the bit field.
+                    Range 0..7.
+  @param  AndData   The value to AND with the PCI configuration register.
+
+  @return The value written back to the PCI configuration register.
+
+**/
+UINT8
+EFIAPI
+PciSegmentBitFieldAnd8 (
+  IN UINT64                    Address,
+  IN UINTN                     StartBit,
+  IN UINTN                     EndBit,
+  IN UINT8                     AndData
+  )
+{
+  return PciSegmentWrite8 (
+           Address,
+           BitFieldAnd8 (PciSegmentRead8 (Address), StartBit, EndBit, AndData)
+           );
+}
+
+/**
+  Reads a bit field in an 8-bit port, performs a bitwise AND followed by a
+  bitwise OR, and writes the result back to the bit field in the
+  8-bit port.
+
+  Reads the 8-bit PCI configuration register specified by Address, performs a
+  bitwise AND followed by a bitwise OR between the read result and
+  the value specified by AndData, and writes the result to the 8-bit PCI
+  configuration register specified by Address. The value written to the PCI
+  configuration register is returned. This function must guarantee that all PCI
+  read and write operations are serialized. Extra left bits in both AndData and
+  OrData are stripped.
+
+  If any reserved bits in Address are set, then ASSERT().
+  If StartBit is greater than 7, then ASSERT().
+  If EndBit is greater than 7, then ASSERT().
+  If EndBit is less than StartBit, then ASSERT().
+  If AndData is larger than the bitmask value range specified by StartBit and EndBit, then ASSERT().
+  If OrData is larger than the bitmask value range specified by StartBit and EndBit, then ASSERT().
+
+  @param  Address   The PCI configuration register to write.
+  @param  StartBit  The ordinal of the least significant bit in the bit field.
+                    Range 0..7.
+  @param  EndBit    The ordinal of the most significant bit in the bit field.
+                    Range 0..7.
+  @param  AndData   The value to AND with the PCI configuration register.
+  @param  OrData    The value to OR with the result of the AND operation.
+
+  @return The value written back to the PCI configuration register.
+
+**/
+UINT8
+EFIAPI
+PciSegmentBitFieldAndThenOr8 (
+  IN UINT64                    Address,
+  IN UINTN                     StartBit,
+  IN UINTN                     EndBit,
+  IN UINT8                     AndData,
+  IN UINT8                     OrData
+  )
+{
+  return PciSegmentWrite8 (
+           Address,
+           BitFieldAndThenOr8 (PciSegmentRead8 (Address), StartBit, EndBit, AndData, OrData)
+           );
+}
+
+/**
+  Reads a 16-bit PCI configuration register.
+
+  Reads and returns the 16-bit PCI configuration register specified by Address.
+  This function must guarantee that all PCI read and write operations are serialized.
+
+  If any reserved bits in Address are set, then ASSERT().
+  If Address is not aligned on a 16-bit boundary, then ASSERT().
+
+  @param  Address   The address that encodes the PCI Segment, Bus, Device, Function, and Register.
+
+  @return The 16-bit PCI configuration register specified by Address.
+
+**/
+UINT16
+EFIAPI
+PciSegmentRead16 (
+  IN UINT64                    Address
+  )
+{
+  ASSERT_INVALID_PCI_SEGMENT_ADDRESS (Address, 1);
+
+  return (UINT16) PciSegmentLibReadWorker (Address, PciCfgWidthUint16);
+}
+
+/**
+  Writes a 16-bit PCI configuration register.
+
+  Writes the 16-bit PCI configuration register specified by Address with the value specified by Value.
+  Value is returned.  This function must guarantee that all PCI read and write operations are serialized.
+
+  If any reserved bits in Address are set, then ASSERT().
+  If Address is not aligned on a 16-bit boundary, then ASSERT().
+
+  @param  Address     The address that encodes the PCI Segment, Bus, Device, Function, and Register.
+  @param  Value       The value to write.
+
+  @return The parameter of Value.
+
+**/
+UINT16
+EFIAPI
+PciSegmentWrite16 (
+  IN UINT64                    Address,
+  IN UINT16                    Value
+  )
+{
+  ASSERT_INVALID_PCI_SEGMENT_ADDRESS (Address, 1);
+
+  return (UINT16) PciSegmentLibWriteWorker (Address, PciCfgWidthUint16, Value);
+}
+
+/**
+  Performs a bitwise OR of a 16-bit PCI configuration register with
+  a 16-bit value.
+
+  Reads the 16-bit PCI configuration register specified by Address, performs a
+  bitwise OR between the read result and the value specified by
+  OrData, and writes the result to the 16-bit PCI configuration register
+  specified by Address. The value written to the PCI configuration register is
+  returned. This function must guarantee that all PCI read and write operations
+  are serialized.
+
+  If any reserved bits in Address are set, then ASSERT().
+  If Address is not aligned on a 16-bit boundary, then ASSERT().
+
+  @param  Address The address that encodes the PCI Segment, Bus, Device, Function and
+                  Register.
+  @param  OrData  The value to OR with the PCI configuration register.
+
+  @return The value written back to the PCI configuration register.
+
+**/
+UINT16
+EFIAPI
+PciSegmentOr16 (
+  IN UINT64                    Address,
+  IN UINT16                    OrData
+  )
+{
+  return PciSegmentWrite16 (Address, (UINT16) (PciSegmentRead16 (Address) | OrData));
+}
+
+/**
+  Performs a bitwise AND of a 16-bit PCI configuration register with a 16-bit value.
+
+  Reads the 16-bit PCI configuration register specified by Address,
+  performs a bitwise AND between the read result and the value specified by AndData,
+  and writes the result to the 16-bit PCI configuration register specified by Address.
+  The value written to the PCI configuration register is returned.
+  This function must guarantee that all PCI read and write operations are serialized.
+
+  If any reserved bits in Address are set, then ASSERT().
+  If Address is not aligned on a 16-bit boundary, then ASSERT().
+
+  @param  Address   The address that encodes the PCI Segment, Bus, Device, Function, and Register.
+  @param  AndData   The value to AND with the PCI configuration register.
+
+  @return The value written to the PCI configuration register.
+
+**/
+UINT16
+EFIAPI
+PciSegmentAnd16 (
+  IN UINT64                    Address,
+  IN UINT16                    AndData
+  )
+{
+  return PciSegmentWrite16 (Address, (UINT16) (PciSegmentRead16 (Address) & AndData));
+}
+
+/**
+  Performs a bitwise AND of a 16-bit PCI configuration register with a 16-bit value,
+  followed a  bitwise OR with another 16-bit value.
+
+  Reads the 16-bit PCI configuration register specified by Address,
+  performs a bitwise AND between the read result and the value specified by AndData,
+  performs a bitwise OR between the result of the AND operation and the value specified by OrData,
+  and writes the result to the 16-bit PCI configuration register specified by Address.
+  The value written to the PCI configuration register is returned.
+  This function must guarantee that all PCI read and write operations are serialized.
+
+  If any reserved bits in Address are set, then ASSERT().
+  If Address is not aligned on a 16-bit boundary, then ASSERT().
+
+  @param  Address   The address that encodes the PCI Segment, Bus, Device, Function, and Register.
+  @param  AndData   The value to AND with the PCI configuration register.
+  @param  OrData    The value to OR with the PCI configuration register.
+
+  @return The value written to the PCI configuration register.
+
+**/
+UINT16
+EFIAPI
+PciSegmentAndThenOr16 (
+  IN UINT64                    Address,
+  IN UINT16                    AndData,
+  IN UINT16                    OrData
+  )
+{
+  return PciSegmentWrite16 (Address, (UINT16) ((PciSegmentRead16 (Address) & AndData) | OrData));
+}
+
+/**
+  Reads a bit field of a PCI configuration register.
+
+  Reads the bit field in a 16-bit PCI configuration register. The bit field is
+  specified by the StartBit and the EndBit. The value of the bit field is
+  returned.
+
+  If any reserved bits in Address are set, then ASSERT().
+  If Address is not aligned on a 16-bit boundary, then ASSERT().
+  If StartBit is greater than 15, then ASSERT().
+  If EndBit is greater than 15, then ASSERT().
+  If EndBit is less than StartBit, then ASSERT().
+
+  @param  Address   The PCI configuration register to read.
+  @param  StartBit  The ordinal of the least significant bit in the bit field.
+                    Range 0..15.
+  @param  EndBit    The ordinal of the most significant bit in the bit field.
+                    Range 0..15.
+
+  @return The value of the bit field read from the PCI configuration register.
+
+**/
+UINT16
+EFIAPI
+PciSegmentBitFieldRead16 (
+  IN UINT64                    Address,
+  IN UINTN                     StartBit,
+  IN UINTN                     EndBit
+  )
+{
+  return BitFieldRead16 (PciSegmentRead16 (Address), StartBit, EndBit);
+}
+
+/**
+  Writes a bit field to a PCI configuration register.
+
+  Writes Value to the bit field of the PCI configuration register. The bit
+  field is specified by the StartBit and the EndBit. All other bits in the
+  destination PCI configuration register are preserved. The new value of the
+  16-bit register is returned.
+
+  If any reserved bits in Address are set, then ASSERT().
+  If Address is not aligned on a 16-bit boundary, then ASSERT().
+  If StartBit is greater than 15, then ASSERT().
+  If EndBit is greater than 15, then ASSERT().
+  If EndBit is less than StartBit, then ASSERT().
+  If Value is larger than the bitmask value range specified by StartBit and EndBit, then ASSERT().
+
+  @param  Address   The PCI configuration register to write.
+  @param  StartBit  The ordinal of the least significant bit in the bit field.
+                    Range 0..15.
+  @param  EndBit    The ordinal of the most significant bit in the bit field.
+                    Range 0..15.
+  @param  Value     The new value of the bit field.
+
+  @return The value written back to the PCI configuration register.
+
+**/
+UINT16
+EFIAPI
+PciSegmentBitFieldWrite16 (
+  IN UINT64                    Address,
+  IN UINTN                     StartBit,
+  IN UINTN                     EndBit,
+  IN UINT16                    Value
+  )
+{
+  return PciSegmentWrite16 (
+           Address,
+           BitFieldWrite16 (PciSegmentRead16 (Address), StartBit, EndBit, Value)
+           );
+}
+
+/**
+  Reads the 16-bit PCI configuration register specified by Address,
+  performs a bitwise OR between the read result and the value specified by OrData,
+  and writes the result to the 16-bit PCI configuration register specified by Address.
+
+  If any reserved bits in Address are set, then ASSERT().
+  If Address is not aligned on a 16-bit boundary, then ASSERT().
+  If StartBit is greater than 15, then ASSERT().
+  If EndBit is greater than 15, then ASSERT().
+  If EndBit is less than StartBit, then ASSERT().
+  If OrData is larger than the bitmask value range specified by StartBit and EndBit, then ASSERT().
+
+  @param  Address   The PCI configuration register to write.
+  @param  StartBit  The ordinal of the least significant bit in the bit field.
+                    Range 0..15.
+  @param  EndBit    The ordinal of the most significant bit in the bit field.
+                    Range 0..15.
+  @param  OrData    The value to OR with the PCI configuration register.
+
+  @return The value written back to the PCI configuration register.
+
+**/
+UINT16
+EFIAPI
+PciSegmentBitFieldOr16 (
+  IN UINT64                    Address,
+  IN UINTN                     StartBit,
+  IN UINTN                     EndBit,
+  IN UINT16                    OrData
+  )
+{
+  return PciSegmentWrite16 (
+           Address,
+           BitFieldOr16 (PciSegmentRead16 (Address), StartBit, EndBit, OrData)
+           );
+}
+
+/**
+  Reads a bit field in a 16-bit PCI configuration, performs a bitwise OR,
+  and writes the result back to the bit field in the 16-bit port.
+
+  Reads the 16-bit PCI configuration register specified by Address,
+  performs a bitwise OR between the read result and the value specified by OrData,
+  and writes the result to the 16-bit PCI configuration register specified by Address.
+  The value written to the PCI configuration register is returned.
+  This function must guarantee that all PCI read and write operations are serialized.
+  Extra left bits in OrData are stripped.
+
+  If any reserved bits in Address are set, then ASSERT().
+  If Address is not aligned on a 16-bit boundary, then ASSERT().
+  If StartBit is greater than 7, then ASSERT().
+  If EndBit is greater than 7, then ASSERT().
+  If EndBit is less than StartBit, then ASSERT().
+  If AndData is larger than the bitmask value range specified by StartBit and EndBit, then ASSERT().
+
+  @param  Address   The address that encodes the PCI Segment, Bus, Device, Function, and Register.
+  @param  StartBit  The ordinal of the least significant bit in the bit field.
+                    The ordinal of the least significant bit in a byte is bit 0.
+  @param  EndBit    The ordinal of the most significant bit in the bit field.
+                    The ordinal of the most significant bit in a byte is bit 7.
+  @param  AndData   The value to AND with the read value from the PCI configuration register.
+
+  @return The value written to the PCI configuration register.
+
+**/
+UINT16
+EFIAPI
+PciSegmentBitFieldAnd16 (
+  IN UINT64                    Address,
+  IN UINTN                     StartBit,
+  IN UINTN                     EndBit,
+  IN UINT16                    AndData
+  )
+{
+  return PciSegmentWrite16 (
+           Address,
+           BitFieldAnd16 (PciSegmentRead16 (Address), StartBit, EndBit, AndData)
+           );
+}
+
+/**
+  Reads a bit field in a 16-bit port, performs a bitwise AND followed by a
+  bitwise OR, and writes the result back to the bit field in the
+  16-bit port.
+
+  Reads the 16-bit PCI configuration register specified by Address, performs a
+  bitwise AND followed by a bitwise OR between the read result and
+  the value specified by AndData, and writes the result to the 16-bit PCI
+  configuration register specified by Address. The value written to the PCI
+  configuration register is returned. This function must guarantee that all PCI
+  read and write operations are serialized. Extra left bits in both AndData and
+  OrData are stripped.
+
+  If any reserved bits in Address are set, then ASSERT().
+  If StartBit is greater than 15, then ASSERT().
+  If EndBit is greater than 15, then ASSERT().
+  If EndBit is less than StartBit, then ASSERT().
+  If AndData is larger than the bitmask value range specified by StartBit and EndBit, then ASSERT().
+  If OrData is larger than the bitmask value range specified by StartBit and EndBit, then ASSERT().
+
+  @param  Address   The PCI configuration register to write.
+  @param  StartBit  The ordinal of the least significant bit in the bit field.
+                    Range 0..15.
+  @param  EndBit    The ordinal of the most significant bit in the bit field.
+                    Range 0..15.
+  @param  AndData   The value to AND with the PCI configuration register.
+  @param  OrData    The value to OR with the result of the AND operation.
+
+  @return The value written back to the PCI configuration register.
+
+**/
+UINT16
+EFIAPI
+PciSegmentBitFieldAndThenOr16 (
+  IN UINT64                    Address,
+  IN UINTN                     StartBit,
+  IN UINTN                     EndBit,
+  IN UINT16                    AndData,
+  IN UINT16                    OrData
+  )
+{
+  return PciSegmentWrite16 (
+           Address,
+           BitFieldAndThenOr16 (PciSegmentRead16 (Address), StartBit, EndBit, AndData, OrData)
+           );
+}
+
+/**
+  Reads a 32-bit PCI configuration register.
+
+  Reads and returns the 32-bit PCI configuration register specified by Address.
+  This function must guarantee that all PCI read and write operations are serialized.
+
+  If any reserved bits in Address are set, then ASSERT().
+  If Address is not aligned on a 32-bit boundary, then ASSERT().
+
+  @param  Address   The address that encodes the PCI Segment, Bus, Device, Function,
+                    and Register.
+
+  @return The 32-bit PCI configuration register specified by Address.
+
+**/
+UINT32
+EFIAPI
+PciSegmentRead32 (
+  IN UINT64                    Address
+  )
+{
+  ASSERT_INVALID_PCI_SEGMENT_ADDRESS (Address, 3);
+
+  return PciSegmentLibReadWorker (Address, PciCfgWidthUint32);
+}
+
+/**
+  Writes a 32-bit PCI configuration register.
+
+  Writes the 32-bit PCI configuration register specified by Address with the value specified by Value.
+  Value is returned.  This function must guarantee that all PCI read and write operations are serialized.
+
+  If any reserved bits in Address are set, then ASSERT().
+  If Address is not aligned on a 32-bit boundary, then ASSERT().
+
+  @param  Address     The address that encodes the PCI Segment, Bus, Device,
+                      Function, and Register.
+  @param  Value       The value to write.
+
+  @return The parameter of Value.
+
+**/
+UINT32
+EFIAPI
+PciSegmentWrite32 (
+  IN UINT64                    Address,
+  IN UINT32                    Value
+  )
+{
+  ASSERT_INVALID_PCI_SEGMENT_ADDRESS (Address, 3);
+
+  return PciSegmentLibWriteWorker (Address, PciCfgWidthUint32, Value);
+}
+
+/**
+  Performs a bitwise OR of a 32-bit PCI configuration register with a 32-bit value.
+
+  Reads the 32-bit PCI configuration register specified by Address,
+  performs a bitwise OR between the read result and the value specified by OrData,
+  and writes the result to the 32-bit PCI configuration register specified by Address.
+  The value written to the PCI configuration register is returned.
+  This function must guarantee that all PCI read and write operations are serialized.
+
+  If any reserved bits in Address are set, then ASSERT().
+  If Address is not aligned on a 32-bit boundary, then ASSERT().
+
+  @param  Address   The address that encodes the PCI Segment, Bus, Device, Function, and Register.
+  @param  OrData    The value to OR with the PCI configuration register.
+
+  @return The value written to the PCI configuration register.
+
+**/
+UINT32
+EFIAPI
+PciSegmentOr32 (
+  IN UINT64                    Address,
+  IN UINT32                    OrData
+  )
+{
+  return PciSegmentWrite32 (Address, PciSegmentRead32 (Address) | OrData);
+}
+
+/**
+  Performs a bitwise AND of a 32-bit PCI configuration register with a 32-bit value.
+
+  Reads the 32-bit PCI configuration register specified by Address,
+  performs a bitwise AND between the read result and the value specified by AndData,
+  and writes the result to the 32-bit PCI configuration register specified by Address.
+  The value written to the PCI configuration register is returned.
+  This function must guarantee that all PCI read and write operations are serialized.
+
+  If any reserved bits in Address are set, then ASSERT().
+  If Address is not aligned on a 32-bit boundary, then ASSERT().
+
+  @param  Address   The address that encodes the PCI Segment, Bus, Device, Function,
+                    and Register.
+  @param  AndData   The value to AND with the PCI configuration register.
+
+  @return The value written to the PCI configuration register.
+
+**/
+UINT32
+EFIAPI
+PciSegmentAnd32 (
+  IN UINT64                    Address,
+  IN UINT32                    AndData
+  )
+{
+  return PciSegmentWrite32 (Address, PciSegmentRead32 (Address) & AndData);
+}
+
+/**
+  Performs a bitwise AND of a 32-bit PCI configuration register with a 32-bit value,
+  followed a  bitwise OR with another 32-bit value.
+
+  Reads the 32-bit PCI configuration register specified by Address,
+  performs a bitwise AND between the read result and the value specified by AndData,
+  performs a bitwise OR between the result of the AND operation and the value specified by OrData,
+  and writes the result to the 32-bit PCI configuration register specified by Address.
+  The value written to the PCI configuration register is returned.
+  This function must guarantee that all PCI read and write operations are serialized.
+
+  If any reserved bits in Address are set, then ASSERT().
+  If Address is not aligned on a 32-bit boundary, then ASSERT().
+
+  @param  Address   The address that encodes the PCI Segment, Bus, Device, Function,
+                    and Register.
+  @param  AndData   The value to AND with the PCI configuration register.
+  @param  OrData    The value to OR with the PCI configuration register.
+
+  @return The value written to the PCI configuration register.
+
+**/
+UINT32
+EFIAPI
+PciSegmentAndThenOr32 (
+  IN UINT64                    Address,
+  IN UINT32                    AndData,
+  IN UINT32                    OrData
+  )
+{
+  return PciSegmentWrite32 (Address, (PciSegmentRead32 (Address) & AndData) | OrData);
+}
+
+/**
+  Reads a bit field of a PCI configuration register.
+
+  Reads the bit field in a 32-bit PCI configuration register. The bit field is
+  specified by the StartBit and the EndBit. The value of the bit field is
+  returned.
+
+  If any reserved bits in Address are set, then ASSERT().
+  If Address is not aligned on a 32-bit boundary, then ASSERT().
+  If StartBit is greater than 31, then ASSERT().
+  If EndBit is greater than 31, then ASSERT().
+  If EndBit is less than StartBit, then ASSERT().
+
+  @param  Address   The PCI configuration register to read.
+  @param  StartBit  The ordinal of the least significant bit in the bit field.
+                    Range 0..31.
+  @param  EndBit    The ordinal of the most significant bit in the bit field.
+                    Range 0..31.
+
+  @return The value of the bit field read from the PCI configuration register.
+
+**/
+UINT32
+EFIAPI
+PciSegmentBitFieldRead32 (
+  IN UINT64                    Address,
+  IN UINTN                     StartBit,
+  IN UINTN                     EndBit
+  )
+{
+  return BitFieldRead32 (PciSegmentRead32 (Address), StartBit, EndBit);
+}
+
+/**
+  Writes a bit field to a PCI configuration register.
+
+  Writes Value to the bit field of the PCI configuration register. The bit
+  field is specified by the StartBit and the EndBit. All other bits in the
+  destination PCI configuration register are preserved. The new value of the
+  32-bit register is returned.
+
+  If any reserved bits in Address are set, then ASSERT().
+  If Address is not aligned on a 32-bit boundary, then ASSERT().
+  If StartBit is greater than 31, then ASSERT().
+  If EndBit is greater than 31, then ASSERT().
+  If EndBit is less than StartBit, then ASSERT().
+  If Value is larger than the bitmask value range specified by StartBit and EndBit, then ASSERT().
+
+  @param  Address   The PCI configuration register to write.
+  @param  StartBit  The ordinal of the least significant bit in the bit field.
+                    Range 0..31.
+  @param  EndBit    The ordinal of the most significant bit in the bit field.
+                    Range 0..31.
+  @param  Value     The new value of the bit field.
+
+  @return The value written back to the PCI configuration register.
+
+**/
+UINT32
+EFIAPI
+PciSegmentBitFieldWrite32 (
+  IN UINT64                    Address,
+  IN UINTN                     StartBit,
+  IN UINTN                     EndBit,
+  IN UINT32                    Value
+  )
+{
+  return PciSegmentWrite32 (
+           Address,
+           BitFieldWrite32 (PciSegmentRead32 (Address), StartBit, EndBit, Value)
+           );
+}
+
+/**
+  Reads a bit field in a 32-bit PCI configuration, performs a bitwise OR, and
+  writes the result back to the bit field in the 32-bit port.
+
+  Reads the 32-bit PCI configuration register specified by Address, performs a
+  bitwise OR between the read result and the value specified by
+  OrData, and writes the result to the 32-bit PCI configuration register
+  specified by Address. The value written to the PCI configuration register is
+  returned. This function must guarantee that all PCI read and write operations
+  are serialized. Extra left bits in OrData are stripped.
+
+  If any reserved bits in Address are set, then ASSERT().
+  If StartBit is greater than 31, then ASSERT().
+  If EndBit is greater than 31, then ASSERT().
+  If EndBit is less than StartBit, then ASSERT().
+  If OrData is larger than the bitmask value range specified by StartBit and EndBit, then ASSERT().
+
+  @param  Address   The PCI configuration register to write.
+  @param  StartBit  The ordinal of the least significant bit in the bit field.
+                    Range 0..31.
+  @param  EndBit    The ordinal of the most significant bit in the bit field.
+                    Range 0..31.
+  @param  OrData    The value to OR with the PCI configuration register.
+
+  @return The value written back to the PCI configuration register.
+
+**/
+UINT32
+EFIAPI
+PciSegmentBitFieldOr32 (
+  IN UINT64                    Address,
+  IN UINTN                     StartBit,
+  IN UINTN                     EndBit,
+  IN UINT32                    OrData
+  )
+{
+  return PciSegmentWrite32 (
+           Address,
+           BitFieldOr32 (PciSegmentRead32 (Address), StartBit, EndBit, OrData)
+           );
+}
+
+/**
+  Reads a bit field in a 32-bit PCI configuration register, performs a bitwise
+  AND, and writes the result back to the bit field in the 32-bit register.
+
+
+  Reads the 32-bit PCI configuration register specified by Address, performs a bitwise
+  AND between the read result and the value specified by AndData, and writes the result
+  to the 32-bit PCI configuration register specified by Address. The value written to
+  the PCI configuration register is returned.  This function must guarantee that all PCI
+  read and write operations are serialized.  Extra left bits in AndData are stripped.
+  If any reserved bits in Address are set, then ASSERT().
+  If Address is not aligned on a 32-bit boundary, then ASSERT().
+  If StartBit is greater than 31, then ASSERT().
+  If EndBit is greater than 31, then ASSERT().
+  If EndBit is less than StartBit, then ASSERT().
+  If AndData is larger than the bitmask value range specified by StartBit and EndBit, then ASSERT().
+
+  @param  Address   The PCI configuration register to write.
+  @param  StartBit  The ordinal of the least significant bit in the bit field.
+                    Range 0..31.
+  @param  EndBit    The ordinal of the most significant bit in the bit field.
+                    Range 0..31.
+  @param  AndData   The value to AND with the PCI configuration register.
+
+  @return The value written back to the PCI configuration register.
+
+**/
+UINT32
+EFIAPI
+PciSegmentBitFieldAnd32 (
+  IN UINT64                    Address,
+  IN UINTN                     StartBit,
+  IN UINTN                     EndBit,
+  IN UINT32                    AndData
+  )
+{
+  return PciSegmentWrite32 (
+           Address,
+           BitFieldAnd32 (PciSegmentRead32 (Address), StartBit, EndBit, AndData)
+           );
+}
+
+/**
+  Reads a bit field in a 32-bit port, performs a bitwise AND followed by a
+  bitwise OR, and writes the result back to the bit field in the
+  32-bit port.
+
+  Reads the 32-bit PCI configuration register specified by Address, performs a
+  bitwise AND followed by a bitwise OR between the read result and
+  the value specified by AndData, and writes the result to the 32-bit PCI
+  configuration register specified by Address. The value written to the PCI
+  configuration register is returned. This function must guarantee that all PCI
+  read and write operations are serialized. Extra left bits in both AndData and
+  OrData are stripped.
+
+  If any reserved bits in Address are set, then ASSERT().
+  If StartBit is greater than 31, then ASSERT().
+  If EndBit is greater than 31, then ASSERT().
+  If EndBit is less than StartBit, then ASSERT().
+  If AndData is larger than the bitmask value range specified by StartBit and EndBit, then ASSERT().
+  If OrData is larger than the bitmask value range specified by StartBit and EndBit, then ASSERT().
+
+  @param  Address   The PCI configuration register to write.
+  @param  StartBit  The ordinal of the least significant bit in the bit field.
+                    Range 0..31.
+  @param  EndBit    The ordinal of the most significant bit in the bit field.
+                    Range 0..31.
+  @param  AndData   The value to AND with the PCI configuration register.
+  @param  OrData    The value to OR with the result of the AND operation.
+
+  @return The value written back to the PCI configuration register.
+
+**/
+UINT32
+EFIAPI
+PciSegmentBitFieldAndThenOr32 (
+  IN UINT64                    Address,
+  IN UINTN                     StartBit,
+  IN UINTN                     EndBit,
+  IN UINT32                    AndData,
+  IN UINT32                    OrData
+  )
+{
+  return PciSegmentWrite32 (
+           Address,
+           BitFieldAndThenOr32 (PciSegmentRead32 (Address), StartBit, EndBit, AndData, OrData)
+           );
+}
+
+/**
+  Reads a range of PCI configuration registers into a caller supplied buffer.
+
+  Reads the range of PCI configuration registers specified by StartAddress and
+  Size into the buffer specified by Buffer. This function only allows the PCI
+  configuration registers from a single PCI function to be read. Size is
+  returned. When possible 32-bit PCI configuration read cycles are used to read
+  from StartAdress to StartAddress + Size. Due to alignment restrictions, 8-bit
+  and 16-bit PCI configuration read cycles may be used at the beginning and the
+  end of the range.
+
+  If any reserved bits in StartAddress are set, then ASSERT().
+  If ((StartAddress & 0xFFF) + Size) > 0x1000, then ASSERT().
+  If Size > 0 and Buffer is NULL, then ASSERT().
+
+  @param  StartAddress  The starting address that encodes the PCI Segment, Bus,
+                        Device, Function and Register.
+  @param  Size          The size in bytes of the transfer.
+  @param  Buffer        The pointer to a buffer receiving the data read.
+
+  @return Size
+
+**/
+UINTN
+EFIAPI
+PciSegmentReadBuffer (
+  IN  UINT64                   StartAddress,
+  IN  UINTN                    Size,
+  OUT VOID                     *Buffer
+  )
+{
+  UINTN                             ReturnValue;
+
+  ASSERT_INVALID_PCI_SEGMENT_ADDRESS (StartAddress, 0);
+  ASSERT (((StartAddress & 0xFFF) + Size) <= 0x1000);
+
+  if (Size == 0) {
+    return Size;
+  }
+
+  ASSERT (Buffer != NULL);
+
+  //
+  // Save Size for return
+  //
+  ReturnValue = Size;
+
+  if ((StartAddress & BIT0) != 0) {
+    //
+    // Read a byte if StartAddress is byte aligned
+    //
+    *(volatile UINT8 *)Buffer = PciSegmentRead8 (StartAddress);
+    StartAddress += sizeof (UINT8);
+    Size -= sizeof (UINT8);
+    Buffer = (UINT8*)Buffer + 1;
+  }
+
+  if (Size >= sizeof (UINT16) && (StartAddress & BIT1) != 0) {
+    //
+    // Read a word if StartAddress is word aligned
+    //
+    WriteUnaligned16 (Buffer, PciSegmentRead16 (StartAddress));
+    StartAddress += sizeof (UINT16);
+    Size -= sizeof (UINT16);
+    Buffer = (UINT16*)Buffer + 1;
+  }
+
+  while (Size >= sizeof (UINT32)) {
+    //
+    // Read as many double words as possible
+    //
+    WriteUnaligned32 (Buffer, PciSegmentRead32 (StartAddress));
+    StartAddress += sizeof (UINT32);
+    Size -= sizeof (UINT32);
+    Buffer = (UINT32*)Buffer + 1;
+  }
+
+  if (Size >= sizeof (UINT16)) {
+    //
+    // Read the last remaining word if exist
+    //
+    WriteUnaligned16 (Buffer, PciSegmentRead16 (StartAddress));
+    StartAddress += sizeof (UINT16);
+    Size -= sizeof (UINT16);
+    Buffer = (UINT16*)Buffer + 1;
+  }
+
+  if (Size >= sizeof (UINT8)) {
+    //
+    // Read the last remaining byte if exist
+    //
+    *(volatile UINT8 *)Buffer = PciSegmentRead8 (StartAddress);
+  }
+
+  return ReturnValue;
+}
+
+
+/**
+  Copies the data in a caller supplied buffer to a specified range of PCI
+  configuration space.
+
+  Writes the range of PCI configuration registers specified by StartAddress and
+  Size from the buffer specified by Buffer. This function only allows the PCI
+  configuration registers from a single PCI function to be written. Size is
+  returned. When possible 32-bit PCI configuration write cycles are used to
+  write from StartAdress to StartAddress + Size. Due to alignment restrictions,
+  8-bit and 16-bit PCI configuration write cycles may be used at the beginning
+  and the end of the range.
+
+  If any reserved bits in StartAddress are set, then ASSERT().
+  If ((StartAddress & 0xFFF) + Size) > 0x1000, then ASSERT().
+  If Size > 0 and Buffer is NULL, then ASSERT().
+
+  @param  StartAddress  The starting address that encodes the PCI Segment, Bus,
+                        Device, Function and Register.
+  @param  Size          The size in bytes of the transfer.
+  @param  Buffer        The pointer to a buffer containing the data to write.
+
+  @return The parameter of Size.
+
+**/
+UINTN
+EFIAPI
+PciSegmentWriteBuffer (
+  IN UINT64                    StartAddress,
+  IN UINTN                     Size,
+  IN VOID                      *Buffer
+  )
+{
+  UINTN                             ReturnValue;
+
+  ASSERT_INVALID_PCI_SEGMENT_ADDRESS (StartAddress, 0);
+  ASSERT (((StartAddress & 0xFFF) + Size) <= 0x1000);
+
+  if (Size == 0) {
+    return 0;
+  }
+
+  ASSERT (Buffer != NULL);
+
+  // The Bcm/Rpi has a single cfg which can be mapped
+  // to any given device on the bus, which means we need to remap
+  // it basically everytime a new config access is done
+
+  //
+  // Save Size for return
+  //
+  ReturnValue = Size;
+
+  if ((StartAddress & BIT0) != 0) {
+    //
+    // Write a byte if StartAddress is byte aligned
+    //
+    PciSegmentWrite8 (StartAddress, *(UINT8*)Buffer);
+    StartAddress += sizeof (UINT8);
+    Size -= sizeof (UINT8);
+    Buffer = (UINT8*)Buffer + 1;
+  }
+
+  if (Size >= sizeof (UINT16) && (StartAddress & BIT1) != 0) {
+    //
+    // Write a word if StartAddress is word aligned
+    //
+    PciSegmentWrite16 (StartAddress, ReadUnaligned16 (Buffer));
+    StartAddress += sizeof (UINT16);
+    Size -= sizeof (UINT16);
+    Buffer = (UINT16*)Buffer + 1;
+  }
+
+  while (Size >= sizeof (UINT32)) {
+    //
+    // Write as many double words as possible
+    //
+    PciSegmentWrite32 (StartAddress, ReadUnaligned32 (Buffer));
+    StartAddress += sizeof (UINT32);
+    Size -= sizeof (UINT32);
+    Buffer = (UINT32*)Buffer + 1;
+  }
+
+  if (Size >= sizeof (UINT16)) {
+    //
+    // Write the last remaining word if exist
+    //
+    PciSegmentWrite16 (StartAddress, ReadUnaligned16 (Buffer));
+    StartAddress += sizeof (UINT16);
+    Size -= sizeof (UINT16);
+    Buffer = (UINT16*)Buffer + 1;
+  }
+
+  if (Size >= sizeof (UINT8)) {
+    //
+    // Write the last remaining byte if exist
+    //
+    PciSegmentWrite8 (StartAddress, *(UINT8*)Buffer);
+  }
+
+  return ReturnValue;
+}
diff --git a/Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciSegmentLib/PciSegmentLib.inf b/Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciSegmentLib/PciSegmentLib.inf
new file mode 100644
index 000000000000..bc3d6ae52100
--- /dev/null
+++ b/Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciSegmentLib/PciSegmentLib.inf
@@ -0,0 +1,35 @@
+## @file
+# PCI Segment Library for Bcm2711 (RPi4) SoC
+#
+# Copyright (c) 2019, Jeremy Linton
+# Copyright (c) 2017, Linaro Ltd. All rights reserved.<BR>
+# Copyright (c) 2007 - 2014, Intel Corporation. All rights reserved.<BR>
+#
+#  SPDX-License-Identifier: BSD-2-Clause-Patent
+#
+##
+
+[Defines]
+  INF_VERSION                    = 0x0001001B
+  BASE_NAME                      = PciSegmentLib
+  FILE_GUID                      = 74fe3f9e-0040-11ea-a7bf-5254005675a0
+  MODULE_TYPE                    = BASE
+  VERSION_STRING                 = 1.0
+  LIBRARY_CLASS                  = PciSegmentLib
+
+[Sources]
+  PciSegmentLib.c
+
+[Packages]
+  MdePkg/MdePkg.dec
+  Silicon/Broadcom/Bcm27xx/Bcm27xx.dec
+
+[LibraryClasses]
+  BaseLib
+  DebugLib
+  IoLib
+  PcdLib
+  UefiLib
+
+[FixedPcd]
+  gBcm27xxTokenSpaceGuid.PcdBcm27xxPciRegBase
-- 
2.21.0.windows.1


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

* [edk2-platforms][PATCH v2 3/4] Silicon/Bcm27xx: Add PCIe host bridge config library
  2019-12-13 17:07 [edk2-platforms][PATCH v2 0/4] Platform/RPi4: Add PCIe and xHCI support Pete Batard
  2019-12-13 17:07 ` [edk2-platforms][PATCH v2 1/4] Silicon/Bcm27xx: Add PCIe constants to Bcm2711.h Pete Batard
  2019-12-13 17:07 ` [edk2-platforms][PATCH v2 2/4] Silicon/Bcm27xx: Add segment library to handle nonstandard ECAM Pete Batard
@ 2019-12-13 17:07 ` Pete Batard
  2019-12-13 17:07 ` [edk2-platforms][PATCH v2 4/4] Platform/RPi4: Build the PCIe and xHCI drivers into the firmware Pete Batard
  2019-12-13 17:40 ` [edk2-platforms][PATCH v2 0/4] Platform/RPi4: Add PCIe and xHCI support Ard Biesheuvel
  4 siblings, 0 replies; 8+ messages in thread
From: Pete Batard @ 2019-12-13 17:07 UTC (permalink / raw)
  To: devel; +Cc: ard.biesheuvel, leif.lindholm, philmd, lintonrjeremy

From: Jeremy Linton <lintonrjeremy@gmail.com>

Enables the instantiation of the PCI host bridge.

Signed-off-by: Pete Batard <pete@akeo.ie>
---
 Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciHostBridgeLib/Bcm2711PciHostBridgeLib.c            | 193 ++++++++++++++++
 Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciHostBridgeLib/Bcm2711PciHostBridgeLib.inf          |  51 +++++
 Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciHostBridgeLib/Bcm2711PciHostBridgeLibConstructor.c | 235 ++++++++++++++++++++
 3 files changed, 479 insertions(+)

diff --git a/Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciHostBridgeLib/Bcm2711PciHostBridgeLib.c b/Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciHostBridgeLib/Bcm2711PciHostBridgeLib.c
new file mode 100644
index 000000000000..e66078cd9ceb
--- /dev/null
+++ b/Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciHostBridgeLib/Bcm2711PciHostBridgeLib.c
@@ -0,0 +1,193 @@
+/** @file
+ *
+ * PCI Host Bridge Library instance for Bcm2711 ARM SOC
+ *
+ * Copyright (c) 2019, Jeremy Linton
+ * Copyright (c) 2017, Linaro Ltd. All rights reserved.<BR>
+ *
+ * SPDX-License-Identifier: BSD-2-Clause-Patent
+ *
+ **/
+
+#include <IndustryStandard/Bcm2711.h>
+#include <IndustryStandard/Pci22.h>
+#include <Library/DebugLib.h>
+#include <Library/DevicePathLib.h>
+#include <Library/MemoryAllocationLib.h>
+#include <Library/PcdLib.h>
+#include <Library/PciHostBridgeLib.h>
+#include <PiDxe.h>
+#include <Protocol/PciRootBridgeIo.h>
+#include <Protocol/PciHostBridgeResourceAllocation.h>
+
+#pragma pack(1)
+
+typedef PACKED struct {
+  ACPI_HID_DEVICE_PATH     AcpiDevicePath;
+  EFI_DEVICE_PATH_PROTOCOL EndDevicePath;
+} EFI_PCI_ROOT_BRIDGE_DEVICE_PATH;
+
+#pragma pack ()
+
+STATIC CONST EFI_PCI_ROOT_BRIDGE_DEVICE_PATH mEfiPciRootBridgeDevicePath[] = {
+  {
+    {
+      {
+        ACPI_DEVICE_PATH,
+        ACPI_DP,
+        {
+          (UINT8)(sizeof (ACPI_HID_DEVICE_PATH)),
+          (UINT8)(sizeof (ACPI_HID_DEVICE_PATH) >> 8)
+        }
+      },
+      EISA_PNP_ID (0x0A08), // PCI Express
+      0
+    },
+
+    {
+      END_DEVICE_PATH_TYPE,
+      END_ENTIRE_DEVICE_PATH_SUBTYPE,
+      {
+        END_DEVICE_PATH_LENGTH,
+        0
+      }
+    }
+  },
+};
+
+GLOBAL_REMOVE_IF_UNREFERENCED
+CHAR16 *mPciHostBridgeLibAcpiAddressSpaceTypeStr[] = {
+  L"Mem", L"I/O", L"Bus"
+};
+
+// These should come from the PCD...
+#define BCM2711_PCI_SEG0_BUSNUM_MIN     0x00
+#define BCM2711_PCI_SEG0_BUSNUM_MAX     0xFF
+#define BCM2711_PCI_SEG0_PORTIO_MIN     0x01
+#define BCM2711_PCI_SEG0_PORTIO_MAX     0x00 // MIN>MAX disables PIO
+#define BCM2711_PCI_SEG0_PORTIO_OFFSET  0x00
+// The bridge thinks its MMIO is here (which means it can't access this area in phy ram)
+#define BCM2711_PCI_SEG0_MMIO32_MIN     PCIE_TOP_OF_MEM_WIN
+#define BCM2711_PCI_SEG0_MMIO32_MAX     (PCIE_TOP_OF_MEM_WIN + PCIE_BRIDGE_MMIO_LEN)
+// The CPU views it via a window here..
+#define BCM2711_PCI_SEG0_MMIO32_XLATE   (PCIE_CPU_MMIO_WINDOW - PCIE_TOP_OF_MEM_WIN)
+
+// We might be able to size another region?
+#define BCM2711_PCI_SEG0_MMIO64_MIN     0x00
+#define BCM2711_PCI_SEG0_MMIO64_MAX     0x00
+
+//
+// See description in MdeModulePkg/Include/Library/PciHostBridgeLib.h
+//
+PCI_ROOT_BRIDGE mPciRootBridges[] = {
+  {
+    0,                                      // Segment
+    0,                                      // Supports
+    0,                                      // Attributes
+    FALSE,                                  // DmaAbove4G
+    FALSE,                                  // NoExtendedConfigSpace (true=256 byte config, false=4k)
+    FALSE,                                  // ResourceAssigned
+    EFI_PCI_HOST_BRIDGE_COMBINE_MEM_PMEM,   // AllocationAttributes
+    { BCM2711_PCI_SEG0_BUSNUM_MIN,
+      BCM2711_PCI_SEG0_BUSNUM_MAX },        // Bus
+    { BCM2711_PCI_SEG0_PORTIO_MIN,
+      BCM2711_PCI_SEG0_PORTIO_MAX,
+      MAX_UINT64 - BCM2711_PCI_SEG0_PORTIO_OFFSET + 1 },   // Io
+    { BCM2711_PCI_SEG0_MMIO32_MIN,
+      BCM2711_PCI_SEG0_MMIO32_MAX,
+      MAX_UINT64 - BCM2711_PCI_SEG0_MMIO32_XLATE + 1 },    // Mem
+    { MAX_UINT64, 0x0 },                    // MemAbove4G
+    { MAX_UINT64, 0x0 },                    // Pefetchable Mem
+    { MAX_UINT64, 0x0 },                    // Pefetchable MemAbove4G
+    (EFI_DEVICE_PATH_PROTOCOL *)&mEfiPciRootBridgeDevicePath[0]
+  }
+};
+
+/**
+  Return all the root bridge instances in an array.
+
+  @param Count  Return the count of root bridge instances.
+
+  @return All the root bridge instances in an array.
+          The array should be passed into PciHostBridgeFreeRootBridges()
+          when it's not used.
+**/
+PCI_ROOT_BRIDGE *
+EFIAPI
+PciHostBridgeGetRootBridges (
+  OUT UINTN     *Count
+  )
+{
+    *Count = ARRAY_SIZE (mPciRootBridges);
+    return mPciRootBridges;
+}
+
+/**
+  Free the root bridge instances array returned from PciHostBridgeGetRootBridges().
+
+  @param Bridges The root bridge instances array.
+  @param Count   The count of the array.
+**/
+VOID
+EFIAPI
+PciHostBridgeFreeRootBridges (
+  PCI_ROOT_BRIDGE *Bridges,
+  UINTN           Count
+  )
+{
+}
+
+/**
+  Inform the platform that the resource conflict happens.
+
+  @param HostBridgeHandle Handle of the Host Bridge.
+  @param Configuration    Pointer to PCI I/O and PCI memory resource
+                          descriptors. The Configuration contains the resources
+                          for all the root bridges. The resource for each root
+                          bridge is terminated with END descriptor and an
+                          additional END is appended indicating the end of the
+                          entire resources. The resource descriptor field
+                          values follow the description in
+                          EFI_PCI_HOST_BRIDGE_RESOURCE_ALLOCATION_PROTOCOL
+                          .SubmitResources().
+**/
+VOID
+EFIAPI
+PciHostBridgeResourceConflict (
+  EFI_HANDLE                        HostBridgeHandle,
+  VOID                              *Configuration
+  )
+{
+  EFI_ACPI_ADDRESS_SPACE_DESCRIPTOR *Descriptor;
+  UINTN                             RootBridgeIndex;
+  DEBUG ((DEBUG_ERROR, "PciHostBridge: Resource conflict happens!\n"));
+
+  RootBridgeIndex = 0;
+  Descriptor = (EFI_ACPI_ADDRESS_SPACE_DESCRIPTOR *) Configuration;
+  while (Descriptor->Desc == ACPI_ADDRESS_SPACE_DESCRIPTOR) {
+    DEBUG ((DEBUG_ERROR, "RootBridge[%d]:\n", RootBridgeIndex++));
+    for (; Descriptor->Desc == ACPI_ADDRESS_SPACE_DESCRIPTOR; Descriptor++) {
+      ASSERT (Descriptor->ResType <
+              ARRAY_SIZE (mPciHostBridgeLibAcpiAddressSpaceTypeStr));
+      DEBUG ((DEBUG_ERROR, " %s: Length/Alignment = 0x%lx / 0x%lx\n",
+              mPciHostBridgeLibAcpiAddressSpaceTypeStr[Descriptor->ResType],
+              Descriptor->AddrLen, Descriptor->AddrRangeMax
+              ));
+      if (Descriptor->ResType == ACPI_ADDRESS_SPACE_TYPE_MEM) {
+        DEBUG ((DEBUG_ERROR, "     Granularity/SpecificFlag = %ld / %02x%s\n",
+                Descriptor->AddrSpaceGranularity, Descriptor->SpecificFlag,
+                ((Descriptor->SpecificFlag &
+                  EFI_ACPI_MEMORY_RESOURCE_SPECIFIC_FLAG_CACHEABLE_PREFETCHABLE
+                  ) != 0) ? L" (Prefetchable)" : L""
+                ));
+      }
+    }
+    //
+    // Skip the END descriptor for root bridge
+    //
+    ASSERT (Descriptor->Desc == ACPI_END_TAG_DESCRIPTOR);
+    Descriptor = (EFI_ACPI_ADDRESS_SPACE_DESCRIPTOR *)(
+                   (EFI_ACPI_END_TAG_DESCRIPTOR *)Descriptor + 1
+                   );
+  }
+}
diff --git a/Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciHostBridgeLib/Bcm2711PciHostBridgeLib.inf b/Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciHostBridgeLib/Bcm2711PciHostBridgeLib.inf
new file mode 100644
index 000000000000..fc23b9486057
--- /dev/null
+++ b/Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciHostBridgeLib/Bcm2711PciHostBridgeLib.inf
@@ -0,0 +1,51 @@
+## @file
+#
+#  PCI Host Bridge Library instance for Bcm2711 ARM SOC
+#  Liberally borrowed from the SynQuacer
+#
+#  Copyright (c) 2019, Jeremy Linton
+#  Copyright (c) 2017, Linaro Ltd. All rights reserved.
+#
+#  SPDX-License-Identifier: BSD-2-Clause-Patent
+#
+##
+
+[Defines]
+  INF_VERSION                    = 0x00010019
+  BASE_NAME                      = Bcm2711PciHostBridgeLib
+  FILE_GUID                      = 8d52c038-0040-11ea-83fb-5254005675a0
+  MODULE_TYPE                    = DXE_DRIVER
+  VERSION_STRING                 = 1.0
+  LIBRARY_CLASS                  = PciHostBridgeLib|DXE_DRIVER
+  CONSTRUCTOR                    = Bcm2711PciHostBridgeLibConstructor
+
+#
+# The following information is for reference only and not required by the build
+# tools.
+#
+#  VALID_ARCHITECTURES           = ARM AARCH64
+#
+
+[Sources]
+  Bcm2711PciHostBridgeLib.c
+  Bcm2711PciHostBridgeLibConstructor.c
+
+[Packages]
+  ArmPkg/ArmPkg.dec
+  MdePkg/MdePkg.dec
+  MdeModulePkg/MdeModulePkg.dec
+  Silicon/Broadcom/Bcm27xx/Bcm27xx.dec
+
+[LibraryClasses]
+  ArmLib
+  DebugLib
+  DevicePathLib
+  MemoryAllocationLib
+  PcdLib
+  UefiBootServicesTableLib
+
+[FixedPcd]
+  gBcm27xxTokenSpaceGuid.PcdBcm27xxPciRegBase
+  gBcm27xxTokenSpaceGuid.PcdBcm27xxPciBusMmioAdr
+  gBcm27xxTokenSpaceGuid.PcdBcm27xxPciBusMmioLen
+  gBcm27xxTokenSpaceGuid.PcdBcm27xxPciCpuMmioAdr
diff --git a/Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciHostBridgeLib/Bcm2711PciHostBridgeLibConstructor.c b/Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciHostBridgeLib/Bcm2711PciHostBridgeLibConstructor.c
new file mode 100644
index 000000000000..90bbc3bf66c4
--- /dev/null
+++ b/Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciHostBridgeLib/Bcm2711PciHostBridgeLibConstructor.c
@@ -0,0 +1,235 @@
+/** @file
+ *
+ * PCI Host Bridge Library instance for Bcm2711 ARM SOC
+ *
+ * Copyright (c) 2019, Jeremy Linton
+ * Copyright (c) 2017, Linaro Ltd. All rights reserved.
+ *
+ * SPDX-License-Identifier: BSD-2-Clause-Patent
+ *
+ * This module initializes the Pci as close to a standard
+ * PCI root complex as possible. The general information
+ * for this driver was sourced from.
+ *
+ * See https://github.com/raspberrypi/linux/blob/rpi-5.3.y/drivers/pci/controller/pcie-brcmstb.c
+ * and https://github.com/raspberrypi/linux/blob/rpi-5.3.y/arch/arm/boot/dts/bcm2838.dtsi
+ *
+ **/
+
+#include <IndustryStandard/Bcm2711.h>
+#include <IndustryStandard/Pci22.h>
+#include <Library/ArmLib.h>
+#include <Library/DebugLib.h>
+#include <Library/IoLib.h>
+#include <Library/PcdLib.h>
+#include <Library/PciHostBridgeLib.h>
+#include <Library/UefiBootServicesTableLib.h>
+#include <PiDxe.h>
+#include <Protocol/PciHostBridgeResourceAllocation.h>
+
+STATIC
+UINT32
+RdRegister (
+  UINT32                Offset
+  )
+{
+  EFI_PHYSICAL_ADDRESS  Base = PCIE_REG_BASE;
+
+  ArmDataMemoryBarrier ();
+
+  return MmioRead32 (Base + Offset);
+}
+
+
+STATIC
+VOID
+RMWRegister (
+  UINT32                Offset,
+  UINT32                Mask,
+  UINT32                In
+  )
+{
+  EFI_PHYSICAL_ADDRESS  Addr = PCIE_REG_BASE;
+  UINT32                Data = 0;
+  UINT32                Shift;
+
+  Addr += Offset;
+  Shift = 1;
+  if (In) {
+    while (!(Mask & Shift))
+      Shift <<= 1;
+    Data = (MmioRead32 (Addr) & ~Mask) | ((In * Shift) & Mask);
+  } else {
+    Data = MmioRead32 (Addr) & ~Mask;
+  }
+
+  MmioWrite32 (Addr, Data);
+
+  ArmDataMemoryBarrier ();
+}
+
+
+STATIC
+VOID
+WdRegister (
+  UINT32                Offset,
+  UINT32                In
+  )
+{
+  EFI_PHYSICAL_ADDRESS  Base = PCIE_REG_BASE;
+
+  MmioWrite32 (Base + Offset, In);
+
+  ArmDataMemoryBarrier ();
+}
+
+
+EFI_STATUS
+EFIAPI
+Bcm2711PciHostBridgeLibConstructor (
+  IN EFI_HANDLE       ImageHandle,
+  IN EFI_SYSTEM_TABLE *SystemTable
+  )
+{
+  INTN                  Timeout = 100;
+  UINT32                Data;
+  EFI_PHYSICAL_ADDRESS  TopOfPciMap;
+
+  DEBUG ((DEBUG_VERBOSE, "PCIe RootBridge constructor\n"));
+
+  // Reset controller
+  RMWRegister (PCIE_RGR1_SW_INIT_1, PCIE_RGR1_SW_INIT_1_INIT_MASK, 1);
+  // PERST
+  RMWRegister (PCIE_RGR1_SW_INIT_1, PCIE_RGR1_SW_INIT_1_PERST_MASK, 1);
+
+  gBS->Stall (1000);
+  // take the bridge out of reset
+  RMWRegister (PCIE_RGR1_SW_INIT_1, PCIE_RGR1_SW_INIT_1_INIT_MASK, 0);
+
+
+  RMWRegister (PCIE_MISC_HARD_PCIE_HARD_DEBUG,
+    PCIE_MISC_HARD_PCIE_HARD_DEBUG_SERDES_IDDQ_MASK, 0);
+  RdRegister (PCIE_MISC_HARD_PCIE_HARD_DEBUG);
+  // Wait for SerDes to be stable
+  gBS->Stall (1000);
+
+  // Read revision
+  Data = RdRegister (PCIE_MISC_REVISION);
+  DEBUG ((DEBUG_INFO, "RootBridge: Revision %x\n", Data & PCIE_MISC_REVISION_MAJMIN_MASK));
+
+  RMWRegister (PCIE_MISC_MISC_CTRL, PCIE_MISC_MISC_CTRL_SCB_ACCESS_EN_MASK, 1);
+  RMWRegister (PCIE_MISC_MISC_CTRL, PCIE_MISC_MISC_CTRL_CFG_READ_UR_MODE_MASK, 1);
+  RMWRegister (PCIE_MISC_MISC_CTRL, PCIE_MISC_MISC_CTRL_MAX_BURST_SIZE_MASK, BURST_SIZE_128);
+
+  //
+  // "RC_BAR2" is the inbound TLP window.
+  // Having non RAM regions in the window is ok (and encouraged? for PtP?)
+  // so lets just map the entire address space.
+  //
+  // For regions > 64K then the pci->mem window size = log2(size)-15
+  // which is dumped into the low bits of the offset and written to
+  // the "LO" register with the high bits of the offset written into
+  // the "HI" part. The Linux driver makes the point that the offset
+  // must be aligned to its size aka a 1G region must start on a 1G
+  // boundary. The size parms are 1GB=0xf=log2(size)-15), or 4G=0x11
+  //
+
+  DEBUG ((DEBUG_VERBOSE, "RootBridge: Program bottom 4G of ram\n"));
+
+  // lets assume a start addr of 0, size 4G
+  WdRegister (PCIE_MISC_RC_BAR2_CONFIG_LO, 0x11);   /* Size = 4G */
+  WdRegister (PCIE_MISC_RC_BAR2_CONFIG_HI, 0);      /* Start at addr0 */
+  RMWRegister (PCIE_MISC_MISC_CTRL, PCIE_MISC_MISC_CTRL_SCB0_SIZE_MASK, 0x11);
+
+  // RC_BAR1 pcie->gisb disable
+  WdRegister (PCIE_MISC_RC_BAR1_CONFIG_LO, 0);
+  // RC_BAR3 pcie->scb disable
+  WdRegister (PCIE_MISC_RC_BAR3_CONFIG_LO, 0);
+
+  TopOfPciMap = PCIE_TOP_OF_MEM_WIN;
+
+  DEBUG ((DEBUG_VERBOSE, "RootBridge: MMIO PCIe addr %llx\n", TopOfPciMap));
+
+  //
+  // Setup the PCI side of the MMIO window.
+  //
+  // All the _WIN0_ values make one think there can be more than one
+  // mapping, which might mean it's possible to program a prefetchable
+  // window, or a PIO window...
+  //
+  WdRegister (PCIE_MISC_CPU_2_PCIE_MEM_WIN0_LO, TopOfPciMap);
+  WdRegister (PCIE_MISC_CPU_2_PCIE_MEM_WIN0_HI, TopOfPciMap >> 32);
+
+  //
+  // Set up the CPU MMIO addresses. The BASE_LIMIT register holds the
+  // bottom part of the start and end addresses in a 16-bit field (64k)
+  // aligned on a 1M boundary (aka only 12 bit active) the top 32-bits
+  // are then in their own registers. Further these address ranges are
+  // setup to match the Linux driver and seem less than ideal on the RPi
+  //
+  // The mapping should be 1:1 if possible
+  //
+  EFI_PHYSICAL_ADDRESS    CpuAddrStart = PCIE_CPU_MMIO_WINDOW;
+  EFI_PHYSICAL_ADDRESS    CpuAddrEnd   = CpuAddrStart + PCIE_BRIDGE_MMIO_LEN;
+
+  DEBUG ((DEBUG_VERBOSE, "RootBridge: MMIO CPU addr %llx\n", CpuAddrStart));
+
+  RMWRegister (PCIE_MISC_CPU_2_PCIE_MEM_WIN0_BASE_LIMIT,
+    PCIE_MISC_CPU_2_PCIE_MEM_WIN0_BASE_LIMIT_BASE_MASK, CpuAddrStart >> 20);
+  RMWRegister (PCIE_MISC_CPU_2_PCIE_MEM_WIN0_BASE_LIMIT,
+    PCIE_MISC_CPU_2_PCIE_MEM_WIN0_BASE_LIMIT_LIMIT_MASK, CpuAddrEnd >> 20);
+  RMWRegister (PCIE_MISC_CPU_2_PCIE_MEM_WIN0_BASE_HI,
+    PCIE_MISC_CPU_2_PCIE_MEM_WIN0_BASE_HI_BASE_MASK, CpuAddrStart >> 32);
+  RMWRegister (PCIE_MISC_CPU_2_PCIE_MEM_WIN0_LIMIT_HI,
+    PCIE_MISC_CPU_2_PCIE_MEM_WIN0_LIMIT_HI_LIMIT_MASK, CpuAddrEnd >> 32);
+
+  //
+  // Consider MSI setup here, not that it matters much its likely the legacy intX
+  // is as fast or faster...
+  //
+
+  // Clear and mask interrupts.
+  WdRegister (PCIE_INTR2_CPU_MASK_CLR, 0xffffffff);
+  WdRegister (PCIE_INTR2_CPU_MASK_SET, 0xffffffff);
+
+  // Set link cap & link ctl?
+  //RMWRegister (BRCM_PCIE_CAP_REGS+PCI_LNKCAP, LNKCAP, pen);
+  //RMWRegister (BRCM_PCIE_CTL_REGS+PCI_LNKCAP, LNKCAP, pen);
+
+  // De-assert PERST
+  RMWRegister (PCIE_RGR1_SW_INIT_1, PCIE_RGR1_SW_INIT_1_PERST_MASK, 0);
+  DEBUG ((DEBUG_VERBOSE, "RootBridge: Reset done\n"));
+
+  // Wait for linkup
+  do {
+      Data = RdRegister (PCIE_MISC_PCIE_STATUS);
+      gBS->Stall (1000);
+      Timeout --;
+  } while (((Data & 0x30) != 0x030) && (Timeout));
+  DEBUG ((DEBUG_VERBOSE, "PCIe link ready (status=%x) Timeout=%d\n", Data, Timeout));
+
+  if ((Data & 0x30) != 0x30) {
+    DEBUG ((DEBUG_ERROR, "PCIe link not ready (status=%x)\n", Data));
+    return EFI_DEVICE_ERROR;
+  }
+
+  if ((Data & 0x80) != 0x80) {
+    DEBUG ((DEBUG_ERROR, "PCIe link not in RC mode (status=%x)\n", Data));
+    return EFI_UNSUPPORTED;
+  }
+
+  // Change class code of the root port
+  RMWRegister(BRCM_PCIE_CLASS, PCIE_RC_CFG_PRIV1_ID_VAL3_CLASS_CODE_MASK, 0x60400);
+
+  //
+  // PCIe->SCB endian mode for BAR
+  // field ENDIAN_MODE_BAR2 = little endian = 0
+  //
+  RMWRegister (PCIE_RC_CFG_VENDOR_VENDOR_SPECIFIC_REG1,
+    PCIE_RC_CFG_VENDOR_VENDOR_SPECIFIC_REG1_ENDIAN_MODE_BAR2_MASK, 0);
+
+  RMWRegister (PCIE_MISC_HARD_PCIE_HARD_DEBUG,
+    PCIE_MISC_HARD_PCIE_HARD_DEBUG_CLKREQ_DEBUG_ENABLE_MASK, 1);
+
+  return EFI_SUCCESS;
+}
-- 
2.21.0.windows.1


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

* [edk2-platforms][PATCH v2 4/4] Platform/RPi4: Build the PCIe and xHCI drivers into the firmware
  2019-12-13 17:07 [edk2-platforms][PATCH v2 0/4] Platform/RPi4: Add PCIe and xHCI support Pete Batard
                   ` (2 preceding siblings ...)
  2019-12-13 17:07 ` [edk2-platforms][PATCH v2 3/4] Silicon/Bcm27xx: Add PCIe host bridge config library Pete Batard
@ 2019-12-13 17:07 ` Pete Batard
  2019-12-13 17:14   ` Philippe Mathieu-Daudé
  2019-12-13 17:40 ` [edk2-platforms][PATCH v2 0/4] Platform/RPi4: Add PCIe and xHCI support Ard Biesheuvel
  4 siblings, 1 reply; 8+ messages in thread
From: Pete Batard @ 2019-12-13 17:07 UTC (permalink / raw)
  To: devel; +Cc: ard.biesheuvel, leif.lindholm, philmd, lintonrjeremy

From: Jeremy Linton <lintonrjeremy@gmail.com>

This uses the recently introduced NonCoherentIoMmuDxe for PCIe access
and should enable USB device usage in the UEFI environment.

As mentioned in https://lkml.org/lkml/2019/9/9/170, imposing a 3 GB
DMA limit might be necessary for the 4 GB models so we follow suit by
setting PcdDmaDeviceLimit to 3 GB - 1 in NonCoherentIoMmuDxe.

Note that this patch does not provide xHCI ACPI support because the
required Xhci.asl table will be provided in a later commit.

Signed-off-by: Pete Batard <pete@akeo.ie>
---
 Platform/RaspberryPi/RPi4/RPi4.dsc  | 29 +++++++++++++++++++-
 Platform/RaspberryPi/RPi4/RPi4.fdf  | 10 ++++++-
 Platform/RaspberryPi/RPi4/Readme.md | 23 +++++-----------
 3 files changed, 44 insertions(+), 18 deletions(-)

diff --git a/Platform/RaspberryPi/RPi4/RPi4.dsc b/Platform/RaspberryPi/RPi4/RPi4.dsc
index 03139e57a8db..00b75741702a 100644
--- a/Platform/RaspberryPi/RPi4/RPi4.dsc
+++ b/Platform/RaspberryPi/RPi4/RPi4.dsc
@@ -161,6 +161,14 @@ [LibraryClasses.common]
   VarCheckLib|MdeModulePkg/Library/VarCheckLib/VarCheckLib.inf
   GpioLib|Silicon/Broadcom/Bcm283x/Library/GpioLib/GpioLib.inf
 
+  #
+  # PCI dependencies
+  #
+  # PCI root port configuation and description
+  PciHostBridgeLib|Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciHostBridgeLib/Bcm2711PciHostBridgeLib.inf
+  # The "segment lib" provides the CAM accessors/etc when they aren't ECAM standard
+  PciSegmentLib|Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciSegmentLib/PciSegmentLib.inf
+
 [LibraryClasses.common.SEC]
   PcdLib|MdePkg/Library/BasePcdLibNull/BasePcdLibNull.inf
   BaseMemoryLib|MdePkg/Library/BaseMemoryLib/BaseMemoryLib.inf
@@ -318,6 +326,7 @@ [PcdsFixedAtBuild.common]
   gEmbeddedTokenSpaceGuid.PcdMemoryTypeEfiLoaderData|0
 
   gEmbeddedTokenSpaceGuid.PcdDmaDeviceOffset|0xc0000000
+  gEmbeddedTokenSpaceGuid.PcdDmaDeviceLimit|0xffffffff
 
   gEfiMdeModulePkgTokenSpaceGuid.PcdFirmwareVersionString|L"EDK2-DEV"
 
@@ -378,6 +387,12 @@ [PcdsFixedAtBuild.common]
   gBcm27xxTokenSpaceGuid.PcdBcm27xxRegistersAddress|0xfc000000
   gBcm283xTokenSpaceGuid.PcdBcm283xRegistersAddress|0xfe000000
 
+  # PCIe specific addresses
+  gBcm27xxTokenSpaceGuid.PcdBcm27xxPciRegBase|0xfd500000
+  gBcm27xxTokenSpaceGuid.PcdBcm27xxPciBusMmioAdr|0xf8000000
+  gBcm27xxTokenSpaceGuid.PcdBcm27xxPciBusMmioLen|0x3ffffff
+  gBcm27xxTokenSpaceGuid.PcdBcm27xxPciCpuMmioAdr|0x600000000
+
   ## NS16550 compatible UART
   gEfiMdeModulePkgTokenSpaceGuid.PcdSerialRegisterBase|0xfe215040
   gEfiMdeModulePkgTokenSpaceGuid.PcdSerialUseMmio|TRUE
@@ -525,7 +540,6 @@ [Components.common]
 
   MdeModulePkg/Universal/HiiDatabaseDxe/HiiDatabaseDxe.inf
 
-  UefiCpuPkg/CpuIo2Dxe/CpuIo2Dxe.inf
   ArmPkg/Drivers/ArmGic/ArmGicDxe.inf
   Platform/RaspberryPi/Drivers/RpiFirmwareDxe/RpiFirmwareDxe.inf
   Platform/RaspberryPi/Drivers/FdtDxe/FdtDxe.inf
@@ -587,6 +601,7 @@ [Components.common]
   #
   # USB Support
   #
+  MdeModulePkg/Bus/Pci/XhciDxe/XhciDxe.inf
   Platform/RaspberryPi/Drivers/DwUsbHostDxe/DwUsbHostDxe.inf
   MdeModulePkg/Bus/Usb/UsbBusDxe/UsbBusDxe.inf
   MdeModulePkg/Bus/Usb/UsbKbDxe/UsbKbDxe.inf
@@ -610,6 +625,18 @@ [Components.common]
   #
   Silicon/Broadcom/Bcm283x/Drivers/Bcm2838RngDxe/Bcm2838RngDxe.inf
 
+  #
+  # PCI Support
+  #
+  ArmPkg/Drivers/ArmPciCpuIo2Dxe/ArmPciCpuIo2Dxe.inf
+  MdeModulePkg/Bus/Pci/PciHostBridgeDxe/PciHostBridgeDxe.inf
+  MdeModulePkg/Bus/Pci/PciBusDxe/PciBusDxe.inf
+  EmbeddedPkg/Drivers/NonCoherentIoMmuDxe/NonCoherentIoMmuDxe.inf {
+    <PcdsFixedAtBuild>
+      gEmbeddedTokenSpaceGuid.PcdDmaDeviceOffset|0x00000000
+      gEmbeddedTokenSpaceGuid.PcdDmaDeviceLimit|0xbfffffff
+  }
+
   #
   # UEFI application (Shell Embedded Boot Loader)
   #
diff --git a/Platform/RaspberryPi/RPi4/RPi4.fdf b/Platform/RaspberryPi/RPi4/RPi4.fdf
index f0ab47c6c0a9..7a506bd2813b 100644
--- a/Platform/RaspberryPi/RPi4/RPi4.fdf
+++ b/Platform/RaspberryPi/RPi4/RPi4.fdf
@@ -205,7 +205,6 @@ [FV.FvMain]
   INF MdeModulePkg/Universal/SerialDxe/SerialDxe.inf
   INF Platform/RaspberryPi/Drivers/DisplayDxe/DisplayDxe.inf
 
-  INF UefiCpuPkg/CpuIo2Dxe/CpuIo2Dxe.inf
   INF ArmPkg/Drivers/ArmGic/ArmGicDxe.inf
   INF Platform/RaspberryPi/Drivers/RpiFirmwareDxe/RpiFirmwareDxe.inf
   INF Platform/RaspberryPi/Drivers/FdtDxe/FdtDxe.inf
@@ -269,6 +268,14 @@ [FV.FvMain]
   #
   INF Silicon/Broadcom/Bcm283x/Drivers/Bcm2838RngDxe/Bcm2838RngDxe.inf
 
+  #
+  # PCI Support
+  #
+  INF ArmPkg/Drivers/ArmPciCpuIo2Dxe/ArmPciCpuIo2Dxe.inf
+  INF MdeModulePkg/Bus/Pci/PciHostBridgeDxe/PciHostBridgeDxe.inf
+  INF MdeModulePkg/Bus/Pci/PciBusDxe/PciBusDxe.inf
+  INF EmbeddedPkg/Drivers/NonCoherentIoMmuDxe/NonCoherentIoMmuDxe.inf
+
   #
   # SCSI Bus and Disk Driver
   #
@@ -278,6 +285,7 @@ [FV.FvMain]
   #
   # USB Support
   #
+  INF MdeModulePkg/Bus/Pci/XhciDxe/XhciDxe.inf
   INF Platform/RaspberryPi/Drivers/DwUsbHostDxe/DwUsbHostDxe.inf
   INF MdeModulePkg/Bus/Usb/UsbBusDxe/UsbBusDxe.inf
   INF MdeModulePkg/Bus/Usb/UsbKbDxe/UsbKbDxe.inf
diff --git a/Platform/RaspberryPi/RPi4/Readme.md b/Platform/RaspberryPi/RPi4/Readme.md
index 917f8436a382..2e37646e043d 100644
--- a/Platform/RaspberryPi/RPi4/Readme.md
+++ b/Platform/RaspberryPi/RPi4/Readme.md
@@ -7,28 +7,19 @@ This is a port of 64-bit Tiano Core UEFI firmware for the Raspberry Pi 4 platfor
 
 This is intended to be useful 64-bit [TF-A](https://www.trustedfirmware.org/) +
 UEFI implementation for the Raspberry Pi 4 which should be good enough for most
-kind of UEFI development, as well as for running consummer Operating Systems
-such as Linux or Windows.
+kind of UEFI development, as well as for running consummer Operating Systems.
 
 Raspberry Pi is a trademark of the [Raspberry Pi Foundation](https://www.raspberrypi.org).
 
 # Status
 
-This firmware is still in early stage of development, meaning that it comes with
-the following __major__ limitations:
+This firmware is still in development stage, meaning that it comes with the
+following __major__ limitations:
 
-- USB is not supported yet (will be added soon)
-- Booting of vanilla Operating Systems (Windows, Linux) is not supported yet,
-  let alone expected to work at all.
-
-The only features that are expected to work with this first iteration of the
-firmware are HDMI and serial I/O.
-
-## Known issues
-
-- The serial output from TF-A is garbled when using a `start4.elf` that was
-  released after 2019.11.18. This is a TF-A issue that will be fixed in a
-  later version.
+- USB is likely to work only in pre-OS phase at this stage (nonstandard ECAM,
+  missing ACPI tables).
+- Serial I/O from the OS may not work at all due to CPU throttling affecting
+  the miniUART baudrate.
 
 # Building
 
-- 
2.21.0.windows.1


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

* Re: [edk2-platforms][PATCH v2 4/4] Platform/RPi4: Build the PCIe and xHCI drivers into the firmware
  2019-12-13 17:07 ` [edk2-platforms][PATCH v2 4/4] Platform/RPi4: Build the PCIe and xHCI drivers into the firmware Pete Batard
@ 2019-12-13 17:14   ` Philippe Mathieu-Daudé
  0 siblings, 0 replies; 8+ messages in thread
From: Philippe Mathieu-Daudé @ 2019-12-13 17:14 UTC (permalink / raw)
  To: Pete Batard, devel; +Cc: ard.biesheuvel, leif.lindholm, lintonrjeremy

On 12/13/19 6:07 PM, Pete Batard wrote:
> From: Jeremy Linton <lintonrjeremy@gmail.com>
> 
> This uses the recently introduced NonCoherentIoMmuDxe for PCIe access
> and should enable USB device usage in the UEFI environment.
> 
> As mentioned in https://lkml.org/lkml/2019/9/9/170, imposing a 3 GB
> DMA limit might be necessary for the 4 GB models so we follow suit by
> setting PcdDmaDeviceLimit to 3 GB - 1 in NonCoherentIoMmuDxe.
> 
> Note that this patch does not provide xHCI ACPI support because the
> required Xhci.asl table will be provided in a later commit.
> 
> Signed-off-by: Pete Batard <pete@akeo.ie>
> ---
>   Platform/RaspberryPi/RPi4/RPi4.dsc  | 29 +++++++++++++++++++-
>   Platform/RaspberryPi/RPi4/RPi4.fdf  | 10 ++++++-
>   Platform/RaspberryPi/RPi4/Readme.md | 23 +++++-----------
>   3 files changed, 44 insertions(+), 18 deletions(-)
> 
> diff --git a/Platform/RaspberryPi/RPi4/RPi4.dsc b/Platform/RaspberryPi/RPi4/RPi4.dsc
> index 03139e57a8db..00b75741702a 100644
> --- a/Platform/RaspberryPi/RPi4/RPi4.dsc
> +++ b/Platform/RaspberryPi/RPi4/RPi4.dsc
> @@ -161,6 +161,14 @@ [LibraryClasses.common]
>     VarCheckLib|MdeModulePkg/Library/VarCheckLib/VarCheckLib.inf
>     GpioLib|Silicon/Broadcom/Bcm283x/Library/GpioLib/GpioLib.inf
>   
> +  #
> +  # PCI dependencies
> +  #
> +  # PCI root port configuation and description
> +  PciHostBridgeLib|Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciHostBridgeLib/Bcm2711PciHostBridgeLib.inf
> +  # The "segment lib" provides the CAM accessors/etc when they aren't ECAM standard
> +  PciSegmentLib|Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciSegmentLib/PciSegmentLib.inf
> +
>   [LibraryClasses.common.SEC]
>     PcdLib|MdePkg/Library/BasePcdLibNull/BasePcdLibNull.inf
>     BaseMemoryLib|MdePkg/Library/BaseMemoryLib/BaseMemoryLib.inf
> @@ -318,6 +326,7 @@ [PcdsFixedAtBuild.common]
>     gEmbeddedTokenSpaceGuid.PcdMemoryTypeEfiLoaderData|0
>   
>     gEmbeddedTokenSpaceGuid.PcdDmaDeviceOffset|0xc0000000
> +  gEmbeddedTokenSpaceGuid.PcdDmaDeviceLimit|0xffffffff
>   
>     gEfiMdeModulePkgTokenSpaceGuid.PcdFirmwareVersionString|L"EDK2-DEV"
>   
> @@ -378,6 +387,12 @@ [PcdsFixedAtBuild.common]
>     gBcm27xxTokenSpaceGuid.PcdBcm27xxRegistersAddress|0xfc000000
>     gBcm283xTokenSpaceGuid.PcdBcm283xRegistersAddress|0xfe000000
>   
> +  # PCIe specific addresses
> +  gBcm27xxTokenSpaceGuid.PcdBcm27xxPciRegBase|0xfd500000
> +  gBcm27xxTokenSpaceGuid.PcdBcm27xxPciBusMmioAdr|0xf8000000
> +  gBcm27xxTokenSpaceGuid.PcdBcm27xxPciBusMmioLen|0x3ffffff
> +  gBcm27xxTokenSpaceGuid.PcdBcm27xxPciCpuMmioAdr|0x600000000
> +
>     ## NS16550 compatible UART
>     gEfiMdeModulePkgTokenSpaceGuid.PcdSerialRegisterBase|0xfe215040
>     gEfiMdeModulePkgTokenSpaceGuid.PcdSerialUseMmio|TRUE
> @@ -525,7 +540,6 @@ [Components.common]
>   
>     MdeModulePkg/Universal/HiiDatabaseDxe/HiiDatabaseDxe.inf
>   
> -  UefiCpuPkg/CpuIo2Dxe/CpuIo2Dxe.inf
>     ArmPkg/Drivers/ArmGic/ArmGicDxe.inf
>     Platform/RaspberryPi/Drivers/RpiFirmwareDxe/RpiFirmwareDxe.inf
>     Platform/RaspberryPi/Drivers/FdtDxe/FdtDxe.inf
> @@ -587,6 +601,7 @@ [Components.common]
>     #
>     # USB Support
>     #
> +  MdeModulePkg/Bus/Pci/XhciDxe/XhciDxe.inf
>     Platform/RaspberryPi/Drivers/DwUsbHostDxe/DwUsbHostDxe.inf
>     MdeModulePkg/Bus/Usb/UsbBusDxe/UsbBusDxe.inf
>     MdeModulePkg/Bus/Usb/UsbKbDxe/UsbKbDxe.inf
> @@ -610,6 +625,18 @@ [Components.common]
>     #
>     Silicon/Broadcom/Bcm283x/Drivers/Bcm2838RngDxe/Bcm2838RngDxe.inf
>   
> +  #
> +  # PCI Support
> +  #
> +  ArmPkg/Drivers/ArmPciCpuIo2Dxe/ArmPciCpuIo2Dxe.inf
> +  MdeModulePkg/Bus/Pci/PciHostBridgeDxe/PciHostBridgeDxe.inf
> +  MdeModulePkg/Bus/Pci/PciBusDxe/PciBusDxe.inf
> +  EmbeddedPkg/Drivers/NonCoherentIoMmuDxe/NonCoherentIoMmuDxe.inf {
> +    <PcdsFixedAtBuild>
> +      gEmbeddedTokenSpaceGuid.PcdDmaDeviceOffset|0x00000000
> +      gEmbeddedTokenSpaceGuid.PcdDmaDeviceLimit|0xbfffffff
> +  }
> +
>     #
>     # UEFI application (Shell Embedded Boot Loader)
>     #
> diff --git a/Platform/RaspberryPi/RPi4/RPi4.fdf b/Platform/RaspberryPi/RPi4/RPi4.fdf
> index f0ab47c6c0a9..7a506bd2813b 100644
> --- a/Platform/RaspberryPi/RPi4/RPi4.fdf
> +++ b/Platform/RaspberryPi/RPi4/RPi4.fdf
> @@ -205,7 +205,6 @@ [FV.FvMain]
>     INF MdeModulePkg/Universal/SerialDxe/SerialDxe.inf
>     INF Platform/RaspberryPi/Drivers/DisplayDxe/DisplayDxe.inf
>   
> -  INF UefiCpuPkg/CpuIo2Dxe/CpuIo2Dxe.inf
>     INF ArmPkg/Drivers/ArmGic/ArmGicDxe.inf
>     INF Platform/RaspberryPi/Drivers/RpiFirmwareDxe/RpiFirmwareDxe.inf
>     INF Platform/RaspberryPi/Drivers/FdtDxe/FdtDxe.inf
> @@ -269,6 +268,14 @@ [FV.FvMain]
>     #
>     INF Silicon/Broadcom/Bcm283x/Drivers/Bcm2838RngDxe/Bcm2838RngDxe.inf
>   
> +  #
> +  # PCI Support
> +  #
> +  INF ArmPkg/Drivers/ArmPciCpuIo2Dxe/ArmPciCpuIo2Dxe.inf
> +  INF MdeModulePkg/Bus/Pci/PciHostBridgeDxe/PciHostBridgeDxe.inf
> +  INF MdeModulePkg/Bus/Pci/PciBusDxe/PciBusDxe.inf
> +  INF EmbeddedPkg/Drivers/NonCoherentIoMmuDxe/NonCoherentIoMmuDxe.inf
> +
>     #
>     # SCSI Bus and Disk Driver
>     #
> @@ -278,6 +285,7 @@ [FV.FvMain]
>     #
>     # USB Support
>     #
> +  INF MdeModulePkg/Bus/Pci/XhciDxe/XhciDxe.inf
>     INF Platform/RaspberryPi/Drivers/DwUsbHostDxe/DwUsbHostDxe.inf
>     INF MdeModulePkg/Bus/Usb/UsbBusDxe/UsbBusDxe.inf
>     INF MdeModulePkg/Bus/Usb/UsbKbDxe/UsbKbDxe.inf
> diff --git a/Platform/RaspberryPi/RPi4/Readme.md b/Platform/RaspberryPi/RPi4/Readme.md
> index 917f8436a382..2e37646e043d 100644
> --- a/Platform/RaspberryPi/RPi4/Readme.md
> +++ b/Platform/RaspberryPi/RPi4/Readme.md
> @@ -7,28 +7,19 @@ This is a port of 64-bit Tiano Core UEFI firmware for the Raspberry Pi 4 platfor
>   
>   This is intended to be useful 64-bit [TF-A](https://www.trustedfirmware.org/) +
>   UEFI implementation for the Raspberry Pi 4 which should be good enough for most
> -kind of UEFI development, as well as for running consummer Operating Systems
> -such as Linux or Windows.
> +kind of UEFI development, as well as for running consummer Operating Systems.
>   
>   Raspberry Pi is a trademark of the [Raspberry Pi Foundation](https://www.raspberrypi.org).
>   
>   # Status
>   
> -This firmware is still in early stage of development, meaning that it comes with
> -the following __major__ limitations:
> +This firmware is still in development stage, meaning that it comes with the
> +following __major__ limitations:
>   
> -- USB is not supported yet (will be added soon)
> -- Booting of vanilla Operating Systems (Windows, Linux) is not supported yet,
> -  let alone expected to work at all.
> -
> -The only features that are expected to work with this first iteration of the
> -firmware are HDMI and serial I/O.
> -
> -## Known issues
> -
> -- The serial output from TF-A is garbled when using a `start4.elf` that was
> -  released after 2019.11.18. This is a TF-A issue that will be fixed in a
> -  later version.
> +- USB is likely to work only in pre-OS phase at this stage (nonstandard ECAM,
> +  missing ACPI tables).
> +- Serial I/O from the OS may not work at all due to CPU throttling affecting
> +  the miniUART baudrate.
>   
>   # Building
>   
> 

Acked-by: Philippe Mathieu-Daude <philmd@redhat.com>


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

* Re: [edk2-platforms][PATCH v2 0/4] Platform/RPi4: Add PCIe and xHCI support
  2019-12-13 17:07 [edk2-platforms][PATCH v2 0/4] Platform/RPi4: Add PCIe and xHCI support Pete Batard
                   ` (3 preceding siblings ...)
  2019-12-13 17:07 ` [edk2-platforms][PATCH v2 4/4] Platform/RPi4: Build the PCIe and xHCI drivers into the firmware Pete Batard
@ 2019-12-13 17:40 ` Ard Biesheuvel
  2019-12-13 17:51   ` Pete Batard
  4 siblings, 1 reply; 8+ messages in thread
From: Ard Biesheuvel @ 2019-12-13 17:40 UTC (permalink / raw)
  To: Pete Batard
  Cc: edk2-devel-groups-io, Leif Lindholm, Philippe Mathieu-Daudé,
	lintonrjeremy

On Fri, 13 Dec 2019 at 18:07, Pete Batard <pete@akeo.ie> wrote:
>
> Changes from v1 (https://edk2.groups.io/g/devel/message/52160 - 52164):
>
> * Ensure that read/write accesses are serialized in PciSegmentLib.
> * Flesh out commit messages.
> * Minor comments and code updates for whitespaces & capitalization.
>
> Jeremy Linton (4):
>   Silicon/Bcm27xx: Add PCIe constants to Bcm2711.h
>   Silicon/Bcm27xx: Add segment library to handle nonstandard ECAM
>   Silicon/Bcm27xx: Add PCIe host bridge config library
>   Platform/RPi4: Build the PCIe and xHCI drivers into the firmware
>

Thanks Pete

Reviewed-by: Ard Biesheuvel <ard.biesheuvel@linaro.org>

I have touched up a couple of style issues, and pushed the series as
c682c58b3a29..9c8c79542eae


>  Platform/RaspberryPi/RPi4/RPi4.dsc                                                            |   29 +-
>  Platform/RaspberryPi/RPi4/RPi4.fdf                                                            |   10 +-
>  Platform/RaspberryPi/RPi4/Readme.md                                                           |   23 +-
>  Silicon/Broadcom/Bcm27xx/Bcm27xx.dec                                                          |    4 +
>  Silicon/Broadcom/Bcm27xx/Include/IndustryStandard/Bcm2711.h                                   |   71 +
>  Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciHostBridgeLib/Bcm2711PciHostBridgeLib.c            |  193 +++
>  Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciHostBridgeLib/Bcm2711PciHostBridgeLib.inf          |   51 +
>  Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciHostBridgeLib/Bcm2711PciHostBridgeLibConstructor.c |  235 ++++
>  Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciSegmentLib/PciSegmentLib.c                         | 1445 ++++++++++++++++++++
>  Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciSegmentLib/PciSegmentLib.inf                       |   35 +
>  10 files changed, 2078 insertions(+), 18 deletions(-)
>  create mode 100644 Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciHostBridgeLib/Bcm2711PciHostBridgeLib.c
>  create mode 100644 Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciHostBridgeLib/Bcm2711PciHostBridgeLib.inf
>  create mode 100644 Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciHostBridgeLib/Bcm2711PciHostBridgeLibConstructor.c
>  create mode 100644 Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciSegmentLib/PciSegmentLib.c
>  create mode 100644 Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciSegmentLib/PciSegmentLib.inf
>
> --
> 2.21.0.windows.1
>

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

* Re: [edk2-platforms][PATCH v2 0/4] Platform/RPi4: Add PCIe and xHCI support
  2019-12-13 17:40 ` [edk2-platforms][PATCH v2 0/4] Platform/RPi4: Add PCIe and xHCI support Ard Biesheuvel
@ 2019-12-13 17:51   ` Pete Batard
  0 siblings, 0 replies; 8+ messages in thread
From: Pete Batard @ 2019-12-13 17:51 UTC (permalink / raw)
  To: Ard Biesheuvel
  Cc: edk2-devel-groups-io, Leif Lindholm, Philippe Mathieu-Daudé,
	lintonrjeremy

On 2019.12.13 17:40, Ard Biesheuvel wrote:
> On Fri, 13 Dec 2019 at 18:07, Pete Batard <pete@akeo.ie> wrote:
>>
>> Changes from v1 (https://edk2.groups.io/g/devel/message/52160 - 52164):
>>
>> * Ensure that read/write accesses are serialized in PciSegmentLib.
>> * Flesh out commit messages.
>> * Minor comments and code updates for whitespaces & capitalization.
>>
>> Jeremy Linton (4):
>>    Silicon/Bcm27xx: Add PCIe constants to Bcm2711.h
>>    Silicon/Bcm27xx: Add segment library to handle nonstandard ECAM
>>    Silicon/Bcm27xx: Add PCIe host bridge config library
>>    Platform/RPi4: Build the PCIe and xHCI drivers into the firmware
>>
> 
> Thanks Pete
> 
> Reviewed-by: Ard Biesheuvel <ard.biesheuvel@linaro.org>
> 
> I have touched up a couple of style issues, and pushed the series as
> c682c58b3a29..9c8c79542eae

Much appreciated, thanks!

Since this RPi4 integration is moving fast, I'll use this opportunity to 
send a gentle ping for https://edk2.groups.io/g/devel/message/52131, 
which I sent before the v1 for the PCIe series.

Regards,

/Pete

> 
> 
>>   Platform/RaspberryPi/RPi4/RPi4.dsc                                                            |   29 +-
>>   Platform/RaspberryPi/RPi4/RPi4.fdf                                                            |   10 +-
>>   Platform/RaspberryPi/RPi4/Readme.md                                                           |   23 +-
>>   Silicon/Broadcom/Bcm27xx/Bcm27xx.dec                                                          |    4 +
>>   Silicon/Broadcom/Bcm27xx/Include/IndustryStandard/Bcm2711.h                                   |   71 +
>>   Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciHostBridgeLib/Bcm2711PciHostBridgeLib.c            |  193 +++
>>   Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciHostBridgeLib/Bcm2711PciHostBridgeLib.inf          |   51 +
>>   Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciHostBridgeLib/Bcm2711PciHostBridgeLibConstructor.c |  235 ++++
>>   Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciSegmentLib/PciSegmentLib.c                         | 1445 ++++++++++++++++++++
>>   Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciSegmentLib/PciSegmentLib.inf                       |   35 +
>>   10 files changed, 2078 insertions(+), 18 deletions(-)
>>   create mode 100644 Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciHostBridgeLib/Bcm2711PciHostBridgeLib.c
>>   create mode 100644 Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciHostBridgeLib/Bcm2711PciHostBridgeLib.inf
>>   create mode 100644 Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciHostBridgeLib/Bcm2711PciHostBridgeLibConstructor.c
>>   create mode 100644 Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciSegmentLib/PciSegmentLib.c
>>   create mode 100644 Silicon/Broadcom/Bcm27xx/Library/Bcm2711PciSegmentLib/PciSegmentLib.inf
>>
>> --
>> 2.21.0.windows.1
>>


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

end of thread, other threads:[~2019-12-13 17:51 UTC | newest]

Thread overview: 8+ messages (download: mbox.gz follow: Atom feed
-- links below jump to the message on this page --
2019-12-13 17:07 [edk2-platforms][PATCH v2 0/4] Platform/RPi4: Add PCIe and xHCI support Pete Batard
2019-12-13 17:07 ` [edk2-platforms][PATCH v2 1/4] Silicon/Bcm27xx: Add PCIe constants to Bcm2711.h Pete Batard
2019-12-13 17:07 ` [edk2-platforms][PATCH v2 2/4] Silicon/Bcm27xx: Add segment library to handle nonstandard ECAM Pete Batard
2019-12-13 17:07 ` [edk2-platforms][PATCH v2 3/4] Silicon/Bcm27xx: Add PCIe host bridge config library Pete Batard
2019-12-13 17:07 ` [edk2-platforms][PATCH v2 4/4] Platform/RPi4: Build the PCIe and xHCI drivers into the firmware Pete Batard
2019-12-13 17:14   ` Philippe Mathieu-Daudé
2019-12-13 17:40 ` [edk2-platforms][PATCH v2 0/4] Platform/RPi4: Add PCIe and xHCI support Ard Biesheuvel
2019-12-13 17:51   ` Pete Batard

This is a public inbox, see mirroring instructions
for how to clone and mirror all data and code used for this inbox