Module Name:    src
Committed By:   hkenken
Date:           Thu Nov 24 12:06:44 UTC 2016

Modified Files:
        src/sys/arch/arm/imx: files.imx6
        src/sys/arch/evbarm/conf: std.nitrogen6
        src/sys/arch/evbarm/nitrogen6: nitrogen6_iomux.c
Added Files:
        src/sys/arch/arm/imx: imx6_pcie.c imx6_pciereg.h
        src/sys/arch/evbarm/conf: HUMMINGBOARD

Log Message:
Add support imx6 PCIe controller.


To generate a diff of this commit:
cvs rdiff -u -r1.7 -r1.8 src/sys/arch/arm/imx/files.imx6
cvs rdiff -u -r0 -r1.1 src/sys/arch/arm/imx/imx6_pcie.c \
    src/sys/arch/arm/imx/imx6_pciereg.h
cvs rdiff -u -r0 -r1.1 src/sys/arch/evbarm/conf/HUMMINGBOARD
cvs rdiff -u -r1.3 -r1.4 src/sys/arch/evbarm/conf/std.nitrogen6
cvs rdiff -u -r1.2 -r1.3 src/sys/arch/evbarm/nitrogen6/nitrogen6_iomux.c

Please note that diffs are not public domain; they are subject to the
copyright notices on the relevant files.

Modified files:

Index: src/sys/arch/arm/imx/files.imx6
diff -u src/sys/arch/arm/imx/files.imx6:1.7 src/sys/arch/arm/imx/files.imx6:1.8
--- src/sys/arch/arm/imx/files.imx6:1.7	Tue May 17 06:44:45 2016
+++ src/sys/arch/arm/imx/files.imx6	Thu Nov 24 12:06:43 2016
@@ -1,4 +1,4 @@
-#	$NetBSD: files.imx6,v 1.7 2016/05/17 06:44:45 ryo Exp $
+#	$NetBSD: files.imx6,v 1.8 2016/11/24 12:06:43 hkenken Exp $
 #
 # Configuration info for the Freescale i.MX6
 #
@@ -26,6 +26,11 @@ device	axi { [addr=-1], [size=0], [irq=-
 attach	axi at mainbus
 file	arch/arm/imx/imx6_axi.c			axi
 
+# iMX6 PCIe
+device	imxpcie: pcibus
+attach	imxpcie at axi
+file	arch/arm/imx/imx6_pcie.c		imxpcie
+
 # iMX6 Clock Control Module
 device	imxccm
 attach	imxccm at axi
@@ -101,4 +106,3 @@ device	imxsnvs
 attach	imxsnvs at axi
 file	arch/arm/imx/imxsnvs.c			imxsnvs
 file	arch/arm/imx/imx6_snvs.c		imxsnvs
-

Index: src/sys/arch/evbarm/conf/std.nitrogen6
diff -u src/sys/arch/evbarm/conf/std.nitrogen6:1.3 src/sys/arch/evbarm/conf/std.nitrogen6:1.4
--- src/sys/arch/evbarm/conf/std.nitrogen6:1.3	Thu Jul 30 08:09:36 2015
+++ src/sys/arch/evbarm/conf/std.nitrogen6	Thu Nov 24 12:06:44 2016
@@ -1,4 +1,4 @@
-#	$NetBSD: std.nitrogen6,v 1.3 2015/07/30 08:09:36 ryo Exp $
+#	$NetBSD: std.nitrogen6,v 1.4 2016/11/24 12:06:44 hkenken Exp $
 #
 # standard NetBSD/evbarm options for Nitrogen6X
 
@@ -14,6 +14,7 @@ options 	ARM_HAS_VBAR
 options 	__HAVE_CPU_COUNTER
 options 	__HAVE_FAST_SOFTINTS		# should be in types.h
 options 	TPIDRPRW_IS_CURCPU
+options 	PCI_NETBSD_CONFIGURE
 
 makeoptions	CPUFLAGS="-mcpu=cortex-a9"
 

Index: src/sys/arch/evbarm/nitrogen6/nitrogen6_iomux.c
diff -u src/sys/arch/evbarm/nitrogen6/nitrogen6_iomux.c:1.2 src/sys/arch/evbarm/nitrogen6/nitrogen6_iomux.c:1.3
--- src/sys/arch/evbarm/nitrogen6/nitrogen6_iomux.c:1.2	Thu Dec 31 11:53:19 2015
+++ src/sys/arch/evbarm/nitrogen6/nitrogen6_iomux.c	Thu Nov 24 12:06:44 2016
@@ -1,4 +1,4 @@
-/*	$NetBSD: nitrogen6_iomux.c,v 1.2 2015/12/31 11:53:19 ryo Exp $	*/
+/*	$NetBSD: nitrogen6_iomux.c,v 1.3 2016/11/24 12:06:44 hkenken Exp $	*/
 
 /*
  * Copyright (c) 2015 Ryo Shimizu <r...@nerv.org>
@@ -26,7 +26,7 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 #include <sys/cdefs.h>
-__KERNEL_RCSID(0, "$NetBSD: nitrogen6_iomux.c,v 1.2 2015/12/31 11:53:19 ryo Exp $");
+__KERNEL_RCSID(0, "$NetBSD: nitrogen6_iomux.c,v 1.3 2016/11/24 12:06:44 hkenken Exp $");
 
 #include "opt_evbarm_boardtype.h"
 #include <sys/bus.h>
@@ -52,10 +52,11 @@ static void nitrogen6_mux_config(const s
 static void nitrogen6_gpio_config(const struct gpio_conf *);
 
 
-#define	nitrogen6x	1
-#define	nitrogen6max	2
-#define	cubox_i		3
-#define	hummingboard	4
+#define	nitrogen6x		1
+#define	nitrogen6max		2
+#define	cubox_i			3
+#define	hummingboard		4
+#define	hummingboard_edge	5
 
 #define PAD_UART	\
 		(PAD_CTL_HYS | PAD_CTL_PUS_100K_PU | PAD_CTL_PULL |	\
@@ -111,6 +112,10 @@ static void nitrogen6_gpio_config(const 
 		 PAD_CTL_SPEED_100MHZ | PAD_CTL_DSE_40OHM | PAD_CTL_SRE_SLOW)
 #define PAD_OUTPUT_40OHM	(PAD_CTL_SPEED_100MHZ | PAD_CTL_DSE_40OHM)
 
+#define PAD_PCIE_GPIO \
+		(PAD_CTL_HYS | PAD_CTL_PUS_22K_PU | PAD_CTL_PULL |	\
+		 PAD_CTL_SPEED_50MHZ | PAD_CTL_DSE_40OHM | PAD_CTL_SRE_FAST)
+
 
 /* iMX6 SoloLite */
 static const struct iomux_conf iomux_data_6sl[] = {
@@ -176,7 +181,8 @@ static const struct iomux_conf iomux_dat
 		.pad = 0
 	},
 #endif
-#if (EVBARM_BOARDTYPE == hummingboard)
+#if (EVBARM_BOARDTYPE == hummingboard) || \
+    (EVBARM_BOARDTYPE == hummingboard_edge)
 	{
 		.pin = MUX_PIN(IMX6SDL, GPIO05),
 		.mux = IOMUX_CONFIG_ALT3,	/* CCM_CLKO1 */
@@ -184,7 +190,8 @@ static const struct iomux_conf iomux_dat
 	},
 #endif
 #if (EVBARM_BOARDTYPE == cubox_i) || \
-    (EVBARM_BOARDTYPE == hummingboard)
+    (EVBARM_BOARDTYPE == hummingboard) || \
+    (EVBARM_BOARDTYPE == hummingboard_edge)
 	{
 		.pin = MUX_PIN(IMX6SDL, EIM_DATA22),
 		.mux = IOMUX_CONFIG_ALT5,	/* GPIO3_IO22 */
@@ -407,15 +414,33 @@ static const struct iomux_conf iomux_dat
 		.pad = 0
 	},
 #endif
-#if (EVBARM_BOARDTYPE == hummingboard)
+#if (EVBARM_BOARDTYPE == hummingboard) || \
+    (EVBARM_BOARDTYPE == hummingboard_edge)
 	{
 		.pin = MUX_PIN(IMX6DQ, GPIO05),
 		.mux = IOMUX_CONFIG_ALT3,	/* CCM_CLKO1 */
 		.pad = PAD_USB
 	},
 #endif
+#if (EVBARM_BOARDTYPE == hummingboard)
+	/* PCIe */
+	{
+		.pin = MUX_PIN(IMX6DQ, EIM_AD04),
+		.mux = IOMUX_CONFIG_ALT5,
+		.pad = PAD_PCIE_GPIO
+	},
+#endif
+#if (EVBARM_BOARDTYPE == hummingboard_edge)
+	/* PCIe */
+	{
+		.pin = MUX_PIN(IMX6DQ, SD4_DATA3),
+		.mux = IOMUX_CONFIG_ALT5,
+		.pad = PAD_PCIE_GPIO
+	},
+#endif
 #if (EVBARM_BOARDTYPE == cubox_i) || \
-    (EVBARM_BOARDTYPE == hummingboard)
+    (EVBARM_BOARDTYPE == hummingboard) || \
+    (EVBARM_BOARDTYPE == hummingboard_edge)
 	{
 		.pin = MUX_PIN(IMX6DQ, EIM_DATA22),
 		.mux = IOMUX_CONFIG_ALT5,	/* GPIO3_IO22 */
@@ -456,6 +481,13 @@ static const struct gpio_conf gpio_data[
 	{	3,	22,	GPIO_DIR_OUT,	1	}, /* USB OTG */
 	{	1,	0,	GPIO_DIR_OUT,	1	}, /* USB H1 */
 	{	1,	4,	GPIO_DIR_IN,	0	}, /* USDHC2 */
+	{	3,	4,	GPIO_DIR_OUT,	0	}, /* PCIe */
+#endif
+#if (EVBARM_BOARDTYPE == hummingboard_edge)
+	{	3,	22,	GPIO_DIR_OUT,	1	}, /* USB OTG */
+	{	1,	0,	GPIO_DIR_OUT,	1	}, /* USB H1 */
+	{	1,	4,	GPIO_DIR_IN,	0	}, /* USDHC2 */
+	{	2,	11,	GPIO_DIR_OUT,	0	}, /* PCIe */
 #endif
 
 	/* end of table */
@@ -554,5 +586,17 @@ nitrogen6_device_register(device_t self,
 #if (EVBARM_BOARDTYPE == hummingboard)
 		prop_dictionary_set_cstring(dict, "usdhc2-cd-gpio", "!1,4");
 #endif
+#if (EVBARM_BOARDTYPE == hummingboard_edge)
+		prop_dictionary_set_cstring(dict, "usdhc2-cd-gpio", "!1,4");
+#endif
+	}
+	if (device_is_a(self, "imxpcie") &&
+	    device_is_a(device_parent(self), "axi")) {
+#if (EVBARM_BOARDTYPE == hummingboard)
+		prop_dictionary_set_cstring(dict, "imx6pcie-reset-gpio", "!3,4");
+#endif
+#if (EVBARM_BOARDTYPE == hummingboard_edge)
+		prop_dictionary_set_cstring(dict, "imx6pcie-reset-gpio", "!2,11");
+#endif
 	}
 }

Added files:

Index: src/sys/arch/arm/imx/imx6_pcie.c
diff -u /dev/null src/sys/arch/arm/imx/imx6_pcie.c:1.1
--- /dev/null	Thu Nov 24 12:06:44 2016
+++ src/sys/arch/arm/imx/imx6_pcie.c	Thu Nov 24 12:06:43 2016
@@ -0,0 +1,942 @@
+/*	$NetBSD: imx6_pcie.c,v 1.1 2016/11/24 12:06:43 hkenken Exp $	*/
+
+/*
+ * Copyright (c) 2016  Genetec Corporation.  All rights reserved.
+ * Written by Hashimoto Kenichi for Genetec Corporation.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ * 1. Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *
+ * THIS SOFTWARE IS PROVIDED BY GENETEC CORPORATION ``AS IS'' AND
+ * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
+ * TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
+ * PURPOSE ARE DISCLAIMED.  IN NO EVENT SHALL GENETEC CORPORATION
+ * BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+ * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+ * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+/*
+ * i.MX6 On-Chip PCI Express Controller
+ */
+
+#include <sys/cdefs.h>
+__KERNEL_RCSID(0, "$NetBSD: imx6_pcie.c,v 1.1 2016/11/24 12:06:43 hkenken Exp $");
+
+#include "opt_pci.h"
+#include "opt_imx6pcie.h"
+
+#include "pci.h"
+#include "imxgpio.h"
+#include "locators.h"
+
+#include <sys/bus.h>
+#include <sys/device.h>
+#include <sys/intr.h>
+#include <sys/systm.h>
+#include <sys/param.h>
+#include <sys/kernel.h>
+#include <sys/extent.h>
+#include <sys/queue.h>
+#include <sys/mutex.h>
+#include <sys/kmem.h>
+#include <sys/gpio.h>
+
+#include <machine/frame.h>
+#include <arm/cpufunc.h>
+
+#include <dev/pci/pcireg.h>
+#include <dev/pci/pcivar.h>
+#include <dev/pci/pciconf.h>
+
+#include <arm/imx/imxgpioreg.h>
+#include <arm/imx/imxgpiovar.h>
+#include <arm/imx/imx6var.h>
+#include <arm/imx/imx6_reg.h>
+#include <arm/imx/imx6_pciereg.h>
+#include <arm/imx/imx6_iomuxreg.h>
+#include <arm/imx/imx6_ccmreg.h>
+#include <arm/imx/imx6_ccmvar.h>
+
+static int imx6pcie_match(device_t, cfdata_t, void *);
+static void imx6pcie_attach(device_t, device_t, void *);
+
+#define IMX6_PCIE_MEM_BASE	0x01000000
+#define IMX6_PCIE_MEM_SIZE	0x00f00000 /* 15MB */
+#define IMX6_PCIE_ROOT_BASE	0x01f00000
+#define IMX6_PCIE_ROOT_SIZE	0x00080000 /* 512KB */
+#define IMX6_PCIE_IO_BASE	0x01f80000
+#define IMX6_PCIE_IO_SIZE	0x00010000 /* 64KB */
+
+struct imx6pcie_ih {
+	int (*ih_handler)(void *);
+	void *ih_arg;
+	int ih_ipl;
+	TAILQ_ENTRY(imx6pcie_ih) ih_entry;
+};
+
+struct imx6pcie_softc {
+	device_t sc_dev;
+
+	bus_space_tag_t sc_iot;
+	bus_space_handle_t sc_ioh;
+	bus_space_handle_t sc_root_ioh;
+	bus_dma_tag_t sc_dmat;
+
+	struct arm32_pci_chipset sc_pc;
+
+	TAILQ_HEAD(, imx6pcie_ih) sc_intrs;
+
+	void *sc_ih;
+	kmutex_t sc_lock;
+	u_int sc_intrgen;
+
+	int32_t sc_gpio_reset;
+	int32_t sc_gpio_reset_active;
+	int32_t sc_gpio_pwren;
+	int32_t sc_gpio_pwren_active;
+};
+
+#define PCIE_CONF_LOCK(s)	(s) = disable_interrupts(I32_bit)
+#define PCIE_CONF_UNLOCK(s)	restore_interrupts((s))
+
+#define PCIE_READ(sc, reg)					\
+	bus_space_read_4((sc)->sc_iot, (sc)->sc_ioh, reg)
+#define PCIE_WRITE(sc, reg, val)				\
+	bus_space_write_4((sc)->sc_iot, (sc)->sc_ioh, reg, val)
+
+static int imx6pcie_intr(void *);
+static void imx6pcie_init(pci_chipset_tag_t, void *);
+static void imx6pcie_setup(struct imx6pcie_softc * const);
+
+static void imx6pcie_attach_hook(device_t, device_t,
+				       struct pcibus_attach_args *);
+static int imx6pcie_bus_maxdevs(void *, int);
+static pcitag_t imx6pcie_make_tag(void *, int, int, int);
+static void imx6pcie_decompose_tag(void *, pcitag_t, int *, int *, int *);
+static pcireg_t imx6pcie_conf_read(void *, pcitag_t, int);
+static void imx6pcie_conf_write(void *, pcitag_t, int, pcireg_t);
+#ifdef __HAVE_PCI_CONF_HOOK
+static int imx6pcie_conf_hook(void *, int, int, int, pcireg_t);
+#endif
+static void imx6pcie_conf_interrupt(void *, int, int, int, int, int *);
+
+static int imx6pcie_intr_map(const struct pci_attach_args *,
+				    pci_intr_handle_t *);
+static const char *imx6pcie_intr_string(void *, pci_intr_handle_t,
+					  char *, size_t);
+const struct evcnt *imx6pcie_intr_evcnt(void *, pci_intr_handle_t);
+static void * imx6pcie_intr_establish(void *, pci_intr_handle_t,
+					 int, int (*)(void *), void *);
+static void imx6pcie_intr_disestablish(void *, void *);
+
+CFATTACH_DECL_NEW(imxpcie, sizeof(struct imx6pcie_softc),
+    imx6pcie_match, imx6pcie_attach, NULL, NULL);
+
+static void
+imx6pcie_clock_enable(struct imx6pcie_softc *sc)
+{
+	uint32_t v;
+
+	v = imx6_ccm_read(CCM_ANALOG_MISC1);
+	v &= ~CCM_ANALOG_MISC1_LVDS_CLK1_IBEN;
+	v &= ~CCM_ANALOG_MISC1_LVDS_CLK1_SRC;
+	v |= CCM_ANALOG_MISC1_LVDS_CLK1_OBEN;
+	v |= CCM_ANALOG_MISC1_LVDS_CLK1_SRC_SATA;
+	imx6_ccm_write(CCM_ANALOG_MISC1, v);
+
+	/* select PCIe clock source from axi */
+	v = imx6_ccm_read(CCM_CBCMR);
+	v &= ~CCM_CBCMR_PCIE_AXI_CLK_SEL;
+	imx6_ccm_write(CCM_CBCMR, v);
+
+	/* AHCISATA clock enable */
+	v = imx6_ccm_read(CCM_CCGR5);
+	v |= CCM_CCGR5_100M_CLK_ENABLE(3);
+	imx6_ccm_write(CCM_CCGR5, v);
+
+	/* PCIe clock enable */
+	v = imx6_ccm_read(CCM_CCGR4);
+	v |= CCM_CCGR4_125M_ROOT_ENABLE(3);
+	imx6_ccm_write(CCM_CCGR4, v);
+
+	/* PLL power up */
+	if (imx6_pll_power(CCM_ANALOG_PLL_ENET, 1,
+		CCM_ANALOG_PLL_ENET_ENABLE_125M |
+		CCM_ANALOG_PLL_ENET_ENABLE_100M) != 0) {
+		aprint_error_dev(sc->sc_dev,
+		    "couldn't enable CCM_ANALOG_PLL_ENET\n");
+		return;
+	}
+}
+
+static int
+imx6pcie_init_phy(struct imx6pcie_softc *sc)
+{
+	uint32_t v;
+
+	/* initialize IOMUX */
+	v = iomux_read(IOMUX_GPR12);
+	v &= ~IOMUX_GPR12_APP_LTSSM_ENABLE;
+	iomux_write(IOMUX_GPR12, v);
+
+	v &= ~IOMUX_GPR12_DEVICE_TYPE;
+	v |= IOMUX_GPR12_DEVICE_TYPE_PCIE_RC;
+	iomux_write(IOMUX_GPR12, v);
+
+	v &= ~IOMUX_GPR12_LOS_LEVEL;
+	v |= __SHIFTIN(9, IOMUX_GPR12_LOS_LEVEL);
+	iomux_write(IOMUX_GPR12, v);
+
+	v = 0;
+	v |= __SHIFTIN(0x7f, IOMUX_GPR8_PCS_TX_SWING_LOW);
+	v |= __SHIFTIN(0x7f, IOMUX_GPR8_PCS_TX_SWING_FULL);
+	v |= __SHIFTIN(20, IOMUX_GPR8_PCS_TX_DEEMPH_GEN2_6DB);
+	v |= __SHIFTIN(0, IOMUX_GPR8_PCS_TX_DEEMPH_GEN2_3P5DB);
+	v |= __SHIFTIN(0, IOMUX_GPR8_PCS_TX_DEEMPH_GEN1);
+	iomux_write(IOMUX_GPR8, v);
+
+	return 0;
+}
+
+static int
+imx6pcie_phy_wait_ack(struct imx6pcie_softc *sc, int ack)
+{
+	uint32_t v;
+	int timeout;
+
+	for (timeout = 10; timeout > 0; --timeout) {
+		v = PCIE_READ(sc, PCIE_PL_PHY_STATUS);
+		if (!!(v & PCIE_PL_PHY_STATUS_ACK) == !!ack)
+			return 0;
+		delay(1);
+	}
+
+	return -1;
+}
+
+static int
+imx6pcie_phy_addr(struct imx6pcie_softc *sc, uint32_t addr)
+{
+	uint32_t v;
+
+	v = __SHIFTIN(addr, PCIE_PL_PHY_CTRL_DATA);
+	PCIE_WRITE(sc, PCIE_PL_PHY_CTRL, v);
+
+	v |= PCIE_PL_PHY_CTRL_CAP_ADR;
+	PCIE_WRITE(sc, PCIE_PL_PHY_CTRL, v);
+
+	if (imx6pcie_phy_wait_ack(sc, 1))
+		return -1;
+
+	v = __SHIFTIN(addr, PCIE_PL_PHY_CTRL_DATA);
+	PCIE_WRITE(sc, PCIE_PL_PHY_CTRL, v);
+
+	if (imx6pcie_phy_wait_ack(sc, 0))
+		return -1;
+
+	return 0;
+}
+
+static int
+imx6pcie_phy_write(struct imx6pcie_softc *sc, uint32_t addr, uint16_t data)
+{
+	/* write address */
+	if (imx6pcie_phy_addr(sc, addr) != 0)
+		return -1;
+
+	/* store data */
+	PCIE_WRITE(sc, PCIE_PL_PHY_CTRL, __SHIFTIN(data, PCIE_PL_PHY_CTRL_DATA));
+
+	/* assert CAP_DAT and wait ack */
+	PCIE_WRITE(sc, PCIE_PL_PHY_CTRL, __SHIFTIN(data, PCIE_PL_PHY_CTRL_DATA) | PCIE_PL_PHY_CTRL_CAP_DAT);
+	if (imx6pcie_phy_wait_ack(sc, 1))
+		return -1;
+
+	/* deassert CAP_DAT and wait ack */
+	PCIE_WRITE(sc, PCIE_PL_PHY_CTRL, __SHIFTIN(data, PCIE_PL_PHY_CTRL_DATA));
+	if (imx6pcie_phy_wait_ack(sc, 0))
+		return -1;
+
+	/* assert WR and wait ack */
+	PCIE_WRITE(sc, PCIE_PL_PHY_CTRL, PCIE_PL_PHY_CTRL_WR);
+	if (imx6pcie_phy_wait_ack(sc, 1))
+		return -1;
+
+	/* deassert WR and wait ack */
+	PCIE_WRITE(sc, PCIE_PL_PHY_CTRL, __SHIFTIN(data, PCIE_PL_PHY_CTRL_DATA));
+	if (imx6pcie_phy_wait_ack(sc, 0))
+		return -1;
+
+	/* done */
+	PCIE_WRITE(sc, PCIE_PL_PHY_CTRL, 0);
+
+	return 0;
+}
+
+static int
+imx6pcie_phy_read(struct imx6pcie_softc *sc, uint32_t addr)
+{
+	uint32_t v;
+
+	/* write address */
+	if (imx6pcie_phy_addr(sc, addr) != 0)
+		return -1;
+
+	/* assert RD */
+	PCIE_WRITE(sc, PCIE_PL_PHY_CTRL, PCIE_PL_PHY_CTRL_RD);
+	if (imx6pcie_phy_wait_ack(sc, 1))
+		return -1;
+
+	/* read data */
+	v = __SHIFTOUT(PCIE_READ(sc, PCIE_PL_PHY_STATUS),
+	    PCIE_PL_PHY_STATUS_DATA);
+
+	/* deassert RD */
+	PCIE_WRITE(sc, PCIE_PL_PHY_CTRL, 0);
+	if (imx6pcie_phy_wait_ack(sc, 0))
+		return -1;
+
+	return v;
+}
+
+static int
+imx6pcie_assert_core_reset(struct imx6pcie_softc *sc)
+{
+	uint32_t gpr1;
+	uint32_t gpr12;
+
+	gpr1 = iomux_read(IOMUX_GPR1);
+	gpr12 = iomux_read(IOMUX_GPR12);
+
+	/* already enabled by bootloader */
+	if ((gpr1 & IOMUX_GPR1_REF_SSP_EN) &&
+	    (gpr12 & IOMUX_GPR12_APP_LTSSM_ENABLE)) {
+		uint32_t v = PCIE_READ(sc, PCIE_PL_PFLR);
+		v &= ~PCIE_PL_PFLR_LINK_STATE;
+		v |= PCIE_PL_PFLR_FORCE_LINK;
+		PCIE_WRITE(sc, PCIE_PL_PFLR, v);
+
+		gpr12 &= ~IOMUX_GPR12_APP_LTSSM_ENABLE;
+		iomux_write(IOMUX_GPR12, gpr12);
+	}
+
+#if defined(IMX6DQP)
+	gpr1 |= IOMUX_GPR1_PCIE_SW_RST;
+	iomux_write(IOMUX_GPR1, gpr1);
+#endif
+
+	gpr1 |= IOMUX_GPR1_TEST_POWERDOWN;
+	iomux_write(IOMUX_GPR1, gpr1);
+	gpr1 &= ~IOMUX_GPR1_REF_SSP_EN;
+	iomux_write(IOMUX_GPR1, gpr1);
+
+	return 0;
+}
+
+static int
+imx6pcie_deassert_core_reset(struct imx6pcie_softc *sc)
+{
+	uint32_t v;
+
+	/* Power ON */
+#if NIMXGPIO > 0
+	if (sc->sc_gpio_pwren >= 0) {
+		gpio_data_write(sc->sc_gpio_pwren, sc->sc_gpio_pwren_active);
+		delay(100 * 1000);
+		gpio_data_write(sc->sc_gpio_pwren, !sc->sc_gpio_pwren_active);
+	}
+#endif
+
+	imx6pcie_clock_enable(sc);
+
+	v = iomux_read(IOMUX_GPR1);
+
+#if defined(IMX6DQP)
+	v &= ~IOMUX_GPR1_PCIE_SW_RST;
+	iomux_write(IOMUX_GPR1, v);
+#endif
+
+	delay(50 * 1000);
+
+	v &= ~IOMUX_GPR1_TEST_POWERDOWN;
+	iomux_write(IOMUX_GPR1, v);
+	delay(10);
+	v |= IOMUX_GPR1_REF_SSP_EN;
+	iomux_write(IOMUX_GPR1, v);
+
+	delay(50 * 1000);
+
+	/* Reset */
+#if NIMXGPIO > 0
+	if (sc->sc_gpio_reset >= 0) {
+		gpio_data_write(sc->sc_gpio_reset, sc->sc_gpio_reset_active);
+		delay(100 * 1000);
+		gpio_data_write(sc->sc_gpio_reset, !sc->sc_gpio_reset_active);
+	}
+#endif
+
+	return 0;
+}
+
+static int
+imx6pcie_wait_for_link(struct imx6pcie_softc *sc)
+{
+	uint32_t ltssm, valid, v;
+	uint32_t linkup;
+	int retry;
+
+#define LINKUP_RETRY	200
+	for (retry = LINKUP_RETRY; retry > 0; --retry) {
+		linkup = PCIE_READ(sc, PCIE_PL_DEBUG1);
+		if ((linkup & PCIE_PL_DEBUG1_XMLH_LINK_UP) &&
+		    !(linkup & PCIE_PL_DEBUG1_XMLH_LINK_IN_TRAINING)) {
+			delay(100);
+			continue;
+		}
+
+		valid = imx6pcie_phy_read(sc, PCIE_PHY_RX_ASIC_OUT) &
+		    PCIE_PHY_RX_ASIC_OUT_VALID;
+		ltssm = __SHIFTOUT(PCIE_READ(sc, PCIE_PL_DEBUG0),
+		    PCIE_PL_DEBUG0_XMLH_LTSSM_STATE);
+
+		if ((ltssm == 0x0d) && !valid) {
+			aprint_normal_dev(sc->sc_dev, "resetting PCIe phy\n");
+
+			v = imx6pcie_phy_read(sc, PCIE_PHY_RX_OVRD_IN_LO);
+			v |= PCIE_PHY_RX_OVRD_IN_LO_RX_PLL_EN_OVRD;
+			v |= PCIE_PHY_RX_OVRD_IN_LO_RX_DATA_EN_OVRD;
+			imx6pcie_phy_write(sc, PCIE_PHY_RX_OVRD_IN_LO, v);
+
+			delay(3000);
+
+			v = imx6pcie_phy_read(sc, PCIE_PHY_RX_OVRD_IN_LO);
+			v &= ~PCIE_PHY_RX_OVRD_IN_LO_RX_PLL_EN_OVRD;
+			v &= ~PCIE_PHY_RX_OVRD_IN_LO_RX_DATA_EN_OVRD;
+			imx6pcie_phy_write(sc, PCIE_PHY_RX_OVRD_IN_LO, v);
+		}
+
+		if (linkup)
+			return 0;
+	}
+
+	aprint_error_dev(sc->sc_dev, "Link Up failed.\n");
+
+	return -1;
+}
+
+static int
+imx6pcie_wait_for_changespeed(struct imx6pcie_softc *sc)
+{
+	uint32_t v;
+	int retry;
+
+#define CHANGESPEED_RETRY	200
+	for (retry = CHANGESPEED_RETRY; retry > 0; --retry) {
+		v = PCIE_READ(sc, PCIE_PL_G2CR);
+		if (!(v & PCIE_PL_G2CR_DIRECTED_SPEED_CHANGE))
+			return 0;
+		delay(100);
+	}
+
+	aprint_error_dev(sc->sc_dev, "Speed change timeout.\n");
+
+	return -1;
+}
+
+static void
+imx6pcie_linkup(struct imx6pcie_softc *sc)
+{
+	uint32_t v;
+	int ret;
+
+	imx6pcie_assert_core_reset(sc);
+	imx6pcie_init_phy(sc);
+	imx6pcie_deassert_core_reset(sc);
+
+	imx6pcie_setup(sc);
+
+	/* GEN1 Operation */
+	v = PCIE_READ(sc, PCIE_RC_LCR);
+	v &= ~PCIE_RC_LCR_MAX_LINK_SPEEDS;
+	v |= PCIE_RC_LCR_MAX_LINK_SPEEDS_GEN1;
+	PCIE_WRITE(sc, PCIE_RC_LCR, v);
+
+	/* Link Up */
+	v = iomux_read(IOMUX_GPR12);
+	v |= IOMUX_GPR12_APP_LTSSM_ENABLE;
+	iomux_write(IOMUX_GPR12, v);
+
+	ret = imx6pcie_wait_for_link(sc);
+	if (ret)
+		goto error;
+
+	/* Change speed */
+	v = PCIE_READ(sc, PCIE_PL_G2CR);
+	v |= PCIE_PL_G2CR_DIRECTED_SPEED_CHANGE;
+	PCIE_WRITE(sc, PCIE_PL_G2CR, v);
+
+	ret = imx6pcie_wait_for_changespeed(sc);
+	if (ret)
+		goto error;
+
+	/* Allow Gen2 mode */
+	v = PCIE_READ(sc, PCIE_RC_LCR);
+	v &= ~PCIE_RC_LCR_MAX_LINK_SPEEDS;
+	v |= PCIE_RC_LCR_MAX_LINK_SPEEDS_GEN2;
+	PCIE_WRITE(sc, PCIE_RC_LCR, v);
+
+	ret = imx6pcie_wait_for_link(sc);
+	if (ret)
+		goto error;
+
+	v = PCIE_READ(sc, PCIE_RC_LCSR);
+	aprint_normal_dev(sc->sc_dev, "LinkUp, Gen %d\n",
+	    (int)__SHIFTOUT(v, PCIE_RC_LCSR_LINK_SPEED));
+
+	return;
+
+error:
+	aprint_error_dev(sc->sc_dev,
+	    "PCIE_PL_DEBUG0,1 = %08x, %08x\n",
+	    PCIE_READ(sc, PCIE_PL_DEBUG0),
+	    PCIE_READ(sc, PCIE_PL_DEBUG1));
+
+	return;
+}
+
+static int
+imx6pcie_match(device_t parent, cfdata_t cf, void *aux)
+{
+	struct axi_attach_args * const aa = aux;
+
+	/* i.MX6 SoloLite has no PCIe controller */
+	switch (IMX6_CHIPID_MAJOR(imx6_chip_id())) {
+	case CHIPID_MAJOR_IMX6SL:
+		return 0;
+	default:
+		break;
+	}
+
+	switch (aa->aa_addr) {
+	case (IMX6_PCIE_BASE):
+		return 1;
+	}
+
+	return 0;
+}
+
+static void
+imx6pcie_attach(device_t parent, device_t self, void *aux)
+{
+	struct imx6pcie_softc * const sc = device_private(self);
+	struct axi_attach_args * const aa = aux;
+	struct pcibus_attach_args pba;
+
+	sc->sc_dev = self;
+	sc->sc_iot = aa->aa_iot;
+	sc->sc_dmat = aa->aa_dmat;
+
+	if (aa->aa_size == AXICF_SIZE_DEFAULT)
+		aa->aa_size = IMX6_PCIE_SIZE;
+
+	aprint_naive("\n");
+	aprint_normal(": PCI Express Controller\n");
+
+	if (bus_space_map(sc->sc_iot, aa->aa_addr, aa->aa_size, 0,
+	    &sc->sc_ioh)) {
+		aprint_error_dev(self, "Cannot map registers\n");
+		return;
+	}
+	if (bus_space_map(sc->sc_iot, IMX6_PCIE_ROOT_BASE,
+	    IMX6_PCIE_ROOT_SIZE, 0, &sc->sc_root_ioh)) {
+		aprint_error_dev(self, "Cannot map registers\n");
+		return;
+	}
+
+	imx6_set_gpio(self, "imx6pcie-reset-gpio", &sc->sc_gpio_reset,
+	    &sc->sc_gpio_reset_active, GPIO_DIR_OUT);
+	imx6_set_gpio(self, "imx6pcie-pwren-gpio", &sc->sc_gpio_pwren,
+	    &sc->sc_gpio_pwren_active, GPIO_DIR_OUT);
+
+	imx6pcie_linkup(sc);
+
+	TAILQ_INIT(&sc->sc_intrs);
+	mutex_init(&sc->sc_lock, MUTEX_DEFAULT, IPL_VM);
+
+	sc->sc_ih = intr_establish(aa->aa_irq, IPL_VM, IST_LEVEL,
+	    imx6pcie_intr, sc);
+	if (sc->sc_ih == NULL) {
+		aprint_error_dev(self, "failed to establish interrupt on %d\n",
+		    aa->aa_irq);
+		return;
+	}
+	aprint_normal_dev(self, "interrupting on %d\n", aa->aa_irq);
+
+	imx6pcie_init(&sc->sc_pc, sc);
+
+#ifdef PCI_NETBSD_CONFIGURE
+	struct extent *ioext, *memext;
+	int error;
+
+	ioext = extent_create("pciio", IMX6_PCIE_IO_BASE,
+	    IMX6_PCIE_IO_BASE + IMX6_PCIE_IO_SIZE - 1,
+	    NULL, 0, EX_NOWAIT);
+	memext = extent_create("pcimem", IMX6_PCIE_MEM_BASE,
+	    IMX6_PCIE_MEM_BASE + IMX6_PCIE_MEM_SIZE - 1,
+	    NULL, 0, EX_NOWAIT);
+
+	error = pci_configure_bus(&sc->sc_pc, ioext, memext, NULL, 0,
+	    arm_dcache_align);
+
+	extent_destroy(ioext);
+	extent_destroy(memext);
+
+	if (error) {
+		aprint_error_dev(self, "configuration failed (%d)\n",
+		    error);
+		return;
+	}
+#endif
+
+	memset(&pba, 0, sizeof(pba));
+	pba.pba_flags = PCI_FLAGS_MEM_OKAY |
+			PCI_FLAGS_IO_OKAY;
+	pba.pba_iot = sc->sc_iot;
+	pba.pba_memt = sc->sc_iot;
+	pba.pba_dmat = sc->sc_dmat;
+	pba.pba_pc = &sc->sc_pc;
+	pba.pba_bus = 0;
+
+	config_found_ia(self, "pcibus", &pba, pcibusprint);
+}
+
+static int
+imx6pcie_intr(void *priv)
+{
+	struct imx6pcie_softc *sc = priv;
+	struct imx6pcie_ih *pcie_ih;
+	int rv = 0;
+	uint32_t v;
+
+	for (int i = 0; i < 8; i++) {
+		v = PCIE_READ(sc, PCIE_PL_MSICIN_STATUS + i * 0xC);
+		int bit;
+		while ((bit = ffs(v) - 1) >= 0) {
+			PCIE_WRITE(sc, PCIE_PL_MSICIN_STATUS + i * 0xC,
+			    __BIT(bit));
+			v &= ~__BIT(bit);
+		}
+	}
+
+	mutex_enter(&sc->sc_lock);
+	const u_int lastgen = sc->sc_intrgen;
+	TAILQ_FOREACH(pcie_ih, &sc->sc_intrs, ih_entry) {
+		int (*callback)(void *) = pcie_ih->ih_handler;
+		void *arg = pcie_ih->ih_arg;
+		mutex_exit(&sc->sc_lock);
+		rv += callback(arg);
+		mutex_enter(&sc->sc_lock);
+		if (lastgen != sc->sc_intrgen)
+			break;
+	}
+	mutex_exit(&sc->sc_lock);
+
+	return rv;
+}
+
+static void
+imx6pcie_setup(struct imx6pcie_softc * const sc)
+{
+	uint32_t v;
+
+	/* Setup RC */
+
+	/* BARs */
+	PCIE_WRITE(sc, PCI_BAR0, 0x00000004);
+	PCIE_WRITE(sc, PCI_BAR1, 0x00000000);
+
+	/* Interurupt pins */
+	v = PCIE_READ(sc, PCI_INTERRUPT_REG);
+	v &= ~(PCI_INTERRUPT_PIN_MASK << PCI_INTERRUPT_PIN_SHIFT);
+	v |= PCI_INTERRUPT_PIN_A << PCI_INTERRUPT_PIN_SHIFT;
+	PCIE_WRITE(sc, PCI_INTERRUPT_REG, v);
+
+	/* Bus number */
+	v = PCIE_READ(sc, PCI_BRIDGE_BUS_REG);
+	v &= ~(PCI_BRIDGE_BUS_EACH_MASK << PCI_BRIDGE_BUS_SUBORDINATE_SHIFT |
+	    PCI_BRIDGE_BUS_EACH_MASK << PCI_BRIDGE_BUS_SECONDARY_SHIFT |
+	    PCI_BRIDGE_BUS_EACH_MASK << PCI_BRIDGE_BUS_PRIMARY_SHIFT);
+	v |= PCI_BRIDGE_BUS_SUBORDINATE(1);
+	v |= PCI_BRIDGE_BUS_SECONDARY(1);
+	v |= PCI_BRIDGE_BUS_PRIMARY(0);
+	PCIE_WRITE(sc, PCI_BRIDGE_BUS_REG, v);
+
+	/* Command register */
+	v = PCIE_READ(sc, PCI_COMMAND_STATUS_REG);
+	v |= PCI_COMMAND_IO_ENABLE |
+	    PCI_COMMAND_MEM_ENABLE |
+	    PCI_COMMAND_MASTER_ENABLE;
+	PCIE_WRITE(sc, PCI_COMMAND_STATUS_REG, v);
+
+	PCIE_WRITE(sc, PCI_CLASS_REG,
+	    PCI_CLASS_CODE(PCI_CLASS_BRIDGE, PCI_SUBCLASS_BRIDGE_PCI, PCI_INTERFACE_BRIDGE_PCI_PCI));
+
+	PCIE_WRITE(sc, PCIE_PL_IATUVR, 0);
+
+	PCIE_WRITE(sc, PCIE_PL_IATURLBA, IMX6_PCIE_ROOT_BASE);
+	PCIE_WRITE(sc, PCIE_PL_IATURUBA, 0);
+	PCIE_WRITE(sc, PCIE_PL_IATURLA, IMX6_PCIE_ROOT_BASE + IMX6_PCIE_ROOT_SIZE);
+
+	PCIE_WRITE(sc, PCIE_PL_IATURLTA, 0);
+	PCIE_WRITE(sc, PCIE_PL_IATURUTA, 0);
+	PCIE_WRITE(sc, PCIE_PL_IATURC1, PCIE_PL_IATURC1_TYPE_CFG0);
+	PCIE_WRITE(sc, PCIE_PL_IATURC2, PCIE_PL_IATURC2_REGION_ENABLE);
+}
+
+void
+imx6pcie_init(pci_chipset_tag_t pc, void *priv)
+{
+	pc->pc_conf_v = priv;
+	pc->pc_attach_hook = imx6pcie_attach_hook;
+	pc->pc_bus_maxdevs = imx6pcie_bus_maxdevs;
+	pc->pc_make_tag = imx6pcie_make_tag;
+	pc->pc_decompose_tag = imx6pcie_decompose_tag;
+	pc->pc_conf_read = imx6pcie_conf_read;
+	pc->pc_conf_write = imx6pcie_conf_write;
+#ifdef __HAVE_PCI_CONF_HOOK
+	pc->pc_conf_hook = imx6pcie_conf_hook;
+#endif
+	pc->pc_conf_interrupt = imx6pcie_conf_interrupt;
+
+	pc->pc_intr_v = priv;
+	pc->pc_intr_map = imx6pcie_intr_map;
+	pc->pc_intr_string = imx6pcie_intr_string;
+	pc->pc_intr_evcnt = imx6pcie_intr_evcnt;
+	pc->pc_intr_establish = imx6pcie_intr_establish;
+	pc->pc_intr_disestablish = imx6pcie_intr_disestablish;
+}
+
+static void
+imx6pcie_attach_hook(device_t parent, device_t self,
+    struct pcibus_attach_args *pba)
+{
+	/* nothing to do */
+}
+
+static int
+imx6pcie_bus_maxdevs(void *v, int busno)
+{
+	return 32;
+}
+
+static pcitag_t
+imx6pcie_make_tag(void *v, int b, int d, int f)
+{
+	return (b << 16) | (d << 11) | (f << 8);
+}
+
+static void
+imx6pcie_decompose_tag(void *v, pcitag_t tag, int *bp, int *dp, int *fp)
+{
+	if (bp)
+		*bp = (tag >> 16) & 0xff;
+	if (dp)
+		*dp = (tag >> 11) & 0x1f;
+	if (fp)
+		*fp = (tag >> 8) & 0x7;
+}
+
+/*
+ * work around.
+ * If there is no PCIe devices, DABT will be generated by read/write access to
+ * config area, so replace original DABT handler with sinple jump-back one.
+ */
+extern u_int data_abort_handler_address;
+static bool data_abort_flag;
+static void
+imx6pcie_data_abort_handler(trapframe_t *tf)
+{
+	data_abort_flag = true;
+	tf->tf_pc += 0x4;
+	return;
+}
+
+static pcireg_t
+imx6pcie_conf_read(void *v, pcitag_t tag, int offset)
+{
+	struct imx6pcie_softc *sc = v;
+	bus_space_handle_t bsh;
+	int b, d, f;
+	pcireg_t ret = -1;
+	int s;
+
+	imx6pcie_decompose_tag(v, tag, &b, &d, &f);
+
+	if ((unsigned int)offset >= PCI_EXTCONF_SIZE)
+		return ret;
+	if (b <= 1 && d > 0)
+		return ret;
+
+	PCIE_WRITE(sc, PCIE_PL_IATUVR, 0);
+	if (b < 2)
+		PCIE_WRITE(sc, PCIE_PL_IATURC1, PCIE_PL_IATURC1_TYPE_CFG0);
+	else
+		PCIE_WRITE(sc, PCIE_PL_IATURC1, PCIE_PL_IATURC1_TYPE_CFG1);
+
+	if (b == 0) {
+		bsh = sc->sc_ioh;
+	} else {
+		PCIE_WRITE(sc, PCIE_PL_IATURLTA, tag << 8);
+		bsh = sc->sc_root_ioh;
+	}
+	PCIE_READ(sc, PCIE_PL_IATURC2);
+
+	PCIE_CONF_LOCK(s);
+
+	u_int saved = data_abort_handler_address;
+	data_abort_handler_address = (u_int)imx6pcie_data_abort_handler;
+	data_abort_flag = false;
+
+	ret = bus_space_read_4(sc->sc_iot, bsh, offset & ~0x3);
+
+	data_abort_handler_address = saved;
+
+	PCIE_CONF_UNLOCK(s);
+
+	if (data_abort_flag)
+		ret = -1;
+
+	return ret;
+}
+
+static void
+imx6pcie_conf_write(void *v, pcitag_t tag, int offset, pcireg_t val)
+{
+	struct imx6pcie_softc *sc = v;
+	bus_space_handle_t bsh;
+	int b, d, f;
+	int s;
+
+	imx6pcie_decompose_tag(v, tag, &b, &d, &f);
+
+	if ((unsigned int)offset >= PCI_EXTCONF_SIZE)
+		return;
+	if (b <= 1 && d > 0)
+		return;
+
+	PCIE_WRITE(sc, PCIE_PL_IATUVR, 0);
+	if (b < 2)
+		PCIE_WRITE(sc, PCIE_PL_IATURC1, PCIE_PL_IATURC1_TYPE_CFG0);
+	else
+		PCIE_WRITE(sc, PCIE_PL_IATURC1, PCIE_PL_IATURC1_TYPE_CFG1);
+
+	if (b == 0) {
+		bsh = sc->sc_ioh;
+	} else {
+		PCIE_WRITE(sc, PCIE_PL_IATURLTA, tag << 8);
+		bsh = sc->sc_root_ioh;
+	}
+	PCIE_READ(sc, PCIE_PL_IATURC2);
+
+	PCIE_CONF_LOCK(s);
+
+	u_int saved = data_abort_handler_address;
+	data_abort_handler_address = (u_int)imx6pcie_data_abort_handler;
+
+	bus_space_write_4(sc->sc_iot, bsh, offset & ~0x3, val);
+
+	data_abort_handler_address = saved;
+
+	PCIE_CONF_UNLOCK(s);
+
+	return;
+}
+
+#ifdef __HAVE_PCI_CONF_HOOK
+static int
+imx6pcie_conf_hook(void *v, int b, int d, int f, pcireg_t id)
+{
+	return PCI_CONF_DEFAULT;
+}
+#endif
+
+static void
+imx6pcie_conf_interrupt(void *v, int bus, int dev, int ipin, int swiz,
+    int *ilinep)
+{
+	/* nothing to do */
+}
+
+static int
+imx6pcie_intr_map(const struct pci_attach_args *pa, pci_intr_handle_t *ih)
+{
+	if (pa->pa_intrpin == 0)
+		return EINVAL;
+	*ih = pa->pa_intrpin;
+	return 0;
+}
+
+static const char *
+imx6pcie_intr_string(void *v, pci_intr_handle_t ih, char *buf, size_t len)
+{
+	if (ih == PCI_INTERRUPT_PIN_NONE)
+		return NULL;
+
+	strlcpy(buf, "pci", len);
+
+	return buf;
+}
+
+const struct evcnt *
+imx6pcie_intr_evcnt(void *v, pci_intr_handle_t ih)
+{
+	return NULL;
+}
+
+static void *
+imx6pcie_intr_establish(void *v, pci_intr_handle_t ih, int ipl,
+    int (*callback)(void *), void *arg)
+{
+	struct imx6pcie_softc *sc = v;
+	struct imx6pcie_ih *pcie_ih;
+
+	if (ih == 0)
+		return NULL;
+
+	pcie_ih = kmem_alloc(sizeof(*pcie_ih), KM_SLEEP);
+	pcie_ih->ih_handler = callback;
+	pcie_ih->ih_arg = arg;
+	pcie_ih->ih_ipl = ipl;
+
+	mutex_enter(&sc->sc_lock);
+	TAILQ_INSERT_TAIL(&sc->sc_intrs, pcie_ih, ih_entry);
+	sc->sc_intrgen++;
+	mutex_exit(&sc->sc_lock);
+
+	return pcie_ih;
+}
+
+static void
+imx6pcie_intr_disestablish(void *v, void *vih)
+{
+	struct imx6pcie_softc *sc = v;
+	struct imx6pcie_ih *pcie_ih = vih;
+
+	mutex_enter(&sc->sc_lock);
+	TAILQ_REMOVE(&sc->sc_intrs, pcie_ih, ih_entry);
+	sc->sc_intrgen++;
+	mutex_exit(&sc->sc_lock);
+
+	kmem_free(pcie_ih, sizeof(*pcie_ih));
+}
Index: src/sys/arch/arm/imx/imx6_pciereg.h
diff -u /dev/null src/sys/arch/arm/imx/imx6_pciereg.h:1.1
--- /dev/null	Thu Nov 24 12:06:44 2016
+++ src/sys/arch/arm/imx/imx6_pciereg.h	Thu Nov 24 12:06:43 2016
@@ -0,0 +1,295 @@
+/*	$NetBSD: imx6_pciereg.h,v 1.1 2016/11/24 12:06:43 hkenken Exp $	*/
+
+/*
+ * Copyright (c) 2015 Ryo Shimizu <r...@nerv.org>
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ * 1. Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR
+ * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+ * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED.  IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT,
+ * INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+ * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+ * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
+ * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
+ * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING
+ * IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef _ARM_IMX_IMX6_PCIEREG_H_
+#define _ARM_IMX_IMX6_PCIEREG_H_
+
+/* PCIe EP Mode Registers */
+#define PCIE_EP_DEVICEID			0x00000000
+#define PCIE_EP_COMMAND				0x00000004
+#define PCIE_EP_BIST				0x0000000c
+#define PCIE_EP_BAR0				0x00000010
+#define PCIE_EP_MASK0				0x00000010
+#define PCIE_EP_MASK1				0x00000014
+#define PCIE_EP_MASK2				0x00000018
+#define PCIE_EP_MASK3				0x0000001c
+#define PCIE_EP_CISP				0x00000028
+#define PCIE_EP_SSID				0x0000002c
+#define PCIE_EP_EROMBAR				0x00000030
+#define PCIE_EP_EROMMASK			0x00000030
+#define PCIE_EP_CAPPR				0x00000034
+#define PCIE_EP_ILR				0x0000003c
+#define PCIE_EP_AER				0x00000100
+#define PCIE_EP_UESR				0x00000104
+#define PCIE_EP_UEMR				0x00000108
+#define PCIE_EP_UESEVR				0x0000010c
+#define PCIE_EP_CESR				0x00000110
+#define PCIE_EP_CEMR				0x00000114
+#define PCIE_EP_ACCR				0x00000118
+#define PCIE_EP_HLR				0x0000011c
+#define PCIE_EP_VCECHR				0x00000140
+#define PCIE_EP_PVCCR1				0x00000144
+#define PCIE_EP_PVCCR2				0x00000148
+#define PCIE_EP_PVCCSR				0x0000014c
+#define PCIE_EP_VCRCR				0x00000150
+#define PCIE_EP_VCRCONR				0x00000154
+#define PCIE_EP_VCRSR				0x00000158
+
+/* PCIe RC Mode Registers */
+#define PCIE_RC_DEVICEID			0x00000000
+#define PCIE_RC_COMMAND				0x00000004
+#define PCIE_RC_REVID				0x00000008
+#define PCIE_RC_BIST				0x0000000c
+#define PCIE_RC_BAR0				0x00000010
+#define PCIE_RC_BAR1				0x00000014
+#define PCIE_RC_BNR				0x00000018
+#define PCIE_RC_IOBLSSR				0x0000001c
+#define PCIE_RC_MEM_BLR				0x00000020
+#define PCIE_RC_PREF_MEM_BLR			0x00000024
+#define PCIE_RC_PREF_BASE_U32			0x00000028
+#define PCIE_RC_PREF_LIM_U32			0x0000002c
+#define PCIE_RC_IO_BASE_LIM_U16			0x00000030
+#define PCIE_RC_CAPPR				0x00000034
+#define PCIE_RC_EROMBAR				0x00000038
+#define PCIE_RC_EROMMASK			0x00000038
+#define PCIE_RC_PMCR				0x00000040
+#define PCIE_RC_PMCSR				0x00000044
+#define PCIE_RC_CIDR				0x00000070
+#define PCIE_RC_DCR				0x00000074
+#define PCIE_RC_DCONR				0x00000078
+#define PCIE_RC_LCR				0x0000007c
+#define  PCIE_RC_LCR_MAX_LINK_SPEEDS		__BITS(3, 0)
+#define  PCIE_RC_LCR_MAX_LINK_SPEEDS_GEN1	__SHIFTIN(0x1, PCIE_RC_LCR_MAX_LINK_SPEEDS)
+#define  PCIE_RC_LCR_MAX_LINK_SPEEDS_GEN2	__SHIFTIN(0x2, PCIE_RC_LCR_MAX_LINK_SPEEDS)
+#define PCIE_RC_LCSR				0x00000080
+#define  PCIE_RC_LCSR_LINK_SPEED		__BITS(19, 16)
+#define PCIE_RC_SCR				0x00000084
+#define PCIE_RC_SCSR				0x00000088
+#define PCIE_RC_RCCR				0x0000008c
+#define PCIE_RC_RSR				0x00000090
+#define PCIE_RC_DCR2				0x00000094
+#define PCIE_RC_DCSR2				0x00000098
+#define PCIE_RC_LCR2				0x0000009c
+#define PCIE_RC_LCSR2				0x000000a0
+#define PCIE_RC_AER				0x00000100
+#define PCIE_RC_UESR				0x00000104
+#define PCIE_RC_UEMR				0x00000108
+#define PCIE_RC_UESEVR				0x0000010c
+#define PCIE_RC_CESR				0x00000110
+#define PCIE_RC_CEMR				0x00000114
+#define PCIE_RC_ACCR				0x00000118
+#define PCIE_RC_HLR				0x0000011c
+#define PCIE_RC_RECR				0x0000012c
+#define PCIE_RC_RESR				0x00000130
+#define PCIE_RC_ESIR				0x00000134
+#define PCIE_RC_VCECHR				0x00000140
+#define PCIE_RC_PVCCR1				0x00000144
+#define PCIE_RC_PVCCR2				0x00000148
+#define PCIE_RC_PVCCSR				0x0000014c
+#define PCIE_RC_VCRCR				0x00000150
+#define PCIE_RC_VCRCONR				0x00000154
+#define PCIE_RC_VCRSR				0x00000158
+
+/* PCIe Port Logic Registers */
+#define PCIE_PL_ALTRTR				0x00000700
+#define PCIE_PL_VSDR				0x00000704
+#define PCIE_PL_PFLR				0x00000708
+#define  PCIE_PL_PFLR_LOW_POWER_ENTRANCE_COUNT	__BITS(31, 24)
+#define  PCIE_PL_PFLR_LINK_STATE		__BITS(21, 16)
+#define  PCIE_PL_PFLR_FORCE_LINK		__BIT(15)
+#define  PCIE_PL_PFLR_LINK_NUMBER		__BITS(7, 0)
+#define PCIE_PL_AFLACR				0x0000070c
+#define PCIE_PL_PLCR				0x00000710
+#define PCIE_PL_LSR				0x00000714
+#define PCIE_PL_SNR				0x00000718
+#define PCIE_PL_STRFM1				0x0000071c
+#define PCIE_PL_STRFM2				0x00000720
+#define PCIE_PL_AMODNPSR			0x00000724
+#define PCIE_PL_DEBUG0				0x00000728
+#define  PCIE_PL_DEBUG0_XMLH_LTSSM_STATE	__BITS(0, 5)
+#define PCIE_PL_DEBUG1				0x0000072c
+#define  PCIE_PL_DEBUG1_XMLH_LINK_UP		__BIT(4)
+#define  PCIE_PL_DEBUG1_XMLH_LINK_IN_TRAINING	__BIT(29)
+#define PCIE_PL_TPFCSR				0x00000730
+#define PCIE_PL_TNFCSR				0x00000734
+#define PCIE_PL_TCFCSR				0x00000738
+#define PCIE_PL_QSR				0x0000073c
+#define PCIE_PL_VCTAR1				0x00000740
+#define PCIE_PL_VCTAR2				0x00000744
+#define PCIE_PL_VC0PRQC				0x00000748
+#define PCIE_PL_VC0NRQC				0x0000074c
+#define PCIE_PL_VC0CRQC				0x00000750
+#define PCIE_PL_VCNPRQC				0x00000754
+#define PCIE_PL_VCNNRQC				0x00000758
+#define PCIE_PL_VCNCRQC				0x0000075c
+#define PCIE_PL_VC0PBD				0x000007a8
+#define PCIE_PL_VC0NPBD				0x000007ac
+#define PCIE_PL_VC0CBD				0x000007b0
+#define PCIE_PL_VC1PBD				0x000007b4
+#define PCIE_PL_VC1NPBD				0x000007b8
+#define PCIE_PL_VC1CBD				0x000007bc
+#define PCIE_PL_G2CR				0x0000080c
+#define  PCIE_PL_G2CR_DIRECTED_SPEED_CHANGE	__BIT(17)
+#define PCIE_PL_PHY_STATUS			0x00000810
+#define  PCIE_PL_PHY_STATUS_ACK			__BIT(16)
+#define  PCIE_PL_PHY_STATUS_DATA		__BITS(0, 15)
+#define PCIE_PL_PHY_CTRL			0x00000814
+#define  PCIE_PL_PHY_CTRL_RD			__BIT(19)
+#define  PCIE_PL_PHY_CTRL_WR			__BIT(18)
+#define  PCIE_PL_PHY_CTRL_CAP_DAT		__BIT(17)
+#define  PCIE_PL_PHY_CTRL_CAP_ADR		__BIT(16)
+#define  PCIE_PL_PHY_CTRL_DATA			__BITS(0, 15)
+#define PCIE_PL_MRCCR0				0x00000818
+#define PCIE_PL_MRCCR1				0x0000081c
+#define PCIE_PL_MSICA				0x00000820
+#define PCIE_PL_MSICUA				0x00000824
+#define PCIE_PL_MSICIN_ENB			0x00000828
+#define PCIE_PL_MSICIN_MASK			0x0000082c
+#define PCIE_PL_MSICIN_STATUS			0x00000830
+#define PCIE_PL_MSICGPIO			0x00000888
+
+// ATU_R_BaseAddress 0x900
+#define PCIE_PL_IATUVR				0x00000900
+// ATU_VIEWPORT_R (ATU_R_BaseAddress + 0x0)
+
+#define PCIE_PL_IATURC1				0x00000904
+// ATU_REGION_CTRL1_R (ATU_R_BaseAddress + 0x4)
+#define  PCIE_PL_IATURC1_FUNC			__BITS(22, 20)
+#define  PCIE_PL_IATURC1_AT			__BITS(17, 16)
+#define  PCIE_PL_IATURC1_ATTR			__BITS(10, 9)
+#define  PCIE_PL_IATURC1_TD			__BIT(8)
+#define  PCIE_PL_IATURC1_TC			__BITS(7, 5)
+#define  PCIE_PL_IATURC1_TYPE			__BITS(4, 0)
+#define   PCIE_PL_IATURC1_TYPE_IO		__SHIFTIN(0, PCIE_PL_IATURC1_TYPE)
+#define   PCIE_PL_IATURC1_TYPE_MEM		__SHIFTIN(2, PCIE_PL_IATURC1_TYPE)
+#define   PCIE_PL_IATURC1_TYPE_CFG0		__SHIFTIN(4, PCIE_PL_IATURC1_TYPE)
+#define   PCIE_PL_IATURC1_TYPE_CFG1		__SHIFTIN(5, PCIE_PL_IATURC1_TYPE)
+
+#define PCIE_PL_IATURC2				0x00000908
+// ATU_REGION_CTRL2_R (ATU_R_BaseAddress + 0x8)
+#define  PCIE_PL_IATURC2_REGION_ENABLE		__BIT(31)
+
+#define PCIE_PL_IATURLBA			0x0000090c
+// ATU_REGION_LOWBASE_R (ATU_R_BaseAddress + 0xC)
+
+#define PCIE_PL_IATURUBA			0x00000910
+// ATU_REGION_UPBASE_R (ATU_R_BaseAddress + 0x10)
+
+#define PCIE_PL_IATURLA				0x00000914
+// ATU_REGION_LIMIT_ADDR_R (ATU_R_BaseAddress + 0x14)
+
+#define PCIE_PL_IATURLTA			0x00000918
+// ATU_REGION_LOW_TRGT_ADDR_R (ATU_R_BaseAddress + 0x18)
+
+#define PCIE_PL_IATURUTA			0x0000091c
+// ATU_REGION_UP_TRGT_ADDR_R (ATU_R_BaseAddress + 0x1C)
+
+/* PCIe PHY registers */
+#define PCIE_PHY_IDCODE_LO			0x0000
+#define PCIE_PHY_IDCODE_HI			0x0001
+#define PCIE_PHY_DEBUG				0x0002
+#define PCIE_PHY_RTUNE_DEBUG			0x0003
+#define PCIE_PHY_RTUNE_STAT			0x0004
+#define PCIE_PHY_SS_PHASE			0x0005
+#define PCIE_PHY_SS_FREQ			0x0006
+#define PCIE_PHY_ATEOVRD			0x0010
+#define PCIE_PHY_MPLL_OVRD_IN_LO		0x0011
+#define PCIE_PHY_MPLL_OVRD_IN_HI		0x0011
+#define PCIE_PHY_SSC_OVRD_IN			0x0013
+#define PCIE_PHY_BS_OVRD_IN			0x0014
+#define PCIE_PHY_LEVEL_OVRD_IN			0x0015
+#define PCIE_PHY_SUP_OVRD_OUT			0x0016
+#define PCIE_PHY_MPLL_ASIC_IN			0x0017
+#define PCIE_PHY_BS_ASIC_IN			0x0018
+#define PCIE_PHY_LEVEL_ASIC_IN			0x0019
+#define PCIE_PHY_SSC_ASIC_IN			0x001a
+#define PCIE_PHY_SUP_ASIC_OUT			0x001b
+#define PCIE_PHY_ATEOVRD_STATUS			0x001c
+#define PCIE_PHY_SCOPE_ENABLES			0x0020
+#define PCIE_PHY_SCOPE_SAMPLES			0x0021
+#define PCIE_PHY_SCOPE_COUNT			0x0022
+#define PCIE_PHY_SCOPE_CTL			0x0023
+#define PCIE_PHY_SCOPE_MASK_000			0x0024
+#define PCIE_PHY_SCOPE_MASK_001			0x0025
+#define PCIE_PHY_SCOPE_MASK_010			0x0026
+#define PCIE_PHY_SCOPE_MASK_011			0x0027
+#define PCIE_PHY_SCOPE_MASK_100			0x0028
+#define PCIE_PHY_SCOPE_MASK_101			0x0029
+#define PCIE_PHY_SCOPE_MASK_110			0x002a
+#define PCIE_PHY_SCOPE_MASK_111			0x002b
+#define PCIE_PHY_MPLL_LOOP_CTL			0x0030
+#define PCIE_PHY_MPLL_ATB_MEAS2			0x0032
+#define PCIE_PHY_MPLL_OVR			0x0033
+#define PCIE_PHY_RTUNE_RTUNE_CTRL		0x0034
+#define PCIE_PHY_TX_OVRD_IN_LO			0x1000
+#define PCIE_PHY_TX_OVRD_IN_HI			0x1001
+#define PCIE_PHY_TX_OVRD_DRV_LO			0x1003
+#define PCIE_PHY_TX_OVRD_OUT			0x1004
+#define PCIE_PHY_RX_OVRD_IN_LO			0x1005
+#define  PCIE_PHY_RX_OVRD_IN_LO_RX_PLL_EN_OVRD	__BIT(3)
+#define  PCIE_PHY_RX_OVRD_IN_LO_RX_DATA_EN_OVRD	__BIT(5)
+#define PCIE_PHY_RX_OVRD_IN_HI			0x1006
+#define PCIE_PHY_RX_OVRD_OUT			0x1007
+#define PCIE_PHY_TX_ASIC_IN			0x1008
+#define PCIE_PHY_TX_ASIC_DRV_LO			0x1009
+#define PCIE_PHY_TX_ASIC_DRV_HI			0x100a
+#define PCIE_PHY_TX_ASIC_OUT			0x100b
+#define PCIE_PHY_RX_ASIC_IN			0x100c
+#define PCIE_PHY_RX_ASIC_OUT			0x100d
+#define  PCIE_PHY_RX_ASIC_OUT_LOS		__BIT(2)
+#define  PCIE_PHY_RX_ASIC_OUT_PLL_STATE		__BIT(1)
+#define  PCIE_PHY_RX_ASIC_OUT_VALID		__BIT(0)
+#define PCIE_PHY_TX_VMD_FSM_TX_VCM_0		0x1011
+#define PCIE_PHY_TX_VMD_FSM_TX_VCM_1		0x1012
+#define PCIE_PHY_TX_VMD_FSM_TX_VCM_DEBUG_IN	0x1013
+#define PCIE_PHY_TX_VMD_FSM_TX_VCM_DEBUG_OUT	0x1014
+#define PCIE_PHY_TX_LBERT_CTL			0x1015
+#define PCIE_PHY_RX_LBERT_CTL			0x1016
+#define PCIE_PHY_RX_LBERT_ERR			0x1017
+#define PCIE_PHY_RX_SCOPE_CTL			0x1018
+#define PCIE_PHY_RX_SCOPE_PHASE			0x1019
+#define PCIE_PHY_RX_DPLL_FREQ			0x101a
+#define PCIE_PHY_RX_CDR_CTL			0x101b
+#define PCIE_PHY_RX_CDR_CDR_FSM_DEBUG		0x101c
+#define PCIE_PHY_RX_CDR_LOCK_VEC_OVRD		0x101d
+#define PCIE_PHY_RX_CDR_LOCK_VEC		0x101e
+#define PCIE_PHY_RX_CDR_ADAP_FSM		0x101f
+#define PCIE_PHY_RX_ATB0			0x1020
+#define PCIE_PHY_RX_ATB1			0x1021
+#define PCIE_PHY_RX_ENPWR0			0x1022
+#define PCIE_PHY_RX_PMIX_PHASE			0x1023
+#define PCIE_PHY_RX_ENPWR1			0x1024
+#define PCIE_PHY_RX_ENPWR2			0x1025
+#define PCIE_PHY_RX_SCOPE			0x1026
+#define PCIE_PHY_TX_TXDRV_CNTRL			0x102b
+#define PCIE_PHY_TX_POWER_CTL			0x102c
+#define PCIE_PHY_TX_ALT_BLOCK			0x102d
+#define PCIE_PHY_TX_ALT_AND_LOOPBACK		0x102e
+#define PCIE_PHY_TX_TX_ATB_REG			0x102f
+
+#endif /* _ARM_IMX_IMX6_PCIEREG_H_ */

Index: src/sys/arch/evbarm/conf/HUMMINGBOARD
diff -u /dev/null src/sys/arch/evbarm/conf/HUMMINGBOARD:1.1
--- /dev/null	Thu Nov 24 12:06:44 2016
+++ src/sys/arch/evbarm/conf/HUMMINGBOARD	Thu Nov 24 12:06:44 2016
@@ -0,0 +1,158 @@
+#
+#	$NetBSD: HUMMINGBOARD,v 1.1 2016/11/24 12:06:44 hkenken Exp $
+#
+#	Hummingboard -- Freescale i.MX6 Eval Board Kernel
+#
+
+include	"arch/evbarm/conf/std.nitrogen6"
+include	"arch/evbarm/conf/GENERIC.common"
+
+# Board Type
+options 	EVBARM_BOARDTYPE=hummingboard
+#options 	EVBARM_BOARDTYPE=hummingboard_edge
+options		HUMMINGBOARD
+
+# CPU options
+options 	CPU_CORTEX
+options 	CPU_CORTEXA9
+options 	IMX6
+options 	MULTIPROCESSOR
+
+# Console options.    also need IMXUARTCONSOLE
+options 	CONSDEVNAME="\"imxuart\"",CONADDR=0x02020000
+options 	CONSPEED=115200	# Console speed
+
+options		DIAGNOSTIC      # internal consistency checks
+options		DEBUG
+#options 	KGDB
+makeoptions	DEBUG="-g"	# compile full symbol table
+makeoptions	COPY_SYMTAB=1
+
+# Valid options for BOOT_ARGS:
+#  single		Boot to single user only
+#  kdb			Give control to kernel debugger
+#  ask			Ask for file name to reboot from
+#  pmapdebug=<n>	If PMAP_DEBUG, set pmap_debug_level to <n>
+#  memorydisk=<n>	Set memorydisk size to <n> KB
+#  quiet		Show aprint_naive output
+#  verbose		Show aprint_normal and aprint_verbose output
+options		BOOT_ARGS="\"verbose\""
+
+# Kernel root file system and dump configuration.
+#config		netbsd		root on ? type ?
+config		netbsd-wd0	root on wd0 type ffs
+
+#
+# Device configuration
+#
+
+mainbus0	at root
+
+cpu*		at mainbus?
+
+# The MPCore interrupt controller and global timer
+armperiph0	at mainbus?		# A9 On-Chip Peripherals
+armgic0 	at armperiph?		# ARM Generic Interrupt Controller
+arml2cc0	at armperiph? flags 0	# ARM PL310 L2CC
+a9tmr0		at armperiph?		# A9 Global Timer
+#a9wdt0		at armperiph? flags 0	# A9 Watchdog Timer
+
+axi0		at mainbus?
+
+# GPIO
+imxgpio0	at axi? addr 0x0209c000 irqbase 256 irq 98
+imxgpio1	at axi? addr 0x020a0000 irqbase 288 irq 100
+imxgpio2	at axi? addr 0x020a4000 irqbase 320 irq 102
+imxgpio3	at axi? addr 0x020a8000 irqbase 352 irq 104
+imxgpio4	at axi? addr 0x020ac000 irqbase 384 irq 106
+imxgpio5	at axi? addr 0x020b0000 irqbase 416 irq 108
+imxgpio6	at axi? addr 0x020b4000 irqbase 448 irq 110
+gpio*		at imxgpio?
+options		IMX_GPIO_INTR_SPLIT
+
+# Clock Control
+imxccm0		at axi? addr 0x020c4000
+
+# On-Chip OTP Controller
+imxocotp0	at axi? addr 0x021bc000
+
+# IOMUX
+imxiomux0	at axi? addr 0x020e0000
+
+# WatchDog
+imxwdog0	at axi? addr 0x020bc000 irq 112 flags 0
+#imxwdog1	at axi? addr 0x020c0000 irq 113 flags 0
+
+# Serial
+imxuart0	at axi? addr 0x02020000 irq 58		# UART1
+#imxuart1	at axi? addr 0x021e8000 irq 59		# UART2
+#imxuart2	at axi? addr 0x021ec000 irq 60		# UART3
+#imxuart3	at axi? addr 0x021f0000 irq 61		# UART4
+#imxuart4	at axi? addr 0x021f4000 irq 62		# UART5
+options		IMXUARTCONSOLE
+
+# I2C
+imxi2c0		at axi? addr 0x021A0000 irq 68
+imxi2c1		at axi? addr 0x021A4000 irq 69
+imxi2c2		at axi? addr 0x021A8000 irq 70
+
+# IIC
+iic*		at imxi2c?
+
+# SATA
+ahcisata*	at axi? addr 0x02200000 irq 71
+atabus* 	at ahcisata? channel ?
+wd*		at atabus? drive ? flags 0x0000
+
+# ATAPI bus support
+atapibus*	at atapi?
+
+# ATAPI devices
+# flags have the same meaning as for IDE drives.
+cd*		at atapibus? drive ? flags 0x0000	# ATAPI CD-ROM drives
+sd*		at atapibus? drive ? flags 0x0000	# ATAPI disk drives
+st*		at atapibus? drive ? flags 0x0000	# ATAPI tape drives
+uk*		at atapibus? drive ? flags 0x0000	# ATAPI unknown
+
+# Network Interfaces
+enet0		at axi? addr 0x02188000 irq 150		# iMX6 SoC Ethernet
+
+# MII/PHY support
+atphy*	at mii? phy ?			# Attansic/Atheros PHYs
+ukphy*	at mii? phy ?			# generic unknown PHYs
+
+# SD/MMC
+#sdhc0    	at axi? addr 0x02190000 irq 54	# uSDHC1
+sdhc1   	at axi? addr 0x02194000 irq 55	# uSDHC2
+#sdhc2   	at axi? addr 0x02198000 irq 56	# uSDHC3
+#sdhc3   	at axi? addr 0x0219c000 irq 57	# uSDHC4
+sdmmc*		at sdhc?
+ld*		at sdmmc?			# MMC/SD card
+#options 	SDHC_DEBUG
+#options 	SDMMC_DEBUG
+
+# USB
+imxusbc0	at axi? addr 0x02184000
+ehci0		at imxusbc0	unit 0	irq 75 # OTG
+ehci1		at imxusbc0	unit 1	irq 72 # Host1
+#ehci2		at imxusbc0	unit 2	irq 73 # Host2
+#ehci3		at imxusbc0	unit 3	irq 74 # Host3
+
+usb*		at ehci?
+
+# USB device drivers
+include "dev/usb/usbdevices.config"
+
+midi*		at midibus?
+
+# PCIe
+imxpcie0	at axi? addr 0x01ffc000 irq 155		# PCIe
+#options PCIVERBOSE
+#options PCI_CONFIG_DUMP
+
+pci*		at imxpcie0
+ppb*		at pci? dev ? function ?
+pci*		at ppb?
+
+iwn*		at pci? dev ? function ?	# Intel PRO/Wireless 4965AGN
+iwm*		at pci? dev ? function ?	# Intel Centrino 7260

Reply via email to