2015-04-10 09:14:58

by Gabriel FERNANDEZ

[permalink] [raw]
Subject: [PATCH v3 0/5] PCI: st: provide support for dw pcie

Changes in v3:
- Remove power management functions (was not fully tested)
- Remove configuration space range from dt binding
- Remove pci_common_init_dev() call in pcie-designware.c to avoid
default IO space declaration.

Changes in v2:
- comestic corrections in device tree binding
- add pci-st.c into MAINTAINERS
- remove st_pcie_ops structure to avoid another level of indirection
- remove nasty busy-loop
- remove useless test using virt_to_phys()
- move disable io support into dw-pcie driver

I don't change the st_pcie_abort_handler() function because abort handling
is masked during boot.


This patch-set introduces a STMicroelectronics PCIe controller.
It's based on designware PCIe driver.

Gabriel Fernandez (5):
ARM: STi: Kconfig update for PCIe support
PCI: st: Add Device Tree bindings for sti pcie
PCI: st: Provide support for the sti PCIe controller
pci: designware: remove pci_common_init_dev()
MAINTAINERS: Add pci-st.c to ARCH/STI architecture

Documentation/devicetree/bindings/pci/st-pcie.txt | 53 ++
MAINTAINERS | 1 +
arch/arm/mach-sti/Kconfig | 2 +
drivers/pci/host/Kconfig | 9 +
drivers/pci/host/Makefile | 1 +
drivers/pci/host/pci-st.c | 583 ++++++++++++++++++++++
drivers/pci/host/pcie-designware.c | 62 +--
drivers/pci/host/pcie-designware.h | 1 +
8 files changed, 682 insertions(+), 30 deletions(-)
create mode 100644 Documentation/devicetree/bindings/pci/st-pcie.txt
create mode 100644 drivers/pci/host/pci-st.c

--
1.9.1


2015-04-10 09:15:00

by Gabriel FERNANDEZ

[permalink] [raw]
Subject: [PATCH v3 1/5] ARM: STi: Kconfig update for PCIe support

Update Kconfig:
- MIGHT_HAVE_PCI
- PCI_DOMAINS

Signed-off-by: Fabrice Gasnier <[email protected]>
---
arch/arm/mach-sti/Kconfig | 2 ++
1 file changed, 2 insertions(+)

diff --git a/arch/arm/mach-sti/Kconfig b/arch/arm/mach-sti/Kconfig
index 3b1ac46..7f9b432 100644
--- a/arch/arm/mach-sti/Kconfig
+++ b/arch/arm/mach-sti/Kconfig
@@ -8,6 +8,8 @@ menuconfig ARCH_STI
select ARCH_HAS_RESET_CONTROLLER
select HAVE_ARM_SCU if SMP
select ARCH_REQUIRE_GPIOLIB
+ select PCI_DOMAINS if PCI
+ select MIGHT_HAVE_PCI
select ARM_ERRATA_754322
select ARM_ERRATA_764369 if SMP
select ARM_ERRATA_775420
--
1.9.1

2015-04-10 09:14:53

by Gabriel FERNANDEZ

[permalink] [raw]
Subject: [PATCH v3 2/5] PCI: st: Add Device Tree bindings for sti pcie

sti pcie is built around a Synopsis Designware PCIe IP.

Signed-off-by: Fabrice Gasnier <[email protected]>
Signed-off-by: Gabriel Fernandez <[email protected]>
---
Documentation/devicetree/bindings/pci/st-pcie.txt | 53 +++++++++++++++++++++++
1 file changed, 53 insertions(+)
create mode 100644 Documentation/devicetree/bindings/pci/st-pcie.txt

diff --git a/Documentation/devicetree/bindings/pci/st-pcie.txt b/Documentation/devicetree/bindings/pci/st-pcie.txt
new file mode 100644
index 0000000..25fcab3
--- /dev/null
+++ b/Documentation/devicetree/bindings/pci/st-pcie.txt
@@ -0,0 +1,53 @@
+STMicroelectronics STi PCIe controller
+
+This PCIe host controller is based on the Synopsis Designware PCIe IP
+and thus inherits all the common properties defined in designware-pcie.txt.
+
+Required properties:
+ - compatible: "st,stih407-pcie"
+ - reg: base address and length of the pcie controller, mem-window address
+ and length available to the controller.
+ - interrupts: A list of interrupt outputs of the controller. Must contain an
+ entry for each entry in the interrupt-names property.
+ - interrupt-names: Should be "msi". STi interrupt that is asserted when an
+ MSI is received.
+ - st,syscfg : should be a phandle of the syscfg node. Also contains syscfg
+ offset for IP configuration.
+ - resets, reset-names: the power-down and soft-reset lines of PCIe IP.
+ Associated names must be "powerdown" and "softreset".
+ - phys, phy-names: the phandle for the PHY device.
+ Associated name must be "pcie"
+
+Optional properties:
+ - reset-gpio: a GPIO spec to define which pin is connected to the bus reset.
+
+Example:
+
+pcie0: pcie@9b00000 {
+ compatible = "st,pcie", "snps,dw-pcie";
+ device_type = "pci";
+ reg = <0x09b00000 0x4000>, /* dbi cntrl registers */
+ <0x2fff0000 0x00010000>, /* configuration space */
+ <0x40000000 0x80000000>; /* lmi mem window */
+ reg-names = "dbi", "config", "mem-window";
+ st,syscfg = <&syscfg_core 0xd8 0xe0>;
+ #address-cells = <3>;
+ #size-cells = <2>;
+ ranges = <0x82000000 0 0x20000000 0x20000000 0 0x0FFF0000>; /* non-prefetchable memory */
+ num-lanes = <1>;
+ interrupts = <GIC_SPI 164 IRQ_TYPE_LEVEL_HIGH>;
+ interrupt-names = "msi";
+ #interrupt-cells = <1>;
+ interrupt-map-mask = <0 0 0 7>;
+ interrupt-map = <0 0 0 1 &intc GIC_SPI 160 IRQ_TYPE_LEVEL_HIGH>, /* INT A */
+ <0 0 0 2 &intc GIC_SPI 161 IRQ_TYPE_LEVEL_HIGH>, /* INT B */
+ <0 0 0 3 &intc GIC_SPI 162 IRQ_TYPE_LEVEL_HIGH>, /* INT C */
+ <0 0 0 4 &intc GIC_SPI 163 IRQ_TYPE_LEVEL_HIGH>; /* INT D */
+
+ resets = <&powerdown STIH407_PCIE0_POWERDOWN>,
+ <&softreset STIH407_PCIE0_SOFTRESET>;
+ reset-names = "powerdown",
+ "softreset";
+ phys = <&phy_port0 PHY_TYPE_PCIE>;
+ phy-names = "pcie";
+};
--
1.9.1

2015-04-10 09:15:16

by Gabriel FERNANDEZ

[permalink] [raw]
Subject: [PATCH v3 3/5] PCI: st: Provide support for the sti PCIe controller

sti pcie is built around a Synopsis Designware PCIe IP.

Signed-off-by: Fabrice Gasnier <[email protected]>
Signed-off-by: Gabriel Fernandez <[email protected]>
---
drivers/pci/host/Kconfig | 9 +
drivers/pci/host/Makefile | 1 +
drivers/pci/host/pci-st.c | 583 ++++++++++++++++++++++++++++++++++++++++++++++
3 files changed, 593 insertions(+)
create mode 100644 drivers/pci/host/pci-st.c

diff --git a/drivers/pci/host/Kconfig b/drivers/pci/host/Kconfig
index 7b892a9..af9f9212 100644
--- a/drivers/pci/host/Kconfig
+++ b/drivers/pci/host/Kconfig
@@ -106,4 +106,13 @@ config PCI_VERSATILE
bool "ARM Versatile PB PCI controller"
depends on ARCH_VERSATILE

+config PCI_ST
+ bool "ST PCIe controller"
+ depends on ARCH_STI || (ARM && COMPILE_TEST)
+ select PCIE_DW
+ help
+ Enable PCIe controller support on ST Socs. This controller is based
+ on Designware hardware and therefore the driver re-uses the
+ Designware core functions to implement the driver.
+
endmenu
diff --git a/drivers/pci/host/Makefile b/drivers/pci/host/Makefile
index e61d91c..97c6622 100644
--- a/drivers/pci/host/Makefile
+++ b/drivers/pci/host/Makefile
@@ -13,3 +13,4 @@ obj-$(CONFIG_PCIE_XILINX) += pcie-xilinx.o
obj-$(CONFIG_PCI_XGENE) += pci-xgene.o
obj-$(CONFIG_PCI_LAYERSCAPE) += pci-layerscape.o
obj-$(CONFIG_PCI_VERSATILE) += pci-versatile.o
+obj-$(CONFIG_PCI_ST) += pci-st.o
diff --git a/drivers/pci/host/pci-st.c b/drivers/pci/host/pci-st.c
new file mode 100644
index 0000000..1ff5ce2
--- /dev/null
+++ b/drivers/pci/host/pci-st.c
@@ -0,0 +1,583 @@
+/*
+ * Copyright (C) 2014 STMicroelectronics
+ *
+ * STMicroelectronics PCI express Driver for sti SoCs.
+ * ST PCIe IPs are built around a Synopsys IP Core.
+ *
+ * Author: Fabrice Gasnier <[email protected]>
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2, as
+ * published by the Free Software Foundation.
+ *
+ */
+
+#include <linux/delay.h>
+#include <linux/interrupt.h>
+#include <linux/mfd/syscon.h>
+#include <linux/module.h>
+#include <linux/of_address.h>
+#include <linux/of_gpio.h>
+#include <linux/of_pci.h>
+#include <linux/of_platform.h>
+#include <linux/phy/phy.h>
+#include <linux/regmap.h>
+#include <linux/reset.h>
+
+#include "pcie-designware.h"
+
+#define TRANSLATION_CONTROL 0x900
+/* Controls if area is inclusive or exclusive */
+#define RC_PASS_ADDR_RANGE BIT(1)
+
+/* Base of area reserved for config accesses. Fixed size of 64K. */
+#define CFG_BASE_ADDRESS 0x92c
+#define CFG_REGION_SIZE 65536
+#define CFG_SPACE1_OFFSET 0x1000
+
+/* First 4K of config space has this BDF (bus,device,function) */
+#define FUNC0_BDF_NUM 0x930
+
+/* Mem regions */
+#define IN0_MEM_ADDR_START 0x964
+#define IN0_MEM_ADDR_LIMIT 0x968
+#define IN1_MEM_ADDR_START 0x974
+#define IN1_MEM_ADDR_LIMIT 0x978
+
+/* This actually contains the LTSSM state machine state */
+#define PORT_LOGIC_DEBUG_REG_0 0x728
+
+/* LTSSM state machine values */
+#define DEBUG_REG_0_LTSSM_MASK 0x1f
+#define S_DETECT_QUIET 0x00
+#define S_DETECT_ACT 0x01
+#define S_POLL_ACTIVE 0x02
+#define S_POLL_COMPLIANCE 0x03
+#define S_POLL_CONFIG 0x04
+#define S_PRE_DETECT_QUIET 0x05
+#define S_DETECT_WAIT 0x06
+#define S_CFG_LINKWD_START 0x07
+#define S_CFG_LINKWD_ACEPT 0x08
+#define S_CFG_LANENUM_WAIT 0x09
+#define S_CFG_LANENUM_ACEPT 0x0A
+#define S_CFG_COMPLETE 0x0B
+#define S_CFG_IDLE 0x0C
+#define S_RCVRY_LOCK 0x0D
+#define S_RCVRY_SPEED 0x0E
+#define S_RCVRY_RCVRCFG 0x0F
+#define S_RCVRY_IDLE 0x10
+#define S_L0 0x11
+#define S_L0S 0x12
+#define S_L123_SEND_EIDLE 0x13
+#define S_L1_IDLE 0x14
+#define S_L2_IDLE 0x15
+#define S_L2_WAKE 0x16
+#define S_DISABLED_ENTRY 0x17
+#define S_DISABLED_IDLE 0x18
+#define S_DISABLED 0x19
+#define S_LPBK_ENTRY 0x1A
+#define S_LPBK_ACTIVE 0x1B
+#define S_LPBK_EXIT 0x1C
+#define S_LPBK_EXIT_TIMEOUT 0x1D
+#define S_HOT_RESET_ENTRY 0x1E
+#define S_HOT_RESET 0x1F
+
+/* syscfg bits */
+#define PCIE_SYS_INT BIT(5)
+#define PCIE_APP_REQ_RETRY_EN BIT(3)
+#define PCIE_APP_LTSSM_ENABLE BIT(2)
+#define PCIE_APP_INIT_RST BIT(1)
+#define PCIE_DEVICE_TYPE BIT(0)
+#define PCIE_DEFAULT_VAL PCIE_DEVICE_TYPE
+
+/* Time to wait between testing the link in msecs (hardware poll interval) */
+#define LINK_LOOP_DELAY_MS 1
+/* Total amount of time to wait for the link to come up in msecs */
+#define LINK_WAIT_MS 120
+#define LINK_LOOP_COUNT (LINK_WAIT_MS / LINK_LOOP_DELAY_MS)
+
+/* st,syscfg offsets */
+#define SYSCFG0_REG 1
+#define SYSCFG1_REG 2
+
+#define to_st_pcie(x) container_of(x, struct st_pcie, pp)
+
+/**
+ * struct st_pcie - private data of the controller
+ * @pp: designware pcie port
+ * @syscfg0: PCIe configuration 0 register, regmap offset
+ * @syscfg1: PCIe configuration 1 register, regmap offset
+ * @phy: associated pcie phy
+ * @lmi: memory made available to the controller
+ * @regmap: Syscfg registers bank in which PCIe port is configured
+ * @pwr: power control
+ * @rst: reset control
+ * @reset_gpio: optional reset gpio
+ * @config_window_start: start address of 64K config space area
+ */
+struct st_pcie {
+ struct pcie_port pp;
+ int syscfg0;
+ int syscfg1;
+ struct phy *phy;
+ struct resource *lmi;
+ struct regmap *regmap;
+ struct reset_control *pwr;
+ struct reset_control *rst;
+ int reset_gpio;
+ phys_addr_t config_window_start;
+};
+
+/*
+ * Function to test if the link is in an operational state or not. We must
+ * ensure the link is operational before we try to do a configuration access.
+ */
+static int st_pcie_link_up(struct pcie_port *pp)
+{
+ u32 status;
+ int link_up;
+ int count = 0;
+
+ /*
+ * We have to be careful here. This is used in config read/write,
+ * The higher levels switch off interrupts, so you cannot use
+ * jiffies to do a timeout, or reschedule
+ */
+ do {
+ /*
+ * What about L2? I think software intervention is
+ * required to get it out of L2, so in effect the link
+ * is down. Requires more work when/if we implement power
+ * management
+ */
+ status = readl_relaxed(pp->dbi_base + PORT_LOGIC_DEBUG_REG_0);
+ status &= DEBUG_REG_0_LTSSM_MASK;
+
+ link_up = (status == S_L0) || (status == S_L0S) ||
+ (status == S_L1_IDLE);
+
+ /*
+ * It can take some considerable time for the link to actually
+ * come up, caused by the PLLs. Experiments indicate it takes
+ * about 8ms to actually bring the link up, but this can vary
+ * considerably according to the specification. This code should
+ * allow sufficient time
+ */
+ if (!link_up)
+ mdelay(LINK_LOOP_DELAY_MS);
+
+ } while (!link_up && ++count < LINK_LOOP_COUNT);
+
+ return link_up;
+}
+
+/*
+ * On ARM platforms, we actually get a bus error returned when the PCIe IP
+ * returns a UR or CRS instead of an OK.
+ */
+static int st_pcie_abort_handler(unsigned long addr, unsigned int fsr,
+ struct pt_regs *regs)
+{
+ return 0;
+}
+
+/*
+ * The PCI express core IP expects the following arrangement on it's address
+ * bus (slv_haddr) when driving config cycles.
+ * bus_number [31:24]
+ * dev_number [23:19]
+ * func_number [18:16]
+ * unused [15:12]
+ * ext_reg_number [11:8]
+ * reg_number [7:2]
+ *
+ * Bits [15:12] are unused.
+ *
+ * In the glue logic there is a 64K region of address space that can be
+ * written/read to generate config cycles. The base address of this is
+ * controlled by CFG_BASE_ADDRESS. There are 8 16 bit registers called
+ * FUNC0_BDF_NUM to FUNC8_BDF_NUM. These split the bottom half of the 64K
+ * window into 8 regions at 4K boundaries. These control the bus,device and
+ * function number you are trying to talk to.
+ *
+ * The decision on whether to generate a type 0 or type 1 access is controlled
+ * by bits 15:12 of the address you write to. If they are zero, then a type 0
+ * is generated, if anything else it will be a type 1. Thus the bottom 4K
+ * region controlled by FUNC0_BDF_NUM can only generate type 0, all the others
+ * can only generate type 1.
+ *
+ * We only use FUNC0_BDF_NUM and FUNC1_BDF_NUM. Which one you use is selected
+ * by bit 12 of the address you write to. The selected register is then used
+ * for the top 16 bits of the slv_haddr to form the bus/dev/func, bit 15:12 are
+ * wired to zero, and bits 11:2 form the address of the register you want to
+ * read in config space.
+ *
+ * We always write FUNC0_BDF_NUM as a 32 bit write. So if we want type 1
+ * accesses we have to shift by 16 so in effect we are writing to FUNC1_BDF_NUM
+ */
+static inline u32 bdf_num(int bus, int devfn, int is_root_bus)
+{
+ return ((bus << 8) | devfn) << (is_root_bus ? 0 : 16);
+}
+
+static int st_pcie_rd_other_conf(struct pcie_port *pp, struct pci_bus *bus,
+ unsigned int devfn, int where, int size,
+ u32 *val)
+{
+ int ret;
+ u32 bdf, addr;
+
+ addr = where & ~0x3;
+ bdf = bdf_num(bus->number, devfn, pci_is_root_bus(bus));
+
+ /* Set the config packet devfn */
+ writel_relaxed(bdf, pp->dbi_base + FUNC0_BDF_NUM);
+ readl_relaxed(pp->dbi_base + FUNC0_BDF_NUM);
+
+ if (bus->parent->number == pp->root_bus_nr)
+ ret = dw_pcie_cfg_read(pp->va_cfg0_base + addr, where, size,
+ val);
+ else
+ ret = dw_pcie_cfg_read(pp->va_cfg1_base + addr, where, size,
+ val);
+ return ret;
+}
+
+static int st_pcie_wr_other_conf(struct pcie_port *pp, struct pci_bus *bus,
+ unsigned int devfn, int where, int size,
+ u32 val)
+{
+ int ret;
+ u32 bdf, addr;
+
+ addr = where & ~0x3;
+ bdf = bdf_num(bus->number, devfn, pci_is_root_bus(bus));
+
+ /* Set the config packet devfn */
+ writel_relaxed(bdf, pp->dbi_base + FUNC0_BDF_NUM);
+ readl_relaxed(pp->dbi_base + FUNC0_BDF_NUM);
+
+ if (bus->parent->number == pp->root_bus_nr)
+ ret = dw_pcie_cfg_write(pp->va_cfg0_base + addr, where, size,
+ val);
+ else
+ ret = dw_pcie_cfg_write(pp->va_cfg1_base + addr, where, size,
+ val);
+ return ret;
+}
+
+static void st_pcie_board_reset(struct pcie_port *pp)
+{
+ struct st_pcie *pcie = to_st_pcie(pp);
+
+ if (!gpio_is_valid(pcie->reset_gpio))
+ return;
+
+ if (gpio_direction_output(pcie->reset_gpio, 0)) {
+ dev_err(pp->dev, "Cannot set PERST# (gpio %u) to output\n",
+ pcie->reset_gpio);
+ return;
+ }
+
+ /* From PCIe spec */
+ msleep(2);
+ gpio_direction_output(pcie->reset_gpio, 1);
+
+ /*
+ * PCIe specification states that you should not issue any config
+ * requests until 100ms after asserting reset, so we enforce that here
+ */
+ msleep(100);
+}
+
+static void st_pcie_hw_setup(struct pcie_port *pp)
+{
+ struct st_pcie *pcie = to_st_pcie(pp);
+
+ dw_pcie_setup_rc(pp);
+
+ /* Set up the config window to the top of the PCI address space */
+ writel_relaxed(pcie->config_window_start,
+ pp->dbi_base + CFG_BASE_ADDRESS);
+
+ /*
+ * Open up memory to the PCI controller. We could do slightly
+ * better than this and exclude the kernel text segment and bss etc.
+ * They are base/limit registers so can be of arbitrary alignment
+ * presumably
+ */
+ writel_relaxed(pcie->lmi->start, pp->dbi_base + IN0_MEM_ADDR_START);
+ writel_relaxed(pcie->lmi->end, pp->dbi_base + IN0_MEM_ADDR_LIMIT);
+
+ /* Disable the 2nd region */
+ writel_relaxed(~0, pp->dbi_base + IN1_MEM_ADDR_START);
+ writel_relaxed(0, pp->dbi_base + IN1_MEM_ADDR_LIMIT);
+
+ writel_relaxed(RC_PASS_ADDR_RANGE, pp->dbi_base + TRANSLATION_CONTROL);
+
+ /* Now assert the board level reset to the other PCIe device */
+ st_pcie_board_reset(pp);
+}
+
+static irqreturn_t st_pcie_msi_irq_handler(int irq, void *arg)
+{
+ struct pcie_port *pp = arg;
+
+ return dw_handle_msi_irq(pp);
+}
+
+static int st_pcie_init(struct pcie_port *pp)
+{
+ struct st_pcie *pcie = to_st_pcie(pp);
+ int ret;
+
+ ret = reset_control_deassert(pcie->pwr);
+ if (ret) {
+ dev_err(pp->dev, "unable to bring out of powerdown\n");
+ return ret;
+ }
+
+ ret = reset_control_deassert(pcie->rst);
+ if (ret) {
+ dev_err(pp->dev, "unable to bring out of softreset\n");
+ return ret;
+ }
+
+ /* Set device type : Root Complex */
+ ret = regmap_write(pcie->regmap, pcie->syscfg0, PCIE_DEVICE_TYPE);
+ if (ret < 0) {
+ dev_err(pp->dev, "unable to set device type\n");
+ return ret;
+ }
+
+ usleep_range(1000, 2000);
+ return ret;
+}
+
+static int st_pcie_enable_ltssm(struct pcie_port *pp)
+{
+ struct st_pcie *pcie = to_st_pcie(pp);
+
+ return regmap_update_bits(pcie->regmap, pcie->syscfg1,
+ PCIE_APP_LTSSM_ENABLE, PCIE_APP_LTSSM_ENABLE);
+}
+
+static int st_pcie_disable_ltssm(struct pcie_port *pp)
+{
+ struct st_pcie *pcie = to_st_pcie(pp);
+
+ return regmap_update_bits(pcie->regmap, pcie->syscfg1,
+ PCIE_APP_LTSSM_ENABLE, 0);
+}
+
+static void st_pcie_host_init(struct pcie_port *pp)
+{
+ struct st_pcie *pcie = to_st_pcie(pp);
+ int err;
+
+ /*
+ * We have to initialise the PCIe cell on some hardware before we can
+ * talk to the phy
+ */
+ err = st_pcie_init(pp);
+ if (err)
+ return;
+
+ err = st_pcie_disable_ltssm(pp);
+ if (err) {
+ dev_err(pp->dev, "disable ltssm failed, %d\n", err);
+ return;
+ }
+
+ /* Now init the associated miphy */
+ err = phy_init(pcie->phy);
+ if (err < 0) {
+ dev_err(pp->dev, "Cannot init PHY: %d\n", err);
+ return;
+ }
+
+ /* Now do all the register poking */
+ st_pcie_hw_setup(pp);
+
+ /* Re-enable the link */
+ err = st_pcie_enable_ltssm(pp);
+ if (err)
+ dev_err(pp->dev, "enable ltssm failed, %d\n", err);
+
+ if (IS_ENABLED(CONFIG_PCI_MSI))
+ dw_pcie_msi_init(pp);
+}
+
+static struct pcie_host_ops st_pcie_host_ops = {
+ .rd_other_conf = st_pcie_rd_other_conf,
+ .wr_other_conf = st_pcie_wr_other_conf,
+ .link_up = st_pcie_link_up,
+ .host_init = st_pcie_host_init,
+};
+
+static const struct of_device_id st_pcie_of_match[] = {
+ { .compatible = "st,pcie", },
+ { },
+};
+
+static int st_pcie_probe(struct platform_device *pdev)
+{
+ struct resource *res;
+ struct st_pcie *pcie;
+ struct device_node *np = pdev->dev.of_node;
+ struct pcie_port *pp;
+ int ret;
+
+ pcie = devm_kzalloc(&pdev->dev, sizeof(*pcie), GFP_KERNEL);
+ if (!pcie)
+ return -ENOMEM;
+
+ memset(pcie, 0, sizeof(*pcie));
+
+ pp = &pcie->pp;
+ pp->dev = &pdev->dev;
+
+ /* mem regions */
+ res = platform_get_resource_byname(pdev, IORESOURCE_MEM, "dbi");
+ pp->dbi_base = devm_ioremap_resource(&pdev->dev, res);
+ if (IS_ERR(pp->dbi_base))
+ return PTR_ERR(pp->dbi_base);
+
+ res = platform_get_resource_byname(pdev, IORESOURCE_MEM, "config");
+ if (!res)
+ return -ENXIO;
+
+ /* Check that this has sensible values */
+ if ((resource_size(res) != CFG_REGION_SIZE) ||
+ (res->start & (CFG_REGION_SIZE - 1))) {
+ dev_err(&pdev->dev, "Invalid config space properties\n");
+ return -EINVAL;
+ }
+ pcie->config_window_start = res->start;
+
+ pp->va_cfg0_base = devm_ioremap_resource(&pdev->dev, res);
+ if (IS_ERR(pp->va_cfg0_base))
+ return PTR_ERR(pp->va_cfg0_base);
+ pp->va_cfg1_base = pp->va_cfg0_base + CFG_SPACE1_OFFSET;
+
+ pcie->lmi = platform_get_resource_byname(pdev, IORESOURCE_MEM,
+ "mem-window");
+ if (!pcie->lmi)
+ return -ENXIO;
+
+ /* regmap registers for PCIe IP configuration */
+ pcie->regmap = syscon_regmap_lookup_by_phandle(np, "st,syscfg");
+ if (IS_ERR(pcie->regmap)) {
+ dev_err(&pdev->dev, "No syscfg phandle specified\n");
+ return PTR_ERR(pcie->regmap);
+ }
+
+ ret = of_property_read_u32_index(np, "st,syscfg", SYSCFG0_REG,
+ &pcie->syscfg0);
+ if (ret) {
+ dev_err(&pdev->dev, "can't get syscfg0 offset (%d)\n", ret);
+ return ret;
+ }
+
+ ret = of_property_read_u32_index(np, "st,syscfg", SYSCFG1_REG,
+ &pcie->syscfg1);
+ if (ret) {
+ dev_err(&pdev->dev, "can't get syscfg1 offset (%d)\n", ret);
+ return ret;
+ }
+
+ /* powerdown / resets */
+ pcie->pwr = devm_reset_control_get(&pdev->dev, "powerdown");
+ if (IS_ERR(pcie->pwr)) {
+ dev_err(&pdev->dev, "powerdown reset control not defined\n");
+ return PTR_ERR(pcie->pwr);
+ }
+
+ pcie->rst = devm_reset_control_get(&pdev->dev, "softreset");
+ if (IS_ERR(pcie->rst)) {
+ dev_err(&pdev->dev, "Soft reset control not defined\n");
+ return PTR_ERR(pcie->pwr);
+ }
+
+ /* phy */
+ pcie->phy = devm_phy_get(&pdev->dev, "pcie");
+ if (IS_ERR(pcie->phy)) {
+ dev_err(&pdev->dev, "no PHY configured\n");
+ return PTR_ERR(pcie->phy);
+ }
+
+ /* Claim the GPIO for PRST# if available */
+ pcie->reset_gpio = of_get_named_gpio(np, "reset-gpio", 0);
+ if (!gpio_is_valid(pcie->reset_gpio))
+ dev_dbg(&pdev->dev, "No reset-gpio configured\n");
+ else {
+ ret = devm_gpio_request(&pdev->dev,
+ pcie->reset_gpio,
+ "PCIe reset");
+ if (ret) {
+ dev_err(&pdev->dev, "Cannot request reset-gpio %d\n",
+ pcie->reset_gpio);
+ return ret;
+ }
+ }
+
+ if (IS_ENABLED(CONFIG_PCI_MSI)) {
+ pp->msi_irq = platform_get_irq_byname(pdev, "msi");
+ if (pp->msi_irq <= 0) {
+ dev_err(&pdev->dev, "failed to get MSI irq\n");
+ return -ENODEV;
+ }
+
+ ret = devm_request_irq(&pdev->dev, pp->msi_irq,
+ st_pcie_msi_irq_handler,
+ IRQF_SHARED, "st-pcie-msi", pp);
+ if (ret) {
+ dev_err(&pdev->dev, "failed to request MSI irq\n");
+ return -ENODEV;
+ }
+ }
+
+ if (IS_ENABLED(CONFIG_ARM)) {
+ /*
+ * We have to hook the abort handler so that we can intercept
+ * bus errors when doing config read/write that return UR,
+ * which is flagged up as a bus error
+ */
+ hook_fault_code(16+6, st_pcie_abort_handler, SIGBUS, 0,
+ "imprecise external abort");
+ }
+
+ pp->root_bus_nr = -1;
+ pp->ops = &st_pcie_host_ops;
+
+ ret = dw_pcie_host_init(pp);
+ if (ret) {
+ dev_err(&pdev->dev, "failed to initialize host\n");
+ return ret;
+ }
+
+ platform_set_drvdata(pdev, pcie);
+
+ dev_info(&pdev->dev, "Initialized\n");
+ return 0;
+}
+
+MODULE_DEVICE_TABLE(of, st_pcie_of_match);
+
+static struct platform_driver st_pcie_driver = {
+ .driver = {
+ .name = "st-pcie",
+ .of_match_table = st_pcie_of_match,
+ },
+};
+
+/* ST PCIe driver does not allow module unload */
+static int __init pcie_init(void)
+{
+ return platform_driver_probe(&st_pcie_driver, st_pcie_probe);
+}
+device_initcall(pcie_init);
+
+MODULE_AUTHOR("Fabrice Gasnier <[email protected]>");
+MODULE_DESCRIPTION("PCI express Driver for ST SoCs");
+MODULE_LICENSE("GPL v2");
--
1.9.1

2015-04-10 09:17:58

by Gabriel FERNANDEZ

[permalink] [raw]
Subject: [PATCH v3 4/5] pci: designware: remove pci_common_init_dev()

Call directly pci_*() instead of using pci_common_init_dev().
Enforce error handling in probe.
It also allows st pcie driver not to declare IO space:
pci_common_init_dev() is assigning one by default.

Signed-off-by: Fabrice Gasnier <[email protected]>
---
drivers/pci/host/pcie-designware.c | 62 ++++++++++++++++++++------------------
drivers/pci/host/pcie-designware.h | 1 +
2 files changed, 33 insertions(+), 30 deletions(-)

diff --git a/drivers/pci/host/pcie-designware.c b/drivers/pci/host/pcie-designware.c
index 1f4ea6f..d4b1bf7 100644
--- a/drivers/pci/host/pcie-designware.c
+++ b/drivers/pci/host/pcie-designware.c
@@ -67,8 +67,6 @@
#define PCIE_ATU_FUNC(x) (((x) & 0x7) << 16)
#define PCIE_ATU_UPPER_TARGET 0x91C

-static struct hw_pci dw_pci;
-
static unsigned long global_io_offset;

static inline struct pcie_port *sys_to_pcie(struct pci_sys_data *sys)
@@ -342,6 +340,9 @@ static const struct irq_domain_ops msi_domain_ops = {
.map = dw_pcie_msi_map,
};

+static int dw_pcie_setup(struct pci_sys_data *sys);
+static struct pci_bus *dw_pcie_scan_bus(struct pci_sys_data *sys);
+
int __init dw_pcie_host_init(struct pcie_port *pp)
{
struct device_node *np = pp->dev->of_node;
@@ -352,6 +353,9 @@ int __init dw_pcie_host_init(struct pcie_port *pp)
u32 val, na, ns;
const __be32 *addrp;
int i, index, ret;
+ struct list_head *resources = &pp->sysdata.resources;
+
+ INIT_LIST_HEAD(resources);

/* Find the address cell size and the number of cells in order to get
* the untranslated address.
@@ -504,13 +508,17 @@ int __init dw_pcie_host_init(struct pcie_port *pp)

#ifdef CONFIG_PCI_MSI
dw_pcie_msi_chip.dev = pp->dev;
- dw_pci.msi_ctrl = &dw_pcie_msi_chip;
+ pp->sysdata.msi_ctrl = &dw_pcie_msi_chip;
#endif

- dw_pci.nr_controllers = 1;
- dw_pci.private_data = (void **)&pp;
+ pp->sysdata.private_data = pp;

- pci_common_init_dev(pp->dev, &dw_pci);
+ ret = dw_pcie_setup(&pp->sysdata);
+ if (ret)
+ return ret;
+
+ if (!dw_pcie_scan_bus(&pp->sysdata))
+ return -ENXIO;

return 0;
}
@@ -701,15 +709,19 @@ static struct pci_ops dw_pcie_ops = {
.write = dw_pcie_wr_conf,
};

-static int dw_pcie_setup(int nr, struct pci_sys_data *sys)
+static int dw_pcie_setup(struct pci_sys_data *sys)
{
struct pcie_port *pp;
+ int err;

pp = sys_to_pcie(sys);

if (global_io_offset < SZ_1M && pp->io_size > 0) {
sys->io_offset = global_io_offset - pp->io_bus_addr;
- pci_ioremap_io(global_io_offset, pp->io_base);
+ err = pci_ioremap_io(global_io_offset, pp->io_base);
+ if (err)
+ return err;
+
global_io_offset += SZ_64K;
pci_add_resource_offset(&sys->resources, &pp->io,
sys->io_offset);
@@ -719,10 +731,10 @@ static int dw_pcie_setup(int nr, struct pci_sys_data *sys)
pci_add_resource_offset(&sys->resources, &pp->mem, sys->mem_offset);
pci_add_resource(&sys->resources, &pp->busn);

- return 1;
+ return 0;
}

-static struct pci_bus *dw_pcie_scan_bus(int nr, struct pci_sys_data *sys)
+static struct pci_bus *dw_pcie_scan_bus(struct pci_sys_data *sys)
{
struct pci_bus *bus;
struct pcie_port *pp = sys_to_pcie(sys);
@@ -738,27 +750,13 @@ static struct pci_bus *dw_pcie_scan_bus(int nr, struct pci_sys_data *sys)
if (bus && pp->ops->scan_bus)
pp->ops->scan_bus(pp);

- return bus;
-}
-
-static int dw_pcie_map_irq(const struct pci_dev *dev, u8 slot, u8 pin)
-{
- struct pcie_port *pp = sys_to_pcie(dev->bus->sysdata);
- int irq;
-
- irq = of_irq_parse_and_map_pci(dev, slot, pin);
- if (!irq)
- irq = pp->irq;
+ pci_fixup_irqs(pci_common_swizzle, of_irq_parse_and_map_pci);
+ pci_assign_unassigned_bus_resources(bus);
+ pci_bus_add_devices(bus);

- return irq;
+ return bus;
}

-static struct hw_pci dw_pci = {
- .setup = dw_pcie_setup,
- .scan = dw_pcie_scan_bus,
- .map_irq = dw_pcie_map_irq,
-};
-
void dw_pcie_setup_rc(struct pcie_port *pp)
{
u32 val;
@@ -822,8 +820,12 @@ void dw_pcie_setup_rc(struct pcie_port *pp)
/* setup command register */
dw_pcie_readl_rc(pp, PCI_COMMAND, &val);
val &= 0xffff0000;
- val |= PCI_COMMAND_IO | PCI_COMMAND_MEMORY |
- PCI_COMMAND_MASTER | PCI_COMMAND_SERR;
+
+ if (!pp->io_size)
+ val |= PCI_COMMAND_IO;
+
+ val |= PCI_COMMAND_MEMORY | PCI_COMMAND_MASTER | PCI_COMMAND_SERR;
+
dw_pcie_writel_rc(pp, val, PCI_COMMAND);
}

diff --git a/drivers/pci/host/pcie-designware.h b/drivers/pci/host/pcie-designware.h
index d0bbd27..45bc2c2 100644
--- a/drivers/pci/host/pcie-designware.h
+++ b/drivers/pci/host/pcie-designware.h
@@ -46,6 +46,7 @@ struct pcie_port {
struct resource io;
struct resource mem;
struct resource busn;
+ struct pci_sys_data sysdata;
int irq;
u32 lanes;
struct pcie_host_ops *ops;
--
1.9.1

2015-04-10 09:14:55

by Gabriel FERNANDEZ

[permalink] [raw]
Subject: [PATCH v3 5/5] MAINTAINERS: Add pci-st.c to ARCH/STI architecture

This patch adds the pci-st.c pci driver found on STMicroelectronics
SoC's into the STI arch section of the maintainers file.

Signed-off-by: Gabriel Fernandez <[email protected]>
---
MAINTAINERS | 1 +
1 file changed, 1 insertion(+)

diff --git a/MAINTAINERS b/MAINTAINERS
index efbcb50..4639d2d 100644
--- a/MAINTAINERS
+++ b/MAINTAINERS
@@ -1468,6 +1468,7 @@ F: drivers/clocksource/arm_global_timer.c
F: drivers/i2c/busses/i2c-st.c
F: drivers/media/rc/st_rc.c
F: drivers/mmc/host/sdhci-st.c
+F: drivers/pci/host/pci-st.c
F: drivers/phy/phy-stih407-usb.c
F: drivers/phy/phy-stih41x-usb.c
F: drivers/pinctrl/pinctrl-st.c
--
1.9.1

2015-04-11 10:18:12

by Paul Bolle

[permalink] [raw]
Subject: Re: [PATCH v3 3/5] PCI: st: Provide support for the sti PCIe controller

Something I didn't spot in my first look at this patch.

On Fri, 2015-04-10 at 11:12 +0200, Gabriel FERNANDEZ wrote:
> --- a/drivers/pci/host/Kconfig
> +++ b/drivers/pci/host/Kconfig
>
> +config PCI_ST
> + bool "ST PCIe controller"
> + depends on ARCH_STI || (ARM && COMPILE_TEST)
> + select PCIE_DW
> + help
> + Enable PCIe controller support on ST Socs. This controller is based
> + on Designware hardware and therefore the driver re-uses the
> + Designware core functions to implement the driver.

You can't have ARCH_STI without ARM, so ARM will always be set if this
driver is enabled. Correct?

> --- /dev/null
> +++ b/drivers/pci/host/pci-st.c

> + if (IS_ENABLED(CONFIG_ARM)) {
> + /*
> + * We have to hook the abort handler so that we can intercept
> + * bus errors when doing config read/write that return UR,
> + * which is flagged up as a bus error
> + */
> + hook_fault_code(16+6, st_pcie_abort_handler, SIGBUS, 0,
> + "imprecise external abort");
> + }

So, unless I'm missing something obvious here, IS_ENABLED(CONFIG_ARM)
will always evaluate to 1. Can't that test be dropped?


Paul Bolle

2015-04-11 14:56:40

by Arnd Bergmann

[permalink] [raw]
Subject: Re: [PATCH v3 3/5] PCI: st: Provide support for the sti PCIe controller

On Saturday 11 April 2015 12:17:57 Paul Bolle wrote:
> Something I didn't spot in my first look at this patch.
>
> On Fri, 2015-04-10 at 11:12 +0200, Gabriel FERNANDEZ wrote:
> > --- a/drivers/pci/host/Kconfig
> > +++ b/drivers/pci/host/Kconfig
> >
> > +config PCI_ST
> > + bool "ST PCIe controller"
> > + depends on ARCH_STI || (ARM && COMPILE_TEST)
> > + select PCIE_DW
> > + help
> > + Enable PCIe controller support on ST Socs. This controller is based
> > + on Designware hardware and therefore the driver re-uses the
> > + Designware core functions to implement the driver.
>
> You can't have ARCH_STI without ARM, so ARM will always be set if this
> driver is enabled. Correct?

Right, though the ARM dependency could soon be dropped, once the PCIE_DW
driver can use generic infrastructure in the few places it relies on
ARM specific code today.

> > --- /dev/null
> > +++ b/drivers/pci/host/pci-st.c
>
> > + if (IS_ENABLED(CONFIG_ARM)) {
> > + /*
> > + * We have to hook the abort handler so that we can intercept
> > + * bus errors when doing config read/write that return UR,
> > + * which is flagged up as a bus error
> > + */
> > + hook_fault_code(16+6, st_pcie_abort_handler, SIGBUS, 0,
> > + "imprecise external abort");
> > + }
>
> So, unless I'm missing something obvious here, IS_ENABLED(CONFIG_ARM)
> will always evaluate to 1. Can't that test be dropped?

I would leave it in, as it's quite likely to get reused with ARM64 at some
point in the future (no, I don't know anything about ST's product plans,
but everybody seems to be doing this).

Arnd

2015-04-13 07:35:39

by Gabriel Fernandez

[permalink] [raw]
Subject: Re: [PATCH v3 3/5] PCI: st: Provide support for the sti PCIe controller

Hi

Thanks for reviewing.

On 11 April 2015 at 16:55, Arnd Bergmann <[email protected]> wrote:
> On Saturday 11 April 2015 12:17:57 Paul Bolle wrote:
>> Something I didn't spot in my first look at this patch.
>>
>> On Fri, 2015-04-10 at 11:12 +0200, Gabriel FERNANDEZ wrote:
>> > --- a/drivers/pci/host/Kconfig
>> > +++ b/drivers/pci/host/Kconfig
>> >
>> > +config PCI_ST
>> > + bool "ST PCIe controller"
>> > + depends on ARCH_STI || (ARM && COMPILE_TEST)
>> > + select PCIE_DW
>> > + help
>> > + Enable PCIe controller support on ST Socs. This controller is based
>> > + on Designware hardware and therefore the driver re-uses the
>> > + Designware core functions to implement the driver.
>>
>> You can't have ARCH_STI without ARM, so ARM will always be set if this
>> driver is enabled. Correct?
>
> Right, though the ARM dependency could soon be dropped, once the PCIE_DW
> driver can use generic infrastructure in the few places it relies on
> ARM specific code today.
>
>> > --- /dev/null
>> > +++ b/drivers/pci/host/pci-st.c
>>
>> > + if (IS_ENABLED(CONFIG_ARM)) {
>> > + /*
>> > + * We have to hook the abort handler so that we can intercept
>> > + * bus errors when doing config read/write that return UR,
>> > + * which is flagged up as a bus error
>> > + */
>> > + hook_fault_code(16+6, st_pcie_abort_handler, SIGBUS, 0,
>> > + "imprecise external abort");
>> > + }
>>
>> So, unless I'm missing something obvious here, IS_ENABLED(CONFIG_ARM)
>> will always evaluate to 1. Can't that test be dropped?
>
> I would leave it in, as it's quite likely to get reused with ARM64 at some
> point in the future (no, I don't know anything about ST's product plans,
> but everybody seems to be doing this).
>
> Arnd

Yes i agree with that.

Gabriel

2015-05-05 21:42:36

by Bjorn Helgaas

[permalink] [raw]
Subject: Re: [PATCH v3 5/5] MAINTAINERS: Add pci-st.c to ARCH/STI architecture

On Fri, Apr 10, 2015 at 11:12:48AM +0200, Gabriel FERNANDEZ wrote:
> This patch adds the pci-st.c pci driver found on STMicroelectronics
> SoC's into the STI arch section of the maintainers file.
>
> Signed-off-by: Gabriel Fernandez <[email protected]>

I'd like an ack from the current maintainers:

ARM/STI ARCHITECTURE
M: Srinivas Kandagatla <[email protected]>
M: Maxime Coquelin <[email protected]>
M: Patrice Chotard <[email protected]>

that they're OK with taking on this additional file.

> ---
> MAINTAINERS | 1 +
> 1 file changed, 1 insertion(+)
>
> diff --git a/MAINTAINERS b/MAINTAINERS
> index efbcb50..4639d2d 100644
> --- a/MAINTAINERS
> +++ b/MAINTAINERS
> @@ -1468,6 +1468,7 @@ F: drivers/clocksource/arm_global_timer.c
> F: drivers/i2c/busses/i2c-st.c
> F: drivers/media/rc/st_rc.c
> F: drivers/mmc/host/sdhci-st.c
> +F: drivers/pci/host/pci-st.c
> F: drivers/phy/phy-stih407-usb.c
> F: drivers/phy/phy-stih41x-usb.c
> F: drivers/pinctrl/pinctrl-st.c
> --
> 1.9.1
>

2015-05-05 22:09:17

by Bjorn Helgaas

[permalink] [raw]
Subject: Re: [PATCH v3 2/5] PCI: st: Add Device Tree bindings for sti pcie

On Fri, Apr 10, 2015 at 11:12:45AM +0200, Gabriel FERNANDEZ wrote:
> sti pcie is built around a Synopsis Designware PCIe IP.
>
> Signed-off-by: Fabrice Gasnier <[email protected]>
> Signed-off-by: Gabriel Fernandez <[email protected]>

Arnd, Rob, can you ack this?

> ---
> Documentation/devicetree/bindings/pci/st-pcie.txt | 53 +++++++++++++++++++++++
> 1 file changed, 53 insertions(+)
> create mode 100644 Documentation/devicetree/bindings/pci/st-pcie.txt
>
> diff --git a/Documentation/devicetree/bindings/pci/st-pcie.txt b/Documentation/devicetree/bindings/pci/st-pcie.txt
> new file mode 100644
> index 0000000..25fcab3
> --- /dev/null
> +++ b/Documentation/devicetree/bindings/pci/st-pcie.txt
> @@ -0,0 +1,53 @@
> +STMicroelectronics STi PCIe controller
> +
> +This PCIe host controller is based on the Synopsis Designware PCIe IP
> +and thus inherits all the common properties defined in designware-pcie.txt.
> +
> +Required properties:
> + - compatible: "st,stih407-pcie"
> + - reg: base address and length of the pcie controller, mem-window address
> + and length available to the controller.
> + - interrupts: A list of interrupt outputs of the controller. Must contain an
> + entry for each entry in the interrupt-names property.
> + - interrupt-names: Should be "msi". STi interrupt that is asserted when an
> + MSI is received.
> + - st,syscfg : should be a phandle of the syscfg node. Also contains syscfg
> + offset for IP configuration.
> + - resets, reset-names: the power-down and soft-reset lines of PCIe IP.
> + Associated names must be "powerdown" and "softreset".
> + - phys, phy-names: the phandle for the PHY device.
> + Associated name must be "pcie"
> +
> +Optional properties:
> + - reset-gpio: a GPIO spec to define which pin is connected to the bus reset.
> +
> +Example:
> +
> +pcie0: pcie@9b00000 {
> + compatible = "st,pcie", "snps,dw-pcie";
> + device_type = "pci";
> + reg = <0x09b00000 0x4000>, /* dbi cntrl registers */
> + <0x2fff0000 0x00010000>, /* configuration space */
> + <0x40000000 0x80000000>; /* lmi mem window */
> + reg-names = "dbi", "config", "mem-window";
> + st,syscfg = <&syscfg_core 0xd8 0xe0>;
> + #address-cells = <3>;
> + #size-cells = <2>;
> + ranges = <0x82000000 0 0x20000000 0x20000000 0 0x0FFF0000>; /* non-prefetchable memory */
> + num-lanes = <1>;
> + interrupts = <GIC_SPI 164 IRQ_TYPE_LEVEL_HIGH>;
> + interrupt-names = "msi";
> + #interrupt-cells = <1>;
> + interrupt-map-mask = <0 0 0 7>;
> + interrupt-map = <0 0 0 1 &intc GIC_SPI 160 IRQ_TYPE_LEVEL_HIGH>, /* INT A */
> + <0 0 0 2 &intc GIC_SPI 161 IRQ_TYPE_LEVEL_HIGH>, /* INT B */
> + <0 0 0 3 &intc GIC_SPI 162 IRQ_TYPE_LEVEL_HIGH>, /* INT C */
> + <0 0 0 4 &intc GIC_SPI 163 IRQ_TYPE_LEVEL_HIGH>; /* INT D */
> +
> + resets = <&powerdown STIH407_PCIE0_POWERDOWN>,
> + <&softreset STIH407_PCIE0_SOFTRESET>;
> + reset-names = "powerdown",
> + "softreset";
> + phys = <&phy_port0 PHY_TYPE_PCIE>;
> + phy-names = "pcie";
> +};
> --
> 1.9.1
>

2015-05-05 22:17:01

by Bjorn Helgaas

[permalink] [raw]
Subject: Re: [PATCH v3 3/5] PCI: st: Provide support for the sti PCIe controller

On Fri, Apr 10, 2015 at 11:12:46AM +0200, Gabriel FERNANDEZ wrote:
> sti pcie is built around a Synopsis Designware PCIe IP.
>
> Signed-off-by: Fabrice Gasnier <[email protected]>
> Signed-off-by: Gabriel Fernandez <[email protected]>

> +/* ST PCIe driver does not allow module unload */

Is there something that prevents module unload, or is it just untested?

> +static int __init pcie_init(void)
> +{
> + return platform_driver_probe(&st_pcie_driver, st_pcie_probe);
> +}
> +device_initcall(pcie_init);

Can you use module_platform_driver_probe() or module_init() here?

> +MODULE_AUTHOR("Fabrice Gasnier <[email protected]>");
> +MODULE_DESCRIPTION("PCI express Driver for ST SoCs");
> +MODULE_LICENSE("GPL v2");
> --
> 1.9.1
>

2015-05-06 06:47:15

by Maxime Coquelin

[permalink] [raw]
Subject: Re: [PATCH v3 5/5] MAINTAINERS: Add pci-st.c to ARCH/STI architecture

Hello Bjorn,

On 05/05/2015 11:42 PM, Bjorn Helgaas wrote:
> On Fri, Apr 10, 2015 at 11:12:48AM +0200, Gabriel FERNANDEZ wrote:
>> This patch adds the pci-st.c pci driver found on STMicroelectronics
>> SoC's into the STI arch section of the maintainers file.
>>
>> Signed-off-by: Gabriel Fernandez <[email protected]>
> I'd like an ack from the current maintainers:
>
> ARM/STI ARCHITECTURE
> M: Srinivas Kandagatla <[email protected]>
> M: Maxime Coquelin <[email protected]>
> M: Patrice Chotard <[email protected]>
>
> that they're OK with taking on this additional file.
Yes, you can add my:
Acked-by: Maxime Coquelin <[email protected]>

Thanks,
Maxime

2015-05-06 09:14:31

by Gabriel Fernandez

[permalink] [raw]
Subject: Re: [PATCH v3 3/5] PCI: st: Provide support for the sti PCIe controller

Hi Bjorn,

On 6 May 2015 at 00:16, Bjorn Helgaas <[email protected]> wrote:
> On Fri, Apr 10, 2015 at 11:12:46AM +0200, Gabriel FERNANDEZ wrote:
>> sti pcie is built around a Synopsis Designware PCIe IP.
>>
>> Signed-off-by: Fabrice Gasnier <[email protected]>
>> Signed-off-by: Gabriel Fernandez <[email protected]>
>
>> +/* ST PCIe driver does not allow module unload */
>
> Is there something that prevents module unload, or is it just untested?
>
Yes we haven't tested

>> +static int __init pcie_init(void)
>> +{
>> + return platform_driver_probe(&st_pcie_driver, st_pcie_probe);
>> +}
>> +device_initcall(pcie_init);
>
> Can you use module_platform_driver_probe() or module_init() here?
>

Yes we can use module_init() here.

By the way if figure out i removed __init attribute on st_pcie_probe()
in previous version to follow Arnd's remark.
But st_pcie_probe calls hook_fault_code() that has __init attribute.
So I think we need to keep __init for probe routine ?
Also, we have to restrict bind/unbind with "suppress_bind_attrs" in
platform_driver structure.
This is the main reason to not allow module unload/reload.

If you are ok i will send a v4 ?

BR
Gabriel

>> +MODULE_AUTHOR("Fabrice Gasnier <[email protected]>");
>> +MODULE_DESCRIPTION("PCI express Driver for ST SoCs");
>> +MODULE_LICENSE("GPL v2");
>> --
>> 1.9.1
>>

2015-05-06 09:26:14

by Arnd Bergmann

[permalink] [raw]
Subject: Re: [PATCH v3 3/5] PCI: st: Provide support for the sti PCIe controller

On Wednesday 06 May 2015 11:14:25 Gabriel Fernandez wrote:
>
> >> +static int __init pcie_init(void)
> >> +{
> >> + return platform_driver_probe(&st_pcie_driver, st_pcie_probe);
> >> +}
> >> +device_initcall(pcie_init);
> >
> > Can you use module_platform_driver_probe() or module_init() here?
> >
>
> Yes we can use module_init() here.
>
> By the way if figure out i removed __init attribute on st_pcie_probe()
> in previous version to follow Arnd's remark.
> But st_pcie_probe calls hook_fault_code() that has __init attribute.
> So I think we need to keep __init for probe routine ?
> Also, we have to restrict bind/unbind with "suppress_bind_attrs" in
> platform_driver structure.
> This is the main reason to not allow module unload/reload.
>
> If you are ok i will send a v4 ?
>

If you mark the probe function as __init, you have to use
module_platform_driver_probe() or platform_driver_probe() instead,
to prevent the probe function from being deferred.

Calling hook_fault_code() also means you need to prevent module
unloading, by providing only a module_init but not a module_exit
function, so module_platform_driver_probe() also won't work.

It may be a good idea to work on improving the hook_fault_code()
infrastructure to make it more usable with loadable device drivers.

Arnd

2015-05-06 13:29:39

by Bjorn Helgaas

[permalink] [raw]
Subject: Re: [PATCH v3 3/5] PCI: st: Provide support for the sti PCIe controller

On Wed, May 6, 2015 at 4:14 AM, Gabriel Fernandez
<[email protected]> wrote:
> Hi Bjorn,
>
> On 6 May 2015 at 00:16, Bjorn Helgaas <[email protected]> wrote:
>> On Fri, Apr 10, 2015 at 11:12:46AM +0200, Gabriel FERNANDEZ wrote:
>>> sti pcie is built around a Synopsis Designware PCIe IP.
>>>
>>> Signed-off-by: Fabrice Gasnier <[email protected]>
>>> Signed-off-by: Gabriel Fernandez <[email protected]>
>>
>>> +/* ST PCIe driver does not allow module unload */
>>
>> Is there something that prevents module unload, or is it just untested?
>>
> Yes we haven't tested
>
>>> +static int __init pcie_init(void)
>>> +{
>>> + return platform_driver_probe(&st_pcie_driver, st_pcie_probe);
>>> +}
>>> +device_initcall(pcie_init);
>>
>> Can you use module_platform_driver_probe() or module_init() here?
>>
>
> Yes we can use module_init() here.
>
> By the way if figure out i removed __init attribute on st_pcie_probe()
> in previous version to follow Arnd's remark.
> But st_pcie_probe calls hook_fault_code() that has __init attribute.
> So I think we need to keep __init for probe routine ?
> Also, we have to restrict bind/unbind with "suppress_bind_attrs" in
> platform_driver structure.
> This is the main reason to not allow module unload/reload.

I don't really care which solution you end up with here. But please
do take a look at how the other drivers solve the same problem. Using
"device_initcall()" is unique in drivers/pci/host, and I don't believe
the problem is unique. If several drivers have the same issue, they
should solve it the same way.

> If you are ok i will send a v4 ?

I think I'll have a few questions about the designware changes, too,
so you might want to wait a day or two.

>>> +MODULE_AUTHOR("Fabrice Gasnier <[email protected]>");
>>> +MODULE_DESCRIPTION("PCI express Driver for ST SoCs");
>>> +MODULE_LICENSE("GPL v2");
>>> --
>>> 1.9.1
>>>

2015-05-06 13:40:47

by Gabriel Fernandez

[permalink] [raw]
Subject: Re: [PATCH v3 3/5] PCI: st: Provide support for the sti PCIe controller

Hi Arnd, Bjorn,

I agree with last reply of Arnd.
I will mark the probe function as __init and use
platform_driver_probe() to prevent the probe function from being
deferred.
And to prevent module unloading, i will use module_init only.

Ok i will wait before sending a v4.

Thanks.
Gabriel.

On 6 May 2015 at 15:29, Bjorn Helgaas <[email protected]> wrote:
> On Wed, May 6, 2015 at 4:14 AM, Gabriel Fernandez
> <[email protected]> wrote:
>> Hi Bjorn,
>>
>> On 6 May 2015 at 00:16, Bjorn Helgaas <[email protected]> wrote:
>>> On Fri, Apr 10, 2015 at 11:12:46AM +0200, Gabriel FERNANDEZ wrote:
>>>> sti pcie is built around a Synopsis Designware PCIe IP.
>>>>
>>>> Signed-off-by: Fabrice Gasnier <[email protected]>
>>>> Signed-off-by: Gabriel Fernandez <[email protected]>
>>>
>>>> +/* ST PCIe driver does not allow module unload */
>>>
>>> Is there something that prevents module unload, or is it just untested?
>>>
>> Yes we haven't tested
>>
>>>> +static int __init pcie_init(void)
>>>> +{
>>>> + return platform_driver_probe(&st_pcie_driver, st_pcie_probe);
>>>> +}
>>>> +device_initcall(pcie_init);
>>>
>>> Can you use module_platform_driver_probe() or module_init() here?
>>>
>>
>> Yes we can use module_init() here.
>>
>> By the way if figure out i removed __init attribute on st_pcie_probe()
>> in previous version to follow Arnd's remark.
>> But st_pcie_probe calls hook_fault_code() that has __init attribute.
>> So I think we need to keep __init for probe routine ?
>> Also, we have to restrict bind/unbind with "suppress_bind_attrs" in
>> platform_driver structure.
>> This is the main reason to not allow module unload/reload.
>
> I don't really care which solution you end up with here. But please
> do take a look at how the other drivers solve the same problem. Using
> "device_initcall()" is unique in drivers/pci/host, and I don't believe
> the problem is unique. If several drivers have the same issue, they
> should solve it the same way.
>
>> If you are ok i will send a v4 ?
>
> I think I'll have a few questions about the designware changes, too,
> so you might want to wait a day or two.
>
>>>> +MODULE_AUTHOR("Fabrice Gasnier <[email protected]>");
>>>> +MODULE_DESCRIPTION("PCI express Driver for ST SoCs");
>>>> +MODULE_LICENSE("GPL v2");
>>>> --
>>>> 1.9.1
>>>>

2015-05-06 15:34:23

by Arnd Bergmann

[permalink] [raw]
Subject: Re: [PATCH v3 3/5] PCI: st: Provide support for the sti PCIe controller

On Wednesday 06 May 2015 15:40:39 Gabriel Fernandez wrote:
> On 6 May 2015 at 15:29, Bjorn Helgaas <[email protected]> wrote:
> > I don't really care which solution you end up with here. But please
> > do take a look at how the other drivers solve the same problem. Using
> > "device_initcall()" is unique in drivers/pci/host, and I don't believe
> > the problem is unique. If several drivers have the same issue, they
> > should solve it the same way.
>
> I agree with last reply of Arnd.
> I will mark the probe function as __init and use
> platform_driver_probe() to prevent the probe function from being
> deferred.
> And to prevent module unloading, i will use module_init only.
>
> Ok i will wait before sending a v4.

I think in order to address Bjorn's concern, you should modify make sure
that the keystone and imx6 drivers that call hook_fault_code() do it
the same way. I think imx6 already does, but keystone does not, so
please send a patch for it, explaining why it's needed.

Conversely, I think the other dw-pcie based drivers should be changed
not to use an __init annotation at all, and instead use
module_platform_driver().

Arnd

2015-05-06 19:22:13

by Bjorn Helgaas

[permalink] [raw]
Subject: Re: [PATCH v3 4/5] pci: designware: remove pci_common_init_dev()

On Fri, Apr 10, 2015 at 11:12:47AM +0200, Gabriel FERNANDEZ wrote:
> Call directly pci_*() instead of using pci_common_init_dev().
> Enforce error handling in probe.
> It also allows st pcie driver not to declare IO space:
> pci_common_init_dev() is assigning one by default.

Can you verify that none of the other users (dra7xx, exynos, etc.) depends
on the default I/O space, and mention that here?

> Signed-off-by: Fabrice Gasnier <[email protected]>

This requires an ack from Jingoo (DesignWare maintainer), of course.
I think this code is used by dra7xx, exynos, imx6, spear13xx, keystone, and
layerscape. It'd be nice to have some review and testing from them, too.

> ---
> drivers/pci/host/pcie-designware.c | 62 ++++++++++++++++++++------------------
> drivers/pci/host/pcie-designware.h | 1 +
> 2 files changed, 33 insertions(+), 30 deletions(-)
>
> diff --git a/drivers/pci/host/pcie-designware.c b/drivers/pci/host/pcie-designware.c
> index 1f4ea6f..d4b1bf7 100644
> --- a/drivers/pci/host/pcie-designware.c
> +++ b/drivers/pci/host/pcie-designware.c
> @@ -67,8 +67,6 @@
> #define PCIE_ATU_FUNC(x) (((x) & 0x7) << 16)
> #define PCIE_ATU_UPPER_TARGET 0x91C
>
> -static struct hw_pci dw_pci;
> -
> static unsigned long global_io_offset;
>
> static inline struct pcie_port *sys_to_pcie(struct pci_sys_data *sys)
> @@ -342,6 +340,9 @@ static const struct irq_domain_ops msi_domain_ops = {
> .map = dw_pcie_msi_map,
> };
>
> +static int dw_pcie_setup(struct pci_sys_data *sys);
> +static struct pci_bus *dw_pcie_scan_bus(struct pci_sys_data *sys);
> +
> int __init dw_pcie_host_init(struct pcie_port *pp)
> {
> struct device_node *np = pp->dev->of_node;
> @@ -352,6 +353,9 @@ int __init dw_pcie_host_init(struct pcie_port *pp)
> u32 val, na, ns;
> const __be32 *addrp;
> int i, index, ret;
> + struct list_head *resources = &pp->sysdata.resources;
> +
> + INIT_LIST_HEAD(resources);
>
> /* Find the address cell size and the number of cells in order to get
> * the untranslated address.
> @@ -504,13 +508,17 @@ int __init dw_pcie_host_init(struct pcie_port *pp)
>
> #ifdef CONFIG_PCI_MSI
> dw_pcie_msi_chip.dev = pp->dev;
> - dw_pci.msi_ctrl = &dw_pcie_msi_chip;
> + pp->sysdata.msi_ctrl = &dw_pcie_msi_chip;
> #endif
>
> - dw_pci.nr_controllers = 1;
> - dw_pci.private_data = (void **)&pp;
> + pp->sysdata.private_data = pp;
>
> - pci_common_init_dev(pp->dev, &dw_pci);
> + ret = dw_pcie_setup(&pp->sysdata);

It's not completely obvious that replacing pci_common_init_dev() with
dw_pcie_setup() is equivalent. Here are my notes from trying to convince
myself that this is correct. I think your changelog could stand some
enhancement. It would be ideal if you could break this into a few smaller
patches that were more obviously correct, but I suspect it's too
intertwined to do that.

Here's an outline of pci_common_init_dev():

pci_common_init_dev(parent, hw)
pci_add_flags(PCI_REASSIGN_ALL_RSRC) # [1]
if (hw->preinit)
hw->preinit # [2]
pcibios_init_hw
for (nr = 0; nr < hw->nr_controllers; # [3]
sys = kzalloc # [4]
sys->msi_ctrl = hw->msi_ctrl # [5]
sys->busnr = busnr # [6]
sys->swizzle = hw->swizzle # [7]
sys->map_irq = hw->map_irq # [8]
sys->align_resource = hw->align_resource # [9]
INIT_LIST_HEAD(&sys->resources) # [10]
sys->private_data = hw->private_data # [11]
hw->setup # [12]
pcibios_init_resources # [13]
hw->scan # [14]
if (hw->postinit)
hw->postinit # [15]
pci_fixup_irqs # [16]
list_for_each_entry(sys, &head, # [17]
if (!pci_has_flag(PCI_PROBE_ONLY)) # [18]
pci_bus_size_bridges # [19]
pci_bus_assign_resources
pci_bus_add_devices
list_for_each_entry(sys, &head,
...
pcie_bus_configure_settings # [20]

[1] You don't set PCI_REASSIGN_ALL_RSRC; have you verified that nobody
cares about that?

[2] dw_pci.preinit was NULL, so skipping this doesn't matter; looks OK.

[3] dw_pci.nr_controllers was always 1, so skipping the loop doesn't
matter; looks OK.

[4] You added struct pci_sys_data sysdata as a member of struct
pcie_port, so it is now allocated by dw_pcie_host_init() callers, e.g.,
st_pcie_probe(); looks OK.

[5] You set pp->sysdata.msi_ctrl in dw_pcie_host_init() instead of
pcibios_init_hw(); looks OK.

[6] Since dw_pci.nr_controllers was always 1, sys->busnr was always 0.
You don't set sys->busnr, so it will retain its initial zero value. OK, I
guess. It's still a little broken that we have both pp->busn and
pp->sysdata.busnr, but you didn't break it and it's OK that you didn't
change anything in this regard.

[7] dw_pci.swizzle was NULL, so pcibios_swizzle() would default to
pci_common_swizzle(), which is what you use when you call pci_fixup_irqs()
in dw_pcie_scan_bus(); looks OK.

[8] dw_pci.map_irq was dw_pcie_map_irq() (which used
of_irq_parse_and_map_pci()) and sys->map_irq was used by pcibios_map_irq().
You call pci_fixup_irqs() and pass a pointer to of_irq_parse_and_map_pci();
looks OK.

[9] dw_pci.align_resource was NULL, and I assume
pcie_port.sysdata.align_resource was initialized to zeroes; looks OK.

[10] You call INIT_LIST_HEAD() in dw_pcie_host_init() instead of
pcibios_init_hw(); looks OK.

[11] You set sys->private_data in dw_pcie_host_init() instead of
pcibios_init_hw(); looks OK.

[12] dw_pci.setup was dw_pcie_setup(), and you call that from
dw_pcie_host_init(); looks OK.

[13] You no longer call pcibios_init_resources(). You don't want the
default I/O space, which makes sense; looks OK (but you need to audit other
users and make sure they don't need it either).

[14] dw_pci.scan was dw_pcie_scan_bus(), and you call that from
dw_pcie_host_init(); looks OK.

[15] dw_pci.postinit was NULL, so skipping this doesn't matter; looks OK.

[16] You call pci_fixup_irqs() from dw_pcie_scan_bus() instead of
pci_common_init_dev(); looks OK.

[17] "head" is a local list in pci_common_init_dev(), and you don't need
anything similar because dw_pcie_host_init() is called once per host
bridge; looks OK.

[18] You don't test PCI_PROBE_ONLY; it looks like it can still be set by
booting with "pci=firmware". So previously, "pci=firmware" prevented
resource assignment, but it no longer does. Is that right? Is that what
you intend?

[19] Instead of pci_bus_size_bridges() and pci_bus_assign_resources(), you
call pci_assign_unassigned_bus_resources() from dw_pcie_scan_bus(). That
seems like an improvement because it holds pci_bus_sem and supplies
add_list; looks OK.

[20] I think you no longer call pcie_bus_configure_settings(). That
configured MPS settings, and I think you still want to do that, don't you?

> + if (ret)
> + return ret;
> +
> + if (!dw_pcie_scan_bus(&pp->sysdata))
> + return -ENXIO;
>
> return 0;
> }
> @@ -701,15 +709,19 @@ static struct pci_ops dw_pcie_ops = {
> .write = dw_pcie_wr_conf,
> };
>
> -static int dw_pcie_setup(int nr, struct pci_sys_data *sys)
> +static int dw_pcie_setup(struct pci_sys_data *sys)
> {
> struct pcie_port *pp;
> + int err;
>
> pp = sys_to_pcie(sys);
>
> if (global_io_offset < SZ_1M && pp->io_size > 0) {
> sys->io_offset = global_io_offset - pp->io_bus_addr;
> - pci_ioremap_io(global_io_offset, pp->io_base);
> + err = pci_ioremap_io(global_io_offset, pp->io_base);
> + if (err)
> + return err;
> +
> global_io_offset += SZ_64K;
> pci_add_resource_offset(&sys->resources, &pp->io,
> sys->io_offset);
> @@ -719,10 +731,10 @@ static int dw_pcie_setup(int nr, struct pci_sys_data *sys)
> pci_add_resource_offset(&sys->resources, &pp->mem, sys->mem_offset);
> pci_add_resource(&sys->resources, &pp->busn);
>
> - return 1;
> + return 0;
> }
>
> -static struct pci_bus *dw_pcie_scan_bus(int nr, struct pci_sys_data *sys)
> +static struct pci_bus *dw_pcie_scan_bus(struct pci_sys_data *sys)
> {
> struct pci_bus *bus;
> struct pcie_port *pp = sys_to_pcie(sys);
> @@ -738,27 +750,13 @@ static struct pci_bus *dw_pcie_scan_bus(int nr, struct pci_sys_data *sys)
> if (bus && pp->ops->scan_bus)
> pp->ops->scan_bus(pp);
>
> - return bus;
> -}
> -
> -static int dw_pcie_map_irq(const struct pci_dev *dev, u8 slot, u8 pin)
> -{
> - struct pcie_port *pp = sys_to_pcie(dev->bus->sysdata);
> - int irq;
> -
> - irq = of_irq_parse_and_map_pci(dev, slot, pin);
> - if (!irq)
> - irq = pp->irq;
> + pci_fixup_irqs(pci_common_swizzle, of_irq_parse_and_map_pci);
> + pci_assign_unassigned_bus_resources(bus);
> + pci_bus_add_devices(bus);
>
> - return irq;
> + return bus;
> }
>
> -static struct hw_pci dw_pci = {
> - .setup = dw_pcie_setup,
> - .scan = dw_pcie_scan_bus,
> - .map_irq = dw_pcie_map_irq,
> -};
> -
> void dw_pcie_setup_rc(struct pcie_port *pp)
> {
> u32 val;
> @@ -822,8 +820,12 @@ void dw_pcie_setup_rc(struct pcie_port *pp)
> /* setup command register */
> dw_pcie_readl_rc(pp, PCI_COMMAND, &val);
> val &= 0xffff0000;
> - val |= PCI_COMMAND_IO | PCI_COMMAND_MEMORY |
> - PCI_COMMAND_MASTER | PCI_COMMAND_SERR;
> +
> + if (!pp->io_size)
> + val |= PCI_COMMAND_IO;
> +
> + val |= PCI_COMMAND_MEMORY | PCI_COMMAND_MASTER | PCI_COMMAND_SERR;
> +
> dw_pcie_writel_rc(pp, val, PCI_COMMAND);
> }
>
> diff --git a/drivers/pci/host/pcie-designware.h b/drivers/pci/host/pcie-designware.h
> index d0bbd27..45bc2c2 100644
> --- a/drivers/pci/host/pcie-designware.h
> +++ b/drivers/pci/host/pcie-designware.h
> @@ -46,6 +46,7 @@ struct pcie_port {
> struct resource io;
> struct resource mem;
> struct resource busn;
> + struct pci_sys_data sysdata;
> int irq;
> u32 lanes;
> struct pcie_host_ops *ops;
> --
> 1.9.1
>

2015-05-25 14:30:56

by Fabrice Gasnier

[permalink] [raw]
Subject: Re: [PATCH v3 4/5] pci: designware: remove pci_common_init_dev()

Hi Bjorn,

On 05/06/2015 09:22 PM, Bjorn Helgaas wrote:
> It's not completely obvious that replacing pci_common_init_dev() with
> dw_pcie_setup() is equivalent. Here are my notes from trying to convince
> myself that this is correct. I think your changelog could stand some
> enhancement. It would be ideal if you could break this into a few smaller
> patches that were more obviously correct, but I suspect it's too
> intertwined to do that.

Thanks you for your review !

Sorry for the late reply, from your detailed analysis bellow, yes, it
looks like pci_common_init_dev isn't
completely equivalent.
I'm wondering about PCI_PROBE_ONLY flag...

The idea in the first place, to move to generic probing directly, instead of
pci_common_init_dev() was to avoid being assigned default I/O (e.g. in
bios32.c).
Please refer to discussion with Arnd :
http://lists.infradead.org/pipermail/linux-arm-kernel/2015-January/317726.html
But, I don't see how to be fully compatible (e.g. ARM specific option
like PCI_PROBE_ONLY)
without calling pci_common_init_dev() or duplicating code from bios32.c.

Maybe should I fall back to the first idea of using specifc handling of
an "empty" IO space, and keep pci_common_init_dev() ?

Please advise,

BR,
Fabrice

> Here's an outline of pci_common_init_dev():
>
> pci_common_init_dev(parent, hw)
> pci_add_flags(PCI_REASSIGN_ALL_RSRC) # [1]
> if (hw->preinit)
> hw->preinit # [2]
> pcibios_init_hw
> for (nr = 0; nr < hw->nr_controllers; # [3]
> sys = kzalloc # [4]
> sys->msi_ctrl = hw->msi_ctrl # [5]
> sys->busnr = busnr # [6]
> sys->swizzle = hw->swizzle # [7]
> sys->map_irq = hw->map_irq # [8]
> sys->align_resource = hw->align_resource # [9]
> INIT_LIST_HEAD(&sys->resources) # [10]
> sys->private_data = hw->private_data # [11]
> hw->setup # [12]
> pcibios_init_resources # [13]
> hw->scan # [14]
> if (hw->postinit)
> hw->postinit # [15]
> pci_fixup_irqs # [16]
> list_for_each_entry(sys, &head, # [17]
> if (!pci_has_flag(PCI_PROBE_ONLY)) # [18]
> pci_bus_size_bridges # [19]
> pci_bus_assign_resources
> pci_bus_add_devices
> list_for_each_entry(sys, &head,
> ...
> pcie_bus_configure_settings # [20]
>
> [1] You don't set PCI_REASSIGN_ALL_RSRC; have you verified that nobody
> cares about that?
>
> [2] dw_pci.preinit was NULL, so skipping this doesn't matter; looks OK.
>
> [3] dw_pci.nr_controllers was always 1, so skipping the loop doesn't
> matter; looks OK.
>
> [4] You added struct pci_sys_data sysdata as a member of struct
> pcie_port, so it is now allocated by dw_pcie_host_init() callers, e.g.,
> st_pcie_probe(); looks OK.
>
> [5] You set pp->sysdata.msi_ctrl in dw_pcie_host_init() instead of
> pcibios_init_hw(); looks OK.
>
> [6] Since dw_pci.nr_controllers was always 1, sys->busnr was always 0.
> You don't set sys->busnr, so it will retain its initial zero value. OK, I
> guess. It's still a little broken that we have both pp->busn and
> pp->sysdata.busnr, but you didn't break it and it's OK that you didn't
> change anything in this regard.
>
> [7] dw_pci.swizzle was NULL, so pcibios_swizzle() would default to
> pci_common_swizzle(), which is what you use when you call pci_fixup_irqs()
> in dw_pcie_scan_bus(); looks OK.
>
> [8] dw_pci.map_irq was dw_pcie_map_irq() (which used
> of_irq_parse_and_map_pci()) and sys->map_irq was used by pcibios_map_irq().
> You call pci_fixup_irqs() and pass a pointer to of_irq_parse_and_map_pci();
> looks OK.
>
> [9] dw_pci.align_resource was NULL, and I assume
> pcie_port.sysdata.align_resource was initialized to zeroes; looks OK.
>
> [10] You call INIT_LIST_HEAD() in dw_pcie_host_init() instead of
> pcibios_init_hw(); looks OK.
>
> [11] You set sys->private_data in dw_pcie_host_init() instead of
> pcibios_init_hw(); looks OK.
>
> [12] dw_pci.setup was dw_pcie_setup(), and you call that from
> dw_pcie_host_init(); looks OK.
>
> [13] You no longer call pcibios_init_resources(). You don't want the
> default I/O space, which makes sense; looks OK (but you need to audit other
> users and make sure they don't need it either).
>
> [14] dw_pci.scan was dw_pcie_scan_bus(), and you call that from
> dw_pcie_host_init(); looks OK.
>
> [15] dw_pci.postinit was NULL, so skipping this doesn't matter; looks OK.
>
> [16] You call pci_fixup_irqs() from dw_pcie_scan_bus() instead of
> pci_common_init_dev(); looks OK.
>
> [17] "head" is a local list in pci_common_init_dev(), and you don't need
> anything similar because dw_pcie_host_init() is called once per host
> bridge; looks OK.
>
> [18] You don't test PCI_PROBE_ONLY; it looks like it can still be set by
> booting with "pci=firmware". So previously, "pci=firmware" prevented
> resource assignment, but it no longer does. Is that right? Is that what
> you intend?
>
> [19] Instead of pci_bus_size_bridges() and pci_bus_assign_resources(), you
> call pci_assign_unassigned_bus_resources() from dw_pcie_scan_bus(). That
> seems like an improvement because it holds pci_bus_sem and supplies
> add_list; looks OK.
>
> [20] I think you no longer call pcie_bus_configure_settings(). That
> configured MPS settings, and I think you still want to do that, don't you?

2015-08-14 14:53:18

by Bjorn Helgaas

[permalink] [raw]
Subject: Re: [PATCH v3 0/5] PCI: st: provide support for dw pcie

On Fri, Apr 10, 2015 at 11:12:43AM +0200, Gabriel FERNANDEZ wrote:
> Changes in v3:
> - Remove power management functions (was not fully tested)
> - Remove configuration space range from dt binding
> - Remove pci_common_init_dev() call in pcie-designware.c to avoid
> default IO space declaration.
>
> Changes in v2:
> - comestic corrections in device tree binding
> - add pci-st.c into MAINTAINERS
> - remove st_pcie_ops structure to avoid another level of indirection
> - remove nasty busy-loop
> - remove useless test using virt_to_phys()
> - move disable io support into dw-pcie driver
>
> I don't change the st_pcie_abort_handler() function because abort handling
> is masked during boot.
>
>
> This patch-set introduces a STMicroelectronics PCIe controller.
> It's based on designware PCIe driver.
>
> Gabriel Fernandez (5):
> ARM: STi: Kconfig update for PCIe support
> PCI: st: Add Device Tree bindings for sti pcie
> PCI: st: Provide support for the sti PCIe controller
> pci: designware: remove pci_common_init_dev()
> MAINTAINERS: Add pci-st.c to ARCH/STI architecture

Hi Gabriel,

I lost track of where we are with this. I *think* I'm waiting for a v4
posting, but I haven't seen it yet. Let me know if I've missed something.

Bjorn

2015-08-17 07:53:59

by Gabriel Fernandez

[permalink] [raw]
Subject: Re: [PATCH v3 0/5] PCI: st: provide support for dw pcie

Hi Bjorn,

To be honest I'm wainting that Zhou patch (PCI: designware: Add ARM64
support) is accepted.

Because this patch allows to remove "pci: designware: remove
pci_common_init_dev()" from my patchset. I think it's more judicious
to do that.

I can send a v4 based on Zhou patchset ([PATCH v6 0/6] PCI: hisi: Add
PCIe host support for HiSilicon SoC Hip05) if you want ?

Best Regards

Gabriel.

On 14 August 2015 at 16:53, Bjorn Helgaas <[email protected]> wrote:
> On Fri, Apr 10, 2015 at 11:12:43AM +0200, Gabriel FERNANDEZ wrote:
>> Changes in v3:
>> - Remove power management functions (was not fully tested)
>> - Remove configuration space range from dt binding
>> - Remove pci_common_init_dev() call in pcie-designware.c to avoid
>> default IO space declaration.
>>
>> Changes in v2:
>> - comestic corrections in device tree binding
>> - add pci-st.c into MAINTAINERS
>> - remove st_pcie_ops structure to avoid another level of indirection
>> - remove nasty busy-loop
>> - remove useless test using virt_to_phys()
>> - move disable io support into dw-pcie driver
>>
>> I don't change the st_pcie_abort_handler() function because abort handling
>> is masked during boot.
>>
>>
>> This patch-set introduces a STMicroelectronics PCIe controller.
>> It's based on designware PCIe driver.
>>
>> Gabriel Fernandez (5):
>> ARM: STi: Kconfig update for PCIe support
>> PCI: st: Add Device Tree bindings for sti pcie
>> PCI: st: Provide support for the sti PCIe controller
>> pci: designware: remove pci_common_init_dev()
>> MAINTAINERS: Add pci-st.c to ARCH/STI architecture
>
> Hi Gabriel,
>
> I lost track of where we are with this. I *think* I'm waiting for a v4
> posting, but I haven't seen it yet. Let me know if I've missed something.
>
> Bjorn