Index: head/sys/arm/mv/gpio.c
===================================================================
--- head/sys/arm/mv/gpio.c	(revision 333030)
+++ head/sys/arm/mv/gpio.c	(revision 333031)
@@ -1,1127 +1,1284 @@
 /*-
  * SPDX-License-Identifier: BSD-2-Clause-FreeBSD
  *
  * Copyright (c) 2006 Benno Rice.
  * Copyright (C) 2008 MARVELL INTERNATIONAL LTD.
  * Copyright (c) 2017 Semihalf.
  * All rights reserved.
  *
  * Adapted and extended for Marvell SoCs by Semihalf.
  *
  * 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.
  *
  * from: FreeBSD: //depot/projects/arm/src/sys/arm/xscale/pxa2x0/pxa2x0_gpio.c, rev 1
  */
 
 #include <sys/cdefs.h>
 __FBSDID("$FreeBSD$");
 
 #include <sys/param.h>
 #include <sys/systm.h>
 #include <sys/bus.h>
 #include <sys/kernel.h>
 #include <sys/lock.h>
 #include <sys/interrupt.h>
 #include <sys/module.h>
 #include <sys/malloc.h>
 #include <sys/mutex.h>
 #include <sys/rman.h>
 #include <sys/queue.h>
 #include <sys/timetc.h>
 #include <sys/callout.h>
 #include <sys/gpio.h>
 #include <machine/bus.h>
 #include <machine/intr.h>
 
+#include <dev/gpio/gpiobusvar.h>
 #include <dev/fdt/fdt_common.h>
 #include <dev/ofw/ofw_bus.h>
 #include <dev/ofw/ofw_bus_subr.h>
 
 #include <arm/mv/mvvar.h>
 #include <arm/mv/mvreg.h>
 
+#include "gpio_if.h"
+
 #define GPIO_MAX_INTR_COUNT	8
 #define GPIO_PINS_PER_REG	32
+#define GPIO_GENERIC_CAP	(GPIO_PIN_INPUT | GPIO_PIN_OUTPUT |		\
+				GPIO_PIN_OPENDRAIN | GPIO_PIN_PUSHPULL |	\
+				GPIO_PIN_TRISTATE | GPIO_PIN_PULLUP |		\
+				GPIO_PIN_PULLDOWN | GPIO_PIN_INVIN |		\
+				GPIO_PIN_INVOUT)
 
 #define DEBOUNCE_CHECK_MS	1
 #define DEBOUNCE_LO_HI_MS	2
 #define DEBOUNCE_HI_LO_MS	2
 #define DEBOUNCE_CHECK_TICKS	((hz / 1000) * DEBOUNCE_CHECK_MS)
 
 struct mv_gpio_softc {
+	device_t		sc_busdev;
 	struct resource	*	mem_res;
 	int			mem_rid;
 	struct resource	*	irq_res[GPIO_MAX_INTR_COUNT];
 	int			irq_rid[GPIO_MAX_INTR_COUNT];
 	struct intr_event *	gpio_events[MV_GPIO_MAX_NPINS];
 	void			*ih_cookie[GPIO_MAX_INTR_COUNT];
 	bus_space_tag_t		bst;
 	bus_space_handle_t	bsh;
 	struct mtx		mutex;
 	uint8_t			pin_num;	/* number of GPIO pins */
 	uint8_t			irq_num;	/* number of real IRQs occupied by GPIO controller */
 	struct gpio_pin		gpio_setup[MV_GPIO_MAX_NPINS];
 
 	/* Used for debouncing. */
 	uint32_t		debounced_state_lo;
 	uint32_t		debounced_state_hi;
 	struct callout		**debounce_callouts;
 	int			*debounce_counters;
 };
 
 struct mv_gpio_pindev {
 	device_t dev;
 	int pin;
 };
 
 static int	mv_gpio_probe(device_t);
 static int	mv_gpio_attach(device_t);
 static int	mv_gpio_intr(device_t, void *);
 static int	mv_gpio_init(device_t);
 
 static void	mv_gpio_double_edge_init(device_t, int);
 
 static int	mv_gpio_debounce_setup(device_t, int);
 static int	mv_gpio_debounce_prepare(device_t, int);
 static int	mv_gpio_debounce_init(device_t, int);
 static void	mv_gpio_debounce_start(device_t, int);
 static void	mv_gpio_debounce(void *);
 static void	mv_gpio_debounced_state_set(device_t, int, uint8_t);
 static uint32_t	mv_gpio_debounced_state_get(device_t, int);
 
 static void	mv_gpio_exec_intr_handlers(device_t, uint32_t, int);
 static void	mv_gpio_intr_handler(device_t, int);
 static uint32_t	mv_gpio_reg_read(device_t, uint32_t);
 static void	mv_gpio_reg_write(device_t, uint32_t, uint32_t);
 static void	mv_gpio_reg_set(device_t, uint32_t, uint32_t);
 static void	mv_gpio_reg_clear(device_t, uint32_t, uint32_t);
 
 static void	mv_gpio_blink(device_t, uint32_t, uint8_t);
 static void	mv_gpio_polarity(device_t, uint32_t, uint8_t, uint8_t);
 static void	mv_gpio_level(device_t, uint32_t, uint8_t);
 static void	mv_gpio_edge(device_t, uint32_t, uint8_t);
 static void	mv_gpio_out_en(device_t, uint32_t, uint8_t);
 static void	mv_gpio_int_ack(struct mv_gpio_pindev *);
 static void	mv_gpio_value_set(device_t, uint32_t, uint8_t);
 static uint32_t	mv_gpio_value_get(device_t, uint32_t, uint8_t);
 
 static void	mv_gpio_intr_mask(struct mv_gpio_pindev *);
 static void	mv_gpio_intr_unmask(struct mv_gpio_pindev *);
 
 void mv_gpio_finish_intrhandler(struct mv_gpio_pindev *);
 int mv_gpio_setup_intrhandler(device_t, const char *,
     driver_filter_t *, void (*)(void *), void *,
     int, int, void **);
 int mv_gpio_configure(device_t, uint32_t, uint32_t, uint32_t);
 void mv_gpio_out(device_t, uint32_t, uint8_t, uint8_t);
 uint8_t mv_gpio_in(device_t, uint32_t);
 
+/*
+ * GPIO interface
+ */
+static device_t mv_gpio_get_bus(device_t);
+static int mv_gpio_pin_max(device_t, int *);
+static int mv_gpio_pin_getcaps(device_t, uint32_t, uint32_t *);
+static int mv_gpio_pin_getflags(device_t, uint32_t, uint32_t *);
+static int mv_gpio_pin_getname(device_t, uint32_t, char *);
+static int mv_gpio_pin_setflags(device_t, uint32_t, uint32_t);
+static int mv_gpio_pin_set(device_t, uint32_t, unsigned int);
+static int mv_gpio_pin_get(device_t, uint32_t, unsigned int *);
+static int mv_gpio_pin_toggle(device_t, uint32_t);
+
 #define MV_GPIO_LOCK()		mtx_lock_spin(&sc->mutex)
 #define MV_GPIO_UNLOCK()	mtx_unlock_spin(&sc->mutex)
 #define MV_GPIO_ASSERT_LOCKED()	mtx_assert(&sc->mutex, MA_OWNED)
 
 static device_method_t mv_gpio_methods[] = {
 	DEVMETHOD(device_probe,		mv_gpio_probe),
 	DEVMETHOD(device_attach,	mv_gpio_attach),
-	{ 0, 0 }
+
+	/* GPIO protocol */
+	DEVMETHOD(gpio_get_bus,		mv_gpio_get_bus),
+	DEVMETHOD(gpio_pin_max,		mv_gpio_pin_max),
+	DEVMETHOD(gpio_pin_getname,	mv_gpio_pin_getname),
+	DEVMETHOD(gpio_pin_getflags,	mv_gpio_pin_getflags),
+	DEVMETHOD(gpio_pin_getcaps,	mv_gpio_pin_getcaps),
+	DEVMETHOD(gpio_pin_setflags,	mv_gpio_pin_setflags),
+	DEVMETHOD(gpio_pin_get,		mv_gpio_pin_get),
+	DEVMETHOD(gpio_pin_set,		mv_gpio_pin_set),
+	DEVMETHOD(gpio_pin_toggle,	mv_gpio_pin_toggle),
+
+	DEVMETHOD_END
 };
 
 static driver_t mv_gpio_driver = {
 	"gpio",
 	mv_gpio_methods,
 	sizeof(struct mv_gpio_softc),
 };
 
 static devclass_t mv_gpio_devclass;
 
-DRIVER_MODULE(gpio, simplebus, mv_gpio_driver, mv_gpio_devclass, 0, 0);
+DRIVER_MODULE(mv_gpio, simplebus, mv_gpio_driver, mv_gpio_devclass, 0, 0);
 
-typedef int (*gpios_phandler_t)(device_t, phandle_t, pcell_t *, int);
-
-struct gpio_ctrl_entry {
-	const char		*compat;
-	gpios_phandler_t	handler;
-};
-
 static int mv_handle_gpios_prop(device_t, phandle_t, pcell_t *, int);
-int gpio_get_config_from_dt(void);
 
-struct gpio_ctrl_entry gpio_controllers[] = {
-	{ "mrvl,gpio", &mv_handle_gpios_prop },
-	{ NULL, NULL }
+struct ofw_compat_data gpio_controllers[] = {
+	{ "mrvl,gpio", (uintptr_t)&mv_handle_gpios_prop },
+	{ "marvell,orion-gpio", (uintptr_t)&mv_handle_gpios_prop },
+	{ NULL, 0 }
 };
 
 static int
 mv_gpio_probe(device_t dev)
 {
-
 	if (!ofw_bus_status_okay(dev))
 		return (ENXIO);
 
-	if (!ofw_bus_is_compatible(dev, "mrvl,gpio"))
+	if (ofw_bus_search_compatible(dev, gpio_controllers)->ocd_data == 0)
 		return (ENXIO);
 
 	device_set_desc(dev, "Marvell Integrated GPIO Controller");
 	return (0);
 }
 
 static int
 mv_gpio_attach(device_t dev)
 {
 	int error, i, size;
 	struct mv_gpio_softc *sc;
-	uint32_t dev_id, rev_id;
 	pcell_t pincnt = 0;
 	pcell_t irq_cells = 0;
 	phandle_t iparent;
 
 	sc = (struct mv_gpio_softc *)device_get_softc(dev);
 	if (sc == NULL)
 		return (ENXIO);
 
-	/* Get chip id and revision */
-	soc_id(&dev_id, &rev_id);
-
-	if (dev_id == MV_DEV_88F5182 ||
-	    dev_id == MV_DEV_88F5281 ||
-	    dev_id == MV_DEV_MV78100 ||
-	    dev_id == MV_DEV_MV78100_Z0 ) {
-		sc->pin_num = 32;
-		sc->irq_num = 4;
-
-	} else if (dev_id == MV_DEV_88F6281 ||
-	    dev_id == MV_DEV_88F6282) {
-		sc->pin_num = 50;
-		sc->irq_num = 7;
-
-	} else {
-		if (OF_getencprop(ofw_bus_get_node(dev), "pin-count", &pincnt,
-		    sizeof(pcell_t)) >= 0 ||
-		    OF_getencprop(ofw_bus_get_node(dev), "ngpios", &pincnt,
-		    sizeof(pcell_t)) >= 0) {
-			sc->pin_num = pincnt;
+	if (OF_getencprop(ofw_bus_get_node(dev), "pin-count", &pincnt,
+	    sizeof(pcell_t)) >= 0 ||
+	    OF_getencprop(ofw_bus_get_node(dev), "ngpios", &pincnt,
+	    sizeof(pcell_t)) >= 0) {
+		sc->pin_num = MIN(pincnt, MV_GPIO_MAX_NPINS);
+		if (bootverbose)
 			device_printf(dev, "%d pins available\n", sc->pin_num);
-		} else {
-			device_printf(dev, "ERROR: no pin-count entry found!\n");
-			return (ENXIO);
-		}
+	} else {
+		device_printf(dev, "ERROR: no pin-count or ngpios entry found!\n");
+		return (ENXIO);
 	}
 
+	/* Assign generic capabilities to every gpio pin */
+	for(i = 0; i < sc->pin_num; i++)
+		sc->gpio_setup[i].gp_caps = GPIO_GENERIC_CAP;
+
 	/* Find root interrupt controller */
 	iparent = ofw_bus_find_iparent(ofw_bus_get_node(dev));
 	if (iparent == 0) {
 		device_printf(dev, "No interrupt-parrent found. "
 				"Error in DTB\n");
 		return (ENXIO);
 	} else {
 		/* While at parent - store interrupt cells prop */
 		if (OF_searchencprop(OF_node_from_xref(iparent),
 		    "#interrupt-cells", &irq_cells, sizeof(irq_cells)) == -1) {
 			device_printf(dev, "DTB: Missing #interrupt-cells "
 			    "property in interrupt parent node\n");
 			return (ENXIO);
 		}
 	}
 
 	size = OF_getproplen(ofw_bus_get_node(dev), "interrupts");
 	if (size != -1) {
 		size = size / sizeof(pcell_t);
 		size = size / irq_cells;
 		sc->irq_num = size;
 		device_printf(dev, "%d IRQs available\n", sc->irq_num);
 	} else {
 		device_printf(dev, "ERROR: no interrupts entry found!\n");
 		return (ENXIO);
 	}
 
 	sc->debounce_callouts = (struct callout **)malloc(sc->pin_num *
 	    sizeof(struct callout *), M_DEVBUF, M_WAITOK | M_ZERO);
 	if (sc->debounce_callouts == NULL)
 		return (ENOMEM);
 
 	sc->debounce_counters = (int *)malloc(sc->pin_num * sizeof(int),
 	    M_DEVBUF, M_WAITOK);
 	if (sc->debounce_counters == NULL)
 		return (ENOMEM);
 
 	mtx_init(&sc->mutex, device_get_nameunit(dev), NULL, MTX_SPIN);
 
 	sc->mem_rid = 0;
 	sc->mem_res = bus_alloc_resource_any(dev, SYS_RES_MEMORY, &sc->mem_rid,
 		 RF_ACTIVE);
 
 	if (!sc->mem_res) {
 		mtx_destroy(&sc->mutex);
 		device_printf(dev, "could not allocate memory window\n");
 		return (ENXIO);
 	}
 
 	sc->bst = rman_get_bustag(sc->mem_res);
 	sc->bsh = rman_get_bushandle(sc->mem_res);
 
 	for (i = 0; i < sc->irq_num; i++) {
 		sc->irq_rid[i] = i;
 		sc->irq_res[i] = bus_alloc_resource_any(dev, SYS_RES_IRQ,
 			&sc->irq_rid[i], RF_ACTIVE);
 		if (!sc->irq_res[i]) {
 			mtx_destroy(&sc->mutex);
 			device_printf(dev,
 			    "could not allocate gpio%d interrupt\n", i+1);
 			return (ENXIO);
 		}
 	}
 
 	/* Disable all interrupts */
 	bus_space_write_4(sc->bst, sc->bsh, GPIO_INT_EDGE_MASK, 0);
 	bus_space_write_4(sc->bst, sc->bsh, GPIO_INT_LEV_MASK, 0);
 
 	for (i = 0; i < sc->irq_num; i++) {
 		if (bus_setup_intr(dev, sc->irq_res[i],
 		    INTR_TYPE_MISC,
 		    (driver_filter_t *)mv_gpio_intr, NULL,
 		    sc, &sc->ih_cookie[i]) != 0) {
 			mtx_destroy(&sc->mutex);
 			bus_release_resource(dev, SYS_RES_IRQ,
 				sc->irq_rid[i], sc->irq_res[i]);
 			device_printf(dev, "could not set up intr %d\n", i);
 			return (ENXIO);
 		}
 	}
 
 	error = mv_gpio_init(dev);
 	if (error) {
 		device_printf(dev, "WARNING: failed to initialize GPIO pins, "
 		    "error = %d\n", error);
 	}
 
 	/* Clear interrupt status. */
 	bus_space_write_4(sc->bst, sc->bsh, GPIO_INT_CAUSE, 0);
 
-	device_add_child(dev, "gpioc", device_get_unit(dev));
-	device_add_child(dev, "gpiobus", device_get_unit(dev));
+	sc->sc_busdev = gpiobus_attach_bus(dev);
+	if (sc->sc_busdev == NULL) {
+		mtx_destroy(&sc->mutex);
+		bus_release_resource(dev, SYS_RES_IRQ,
+			sc->irq_rid[i], sc->irq_res[i]);
+		return (ENXIO);
+	}
 
 	return (0);
 }
 
 static int
 mv_gpio_intr(device_t dev, void *arg)
 {
 	uint32_t int_cause, gpio_val;
 	struct mv_gpio_softc *sc;
 	sc = (struct mv_gpio_softc *)device_get_softc(dev);
 
 	MV_GPIO_LOCK();
 
 	/*
 	 * According to documentation, edge sensitive interrupts are asserted
 	 * when unmasked GPIO_INT_CAUSE register bits are set.
 	 */
 	int_cause = mv_gpio_reg_read(dev, GPIO_INT_CAUSE);
 	int_cause &= mv_gpio_reg_read(dev, GPIO_INT_EDGE_MASK);
 
 	/*
 	 * Level sensitive interrupts are asserted when unmasked GPIO_DATA_IN
 	 * register bits are set.
 	 */
 	gpio_val = mv_gpio_reg_read(dev, GPIO_DATA_IN);
 	gpio_val &= mv_gpio_reg_read(dev, GPIO_INT_LEV_MASK);
 
 	mv_gpio_exec_intr_handlers(dev, int_cause | gpio_val, 0);
 
 	MV_GPIO_UNLOCK();
 
 	return (FILTER_HANDLED);
 }
 
 /*
  * GPIO interrupt handling
  */
 
 void
 mv_gpio_finish_intrhandler(struct mv_gpio_pindev *s)
 {
 	/* When we acheive full interrupt support
 	 * This function will be opposite to
 	 * mv_gpio_setup_intrhandler
 	 */
 
 	/* Now it exists only to remind that
 	 * there should be place to free mv_gpio_pindev
 	 * allocated by mv_gpio_setup_intrhandler
 	 */
 	free(s, M_DEVBUF);
 }
 
 int
 mv_gpio_setup_intrhandler(device_t dev, const char *name, driver_filter_t *filt,
     void (*hand)(void *), void *arg, int pin, int flags, void **cookiep)
 {
 	struct	intr_event *event;
 	int	error;
 	struct mv_gpio_pindev *s;
 	struct mv_gpio_softc *sc;
 	sc = (struct mv_gpio_softc *)device_get_softc(dev);
 	s = malloc(sizeof(struct mv_gpio_pindev), M_DEVBUF, M_NOWAIT | M_ZERO);
 
 	if (pin < 0 || pin >= sc->pin_num)
 		return (ENXIO);
 	event = sc->gpio_events[pin];
 	if (event == NULL) {
 		MV_GPIO_LOCK();
 		if (sc->gpio_setup[pin].gp_flags & MV_GPIO_IN_DEBOUNCE) {
 			error = mv_gpio_debounce_init(dev, pin);
 			if (error != 0) {
 				MV_GPIO_UNLOCK();
 				return (error);
 			}
 		} else if (sc->gpio_setup[pin].gp_flags & MV_GPIO_IN_IRQ_DOUBLE_EDGE)
 			mv_gpio_double_edge_init(dev, pin);
 		MV_GPIO_UNLOCK();
 		error = intr_event_create(&event, (void *)s, 0, pin,
 		    (void (*)(void *))mv_gpio_intr_mask,
 		    (void (*)(void *))mv_gpio_intr_unmask,
 		    (void (*)(void *))mv_gpio_int_ack,
 		    NULL,
 		    "gpio%d:", pin);
 		if (error != 0)
 			return (error);
 		sc->gpio_events[pin] = event;
 	}
 
 	intr_event_add_handler(event, name, filt, hand, arg,
 	    intr_priority(flags), flags, cookiep);
 	return (0);
 }
 
 static void
 mv_gpio_intr_mask(struct mv_gpio_pindev *s)
 {
 	struct mv_gpio_softc *sc;
 	sc = (struct mv_gpio_softc *)device_get_softc(s->dev);
 
 	if (s->pin >= sc->pin_num)
 		return;
 
 	MV_GPIO_LOCK();
 
 	if (sc->gpio_setup[s->pin].gp_flags & (MV_GPIO_IN_IRQ_EDGE |
 	    MV_GPIO_IN_IRQ_DOUBLE_EDGE))
 		mv_gpio_edge(s->dev, s->pin, 0);
 	else
 		mv_gpio_level(s->dev, s->pin, 0);
 
 	/*
 	 * The interrupt has to be acknowledged before scheduling an interrupt
 	 * thread. This way we allow for interrupt source to trigger again
 	 * (which can happen with shared IRQs e.g. PCI) while processing the
 	 * current event.
 	 */
 	mv_gpio_int_ack(s);
 
 	MV_GPIO_UNLOCK();
 
 	return;
 }
 
 static void
 mv_gpio_intr_unmask(struct mv_gpio_pindev *s)
 {
 	struct mv_gpio_softc *sc;
 	sc = (struct mv_gpio_softc *)device_get_softc(s->dev);
 
 	if (s->pin >= sc->pin_num)
 		return;
 
 	MV_GPIO_LOCK();
 
 	if (sc->gpio_setup[s->pin].gp_flags & (MV_GPIO_IN_IRQ_EDGE |
 	    MV_GPIO_IN_IRQ_DOUBLE_EDGE))
 		mv_gpio_edge(s->dev, s->pin, 1);
 	else
 		mv_gpio_level(s->dev, s->pin, 1);
 
 	MV_GPIO_UNLOCK();
 
 	return;
 }
 
 static void
 mv_gpio_exec_intr_handlers(device_t dev, uint32_t status, int high)
 {
 	int i, pin;
 	struct mv_gpio_softc *sc;
 	sc = (struct mv_gpio_softc *)device_get_softc(dev);
 
 	MV_GPIO_ASSERT_LOCKED();
 
 	i = 0;
 	while (status != 0) {
 		if (status & 1) {
 			pin = (high ? (i + GPIO_PINS_PER_REG) : i);
 			if (sc->gpio_setup[pin].gp_flags & MV_GPIO_IN_DEBOUNCE)
 				mv_gpio_debounce_start(dev, pin);
 			else if (sc->gpio_setup[pin].gp_flags & MV_GPIO_IN_IRQ_DOUBLE_EDGE) {
 				mv_gpio_polarity(dev, pin, 0, 1);
 				mv_gpio_intr_handler(dev, pin);
 			} else
 				mv_gpio_intr_handler(dev, pin);
 		}
 		status >>= 1;
 		i++;
 	}
 }
 
 static void
 mv_gpio_intr_handler(device_t dev, int pin)
 {
 #ifdef INTRNG
 	struct intr_irqsrc isrc;
 	struct mv_gpio_softc *sc;
 	sc = (struct mv_gpio_softc *)device_get_softc(dev);
 
 	MV_GPIO_ASSERT_LOCKED();
 
 #ifdef INTR_SOLO
 	isrc.isrc_filter = NULL;
 #endif
 	isrc.isrc_event = sc->gpio_events[pin];
 
 	if (isrc.isrc_event == NULL || TAILQ_EMPTY(&isrc.isrc_event->ie_handlers))
 		return;
 
 	intr_isrc_dispatch(&isrc, NULL);
 #endif
 }
 
 int
 mv_gpio_configure(device_t dev, uint32_t pin, uint32_t flags, uint32_t mask)
 {
 	int error;
 	struct mv_gpio_softc *sc;
 	sc = (struct mv_gpio_softc *)device_get_softc(dev);
 	error = 0;
 
 	if (pin >= sc->pin_num)
 		return (EINVAL);
 
 	/* check flags consistency */
 	if (((flags & mask) & (GPIO_PIN_INPUT | GPIO_PIN_OUTPUT)) ==
 	    (GPIO_PIN_INPUT | GPIO_PIN_OUTPUT))
 		return (EINVAL);
 
 	if (mask & MV_GPIO_IN_DEBOUNCE) {
 		error = mv_gpio_debounce_prepare(dev, pin);
 		if (error != 0)
 			return (error);
 	}
 
 	MV_GPIO_LOCK();
 
+	if ((mask & flags) & GPIO_PIN_INPUT)
+		mv_gpio_out_en(dev, pin, 0);
+	if ((mask & flags) & GPIO_PIN_OUTPUT) {
+		if ((flags & mask) & GPIO_PIN_OPENDRAIN)
+			mv_gpio_value_set(dev, pin, 0);
+		else
+			mv_gpio_value_set(dev, pin, 1);
+		mv_gpio_out_en(dev, pin, 1);
+	}
+
 	if (mask & MV_GPIO_OUT_BLINK)
 		mv_gpio_blink(dev, pin, flags & MV_GPIO_OUT_BLINK);
 	if (mask & MV_GPIO_IN_POL_LOW)
 		mv_gpio_polarity(dev, pin, flags & MV_GPIO_IN_POL_LOW, 0);
 	if (mask & MV_GPIO_IN_DEBOUNCE) {
 		error = mv_gpio_debounce_setup(dev, pin);
 		if (error) {
 			MV_GPIO_UNLOCK();
 			return (error);
 		}
 	}
 
 	sc->gpio_setup[pin].gp_flags &= ~(mask);
 	sc->gpio_setup[pin].gp_flags |= (flags & mask);
 
 	MV_GPIO_UNLOCK();
 
 	return (0);
 }
 
 static void
 mv_gpio_double_edge_init(device_t dev, int pin)
 {
 	uint8_t raw_read;
 	struct mv_gpio_softc *sc;
 	sc = (struct mv_gpio_softc *)device_get_softc(dev);
 
 	MV_GPIO_ASSERT_LOCKED();
 
 	raw_read = (mv_gpio_value_get(dev, pin, 1) ? 1 : 0);
 
 	if (raw_read)
 		mv_gpio_polarity(dev, pin, 1, 0);
 	else
 		mv_gpio_polarity(dev, pin, 0, 0);
 }
 
 static int
 mv_gpio_debounce_setup(device_t dev, int pin)
 {
 	struct callout *c;
 	struct mv_gpio_softc *sc;
 
 	sc = (struct mv_gpio_softc *)device_get_softc(dev);
 
 	MV_GPIO_ASSERT_LOCKED();
 
 	c = sc->debounce_callouts[pin];
 	if (c == NULL)
 		return (ENXIO);
 
 	if (callout_active(c))
 		callout_deactivate(c);
 
 	callout_stop(c);
 
 	return (0);
 }
 
 static int
 mv_gpio_debounce_prepare(device_t dev, int pin)
 {
 	struct callout *c;
 	struct mv_gpio_softc *sc;
 
 	sc = (struct mv_gpio_softc *)device_get_softc(dev);
 
 	c = sc->debounce_callouts[pin];
 	if (c == NULL) {
 		c = (struct callout *)malloc(sizeof(struct callout),
 		    M_DEVBUF, M_WAITOK);
 		sc->debounce_callouts[pin] = c;
 		if (c == NULL)
 			return (ENOMEM);
 		callout_init(c, 1);
 	}
 
 	return (0);
 }
 
 static int
 mv_gpio_debounce_init(device_t dev, int pin)
 {
 	uint8_t raw_read;
 	int *cnt;
 	struct mv_gpio_softc *sc;
 
 	sc = (struct mv_gpio_softc *)device_get_softc(dev);
 
 	MV_GPIO_ASSERT_LOCKED();
 
 	cnt = &sc->debounce_counters[pin];
 	raw_read = (mv_gpio_value_get(dev, pin, 1) ? 1 : 0);
 	if (raw_read) {
 		mv_gpio_polarity(dev, pin, 1, 0);
 		*cnt = DEBOUNCE_HI_LO_MS / DEBOUNCE_CHECK_MS;
 	} else {
 		mv_gpio_polarity(dev, pin, 0, 0);
 		*cnt = DEBOUNCE_LO_HI_MS / DEBOUNCE_CHECK_MS;
 	}
 
 	mv_gpio_debounced_state_set(dev, pin, raw_read);
 
 	return (0);
 }
 
 static void
 mv_gpio_debounce_start(device_t dev, int pin)
 {
 	struct callout *c;
 	struct mv_gpio_pindev s = {dev, pin};
 	struct mv_gpio_pindev *sd;
 	struct mv_gpio_softc *sc;
 	sc = (struct mv_gpio_softc *)device_get_softc(dev);
 
 	MV_GPIO_ASSERT_LOCKED();
 
 	c = sc->debounce_callouts[pin];
 	if (c == NULL) {
 		mv_gpio_int_ack(&s);
 		return;
 	}
 
 	if (callout_pending(c) || callout_active(c)) {
 		mv_gpio_int_ack(&s);
 		return;
 	}
 
 	sd = (struct mv_gpio_pindev *)malloc(sizeof(struct mv_gpio_pindev),
 	    M_DEVBUF, M_WAITOK);
 	if (sd == NULL) {
 		mv_gpio_int_ack(&s);
 		return;
 	}
 	sd->pin = pin;
 	sd->dev = dev;
 
 	callout_reset(c, DEBOUNCE_CHECK_TICKS, mv_gpio_debounce, sd);
 }
 
 static void
 mv_gpio_debounce(void *arg)
 {
 	uint8_t raw_read, last_state;
 	int pin;
 	device_t dev;
 	int *debounce_counter;
 	struct mv_gpio_softc *sc;
 	struct mv_gpio_pindev *s;
 
 	s = (struct mv_gpio_pindev *)arg;
 	dev = s->dev;
 	pin = s->pin;
 	sc = (struct mv_gpio_softc *)device_get_softc(dev);
 
 	MV_GPIO_LOCK();
 
 	raw_read = (mv_gpio_value_get(dev, pin, 1) ? 1 : 0);
 	last_state = (mv_gpio_debounced_state_get(dev, pin) ? 1 : 0);
 	debounce_counter = &sc->debounce_counters[pin];
 
 	if (raw_read == last_state) {
 		if (last_state)
 			*debounce_counter = DEBOUNCE_HI_LO_MS /
 			    DEBOUNCE_CHECK_MS;
 		else
 			*debounce_counter = DEBOUNCE_LO_HI_MS /
 			    DEBOUNCE_CHECK_MS;
 
 		callout_reset(sc->debounce_callouts[pin],
 		    DEBOUNCE_CHECK_TICKS, mv_gpio_debounce, arg);
 	} else {
 		*debounce_counter = *debounce_counter - 1;
 		if (*debounce_counter != 0)
 			callout_reset(sc->debounce_callouts[pin],
 			    DEBOUNCE_CHECK_TICKS, mv_gpio_debounce, arg);
 		else {
 			mv_gpio_debounced_state_set(dev, pin, raw_read);
 
 			if (last_state)
 				*debounce_counter = DEBOUNCE_HI_LO_MS /
 				    DEBOUNCE_CHECK_MS;
 			else
 				*debounce_counter = DEBOUNCE_LO_HI_MS /
 				    DEBOUNCE_CHECK_MS;
 
 			if (((sc->gpio_setup[pin].gp_flags & MV_GPIO_IN_POL_LOW) &&
 			    (raw_read == 0)) ||
 			    (((sc->gpio_setup[pin].gp_flags & MV_GPIO_IN_POL_LOW) == 0) &&
 			    raw_read) ||
 			    (sc->gpio_setup[pin].gp_flags & MV_GPIO_IN_IRQ_DOUBLE_EDGE))
 				mv_gpio_intr_handler(dev, pin);
 
 			/* Toggle polarity for next edge. */
 			mv_gpio_polarity(dev, pin, 0, 1);
 
 			free(arg, M_DEVBUF);
 			callout_deactivate(sc->debounce_callouts[pin]);
 		}
 	}
 
 	MV_GPIO_UNLOCK();
 }
 
 static void
 mv_gpio_debounced_state_set(device_t dev, int pin, uint8_t new_state)
 {
 	uint32_t *old_state;
 	struct mv_gpio_softc *sc;
 	sc = (struct mv_gpio_softc *)device_get_softc(dev);
 
 	MV_GPIO_ASSERT_LOCKED();
 
 	if (pin >= GPIO_PINS_PER_REG) {
 		old_state = &sc->debounced_state_hi;
 		pin -= GPIO_PINS_PER_REG;
 	} else
 		old_state = &sc->debounced_state_lo;
 
 	if (new_state)
 		*old_state |= (1 << pin);
 	else
 		*old_state &= ~(1 << pin);
 }
 
 static uint32_t
 mv_gpio_debounced_state_get(device_t dev, int pin)
 {
 	uint32_t *state;
 	struct mv_gpio_softc *sc;
 	sc = (struct mv_gpio_softc *)device_get_softc(dev);
 
 	MV_GPIO_ASSERT_LOCKED();
 
 	if (pin >= GPIO_PINS_PER_REG) {
 		state = &sc->debounced_state_hi;
 		pin -= GPIO_PINS_PER_REG;
 	} else
 		state = &sc->debounced_state_lo;
 
 	return (*state & (1 << pin));
 }
 
 void
 mv_gpio_out(device_t dev, uint32_t pin, uint8_t val, uint8_t enable)
 {
 	struct mv_gpio_softc *sc;
 	sc = (struct mv_gpio_softc *)device_get_softc(dev);
 
 	MV_GPIO_LOCK();
 
 	mv_gpio_value_set(dev, pin, val);
 	mv_gpio_out_en(dev, pin, enable);
 
 	MV_GPIO_UNLOCK();
 }
 
 uint8_t
 mv_gpio_in(device_t dev, uint32_t pin)
 {
 	uint8_t state;
 	struct mv_gpio_softc *sc;
 	sc = (struct mv_gpio_softc *)device_get_softc(dev);
 
-	MV_GPIO_LOCK();
+	MV_GPIO_ASSERT_LOCKED();
 
 	if (sc->gpio_setup[pin].gp_flags & MV_GPIO_IN_DEBOUNCE) {
 		if (sc->gpio_setup[pin].gp_flags & MV_GPIO_IN_POL_LOW)
 			state = (mv_gpio_debounced_state_get(dev, pin) ? 0 : 1);
 		else
 			state = (mv_gpio_debounced_state_get(dev, pin) ? 1 : 0);
 	} else if (sc->gpio_setup[pin].gp_flags & MV_GPIO_IN_IRQ_DOUBLE_EDGE) {
 		if (sc->gpio_setup[pin].gp_flags & MV_GPIO_IN_POL_LOW)
 			state = (mv_gpio_value_get(dev, pin, 1) ? 0 : 1);
 		else
 			state = (mv_gpio_value_get(dev, pin, 1) ? 1 : 0);
 	} else
 		state = (mv_gpio_value_get(dev, pin, 0) ? 1 : 0);
 
-
 	return (state);
 }
 
 static uint32_t
 mv_gpio_reg_read(device_t dev, uint32_t reg)
 {
 	struct mv_gpio_softc *sc;
 	sc = (struct mv_gpio_softc *)device_get_softc(dev);
 
 	return (bus_space_read_4(sc->bst, sc->bsh, reg));
 }
 
 static void
 mv_gpio_reg_write(device_t dev, uint32_t reg, uint32_t val)
 {
 	struct mv_gpio_softc *sc;
 	sc = (struct mv_gpio_softc *)device_get_softc(dev);
 
 	bus_space_write_4(sc->bst, sc->bsh, reg, val);
 }
 
 static void
 mv_gpio_reg_set(device_t dev, uint32_t reg, uint32_t pin)
 {
 	uint32_t reg_val;
 
 	reg_val = mv_gpio_reg_read(dev, reg);
 	reg_val |= GPIO(pin);
 	mv_gpio_reg_write(dev, reg, reg_val);
 }
 
 static void
 mv_gpio_reg_clear(device_t dev, uint32_t reg, uint32_t pin)
 {
 	uint32_t reg_val;
 
 	reg_val = mv_gpio_reg_read(dev, reg);
 	reg_val &= ~(GPIO(pin));
 	mv_gpio_reg_write(dev, reg, reg_val);
 }
 
 static void
 mv_gpio_out_en(device_t dev, uint32_t pin, uint8_t enable)
 {
 	uint32_t reg;
 	struct mv_gpio_softc *sc;
 	sc = (struct mv_gpio_softc *)device_get_softc(dev);
 
 	if (pin >= sc->pin_num)
 		return;
 
 	reg = GPIO_DATA_OUT_EN_CTRL;
 
 	if (enable)
 		mv_gpio_reg_clear(dev, reg, pin);
 	else
 		mv_gpio_reg_set(dev, reg, pin);
 }
 
 static void
 mv_gpio_blink(device_t dev, uint32_t pin, uint8_t enable)
 {
 	uint32_t reg;
 	struct mv_gpio_softc *sc;
 	sc = (struct mv_gpio_softc *)device_get_softc(dev);
 
 	if (pin >= sc->pin_num)
 		return;
 
 	reg = GPIO_BLINK_EN;
 
 	if (enable)
 		mv_gpio_reg_set(dev, reg, pin);
 	else
 		mv_gpio_reg_clear(dev, reg, pin);
 }
 
 static void
 mv_gpio_polarity(device_t dev, uint32_t pin, uint8_t enable, uint8_t toggle)
 {
 	uint32_t reg, reg_val;
 	struct mv_gpio_softc *sc;
 	sc = (struct mv_gpio_softc *)device_get_softc(dev);
 
 	if (pin >= sc->pin_num)
 		return;
 
 	reg = GPIO_DATA_IN_POLAR;
 
 	if (toggle) {
 		reg_val = mv_gpio_reg_read(dev, reg) & GPIO(pin);
 		if (reg_val)
 			mv_gpio_reg_clear(dev, reg, pin);
 		else
 			mv_gpio_reg_set(dev, reg, pin);
 	} else if (enable)
 		mv_gpio_reg_set(dev, reg, pin);
 	else
 		mv_gpio_reg_clear(dev, reg, pin);
 }
 
 static void
 mv_gpio_level(device_t dev, uint32_t pin, uint8_t enable)
 {
 	uint32_t reg;
 	struct mv_gpio_softc *sc;
 	sc = (struct mv_gpio_softc *)device_get_softc(dev);
 
 	if (pin >= sc->pin_num)
 		return;
 
 	reg = GPIO_INT_LEV_MASK;
 
 	if (enable)
 		mv_gpio_reg_set(dev, reg, pin);
 	else
 		mv_gpio_reg_clear(dev, reg, pin);
 }
 
 static void
 mv_gpio_edge(device_t dev, uint32_t pin, uint8_t enable)
 {
 	uint32_t reg;
 	struct mv_gpio_softc *sc;
 	sc = (struct mv_gpio_softc *)device_get_softc(dev);
 
 	if (pin >= sc->pin_num)
 		return;
 
 	reg = GPIO_INT_EDGE_MASK;
 
 	if (enable)
 		mv_gpio_reg_set(dev, reg, pin);
 	else
 		mv_gpio_reg_clear(dev, reg, pin);
 }
 
 static void
 mv_gpio_int_ack(struct mv_gpio_pindev *s)
 {
 	uint32_t reg, pin;
 	struct mv_gpio_softc *sc;
 	sc = (struct mv_gpio_softc *)device_get_softc(s->dev);
 	pin = s->pin;
 
 	if (pin >= sc->pin_num)
 		return;
 
 	reg = GPIO_INT_CAUSE;
 
 	mv_gpio_reg_clear(s->dev, reg, pin);
 }
 
 static uint32_t
 mv_gpio_value_get(device_t dev, uint32_t pin, uint8_t exclude_polar)
 {
 	uint32_t reg, polar_reg, reg_val, polar_reg_val;
 	struct mv_gpio_softc *sc;
 	sc = (struct mv_gpio_softc *)device_get_softc(dev);
 
 	if (pin >= sc->pin_num)
 		return (0);
 
 	reg = GPIO_DATA_IN;
 	polar_reg = GPIO_DATA_IN_POLAR;
 
 	reg_val = mv_gpio_reg_read(dev, reg);
 
 	if (exclude_polar) {
 		polar_reg_val = mv_gpio_reg_read(dev, polar_reg);
 		return ((reg_val & GPIO(pin)) ^ (polar_reg_val & GPIO(pin)));
 	} else
 		return (reg_val & GPIO(pin));
 }
 
 static void
 mv_gpio_value_set(device_t dev, uint32_t pin, uint8_t val)
 {
 	uint32_t reg;
 	struct mv_gpio_softc *sc;
 	sc = (struct mv_gpio_softc *)device_get_softc(dev);
 
+	MV_GPIO_ASSERT_LOCKED();
+
 	if (pin >= sc->pin_num)
 		return;
 
 	reg = GPIO_DATA_OUT;
 
 	if (val)
 		mv_gpio_reg_set(dev, reg, pin);
 	else
 		mv_gpio_reg_clear(dev, reg, pin);
 }
 
 static int
 mv_handle_gpios_prop(device_t dev, phandle_t ctrl, pcell_t *gpios, int len)
 {
 	pcell_t gpio_cells, pincnt;
 	int inc, t, tuples, tuple_size;
-	int dir, flags, pin;
+	int flags, pin;
 	u_long gpio_ctrl, size;
-	struct mv_gpio_softc sc;
 
 	pincnt = 0;
 	if (!OF_hasprop(ctrl, "gpio-controller"))
 		/* Node is not a GPIO controller. */
 		return (ENXIO);
 
 	if (OF_getencprop(ctrl, "#gpio-cells", &gpio_cells, sizeof(pcell_t)) < 0)
 		return (ENXIO);
-	if (gpio_cells != 3)
+	if (gpio_cells != 2)
 		return (ENXIO);
 
 	tuple_size = gpio_cells * sizeof(pcell_t) + sizeof(phandle_t);
 	tuples = len / tuple_size;
 
 	if (fdt_regsize(ctrl, &gpio_ctrl, &size))
 		return (ENXIO);
 
-	if (OF_getencprop(ctrl, "pin-count", &pincnt, sizeof(pcell_t)) < 0)
-		return (ENXIO);
-	sc.pin_num = pincnt;
-
 	/*
 	 * Skip controller reference, since controller's phandle is given
 	 * explicitly (in a function argument).
 	 */
 	inc = sizeof(ihandle_t) / sizeof(pcell_t);
 	gpios += inc;
 
 	for (t = 0; t < tuples; t++) {
 		pin = gpios[0];
-		dir = gpios[1];
-		flags = gpios[2];
+		flags = gpios[1];
 
 		mv_gpio_configure(dev, pin, flags, ~0);
-
-		if (dir == 1)
-			/* Input. */
-			mv_gpio_out_en(dev, pin, 0);
-		else {
-			/* Output. */
-			if (flags & MV_GPIO_OUT_OPEN_DRAIN)
-				mv_gpio_out(dev, pin, 0, 1);
-
-			if (flags & MV_GPIO_OUT_OPEN_SRC)
-				mv_gpio_out(dev, pin, 1, 1);
-		}
 		gpios += gpio_cells + inc;
 	}
 
 	return (0);
 }
 
 #define MAX_PINS_PER_NODE	5
 #define GPIOS_PROP_CELLS	4
 static int
 mv_gpio_init(device_t dev)
 {
 	phandle_t child, parent, root, ctrl;
 	pcell_t gpios[MAX_PINS_PER_NODE * GPIOS_PROP_CELLS];
-	struct gpio_ctrl_entry *e;
+	struct ofw_compat_data *e;
 	int len, rv;
 
 	root = OF_finddevice("/");
 	len = 0;
 	parent = root;
+	rv = 0;
 
 	/* Traverse through entire tree to find nodes with 'gpios' prop */
 	for (child = OF_child(parent); child != 0; child = OF_peer(child)) {
 
 		/* Find a 'leaf'. Start the search from this node. */
 		while (OF_child(child)) {
 			parent = child;
 			child = OF_child(child);
 		}
 		if ((len = OF_getproplen(child, "gpios")) > 0) {
 
 			if (len > sizeof(gpios))
 				return (ENXIO);
 
 			/* Get 'gpios' property. */
 			OF_getencprop(child, "gpios", gpios, len);
 
-			e = (struct gpio_ctrl_entry *)&gpio_controllers;
+			/*
+			 * First cell of 'gpios' property should
+			 * contain a ref. to a node defining GPIO
+			 * controller.
+			 */
+			ctrl = OF_node_from_xref(gpios[0]);
 
+			if(ctrl != ofw_bus_get_node(dev)) {
+				/* Not this gpio controller */
+				device_printf(dev, "Not this gpio controller ctrl: %x, dev: %x\n",
+					 ctrl, ofw_bus_get_node(dev));
+				continue;
+			}
+
+			e = gpio_controllers;
+
 			/* Find and call a handler. */
-			for (; e->compat; e++) {
-				/*
-				 * First cell of 'gpios' property should
-				 * contain a ref. to a node defining GPIO
-				 * controller.
-				 */
-				ctrl = OF_node_from_xref(gpios[0]);
+			for (; e->ocd_str; e++) {
 
-				if (ofw_bus_node_is_compatible(ctrl, e->compat))
+				if (ofw_bus_node_is_compatible(ctrl,e->ocd_str)) {
 					/* Call a handler. */
-					if ((rv = e->handler(dev, ctrl,
-					    (pcell_t *)&gpios, len)))
-						return (rv);
+					rv |= mv_handle_gpios_prop(dev, ctrl,
+					    (pcell_t *)&gpios, len);
+				}
 			}
 		}
 
-		if (OF_peer(child) == 0) {
+		while (OF_peer(child) == 0 && parent != root) {
 			/* No more siblings. */
 			child = parent;
 			parent = OF_parent(child);
 		}
 	}
+	return (rv);
+}
+
+static int
+mv_gpio_pin_max(device_t dev, int *maxpin)
+{
+	struct mv_gpio_softc *sc;
+	if (maxpin == NULL)
+		return (EINVAL);
+
+	sc = device_get_softc(dev);
+	*maxpin = sc->pin_num;
+
 	return (0);
+}
+
+static int
+mv_gpio_pin_getcaps(device_t dev, uint32_t pin, uint32_t *caps)
+{
+	struct mv_gpio_softc *sc = device_get_softc(dev);
+	if (caps == NULL)
+		return (EINVAL);
+
+	if (pin >= sc->pin_num)
+		return (EINVAL);
+
+	MV_GPIO_LOCK();
+	*caps = sc->gpio_setup[pin].gp_caps;
+	MV_GPIO_UNLOCK();
+
+	return (0);
+}
+
+static int
+mv_gpio_pin_getflags(device_t dev, uint32_t pin, uint32_t *flags)
+{
+	struct mv_gpio_softc *sc = device_get_softc(dev);
+	if (flags == NULL)
+		return (EINVAL);
+
+	if (pin >= sc->pin_num)
+		return (EINVAL);
+
+	MV_GPIO_LOCK();
+	*flags = sc->gpio_setup[pin].gp_flags;
+	MV_GPIO_UNLOCK();
+
+	return (0);
+}
+
+static int
+mv_gpio_pin_getname(device_t dev, uint32_t pin, char *name)
+{
+	struct mv_gpio_softc *sc = device_get_softc(dev);
+	if (name == NULL)
+		return (EINVAL);
+
+	if (pin >= sc->pin_num)
+		return (EINVAL);
+
+	MV_GPIO_LOCK();
+	memcpy(name, sc->gpio_setup[pin].gp_name, GPIOMAXNAME);
+	MV_GPIO_UNLOCK();
+
+	return (0);
+}
+
+static int
+mv_gpio_pin_setflags(device_t dev, uint32_t pin, uint32_t flags)
+{
+	int ret;
+	struct mv_gpio_softc *sc = device_get_softc(dev);
+	if (pin >= sc->pin_num)
+		return (EINVAL);
+
+	/* Check for unwanted flags. */
+	if ((flags & sc->gpio_setup[pin].gp_caps) != flags)
+		return (EINVAL);
+
+	ret = mv_gpio_configure(dev, pin, flags, ~0);
+
+	return (ret);
+}
+
+static int
+mv_gpio_pin_set(device_t dev, uint32_t pin, unsigned int value)
+{
+	struct mv_gpio_softc *sc = device_get_softc(dev);
+	if (pin >= sc->pin_num)
+		return (EINVAL);
+
+	MV_GPIO_LOCK();
+	mv_gpio_value_set(dev, pin, value);
+	MV_GPIO_UNLOCK();
+
+	return (0);
+}
+
+static int
+mv_gpio_pin_get(device_t dev, uint32_t pin, unsigned int *value)
+{
+	struct mv_gpio_softc *sc = device_get_softc(dev);
+	if (value == NULL)
+		return (EINVAL);
+
+	if (pin >= sc->pin_num)
+		return (EINVAL);
+
+	MV_GPIO_LOCK();
+	*value = mv_gpio_in(dev, pin);
+	MV_GPIO_UNLOCK();
+
+	return (0);
+}
+
+static int
+mv_gpio_pin_toggle(device_t dev, uint32_t pin)
+{
+	struct mv_gpio_softc *sc = device_get_softc(dev);
+	uint32_t value;
+	if (pin >= sc->pin_num)
+		return (EINVAL);
+
+	MV_GPIO_LOCK();
+	value = mv_gpio_in(dev, pin);
+	value = (~value) & 1;
+	mv_gpio_value_set(dev, pin, value);
+	MV_GPIO_UNLOCK();
+
+	return (0);
+}
+
+static device_t
+mv_gpio_get_bus(device_t dev)
+{
+	struct mv_gpio_softc *sc = device_get_softc(dev);
+
+	return (sc->sc_busdev);
 }
Index: head/sys/dts/arm/db78100.dts
===================================================================
--- head/sys/dts/arm/db78100.dts	(revision 333030)
+++ head/sys/dts/arm/db78100.dts	(revision 333031)
@@ -1,332 +1,332 @@
 /*
  * Copyright (c) 2010 The FreeBSD Foundation
  * All rights reserved.
  *
  * This software was developed by Semihalf under sponsorship from
  * the FreeBSD Foundation.
  *
  * 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 AND CONTRIBUTORS ``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 OR CONTRIBUTORS 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.
  *
  * Marvell DB-78100 Device Tree Source.
  *
  * $FreeBSD$
  */
 
 /dts-v1/;
 
 / {
 	model = "mrvl,DB-78100";
 	compatible = "DB-78100-BP", "DB-78100-BP-A";
 	#address-cells = <1>;
 	#size-cells = <1>;
 
 	aliases {
 		ethernet0 = &enet0;
 		serial0 = &serial0;
 		serial1 = &serial1;
 		mpp = &MPP;
 	};
 
 	cpus {
 		#address-cells = <1>;
 		#size-cells = <0>;
 
 		cpu@0 {
 			device_type = "cpu";
 			compatible = "ARM,88FR571";
 			reg = <0x0>;
 			d-cache-line-size = <32>;	// 32 bytes
 			i-cache-line-size = <32>;	// 32 bytes
 			d-cache-size = <0x4000>;	// L1, 16K
 			i-cache-size = <0x4000>;	// L1, 16K
 			timebase-frequency = <0>;
 			bus-frequency = <0>;
 			clock-frequency = <0>;
 		};
 	};
 
 	memory {
 		device_type = "memory";
 		reg = <0x0 0x20000000>;		// 512M at 0x0
 	};
 
 	localbus@0 {
 		#address-cells = <2>;
 		#size-cells = <1>;
 		compatible = "mrvl,lbc";
 		bank-count = <5>;
 
 		/* This reflects CPU decode windows setup. */
 		ranges = <0x0 0x2f 0xf9300000 0x00100000
 			  0x1 0x3e 0xf9400000 0x00100000
 			  0x2 0x3d 0xf9500000 0x02000000
 			  0x3 0x3b 0xfb500000 0x00100000>;
 
 		nor@0,0 {
 			#address-cells = <1>;
 			#size-cells = <1>;
 			compatible = "cfi-flash";
 			reg = <0x0 0x0 0x00100000>;
 		};
 
 		led@1,0 {
 			#address-cells = <1>;
 			#size-cells = <1>;
 			compatible = "led";
 			reg = <0x1 0x0 0x00100000>;
 		};
 
 		nor@2,0 {
 			#address-cells = <1>;
 			#size-cells = <1>;
 			compatible = "cfi-flash";
 			reg = <0x2 0x0 0x02000000>;
 		};
 
 		nand@3,0 {
 			#address-cells = <1>;
 			#size-cells = <1>;
 			compatible = "mrvl,nfc";
 			reg = <0x3 0x0 0x00100000>;
 		};
 	};
 
 	soc78100@f1000000 {
 		#address-cells = <1>;
 		#size-cells = <1>;
 		compatible = "simple-bus";
 		ranges = <0x0 0xf1000000 0x00100000>;
 		bus-frequency = <0>;
 
 		PIC: pic@20200 {
 			interrupt-controller;
 			#address-cells = <0>;
 			#interrupt-cells = <1>;
 			reg = <0x20200 0x3c>;
 			compatible = "mrvl,pic";
 		};
 
 		timer@20300 {
 			compatible = "mrvl,timer";
 			reg = <0x20300 0x30>;
 			interrupts = <8>;
 			interrupt-parent = <&PIC>;
 			mrvl,has-wdt;
 		};
 
 		MPP: mpp@10000 {
 			#pin-cells = <2>;
 			compatible = "mrvl,mpp";
 			reg = <0x10000 0x34>;
 			pin-count = <50>;
 			pin-map = <
 				0  2		/* MPP[0]:  GE1_TXCLK */
 				1  2		/* MPP[1]:  GE1_TXCTL */
 				2  2		/* MPP[2]:  GE1_RXCTL */
 				3  2		/* MPP[3]:  GE1_RXCLK */
 				4  2		/* MPP[4]:  GE1_TXD[0] */
 				5  2		/* MPP[5]:  GE1_TXD[1] */
 				6  2		/* MPP[6]:  GE1_TXD[2] */
 				7  2		/* MPP[7]:  GE1_TXD[3] */
 				8  2		/* MPP[8]:  GE1_RXD[0] */
 				9  2		/* MPP[9]:  GE1_RXD[1] */
 				10 2		/* MPP[10]: GE1_RXD[2] */
 				11 2		/* MPP[11]: GE1_RXD[3] */
 				13 3		/* MPP[13]: SYSRST_OUTn */
 				14 3		/* MPP[14]: SATA1_ACTn */
 				15 3		/* MPP[15]: SATA0_ACTn */
 				16 4		/* MPP[16]: UA2_TXD */
 				17 4		/* MPP[17]: UA2_RXD */
 				18 3		/* MPP[18]: <UNKNOWN> */
 				19 3		/* MPP[19]: <UNKNOWN> */
 				20 3		/* MPP[20]: <UNKNOWN> */
 				21 3		/* MPP[21]: <UNKNOWN> */
 				22 4		/* MPP[22]: UA3_TXD */
 				23 4 >;		/* MPP[21]: UA3_RXD */
 		};
 
 		GPIO: gpio@10100 {
-			#gpio-cells = <3>;
+			#gpio-cells = <2>;
 			compatible = "mrvl,gpio";
 			reg = <0x10100 0x20>;
 			gpio-controller;
 			interrupts = <56 57 58 59>;
 			interrupt-parent = <&PIC>;
 		};
 
 		rtc@10300 {
 			compatible = "mrvl,rtc";
 			reg = <0x10300 0x08>;
 		};
 
 		twsi@11000 {
 			#address-cells = <1>;
 			#size-cells = <0>;
 			compatible = "mrvl,twsi";
 			reg = <0x11000 0x20>;
 			interrupts = <2>;
 			interrupt-parent = <&PIC>;
 		};
 
 		twsi@11100 {
 			#address-cells = <1>;
 			#size-cells = <0>;
 			compatible = "mrvl,twsi";
 			reg = <0x11100 0x20>;
 			interrupts = <3>;
 			interrupt-parent = <&PIC>;
 		};
 
 		enet0: ethernet@72000 {
 			#address-cells = <1>;
 			#size-cells = <1>;
 			model = "V2";
 			compatible = "mrvl,ge";
 			reg = <0x72000 0x2000>;
 			ranges = <0x0 0x72000 0x2000>;
 			local-mac-address = [ 00 00 00 00 00 00 ];
 			interrupts = <41 42 43 40 70>;
 			interrupt-parent = <&PIC>;
 			phy-handle = <&phy0>;
 
 			mdio@0 {
 				#address-cells = <1>;
 				#size-cells = <0>;
 				compatible = "mrvl,mdio";
 
 				phy0: ethernet-phy@0 {
 					reg = <0x8>;
 				};
 				phy1: ethernet-phy@1 {
 					reg = <0x9>;
 				};
 			};
 		};
 
 		enet1: ethernet@76000 {
 			#address-cells = <1>;
 			#size-cells = <1>;
 			model = "V2";
 			compatible = "mrvl,ge";
 			reg = <0x76000 0x2000>;
 			ranges = <0x0 0x76000 0x2000>;
 			local-mac-address = [ 00 00 00 00 00 00 ];
 			interrupts = <45 46 47 44 70>;
 			interrupt-parent = <&PIC>;
 			phy-handle = <&phy1>;
 		};
 
 		serial0: serial@12000 {
 			compatible = "ns16550";
 			reg = <0x12000 0x20>;
 			reg-shift = <2>;
 			clock-frequency = <0>;
 			interrupts = <12>;
 			interrupt-parent = <&PIC>;
 		};
 
 		serial1: serial@12100 {
 			compatible = "ns16550";
 			reg = <0x12100 0x20>;
 			reg-shift = <2>;
 			clock-frequency = <0>;
 			interrupts = <13>;
 			interrupt-parent = <&PIC>;
 		};
 
 		usb@50000 {
 			compatible = "mrvl,usb-ehci", "usb-ehci";
 			reg = <0x50000 0x1000>;
 			interrupts = <72 16>;
 			interrupt-parent = <&PIC>;
 		};
 
 		usb@51000 {
 			compatible = "mrvl,usb-ehci", "usb-ehci";
 			reg = <0x51000 0x1000>;
 			interrupts = <72 17>;
 			interrupt-parent = <&PIC>;
 		};
 
 		usb@52000 {
 			compatible = "mrvl,usb-ehci", "usb-ehci";
 			reg = <0x52000 0x1000>;
 			interrupts = <72 18>;
 			interrupt-parent = <&PIC>;
 		};
 
 		xor@60000 {
 			compatible = "mrvl,xor";
 			reg = <0x60000 0x1000>;
 			interrupts = <22 23>;
 			interrupt-parent = <&PIC>;
 		};
 
 		crypto@90000 {
 			compatible = "mrvl,cesa";
 			reg = <0x90000 0x1000	/* tdma base reg chan 0 */
 			       0x9D000 0x1000>;	/* cesa base reg chan 0 */
 			interrupts = <19>;
 			interrupt-parent = <&PIC>;
 		};
 
 		sata@a0000 {
 			compatible = "mrvl,sata";
 			reg = <0xa0000 0x6000>;
 			interrupts = <26>;
 			interrupt-parent = <&PIC>;
 		};
 	};
 
 	pci0: pcie@f1040000 {
 		compatible = "mrvl,pcie";
 		device_type = "pci";
 		#interrupt-cells = <1>;
 		#size-cells = <2>;
 		#address-cells = <3>;
 		reg = <0xf1040000 0x2000>;
 		bus-range = <0 255>;
 		ranges = <0x02000000 0x0 0xf2000000 0xf2000000 0x0 0x04000000
 			  0x01000000 0x0 0x00000000 0xf1100000 0x0 0x00100000>;
 		clock-frequency = <33333333>;
 		interrupt-parent = <&PIC>;
 		interrupts = <68>;
 		interrupt-map-mask = <0xf800 0x0 0x0 0x7>;
 		interrupt-map = <
 			/* IDSEL 0x1 */
 			0x0800 0x0 0x0 0x1 &PIC 0x20
 			0x0800 0x0 0x0 0x2 &PIC 0x21
 			0x0800 0x0 0x0 0x3 &PIC 0x22
 			0x0800 0x0 0x0 0x4 &PIC 0x23
 			>;
 	};
 
 	sram@fd000000 {
 		compatible = "mrvl,cesa-sram";
 		reg = <0xfd000000 0x00100000>;
 	};
 
 	chosen {
 		stdin = "serial0";
 		stdout = "serial0";
 	};
 };
Index: head/sys/dts/arm/db88f5182.dts
===================================================================
--- head/sys/dts/arm/db88f5182.dts	(revision 333030)
+++ head/sys/dts/arm/db88f5182.dts	(revision 333031)
@@ -1,223 +1,223 @@
 /*
  * Copyright (c) 2010 The FreeBSD Foundation
  * All rights reserved.
  *
  * This software was developed by Semihalf under sponsorship from
  * the FreeBSD Foundation.
  *
  * 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 AND CONTRIBUTORS ``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 OR CONTRIBUTORS 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.
  *
  * Marvell DB-88F5182 Device Tree Source.
  *
  * $FreeBSD$
  */
 
 /dts-v1/;
 
 / {
 	model = "mrvl,DB-88F5182";
 	compatible = "DB-88F5182-BP", "DB-88F5182-BP-A";
 	#address-cells = <1>;
 	#size-cells = <1>;
 
 	aliases {
 		ethernet0 = &enet0;
 		serial0 = &serial0;
 		serial1 = &serial1;
 		mpp = &MPP;
 	};
 
 	cpus {
 		#address-cells = <1>;
 		#size-cells = <0>;
 
 		cpu@0 {
 			device_type = "cpu";
 			compatible = "ARM,88FR531";
 			reg = <0x0>;
 			d-cache-line-size = <32>;	// 32 bytes
 			i-cache-line-size = <32>;	// 32 bytes
 			d-cache-size = <0x8000>;	// L1, 32K
 			i-cache-size = <0x8000>;	// L1, 32K
 			timebase-frequency = <0>;
 			bus-frequency = <0>;
 			clock-frequency = <0>;
 		};
 	};
 
 	memory {
 		device_type = "memory";
 		reg = <0x0 0x08000000>;		// 128M at 0x0
 	};
 
 	localbus@f1000000 {
 		#address-cells = <2>;
 		#size-cells = <1>;
 		compatible = "mrvl,lbc";
 
 		/* This reflects CPU decode windows setup. */
 		ranges = <0x0 0x0f 0xf9300000 0x00100000
 			  0x1 0x1e 0xfa000000 0x00100000
 			  0x2 0x1d 0xfa100000 0x02000000>;
 
 		nor@0,0 {
 			#address-cells = <1>;
 			#size-cells = <1>;
 			compatible = "cfi-flash";
 			reg = <0x0 0x0 0x00100000>;
 			bank-width = <2>;
 			device-width = <1>;
 		};
 
 		led@1,0 {
 			#address-cells = <1>;
 			#size-cells = <1>;
 			compatible = "led";
 			reg = <0x1 0x0 0x00100000>;
 		};
 
 		nor@2,0 {
 			#address-cells = <1>;
 			#size-cells = <1>;
 			compatible = "cfi-flash";
 			reg = <0x2 0x0 0x02000000>;
 			bank-width = <2>;
 			device-width = <1>;
 		};
 	};
 
 	soc88f5182@f1000000 {
 		#address-cells = <1>;
 		#size-cells = <1>;
 		compatible = "simple-bus";
 		ranges = <0x0 0xf1000000 0x00100000>;
 		bus-frequency = <0>;
 
 		PIC: pic@20200 {
 			interrupt-controller;
 			#address-cells = <0>;
 			#interrupt-cells = <1>;
 			reg = <0x20200 0x3c>;
 			compatible = "mrvl,pic";
 		};
 
 		timer@20300 {
 			compatible = "mrvl,timer";
 			reg = <0x20300 0x30>;
 			interrupts = <0>;
 			interrupt-parent = <&PIC>;
 			mrvl,has-wdt;
 		};
 
 		MPP: mpp@10000 {
 			#pin-cells = <2>;
 			compatible = "mrvl,mpp";
 			reg = <0x10000 0x54>;
 			pin-count = <20>;
 			pin-map = <
 				0  3		/* MPP[0]:  GPIO[0] */
 				2  2		/* MPP[2]:  PCI_REQn[3] */
 				3  2		/* MPP[3]:  PCI_GNTn[3] */
 				4  2		/* MPP[4]:  PCI_REQn[4] */
 				5  2		/* MPP[5]:  PCI_GNTn[4] */
 				6  5		/* MPP[6]:  SATA0_ACT */
 				7  5		/* MPP[7]:  SATA1_ACT */
 				12 5		/* MPP[12]: SATA0_PRESENT */
 				13 5		/* MPP[13]: SATA1_PRESENT */
 				14 4		/* MPP[14]: NAND Flash REn[2] */
 				15 4		/* MPP[15]: NAND Flash WEn[2] */
 				16 0		/* MPP[16]: UA1_RXD */
 				17 0		/* MPP[17]: UA1_TXD */
 				18 0		/* MPP[18]: UA1_CTS */
 				19 0 >;		/* MPP[19]: UA1_RTS */
 		};
 
 		GPIO: gpio@10100 {
-			#gpio-cells = <3>;
+			#gpio-cells = <2>;
 			compatible = "mrvl,gpio";
 			reg = <0x10100 0x20>;
 			gpio-controller;
 			interrupts = <6 7 8 9>;
 			interrupt-parent = <&PIC>;
 		};
 
 		twsi@11000 {
 			#address-cells = <1>;
 			#size-cells = <0>;
 			compatible = "mrvl,twsi";
 			reg = <0x11000 0x20>;
 			interrupts = <43>;
 			interrupt-parent = <&PIC>;
 		};
 
 		enet0: ethernet@72000 {
 			#address-cells = <1>;
 			#size-cells = <1>;
 			model = "V1";
 			compatible = "mrvl,ge";
 			reg = <0x72000 0x2000>;
 			ranges = <0x0 0x72000 0x2000>;
 			local-mac-address = [ 00 00 00 00 00 00 ];
 			interrupts = <18 19 20 21 22>;
 			interrupt-parent = <&PIC>;
 		};
 
 		serial0: serial@12000 {
 			compatible = "ns16550";
 			reg = <0x12000 0x20>;
 			reg-shift = <2>;
 			clock-frequency = <0>;
 			interrupts = <3>;
 			interrupt-parent = <&PIC>;
 		};
 
 		serial1: serial@12100 {
 			compatible = "ns16550";
 			reg = <0x12100 0x20>;
 			reg-shift = <2>;
 			clock-frequency = <0>;
 			interrupts = <4>;
 			interrupt-parent = <&PIC>;
 		};
 
 		usb@50000 {
 			compatible = "mrvl,usb-ehci", "usb-ehci";
 			reg = <0x50000 0x1000>;
 			interrupts = <17 16>;
 			interrupt-parent = <&PIC>;
 		};
 
 		idma@60000 {
 			compatible = "mrvl,idma";
 			reg = <0x60000 0x1000>;
 			interrupts = <24 25 26 27 23>;
 			interrupt-parent = <&PIC>;
 		};
 
 		sata@80000 {
 			compatible = "mrvl,sata";
 			reg = <0x80000 0x6000>;
 			interrupts = <29>;
 			interrupt-parent = <&PIC>;
 		};
 	};
 };
Index: head/sys/dts/arm/db88f5281.dts
===================================================================
--- head/sys/dts/arm/db88f5281.dts	(revision 333030)
+++ head/sys/dts/arm/db88f5281.dts	(revision 333031)
@@ -1,227 +1,227 @@
 /*
  * Copyright (c) 2010 The FreeBSD Foundation
  * All rights reserved.
  *
  * This software was developed by Semihalf under sponsorship from
  * the FreeBSD Foundation.
  *
  * 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 AND CONTRIBUTORS ``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 OR CONTRIBUTORS 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.
  *
  * Marvell DB-88F5281 Device Tree Source.
  *
  * $FreeBSD$
  */
 
 /dts-v1/;
 
 / {
 	model = "mrvl,DB-88F5281";
 	compatible = "DB-88F5281-BP", "DB-88F5281-BP-A";
 	#address-cells = <1>;
 	#size-cells = <1>;
 
 	aliases {
 		ethernet0 = &enet0;
 		serial0 = &serial0;
 		serial1 = &serial1;
 		mpp = &MPP;
 	};
 
 	cpus {
 		#address-cells = <1>;
 		#size-cells = <0>;
 
 		cpu@0 {
 			device_type = "cpu";
 			compatible = "ARM,88FR531";
 			reg = <0x0>;
 			d-cache-line-size = <32>;	// 32 bytes
 			i-cache-line-size = <32>;	// 32 bytes
 			d-cache-size = <0x8000>;	// L1, 32K
 			i-cache-size = <0x8000>;	// L1, 32K
 			timebase-frequency = <0>;
 			bus-frequency = <0>;
 			clock-frequency = <0>;
 		};
 	};
 
 	memory {
 		device_type = "memory";
 		reg = <0x0 0x08000000>;		// 128M at 0x0
 	};
 
 	localbus@f1000000 {
 		#address-cells = <2>;
 		#size-cells = <1>;
 		compatible = "mrvl,lbc";
 
 		/* This reflects CPU decode windows setup. */
 		ranges = <0x0 0x0f 0xf9300000 0x00100000
 			  0x1 0x1e 0xfa000000 0x00100000
 			  0x2 0x1d 0xfa100000 0x02000000>;
 
 		nor@0,0 {
 			#address-cells = <1>;
 			#size-cells = <1>;
 			compatible = "cfi-flash";
 			reg = <0x0 0x0 0x00100000>;
 			bank-width = <2>;
 			device-width = <1>;
 		};
 
 		led@1,0 {
 			#address-cells = <1>;
 			#size-cells = <1>;
 			compatible = "led";
 			reg = <0x1 0x0 0x00100000>;
 		};
 
 		nor@2,0 {
 			#address-cells = <1>;
 			#size-cells = <1>;
 			compatible = "cfi-flash";
 			reg = <0x2 0x0 0x02000000>;
 			bank-width = <2>;
 			device-width = <1>;
 		};
 	};
 
 	soc88f5281@f1000000 {
 		#address-cells = <1>;
 		#size-cells = <1>;
 		compatible = "simple-bus";
 		ranges = <0x0 0xf1000000 0x00100000>;
 		bus-frequency = <0>;
 
 		PIC: pic@20200 {
 			interrupt-controller;
 			#address-cells = <0>;
 			#interrupt-cells = <1>;
 			reg = <0x20200 0x3c>;
 			compatible = "mrvl,pic";
 		};
 
 		timer@20300 {
 			compatible = "mrvl,timer";
 			reg = <0x20300 0x30>;
 			interrupts = <0>;
 			interrupt-parent = <&PIC>;
 			mrvl,has-wdt;
 		};
 
 		MPP: mpp@10000 {
 			#pin-cells = <2>;
 			compatible = "mrvl,mpp";
 			reg = <0x10000 0x54>;
 			pin-count = <20>;
 			pin-map = <
 				0  3		/* MPP[0]:  GPIO[0] */
 				2  2		/* MPP[2]:  PCI_REQn[3] */
 				3  2		/* MPP[3]:  PCI_GNTn[3] */
 				4  2		/* MPP[4]:  PCI_REQn[4] */
 				5  2		/* MPP[5]:  PCI_GNTn[4] */
 				6  3		/* MPP[6]:  <UNKNOWN> */
 				7  3		/* MPP[7]:  <UNKNOWN> */
 				8  3		/* MPP[8]:  <UNKNOWN> */
 				9  3		/* MPP[9]:  <UNKNOWN> */
 				14 4		/* MPP[14]: NAND Flash REn[2] */
 				15 4		/* MPP[15]: NAND Flash WEn[2] */
 				16 0		/* MPP[16]: UA1_RXD */
 				17 0		/* MPP[17]: UA1_TXD */
 				18 0		/* MPP[18]: UA1_CTS */
 				19 0 >;		/* MPP[19]: UA1_RTS */
 		};
 
 		GPIO: gpio@10100 {
-			#gpio-cells = <3>;
+			#gpio-cells = <2>;
 			compatible = "mrvl,gpio";
 			reg = <0x10100 0x20>;
 			gpio-controller;
 			interrupts = <6 7 8 9>;
 			interrupt-parent = <&PIC>;
 		};
 
 		twsi@11000 {
 			#address-cells = <1>;
 			#size-cells = <0>;
 			compatible = "mrvl,twsi";
 			reg = <0x11000 0x20>;
 			interrupts = <43>;
 			interrupt-parent = <&PIC>;
 		};
 
 		enet0: ethernet@72000 {
 			#address-cells = <1>;
 			#size-cells = <1>;
 			model = "V1";
 			compatible = "mrvl,ge";
 			reg = <0x72000 0x2000>;
 			ranges = <0x0 0x72000 0x2000>;
 			local-mac-address = [ 00 00 00 00 00 00 ];
 			interrupts = <18 19 20 21 22>;
 			interrupt-parent = <&PIC>;
 			phy-handle = <&phy0>;
 
 			mdio@0 {
 				#address-cells = <1>;
 				#size-cells = <0>;
 				compatible = "mrvl,mdio";
 
 				phy0: ethernet-phy@0 {
 					reg = <0x8>;
 				};
 			};
 		};
 
 		serial0: serial@12000 {
 			compatible = "ns16550";
 			reg = <0x12000 0x20>;
 			reg-shift = <2>;
 			clock-frequency = <0>;
 			interrupts = <3>;
 			interrupt-parent = <&PIC>;
 		};
 
 		serial1: serial@12100 {
 			compatible = "ns16550";
 			reg = <0x12100 0x20>;
 			reg-shift = <2>;
 			clock-frequency = <0>;
 			interrupts = <4>;
 			interrupt-parent = <&PIC>;
 		};
 
 		usb@50000 {
 			compatible = "mrvl,usb-ehci", "usb-ehci";
 			reg = <0x50000 0x1000>;
 			interrupts = <17 16>;
 			interrupt-parent = <&PIC>;
 		};
 
 		idma@60000 {
 			compatible = "mrvl,idma";
 			reg = <0x60000 0x1000>;
 			interrupts = <24 25 26 27 23>;
 			interrupt-parent = <&PIC>;
 		};
 	};
 };
Index: head/sys/dts/arm/db88f6281.dts
===================================================================
--- head/sys/dts/arm/db88f6281.dts	(revision 333030)
+++ head/sys/dts/arm/db88f6281.dts	(revision 333031)
@@ -1,299 +1,299 @@
 /*
  * Copyright (c) 2009-2010 The FreeBSD Foundation
  * All rights reserved.
  *
  * This software was developed by Semihalf under sponsorship from
  * the FreeBSD Foundation.
  *
  * 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 AND CONTRIBUTORS ``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 OR CONTRIBUTORS 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.
  *
  * Marvell DB-88F6281 Device Tree Source.
  *
  * $FreeBSD$
  */
 
 /dts-v1/;
 
 / {
 	model = "mrvl,DB-88F6281";
 	compatible = "DB-88F6281-BP", "DB-88F6281-BP-A";
 	#address-cells = <1>;
 	#size-cells = <1>;
 
 	aliases {
 		ethernet0 = &enet0;
 		mpp = &MPP;
 		pci0 = &pci0;
 		serial0 = &serial0;
 		serial1 = &serial1;
 		soc = &SOC;
 		sram = &SRAM;
 	};
 
 	cpus {
 		#address-cells = <1>;
 		#size-cells = <0>;
 
 		cpu@0 {
 			device_type = "cpu";
 			compatible = "ARM,88FR131";
 			reg = <0x0>;
 			d-cache-line-size = <32>;	// 32 bytes
 			i-cache-line-size = <32>;	// 32 bytes
 			d-cache-size = <0x4000>;	// L1, 16K
 			i-cache-size = <0x4000>;	// L1, 16K
 			timebase-frequency = <0>;
 			bus-frequency = <0>;
 			clock-frequency = <0>;
 		};
 	};
 
 	memory {
 		device_type = "memory";
 		reg = <0x0 0x20000000>;		// 512M at 0x0
 	};
 
 	localbus@0 {
 		#address-cells = <2>;
 		#size-cells = <1>;
 		compatible = "mrvl,lbc";
 		bank-count = <3>;
 
 		/* This reflects CPU decode windows setup. */
 		ranges = <0x0 0x2f 0xf9300000 0x00100000>;
 
 		nand@0,0 {
 			#address-cells = <1>;
 			#size-cells = <1>;
 			compatible = "mrvl,nfc";
 			reg = <0x0 0x0 0x00100000>;
 			bank-width = <2>;
 			device-width = <1>;
 
 			slice@0 {
 				reg = <0x0 0x200000>;
 				label = "u-boot";
 				read-only;
 			};
 
 			slice@200000 {
 				reg = <0x200000 0x7e00000>;
 				label = "root";
 			};
 		};
 	};
 
 	SOC: soc88f6281@f1000000 {
 		#address-cells = <1>;
 		#size-cells = <1>;
 		compatible = "simple-bus";
 		ranges = <0x0 0xf1000000 0x00100000>;
 		bus-frequency = <0>;
 
 		PIC: pic@20200 {
 			interrupt-controller;
 			#address-cells = <0>;
 			#interrupt-cells = <1>;
 			reg = <0x20200 0x3c>;
 			compatible = "mrvl,pic";
 		};
 
 		timer@20300 {
 			compatible = "mrvl,timer";
 			reg = <0x20300 0x30>;
 			interrupts = <1>;
 			interrupt-parent = <&PIC>;
 			mrvl,has-wdt;
 		};
 
 		MPP: mpp@10000 {
 			#pin-cells = <2>;
 			compatible = "mrvl,mpp";
 			reg = <0x10000 0x34>;
 			pin-count = <50>;
 			pin-map = <
 				0  1		/* MPP[0]:  NF_IO[2] */
 				1  1		/* MPP[1]:  NF_IO[3] */
 				2  1		/* MPP[2]:  NF_IO[4] */
 				3  1		/* MPP[3]:  NF_IO[5] */
 				4  1		/* MPP[4]:  NF_IO[6] */
 				5  1		/* MPP[5]:  NF_IO[7] */
 				6  1		/* MPP[6]:  SYSRST_OUTn */
 				7  2		/* MPP[7]:  SPI_SCn */
 				8  1		/* MPP[8]:  TW_SDA */
 				9  1		/* MPP[9]:  TW_SCK */
 				10 3		/* MPP[10]: UA0_TXD */
 				11 3		/* MPP[11]: UA0_RXD */
 				12 1		/* MPP[12]: SD_CLK */
 				13 1		/* MPP[13]: SD_CMD */
 				14 1		/* MPP[14]: SD_D[0] */
 				15 1		/* MPP[15]: SD_D[1] */
 				16 1		/* MPP[16]: SD_D[2] */
 				17 1		/* MPP[17]: SD_D[3] */
 				18 1		/* MPP[18]: NF_IO[0] */
 				19 1		/* MPP[19]: NF_IO[1] */
 				20 5		/* MPP[20]: SATA1_AC */
 				21 5 >;		/* MPP[21]: SATA0_AC */
 		};
 
 		GPIO: gpio@10100 {
-			#gpio-cells = <3>;
+			#gpio-cells = <2>;
 			compatible = "mrvl,gpio";
 			reg = <0x10100 0x20>;
 			gpio-controller;
 			interrupts = <35 36 37 38 39 40 41>;
 			interrupt-parent = <&PIC>;
 		};
 
 		rtc@10300 {
 			compatible = "mrvl,rtc";
 			reg = <0x10300 0x08>;
 		};
 
 		twsi@11000 {
 			#address-cells = <1>;
 			#size-cells = <0>;
 			compatible = "mrvl,twsi";
 			reg = <0x11000 0x20>;
 			interrupts = <43>;
 			interrupt-parent = <&PIC>;
 		};
 
 		enet0: ethernet@72000 {
 			#address-cells = <1>;
 			#size-cells = <1>;
 			model = "V2";
 			compatible = "mrvl,ge";
 			reg = <0x72000 0x2000>;
 			ranges = <0x0 0x72000 0x2000>;
 			local-mac-address = [ 00 00 00 00 00 00 ];
 			interrupts = <12 13 14 11 46>;
 			interrupt-parent = <&PIC>;
 			phy-handle = <&phy0>;
 
 			mdio@0 {
 				#address-cells = <1>;
 				#size-cells = <0>;
 				compatible = "mrvl,mdio";
 
 				phy0: ethernet-phy@0 {
 					reg = <0x8>;
 				};
 			};
 		};
 
 		serial0: serial@12000 {
 			compatible = "ns16550";
 			reg = <0x12000 0x20>;
 			reg-shift = <2>;
 			clock-frequency = <0>;
 			interrupts = <33>;
 			interrupt-parent = <&PIC>;
 		};
 
 		serial1: serial@12100 {
 			compatible = "ns16550";
 			reg = <0x12100 0x20>;
 			reg-shift = <2>;
 			clock-frequency = <0>;
 			interrupts = <34>;
 			interrupt-parent = <&PIC>;
 		};
 
 		crypto@30000 {
 			compatible = "mrvl,cesa";
 			reg = <0x30000 0x1000	/* tdma base reg chan 0 */
 			       0x3D000 0x1000>;	/* cesa base reg chan 0 */
 			interrupts = <22>;
 			interrupt-parent = <&PIC>;
 
 			sram-handle = <&SRAM>;
 		};
 
 		usb@50000 {
 			compatible = "mrvl,usb-ehci", "usb-ehci";
 			reg = <0x50000 0x1000>;
 			interrupts = <48 19>;
 			interrupt-parent = <&PIC>;
 		};
 
 		xor@60000 {
 			compatible = "mrvl,xor";
 			reg = <0x60000 0x1000>;
 			interrupts = <5 6 7 8>;
 			interrupt-parent = <&PIC>;
 		};
 
 		sata@80000 {
 			compatible = "mrvl,sata";
 			reg = <0x80000 0x6000>;
 			interrupts = <21>;
 			interrupt-parent = <&PIC>;
 		};
 	};
 
 	SRAM: sram@fd000000 {
 		compatible = "mrvl,cesa-sram";
 		reg = <0xfd000000 0x00100000>;
 	};
 
 	pci0: pcie@f1040000 {
 		compatible = "mrvl,pcie";
 		device_type = "pci";
 		#interrupt-cells = <1>;
 		#size-cells = <2>;
 		#address-cells = <3>;
 		reg = <0xf1040000 0x2000>;
 		bus-range = <0 255>;
 		ranges = <0x02000000 0x0 0xf1300000 0xf1300000 0x0 0x04000000
 			  0x01000000 0x0 0x00000000 0xf1100000 0x0 0x00100000>;
 		clock-frequency = <33333333>;
 		interrupt-parent = <&PIC>;
 		interrupts = <44>;
 		interrupt-map-mask = <0xf800 0x0 0x0 0x7>;
 		interrupt-map = <
 			/* IDSEL 0x1 */
 			0x0800 0x0 0x0 0x1 &PIC 0x9
 			0x0800 0x0 0x0 0x2 &PIC 0x9
 			0x0800 0x0 0x0 0x3 &PIC 0x9
 			0x0800 0x0 0x0 0x4 &PIC 0x9
 			>;
 		pcie@0 {
 			reg = <0x0 0x0 0x0 0x0 0x0>;
 			#size-cells = <2>;
 			#address-cells = <3>;
 			device_type = "pci";
 			ranges = <0x02000000 0x0 0xf1300000
 				  0x02000000 0x0 0xf1300000
 				  0x0 0x04000000
 
 				  0x01000000 0x0 0x0
 				  0x01000000 0x0 0x0
 				  0x0 0x00100000>;
 		};
 	};
 
       	chosen {
 		stdin = "serial0";
 		stdout = "serial0";
 	};
 };
Index: head/sys/dts/arm/dockstar.dts
===================================================================
--- head/sys/dts/arm/dockstar.dts	(revision 333030)
+++ head/sys/dts/arm/dockstar.dts	(revision 333031)
@@ -1,241 +1,241 @@
 /*
  * Copyright (c) 2010 The FreeBSD Foundation
  * All rights reserved.
  *
  * This software was developed by Semihalf under sponsorship from
  * the FreeBSD Foundation.
  *
  * 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 AND CONTRIBUTORS ``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 OR CONTRIBUTORS 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.
  *
  * Seagate DockStar (Marvell SheevaPlug based) Device Tree Source.
  *
  * $FreeBSD$
  */
 
 /dts-v1/;
 
 / {
 	model = "seagate,DockStar";
 	compatible = "DockStar";
 	#address-cells = <1>;
 	#size-cells = <1>;
 
 	aliases {
 		ethernet0 = &enet0;
 		mpp = &MPP;
 		serial0 = &serial0;
 		serial1 = &serial1;
 		soc = &SOC;
 		sram = &SRAM;
 	};
 
 	cpus {
 		#address-cells = <1>;
 		#size-cells = <0>;
 
 		cpu@0 {
 			device_type = "cpu";
 			compatible = "ARM,88FR131";
 			reg = <0x0>;
 			d-cache-line-size = <32>;	// 32 bytes
 			i-cache-line-size = <32>;	// 32 bytes
 			d-cache-size = <0x4000>;	// L1, 16K
 			i-cache-size = <0x4000>;	// L1, 16K
 			timebase-frequency = <0>;
 			bus-frequency = <0>;
 			clock-frequency = <0>;
 		};
 	};
 
 	memory {
 		device_type = "memory";
 		reg = <0x0 0x8000000>;		// 128M at 0x0
 	};
 
 	localbus@f1000000 {
 		#address-cells = <2>;
 		#size-cells = <1>;
 		compatible = "mrvl,lbc";
 
 		/* This reflects CPU decode windows setup for NAND access. */
 		ranges = <0x0 0x2f 0xf9300000 0x00100000>;
 
 		nand@0,0 {
 			#address-cells = <1>;
 			#size-cells = <1>;
 			compatible = "mrvl,nfc";
 			reg = <0x0 0x0 0x00100000>;
 			bank-width = <2>;
 			device-width = <1>;
 		};
 	};
 
 	SOC: soc88f6281@f1000000 {
 		#address-cells = <1>;
 		#size-cells = <1>;
 		compatible = "simple-bus";
 		ranges = <0x0 0xf1000000 0x00100000>;
 		bus-frequency = <0>;
 
 		PIC: pic@20200 {
 			interrupt-controller;
 			#address-cells = <0>;
 			#interrupt-cells = <1>;
 			reg = <0x20200 0x3c>;
 			compatible = "mrvl,pic";
 		};
 
 		timer@20300 {
 			compatible = "mrvl,timer";
 			reg = <0x20300 0x30>;
 			interrupts = <1>;
 			interrupt-parent = <&PIC>;
 			mrvl,has-wdt;
 		};
 
 		MPP: mpp@10000 {
 			#pin-cells = <2>;
 			compatible = "mrvl,mpp";
 			reg = <0x10000 0x34>;
 			pin-count = <50>;
 			pin-map = <
 				0  1		/* MPP[0]:  NF_IO[2] */
 				1  1		/* MPP[1]:  NF_IO[3] */
 				2  1		/* MPP[2]:  NF_IO[4] */
 				3  1		/* MPP[3]:  NF_IO[5] */
 				4  1		/* MPP[4]:  NF_IO[6] */
 				5  1		/* MPP[5]:  NF_IO[7] */
 				6  1		/* MPP[6]:  SYSRST_OUTn */
 				8  2		/* MPP[8]:  UA0_RTS */
 				9  2		/* MPP[9]:  UA0_CTS */
 				10 3		/* MPP[10]: UA0_TXD */
 				11 3		/* MPP[11]: UA0_RXD */
 				12 1		/* MPP[12]: SD_CLK */
 				13 1		/* MPP[13]: SD_CMD */
 				14 1		/* MPP[14]: SD_D[0] */
 				15 1		/* MPP[15]: SD_D[1] */
 				16 1		/* MPP[16]: SD_D[2] */
 				17 1		/* MPP[17]: SD_D[3] */
 				18 1		/* MPP[18]: NF_IO[0] */
 				19 1		/* MPP[19]: NF_IO[1] */
 				29 1 >;		/* MPP[29]: TSMP[9] */
 		};
 
 		GPIO: gpio@10100 {
-			#gpio-cells = <3>;
+			#gpio-cells = <2>;
 			compatible = "mrvl,gpio";
 			reg = <0x10100 0x20>;
 			gpio-controller;
 			interrupts = <35 36 37 38 39 40 41>;
 			interrupt-parent = <&PIC>;
 		};
 
 		rtc@10300 {
 			compatible = "mrvl,rtc";
 			reg = <0x10300 0x08>;
 		};
 
 		twsi@11000 {
 			#address-cells = <1>;
 			#size-cells = <0>;
 			compatible = "mrvl,twsi";
 			reg = <0x11000 0x20>;
 			interrupts = <43>;
 			interrupt-parent = <&PIC>;
 		};
 
 		enet0: ethernet@72000 {
 			#address-cells = <1>;
 			#size-cells = <1>;
 			model = "V2";
 			compatible = "mrvl,ge";
 			reg = <0x72000 0x2000>;
 			ranges = <0x0 0x72000 0x2000>;
 			local-mac-address = [ 00 00 00 00 00 00 ];
 			interrupts = <12 13 14 11 46>;
 			interrupt-parent = <&PIC>;
 			phy-handle = <&phy0>;
 
 			mdio@0 {
 				#address-cells = <1>;
 				#size-cells = <0>;
 				compatible = "mrvl,mdio";
 
 				phy0: ethernet-phy@0 {
 					reg = <0x0>;
 				};
 			};
 		};
 
 		serial0: serial@12000 {
 			compatible = "ns16550";
 			reg = <0x12000 0x20>;
 			reg-shift = <2>;
 			clock-frequency = <0>;
 			interrupts = <33>;
 			interrupt-parent = <&PIC>;
 		};
 
 		serial1: serial@12100 {
 			compatible = "ns16550";
 			reg = <0x12100 0x20>;
 			reg-shift = <2>;
 			clock-frequency = <0>;
 			interrupts = <34>;
 			interrupt-parent = <&PIC>;
 		};
 
 		crypto@30000 {
 			compatible = "mrvl,cesa";
 			reg = <0x30000 0x1000	/* tdma base reg chan 0 */
 			       0x3D000 0x1000>;	/* cesa base reg chan 0 */
 			interrupts = <22>;
 			interrupt-parent = <&PIC>;
 
 			sram-handle = <&SRAM>;
 		};
 
 		usb@50000 {
 			compatible = "mrvl,usb-ehci", "usb-ehci";
 			reg = <0x50000 0x1000>;
 			interrupts = <48 19>;
 			interrupt-parent = <&PIC>;
 		};
 
 		xor@60000 {
 			compatible = "mrvl,xor";
 			reg = <0x60000 0x1000>;
 			interrupts = <5 6 7 8>;
 			interrupt-parent = <&PIC>;
 		};
 	};
 
 	SRAM: sram@fd000000 {
 		compatible = "mrvl,cesa-sram";
 		reg = <0xfd000000 0x00100000>;
 	};
 
 	chosen {
 		stdin = "serial0";
 		stdout = "serial0";
 	};
 };
Index: head/sys/dts/arm/sheevaplug.dts
===================================================================
--- head/sys/dts/arm/sheevaplug.dts	(revision 333030)
+++ head/sys/dts/arm/sheevaplug.dts	(revision 333031)
@@ -1,253 +1,253 @@
 /*
  * Copyright (c) 2010 The FreeBSD Foundation
  * All rights reserved.
  *
  * This software was developed by Semihalf under sponsorship from
  * the FreeBSD Foundation.
  *
  * 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 AND CONTRIBUTORS ``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 OR CONTRIBUTORS 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.
  *
  * Marvell SheevaPlug Device Tree Source.
  *
  * $FreeBSD$
  */
 
 /dts-v1/;
 
 / {
 	model = "mrvl,SheevaPlug";
 	compatible = "SheevaPlug";
 	#address-cells = <1>;
 	#size-cells = <1>;
 
 	aliases {
 		ethernet0 = &enet0;
 		mpp = &MPP;
 		serial0 = &serial0;
 		serial1 = &serial1;
 		soc = &SOC;
 		sram = &SRAM;
 	};
 
 	cpus {
 		#address-cells = <1>;
 		#size-cells = <0>;
 
 		cpu@0 {
 			device_type = "cpu";
 			compatible = "ARM,88FR131";
 			reg = <0x0>;
 			d-cache-line-size = <32>;	// 32 bytes
 			i-cache-line-size = <32>;	// 32 bytes
 			d-cache-size = <0x4000>;	// L1, 16K
 			i-cache-size = <0x4000>;	// L1, 16K
 			timebase-frequency = <0>;
 			bus-frequency = <0>;
 			clock-frequency = <0>;
 		};
 	};
 
 	memory {
 		device_type = "memory";
 		reg = <0x0 0x20000000>;		// 512M at 0x0
 	};
 
 	localbus@0 {
 		#address-cells = <2>;
 		#size-cells = <1>;
 		compatible = "mrvl,lbc";
 		bank-count = <3>;
 
 		/* This reflects CPU decode windows setup. */
 		ranges = <0x0 0x2f 0xf9300000 0x00100000>;
 
 		nand@0,0 {
 			#address-cells = <1>;
 			#size-cells = <1>;
 			compatible = "mrvl,nfc";
 			reg = <0x0 0x0 0x00100000>;
 			bank-width = <2>;
 			device-width = <1>;
 
 			slice@0 {
 				reg = <0x0 0x200000>;
 				label = "u-boot";
 				read-only;
 			};
 
 			slice@200000 {
 				reg = <0x200000 0x1fe00000>;
 				label = "root";
 			};
 		};
 	};
 
 	SOC: soc88f6281@f1000000 {
 		#address-cells = <1>;
 		#size-cells = <1>;
 		compatible = "simple-bus";
 		ranges = <0x0 0xf1000000 0x00100000>;
 		bus-frequency = <0>;
 
 		PIC: pic@20200 {
 			interrupt-controller;
 			#address-cells = <0>;
 			#interrupt-cells = <1>;
 			reg = <0x20200 0x3c>;
 			compatible = "mrvl,pic";
 		};
 
 		timer@20300 {
 			compatible = "mrvl,timer";
 			reg = <0x20300 0x30>;
 			interrupts = <1>;
 			interrupt-parent = <&PIC>;
 			mrvl,has-wdt;
 		};
 
 		MPP: mpp@10000 {
 			#pin-cells = <2>;
 			compatible = "mrvl,mpp";
 			reg = <0x10000 0x34>;
 			pin-count = <50>;
 			pin-map = <
 				0  1		/* MPP[0]:  NF_IO[2] */
 				1  1		/* MPP[1]:  NF_IO[3] */
 				2  1		/* MPP[2]:  NF_IO[4] */
 				3  1		/* MPP[3]:  NF_IO[5] */
 				4  1		/* MPP[4]:  NF_IO[6] */
 				5  1		/* MPP[5]:  NF_IO[7] */
 				6  1		/* MPP[6]:  SYSRST_OUTn */
 				8  2		/* MPP[8]:  UA0_RTS */
 				9  2		/* MPP[9]:  UA0_CTS */
 				10 3		/* MPP[10]: UA0_TXD */
 				11 3		/* MPP[11]: UA0_RXD */
 				12 1		/* MPP[12]: SD_CLK */
 				13 1		/* MPP[13]: SD_CMD */
 				14 1		/* MPP[14]: SD_D[0] */
 				15 1		/* MPP[15]: SD_D[1] */
 				16 1		/* MPP[16]: SD_D[2] */
 				17 1		/* MPP[17]: SD_D[3] */
 				18 1		/* MPP[18]: NF_IO[0] */
 				19 1		/* MPP[19]: NF_IO[1] */
 				29 1 >;		/* MPP[29]: TSMP[9] */
 		};
 
 		GPIO: gpio@10100 {
-			#gpio-cells = <3>;
+			#gpio-cells = <2>;
 			compatible = "mrvl,gpio";
 			reg = <0x10100 0x20>;
 			gpio-controller;
 			interrupts = <35 36 37 38 39 40 41>;
 			interrupt-parent = <&PIC>;
 		};
 
 		rtc@10300 {
 			compatible = "mrvl,rtc";
 			reg = <0x10300 0x08>;
 		};
 
 		twsi@11000 {
 			#address-cells = <1>;
 			#size-cells = <0>;
 			compatible = "mrvl,twsi";
 			reg = <0x11000 0x20>;
 			interrupts = <43>;
 			interrupt-parent = <&PIC>;
 		};
 
 		enet0: ethernet@72000 {
 			#address-cells = <1>;
 			#size-cells = <1>;
 			model = "V2";
 			compatible = "mrvl,ge";
 			reg = <0x72000 0x2000>;
 			ranges = <0x0 0x72000 0x2000>;
 			local-mac-address = [ 00 00 00 00 00 00 ];
 			interrupts = <12 13 14 11 46>;
 			interrupt-parent = <&PIC>;
 			phy-handle = <&phy0>;
 
 			mdio@0 {
 				#address-cells = <1>;
 				#size-cells = <0>;
 				compatible = "mrvl,mdio";
 
 				phy0: ethernet-phy@0 {
 					reg = <0x0>;
 				};
 			};
 		};
 
 		serial0: serial@12000 {
 			compatible = "ns16550";
 			reg = <0x12000 0x20>;
 			reg-shift = <2>;
 			clock-frequency = <0>;
 			interrupts = <33>;
 			interrupt-parent = <&PIC>;
 		};
 
 		serial1: serial@12100 {
 			compatible = "ns16550";
 			reg = <0x12100 0x20>;
 			reg-shift = <2>;
 			clock-frequency = <0>;
 			interrupts = <34>;
 			interrupt-parent = <&PIC>;
 		};
 
 		crypto@30000 {
 			compatible = "mrvl,cesa";
 			reg = <0x30000 0x1000	/* tdma base reg chan 0 */
 			       0x3D000 0x1000>;	/* cesa base reg chan 0 */
 			interrupts = <22>;
 			interrupt-parent = <&PIC>;
 
 			sram-handle = <&SRAM>;
 		};
 
 		usb@50000 {
 			compatible = "mrvl,usb-ehci", "usb-ehci";
 			reg = <0x50000 0x1000>;
 			interrupts = <48 19>;
 			interrupt-parent = <&PIC>;
 		};
 
 		xor@60000 {
 			compatible = "mrvl,xor";
 			reg = <0x60000 0x1000>;
 			interrupts = <5 6 7 8>;
 			interrupt-parent = <&PIC>;
 		};
 	};
 
 	SRAM: sram@fd000000 {
 		compatible = "mrvl,cesa-sram";
 		reg = <0xfd000000 0x00100000>;
 	};
 
 	chosen {
 		stdin = "serial0";
 		stdout = "serial0";
 	};
 };
Index: head/sys/dts/bindings-gpio.txt
===================================================================
--- head/sys/dts/bindings-gpio.txt	(revision 333030)
+++ head/sys/dts/bindings-gpio.txt	(revision 333031)
@@ -1,101 +1,106 @@
 $FreeBSD$
 
 GPIO configuration.
 ===================
 
 1. Properties for GPIO Controllers
 
 1.1 #gpio-cells
 
 Property:	#gpio-cells
 
 Value type:	<u32>
 
 Description:	The #gpio-cells property defines the number of cells required
 		to encode a gpio specifier.
 
 
 1.2 gpio-controller
 
 Property:	gpio-controller
 
 Value type:	<empty>
 
 Description:	The presence of a gpio-controller property defines a node as a
 		GPIO controller node.
 
 
 1.3 pin-count
 
 Property:	pin-count
 
 Value type:	<u32>
 
 Description:	The pin-count property defines the number of GPIO pins.
 
 
 1.4 Example
 
 	GPIO: gpio@10100 {
 		#gpio-cells = <3>;
 		compatible = "mrvl,gpio";
 		reg = <0x10100 0x20>;
 		gpio-controller;
 		interrupts = <6 7 8 9>;
 		interrupt-parent = <&PIC>;
 		pin-count = <50>
 	};
 
 2. Properties for GPIO consumer nodes.
 
 2.1 gpios
 
 Property:	gpios
 
 Value type:	<prop-encoded-array> encoded as arbitrary number of GPIO
 		specifiers.
 
 Description:	The gpios property of a device node defines the GPIO or GPIOs
 		that are used by the device. The value of the gpios property
 		consists of an arbitrary number of GPIO specifiers.
 		
 		The first cell of the GPIO specifier is phandle of the node's
 		parent GPIO controller and remaining cells are defined by the
 		binding describing the GPIO parent, typically include
 		information like pin number, direction and various flags.
 
 Example:
-		gpios = <&GPIO 0 1 0		/* GPIO[0]:  IN,  NONE */
-			 &GPIO 1 2 0>;		/* GPIO[1]:  OUT, NONE */
+		gpios = <&GPIO 0 1		/* GPIO[0]:  FLAGS */
+			 &GPIO 1 2>;		/* GPIO[1]:  FLAGS */
 
 
-3. "mrvl,gpio" controller GPIO specifier
+3. GPIO controller specifier
 
 	<phandle pin dir flags>
 
 
 pin:	0-MAX				GPIO pin number.
 
-dir:
-	1		IN		Input direction.
-	2		OUT		Output direction.
-
 flags:
-	0x0000----	IN_NONE
-	0x0001----	IN_POL_LOW	Polarity low (active-low).
-	0x0002----	IN_IRQ_EDGE	Interrupt, edge triggered.
-	0x0004----	IN_IRQ_LEVEL	Interrupt, level triggered.
-	
-	0x----0000	OUT_NONE
-	0x----0001	OUT_BLINK	Blink on the pin.
-	0x----0002	OUT_OPEN_DRAIN	Open drain output line.
-	0x----0004	OUT_OPEN_SRC	Open source output line.
+	Available flags are listed in sys/conf.h. Following combination
+	can be supported by the controller. For details please refer
+	to controller's GPIO reference manual.
 
+	GPIO_PIN_INPUT		0x0001	Input direction
+	GPIO_PIN_OUTPUT		0x0002	Output direction
+	GPIO_PIN_OPENDRAIN	0x0004	Open-drain output
+	GPIO_PIN_OPENSOURCE	0x0008	Open-source output
+	GPIO_PIN_PUSHPULL	0x0010	Push-pull output
+	GPIO_PIN_TRISTATE	0x0020	Output disabled
+	GPIO_PIN_PULLUP		0x0040	Internal pull-up enabled
+	GPIO_PIN_PULLDOWN	0x0080	Internal pull-down enabled
+	GPIO_PIN_INVIN		0x0100	Invert input
+	GPIO_PIN_INVOUT		0x0200	Invert output
+	GPIO_PIN_PULSATE	0x0400	Pulsate in hardware
+	GPIO_PIN_IRQ_POL_EDG	0x0800	IRQ active single edge
+	GPIO_PIN_IRQ_POL_DBL	0x1000	IRQ active double edge
+	GPIO_PIN_IRQ_POL_LVL	0x2000	IRQ active level
+	GPIO_PIN_IRQ_DEBOUNCE	0x4000	Debounce on IRQ pin
 
 Example:
-	gpios = <&GPIO 0  1 0x00000000		/* GPIO[0]:   IN */
-		 &GPIO 1  2 0x00000000		/* GPIO[1]:   OUT */
-		 &GPIO 2  1 0x00020000		/* GPIO[2]:   IN, IRQ (edge) */
-		 &GPIO 3  1 0x00040000		/* GPIO[3]:   IN, IRQ (level) */
+	gpios = <&GPIO 0  0x00000001	/* GPIO[0]:   IN */
+		 &GPIO 1  0x00000002	/* GPIO[1]:   OUT */
+		 &GPIO 2  0x00000801	/* GPIO[2]:   IN, IRQ (edge) */
+		 &GPIO 3  0x00004001	/* GPIO[3]:   IN, IRQ (level) */
 		 ...
-		 &GPIO 10 2 0x00000001>;	/* GPIO[10]:  OUT, blink */
+		 &GPIO 10 0x00000401>;	/* GPIO[10]:  OUT, blink */