mail archive of the barebox mailing list
 help / color / mirror / Atom feed
* [PATCH 00/11] ARM: add initial support for Rockchip boards
@ 2014-04-27  9:30 Beniamino Galvani
  2014-04-27  9:30 ` [PATCH 01/11] net: add ARC EMAC driver Beniamino Galvani
                   ` (11 more replies)
  0 siblings, 12 replies; 18+ messages in thread
From: Beniamino Galvani @ 2014-04-27  9:30 UTC (permalink / raw)
  To: barebox

This series adds an initial support for Rockchip SoCs and has been
tested on a Radxa Rock board, on which I'm able to load a kernel from
the network and boot it [1].

At the moment Barebox must be chainloaded from the Rockchip binary
bootloader which performs low-level initializations and loads Barebox
from the "boot" partition on the NAND.

Barebox should be written using the same procedure used for kernels:
it must be prepared with the mkimage tool and then written with
rkflashkit.

There is a u-boot code released by Rockchip [2] which probably
includes all the low-level initializations but I'm not brave enough to
try it.

The patchset adds ethernet and pinctrl drivers, PLL and clocks
initialization, and code to power on the external PHY of the board
through the PMIC.

Beniamino

[1] https://gist.github.com/anonymous/41ccb09030005acb7f89
[2] http://dl.radxa.com/rock/source/.ubootrk.tar.gz

Beniamino Galvani (11):
  net: add ARC EMAC driver
  mfd: add act8846 driver
  ARM: add basic support for Rockchip SoCs
  ARM: rockchip: add PLL initialization function
  clk: gate: add flags argument to clock gate constructor
  clk: gate: unify enable and disable functions handling
  clk: gate: add CLK_GATE_HIWORD_MASK flag
  clk: add rockchip clock gate driver
  pinctrl: add rockchip pinctrl and gpio drivers
  ARM: dts: add Rockchip devicetree files
  ARM: rockchip: add radxa-rock board

 arch/arm/Kconfig                                   |   11 +
 arch/arm/Makefile                                  |    1 +
 arch/arm/boards/Makefile                           |    1 +
 arch/arm/boards/radxa-rock/Makefile                |    2 +
 arch/arm/boards/radxa-rock/board.c                 |   78 +++
 arch/arm/boards/radxa-rock/env/config-board        |    6 +
 arch/arm/boards/radxa-rock/lowlevel.c              |   23 +
 arch/arm/configs/radxa-rock_defconfig              |   62 +++
 arch/arm/dts/rk3188-clocks.dtsi                    |  289 ++++++++++
 arch/arm/dts/rk3188-radxarock.dts                  |   32 ++
 arch/arm/dts/rk3188.dtsi                           |  298 +++++++++++
 arch/arm/dts/rk3xxx.dtsi                           |  134 +++++
 arch/arm/mach-imx/clk.h                            |    2 +-
 arch/arm/mach-rockchip/Kconfig                     |   15 +
 arch/arm/mach-rockchip/Makefile                    |    2 +
 arch/arm/mach-rockchip/core.c                      |   28 +
 arch/arm/mach-rockchip/include/mach/rockchip-pll.h |   26 +
 .../arm/mach-rockchip/include/mach/rockchip-regs.h |   25 +
 arch/arm/mach-rockchip/pll.c                       |  102 ++++
 arch/arm/mach-zynq/clk-zynq7000.c                  |    8 +-
 drivers/clk/Makefile                               |    1 +
 drivers/clk/clk-gate.c                             |   54 +-
 drivers/clk/mvebu/common.c                         |    2 +-
 drivers/clk/mxs/clk-imx28.c                        |    2 +-
 drivers/clk/rockchip/Makefile                      |    1 +
 drivers/clk/rockchip/clk-rockchip.c                |   86 +++
 drivers/clk/tegra/clk-periph.c                     |    2 +-
 drivers/mfd/Kconfig                                |    4 +
 drivers/mfd/Makefile                               |    1 +
 drivers/mfd/act8846.c                              |  154 ++++++
 drivers/net/Kconfig                                |    7 +
 drivers/net/Makefile                               |    1 +
 drivers/net/arc_emac.c                             |  469 ++++++++++++++++
 drivers/pinctrl/Kconfig                            |    7 +
 drivers/pinctrl/Makefile                           |    1 +
 drivers/pinctrl/pinctrl-rockchip.c                 |  560 ++++++++++++++++++++
 include/dt-bindings/pinctrl/rockchip.h             |   32 ++
 include/linux/clk.h                                |    8 +-
 include/mfd/act8846.h                              |   56 ++
 39 files changed, 2557 insertions(+), 36 deletions(-)
 create mode 100644 arch/arm/boards/radxa-rock/Makefile
 create mode 100644 arch/arm/boards/radxa-rock/board.c
 create mode 100644 arch/arm/boards/radxa-rock/env/config-board
 create mode 100644 arch/arm/boards/radxa-rock/lowlevel.c
 create mode 100644 arch/arm/configs/radxa-rock_defconfig
 create mode 100644 arch/arm/dts/rk3188-clocks.dtsi
 create mode 100644 arch/arm/dts/rk3188-radxarock.dts
 create mode 100644 arch/arm/dts/rk3188.dtsi
 create mode 100644 arch/arm/dts/rk3xxx.dtsi
 create mode 100644 arch/arm/mach-rockchip/Kconfig
 create mode 100644 arch/arm/mach-rockchip/Makefile
 create mode 100644 arch/arm/mach-rockchip/core.c
 create mode 100644 arch/arm/mach-rockchip/include/mach/rockchip-pll.h
 create mode 100644 arch/arm/mach-rockchip/include/mach/rockchip-regs.h
 create mode 100644 arch/arm/mach-rockchip/pll.c
 create mode 100644 drivers/clk/rockchip/Makefile
 create mode 100644 drivers/clk/rockchip/clk-rockchip.c
 create mode 100644 drivers/mfd/act8846.c
 create mode 100644 drivers/net/arc_emac.c
 create mode 100644 drivers/pinctrl/pinctrl-rockchip.c
 create mode 100644 include/dt-bindings/pinctrl/rockchip.h
 create mode 100644 include/mfd/act8846.h

-- 
1.7.10.4


_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

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

* [PATCH 01/11] net: add ARC EMAC driver
  2014-04-27  9:30 [PATCH 00/11] ARM: add initial support for Rockchip boards Beniamino Galvani
@ 2014-04-27  9:30 ` Beniamino Galvani
  2014-04-27  9:30 ` [PATCH 02/11] mfd: add act8846 driver Beniamino Galvani
                   ` (10 subsequent siblings)
  11 siblings, 0 replies; 18+ messages in thread
From: Beniamino Galvani @ 2014-04-27  9:30 UTC (permalink / raw)
  To: barebox

This patch adds support for the Synopsys 10/100 Mbps Ethernet MAC used
on some ARC devices and on Rockchip SoCs.

Signed-off-by: Beniamino Galvani <b.galvani@gmail.com>
---
 drivers/net/Kconfig    |    7 +
 drivers/net/Makefile   |    1 +
 drivers/net/arc_emac.c |  469 ++++++++++++++++++++++++++++++++++++++++++++++++
 3 files changed, 477 insertions(+)
 create mode 100644 drivers/net/arc_emac.c

diff --git a/drivers/net/Kconfig b/drivers/net/Kconfig
index fd96859..057abd2 100644
--- a/drivers/net/Kconfig
+++ b/drivers/net/Kconfig
@@ -32,6 +32,13 @@ config DRIVER_NET_AR231X
 	help
 	  Support for the AR231x/531x ethernet controller
 
+config DRIVER_NET_ARC_EMAC
+	bool "ARC Ethernet MAC driver"
+	select PHYLIB
+	help
+	  This option enables support for the ARC EMAC ethernet
+	  controller.
+
 config DRIVER_NET_AT91_ETHER
 	bool "at91 ethernet driver"
 	depends on HAS_AT91_ETHER
diff --git a/drivers/net/Makefile b/drivers/net/Makefile
index c1c4559..65f0d8b 100644
--- a/drivers/net/Makefile
+++ b/drivers/net/Makefile
@@ -2,6 +2,7 @@ obj-$(CONFIG_PHYLIB)			+= phy/
 obj-$(CONFIG_NET_USB)			+= usb/
 
 obj-$(CONFIG_DRIVER_NET_AR231X)		+= ar231x.o
+obj-$(CONFIG_DRIVER_NET_ARC_EMAC)	+= arc_emac.o
 obj-$(CONFIG_DRIVER_NET_AT91_ETHER)	+= at91_ether.o
 obj-$(CONFIG_DRIVER_NET_CALXEDA_XGMAC)	+= xgmac.o
 obj-$(CONFIG_DRIVER_NET_CS8900)		+= cs8900.o
diff --git a/drivers/net/arc_emac.c b/drivers/net/arc_emac.c
new file mode 100644
index 0000000..1f1e889
--- /dev/null
+++ b/drivers/net/arc_emac.c
@@ -0,0 +1,469 @@
+/*
+ * Driver for ARC EMAC Ethernet controller
+ *
+ * Copyright (C) 2014 Beniamino Galvani <b.galvani@gmail.com>
+ *
+ * Based on Linux kernel driver, which is:
+ *  Copyright (C) 2004-2013 Synopsys, Inc. (www.synopsys.com)
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ */
+
+#include <asm/mmu.h>
+#include <common.h>
+#include <net.h>
+#include <io.h>
+#include <init.h>
+
+/* ARC EMAC register set combines entries for MAC and MDIO */
+enum {
+	R_ID = 0,
+	R_STATUS,
+	R_ENABLE,
+	R_CTRL,
+	R_POLLRATE,
+	R_RXERR,
+	R_MISS,
+	R_TX_RING,
+	R_RX_RING,
+	R_ADDRL,
+	R_ADDRH,
+	R_LAFL,
+	R_LAFH,
+	R_MDIO,
+};
+
+/* STATUS and ENABLE Register bit masks */
+#define TXINT_MASK	(1<<0)	/* Transmit interrupt */
+#define RXINT_MASK	(1<<1)	/* Receive interrupt */
+#define ERR_MASK	(1<<2)	/* Error interrupt */
+#define TXCH_MASK	(1<<3)	/* Transmit chaining error interrupt */
+#define MSER_MASK	(1<<4)	/* Missed packet counter error */
+#define RXCR_MASK	(1<<8)	/* RXCRCERR counter rolled over  */
+#define RXFR_MASK	(1<<9)	/* RXFRAMEERR counter rolled over */
+#define RXFL_MASK	(1<<10)	/* RXOFLOWERR counter rolled over */
+#define MDIO_MASK	(1<<12)	/* MDIO complete interrupt */
+#define TXPL_MASK	(1<<31)	/* Force polling of BD by EMAC */
+
+/* CONTROL Register bit masks */
+#define EN_MASK		(1<<0)	/* VMAC enable */
+#define TXRN_MASK	(1<<3)	/* TX enable */
+#define RXRN_MASK	(1<<4)	/* RX enable */
+#define DSBC_MASK	(1<<8)	/* Disable receive broadcast */
+#define ENFL_MASK	(1<<10)	/* Enable Full-duplex */
+#define PROM_MASK	(1<<11)	/* Promiscuous mode */
+
+/* Buffer descriptor INFO bit masks */
+#define OWN_MASK	(1<<31)	/* 0-CPU owns buffer, 1-EMAC owns buffer */
+#define FIRST_MASK	(1<<16)	/* First buffer in chain */
+#define LAST_MASK	(1<<17)	/* Last buffer in chain */
+#define LEN_MASK	0x000007FF	/* last 11 bits */
+#define CRLS		(1<<21)
+#define DEFR		(1<<22)
+#define DROP		(1<<23)
+#define RTRY		(1<<24)
+#define LTCL		(1<<28)
+#define UFLO		(1<<29)
+
+#define FIRST_OR_LAST_MASK	(FIRST_MASK | LAST_MASK)
+
+#define FOR_EMAC	OWN_MASK
+#define FOR_CPU		0
+
+#define EMAC_ZLEN	64
+
+/**
+ * struct arc_emac_priv - Storage of EMAC's private information.
+ * @bus:	Pointer to the current MII bus.
+ * @regs:	Base address of EMAC memory-mapped control registers.
+ * @rxbd:	Pointer to Rx BD ring.
+ * @txbd:	Pointer to Tx BD ring.
+ * @rxbuf:	Buffers for received packets.
+ * @txbd_curr:	Index of Tx BD to use on the next "ndo_start_xmit".
+ * @last_rx_bd:	Index of the last Rx BD we've got from EMAC.
+ */
+struct arc_emac_priv {
+	struct mii_bus *bus;
+	void __iomem *regs;
+	struct arc_emac_bd *rxbd;
+	struct arc_emac_bd *txbd;
+	u8 *rxbuf;
+	unsigned int txbd_curr;
+	unsigned int last_rx_bd;
+};
+
+/**
+ * struct arc_emac_bd - EMAC buffer descriptor (BD).
+ *
+ * @info:	Contains status information on the buffer itself.
+ * @data:	32-bit byte addressable pointer to the packet data.
+ */
+struct arc_emac_bd {
+	__le32 info;
+	dma_addr_t data;
+};
+
+/* Number of Rx/Tx BD's */
+#define RX_BD_NUM	16
+#define TX_BD_NUM	1
+
+#define RX_RING_SZ	(RX_BD_NUM * sizeof(struct arc_emac_bd))
+#define TX_RING_SZ	(TX_BD_NUM * sizeof(struct arc_emac_bd))
+
+/**
+ * arc_reg_set - Sets EMAC register with provided value.
+ * @priv:	Pointer to ARC EMAC private data structure.
+ * @reg:	Register offset from base address.
+ * @value:	Value to set in register.
+ */
+static inline void arc_reg_set(struct arc_emac_priv *priv, int reg, int value)
+{
+	writel(value, priv->regs + reg * sizeof(int));
+}
+
+/**
+ * arc_reg_get - Gets value of specified EMAC register.
+ * @priv:	Pointer to ARC EMAC private data structure.
+ * @reg:	Register offset from base address.
+ *
+ * returns:	Value of requested register.
+ */
+static inline unsigned int arc_reg_get(struct arc_emac_priv *priv, int reg)
+{
+	return readl(priv->regs + reg * sizeof(int));
+}
+
+/**
+ * arc_reg_or - Applies mask to specified EMAC register - ("reg" | "mask").
+ * @priv:	Pointer to ARC EMAC private data structure.
+ * @reg:	Register offset from base address.
+ * @mask:	Mask to apply to specified register.
+ *
+ * This function reads initial register value, then applies provided mask
+ * to it and then writes register back.
+ */
+static inline void arc_reg_or(struct arc_emac_priv *priv, int reg, int mask)
+{
+	unsigned int value = arc_reg_get(priv, reg);
+	arc_reg_set(priv, reg, value | mask);
+}
+
+/**
+ * arc_reg_clr - Applies mask to specified EMAC register - ("reg" & ~"mask").
+ * @priv:	Pointer to ARC EMAC private data structure.
+ * @reg:	Register offset from base address.
+ * @mask:	Mask to apply to specified register.
+ *
+ * This function reads initial register value, then applies provided mask
+ * to it and then writes register back.
+ */
+static inline void arc_reg_clr(struct arc_emac_priv *priv, int reg, int mask)
+{
+	unsigned int value = arc_reg_get(priv, reg);
+	arc_reg_set(priv, reg, value & ~mask);
+}
+
+static int arc_emac_init(struct eth_device *edev)
+{
+	return 0;
+}
+
+static int arc_emac_open(struct eth_device *edev)
+{
+	struct arc_emac_priv *priv = edev->priv;
+	void *rxbuf;
+	int ret, i;
+
+	priv->last_rx_bd = 0;
+	rxbuf = priv->rxbuf;
+
+	/* Allocate and set buffers for Rx BD's */
+	for (i = 0; i < RX_BD_NUM; i++) {
+		unsigned int *last_rx_bd = &priv->last_rx_bd;
+		struct arc_emac_bd *rxbd = &priv->rxbd[*last_rx_bd];
+
+		rxbd->data = cpu_to_le32(rxbuf);
+
+		/* Return ownership to EMAC */
+		rxbd->info = cpu_to_le32(FOR_EMAC | PKTSIZE);
+
+		*last_rx_bd = (*last_rx_bd + 1) % RX_BD_NUM;
+		rxbuf += PKTSIZE;
+	}
+
+	/* Clean Tx BD's */
+	memset(priv->txbd, 0, TX_RING_SZ);
+
+	/* Initialize logical address filter */
+	arc_reg_set(priv, R_LAFL, 0x0);
+	arc_reg_set(priv, R_LAFH, 0x0);
+
+	/* Set BD ring pointers for device side */
+	arc_reg_set(priv, R_RX_RING, (unsigned int)priv->rxbd);
+	arc_reg_set(priv, R_TX_RING, (unsigned int)priv->txbd);
+
+	/* Enable interrupts */
+	arc_reg_set(priv, R_ENABLE, RXINT_MASK | ERR_MASK);
+
+	/* Set CONTROL */
+	arc_reg_set(priv, R_CTRL,
+		     (RX_BD_NUM << 24) |	/* RX BD table length */
+		     (TX_BD_NUM << 16) |	/* TX BD table length */
+		     TXRN_MASK | RXRN_MASK);
+
+	/* Enable EMAC */
+	arc_reg_or(priv, R_CTRL, EN_MASK);
+
+	ret = phy_device_connect(edev, priv->bus, -1, NULL, 0,
+				 PHY_INTERFACE_MODE_NA);
+	if (ret)
+		return ret;
+
+	return 0;
+}
+
+static int arc_emac_send(struct eth_device *edev, void *data, int length)
+{
+	struct arc_emac_priv *priv = edev->priv;
+	struct arc_emac_bd *bd = &priv->txbd[priv->txbd_curr];
+	char txbuf[EMAC_ZLEN];
+	int ret;
+
+	/* Pad short frames to minimum length */
+	if (length < EMAC_ZLEN) {
+		memcpy(txbuf, data, length);
+		memset(txbuf + length, 0, EMAC_ZLEN - length);
+		data = txbuf;
+		length = EMAC_ZLEN;
+	}
+
+	dma_flush_range((unsigned long)data, (unsigned long)data + length);
+
+	bd->data = cpu_to_le32(data);
+	bd->info = cpu_to_le32(FOR_EMAC | FIRST_OR_LAST_MASK | length);
+	arc_reg_set(priv, R_STATUS, TXPL_MASK);
+
+	ret = wait_on_timeout(20 * MSECOND,
+			      (arc_reg_get(priv, R_STATUS) & TXINT_MASK) != 0);
+
+	if (ret) {
+		dev_err(&edev->dev, "transmit timeout\n");
+		return ret;
+	}
+
+	arc_reg_set(priv, R_STATUS, TXINT_MASK);
+
+	priv->txbd_curr++;
+	priv->txbd_curr %= TX_BD_NUM;
+
+	return 0;
+}
+
+static int arc_emac_recv(struct eth_device *edev)
+{
+	struct arc_emac_priv *priv = edev->priv;
+	unsigned int work_done;
+
+	for (work_done = 0; work_done < RX_BD_NUM; work_done++) {
+		unsigned int *last_rx_bd = &priv->last_rx_bd;
+		struct arc_emac_bd *rxbd = &priv->rxbd[*last_rx_bd];
+		unsigned int pktlen, info = le32_to_cpu(rxbd->info);
+
+		if (unlikely((info & OWN_MASK) == FOR_EMAC))
+			break;
+
+		/*
+		 * Make a note that we saw a packet at this BD.
+		 * So next time, driver starts from this + 1
+		 */
+		*last_rx_bd = (*last_rx_bd + 1) % RX_BD_NUM;
+
+		if (unlikely((info & FIRST_OR_LAST_MASK) !=
+			     FIRST_OR_LAST_MASK)) {
+			/*
+			 * We pre-allocate buffers of MTU size so incoming
+			 * packets won't be split/chained.
+			 */
+			printk(KERN_DEBUG "incomplete packet received\n");
+
+			/* Return ownership to EMAC */
+			rxbd->info = cpu_to_le32(FOR_EMAC | PKTSIZE);
+			continue;
+		}
+
+		pktlen = info & LEN_MASK;
+
+		/* invalidate current receive buffer */
+		dma_inv_range((unsigned long)rxbd->data,
+			      (unsigned long)rxbd->data + pktlen);
+
+		net_receive((unsigned char *)rxbd->data, pktlen);
+
+		rxbd->info = cpu_to_le32(FOR_EMAC | PKTSIZE);
+	}
+
+	return work_done;
+}
+
+static void arc_emac_halt(struct eth_device *edev)
+{
+	struct arc_emac_priv *priv = edev->priv;
+
+	/* Disable interrupts */
+	arc_reg_clr(priv, R_ENABLE, RXINT_MASK | ERR_MASK);
+
+	/* Disable EMAC */
+	arc_reg_clr(priv, R_CTRL, EN_MASK);
+}
+
+static int arc_emac_get_ethaddr(struct eth_device *edev, unsigned char *mac)
+{
+	return -1;
+}
+
+static int arc_emac_set_ethaddr(struct eth_device *edev, unsigned char *mac)
+{
+	struct arc_emac_priv *priv = edev->priv;
+	unsigned int addr_low, addr_hi;
+
+	addr_low = le32_to_cpu(*(__le32 *) &mac[0]);
+	addr_hi = le16_to_cpu(*(__le16 *) &mac[4]);
+
+	arc_reg_set(priv, R_ADDRL, addr_low);
+	arc_reg_set(priv, R_ADDRH, addr_hi);
+
+	return 0;
+}
+
+/* Number of seconds we wait for "MDIO complete" flag to appear */
+#define ARC_MDIO_COMPLETE_POLL_COUNT	1
+
+static int arc_mdio_complete_wait(struct arc_emac_priv *priv)
+{
+	unsigned int i;
+
+	for (i = 0; i < ARC_MDIO_COMPLETE_POLL_COUNT * 40; i++) {
+		unsigned int status = arc_reg_get(priv, R_STATUS);
+
+		status &= MDIO_MASK;
+
+		if (status) {
+			/* Reset "MDIO complete" flag */
+			arc_reg_set(priv, R_STATUS, status);
+			return 0;
+		}
+
+		mdelay(25);
+	}
+	return -ETIMEDOUT;
+}
+
+static int arc_emac_mdio_read(struct mii_bus *bus, int phy_addr, int reg_num)
+{
+	struct arc_emac_priv *priv = bus->priv;
+	int error;
+
+	arc_reg_set(priv, R_MDIO,
+		    0x60020000 | (phy_addr << 23) | (reg_num << 18));
+
+	error = arc_mdio_complete_wait(priv);
+	if (error < 0)
+		return error;
+
+	return arc_reg_get(priv, R_MDIO) & 0xffff;
+}
+
+static int arc_emac_mdio_write(struct mii_bus *bus, int phy_addr, int reg_num,
+			       u16 value)
+{
+	struct arc_emac_priv *priv = bus->priv;
+
+	arc_reg_set(priv, R_MDIO,
+		     0x50020000 | (phy_addr << 23) | (reg_num << 18) | value);
+
+	return arc_mdio_complete_wait(priv);
+}
+
+static int arc_emac_probe(struct device_d *dev)
+{
+	struct eth_device *edev;
+	struct arc_emac_priv *priv;
+	unsigned int clock_frequency;
+	struct mii_bus *miibus;
+	u32 id;
+
+	/* Get CPU clock frequency from device tree */
+	if (of_property_read_u32(dev->device_node, "clock-frequency",
+				 &clock_frequency)) {
+		dev_err(dev, "failed to retrieve <clock-frequency> from device tree\n");
+		return -EINVAL;
+	}
+
+	edev = xzalloc(sizeof(struct eth_device) +
+		       sizeof(struct arc_emac_priv));
+	edev->priv = (struct arc_emac_priv *)(edev + 1);
+	miibus = xzalloc(sizeof(struct mii_bus));
+
+	priv = edev->priv;
+	priv->regs = dev_request_mem_region(dev, 0);
+	priv->bus = miibus;
+
+	id = arc_reg_get(priv, R_ID);
+	/* Check for EMAC revision 5 or 7, magic number */
+	if (!(id == 0x0005fd02 || id == 0x0007fd02)) {
+		dev_err(dev, "ARC EMAC not detected, id=0x%x\n", id);
+		free(edev);
+		free(miibus);
+		return -ENODEV;
+	}
+	dev_info(dev, "ARC EMAC detected with id: 0x%x\n", id);
+
+	edev->init = arc_emac_init;
+	edev->open = arc_emac_open;
+	edev->send = arc_emac_send;
+	edev->recv = arc_emac_recv;
+	edev->halt = arc_emac_halt;
+	edev->get_ethaddr = arc_emac_get_ethaddr;
+	edev->set_ethaddr = arc_emac_set_ethaddr;
+	edev->parent = dev;
+
+	miibus->read = arc_emac_mdio_read;
+	miibus->write = arc_emac_mdio_write;
+	miibus->priv = priv;
+	miibus->parent = dev;
+
+	/* allocate rx/tx descriptors */
+	priv->rxbd = dma_alloc_coherent(RX_BD_NUM * sizeof(struct arc_emac_bd));
+	priv->txbd = dma_alloc_coherent(TX_BD_NUM * sizeof(struct arc_emac_bd));
+	priv->rxbuf = dma_alloc(RX_BD_NUM * PKTSIZE);
+
+	/* Set poll rate so that it polls every 1 ms */
+	arc_reg_set(priv, R_POLLRATE, clock_frequency / 1000000);
+
+	mdiobus_register(miibus);
+	eth_register(edev);
+
+	return 0;
+}
+
+static __maybe_unused struct of_device_id arc_emac_dt_ids[] = {
+	{
+		.compatible = "snps,arc-emac",
+	}, {
+		/* sentinel */
+	}
+};
+
+static struct driver_d arc_emac_driver = {
+	.name = "arc-emac",
+	.probe = arc_emac_probe,
+	.of_compatible = DRV_OF_COMPAT(arc_emac_dt_ids),
+};
+device_platform_driver(arc_emac_driver);
-- 
1.7.10.4


_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

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

* [PATCH 02/11] mfd: add act8846 driver
  2014-04-27  9:30 [PATCH 00/11] ARM: add initial support for Rockchip boards Beniamino Galvani
  2014-04-27  9:30 ` [PATCH 01/11] net: add ARC EMAC driver Beniamino Galvani
@ 2014-04-27  9:30 ` Beniamino Galvani
  2014-04-27  9:30 ` [PATCH 03/11] ARM: add basic support for Rockchip SoCs Beniamino Galvani
                   ` (9 subsequent siblings)
  11 siblings, 0 replies; 18+ messages in thread
From: Beniamino Galvani @ 2014-04-27  9:30 UTC (permalink / raw)
  To: barebox


Signed-off-by: Beniamino Galvani <b.galvani@gmail.com>
---
 drivers/mfd/Kconfig   |    4 ++
 drivers/mfd/Makefile  |    1 +
 drivers/mfd/act8846.c |  154 +++++++++++++++++++++++++++++++++++++++++++++++++
 include/mfd/act8846.h |   56 ++++++++++++++++++
 4 files changed, 215 insertions(+)
 create mode 100644 drivers/mfd/act8846.c
 create mode 100644 include/mfd/act8846.h

diff --git a/drivers/mfd/Kconfig b/drivers/mfd/Kconfig
index 8873764..3af904d 100644
--- a/drivers/mfd/Kconfig
+++ b/drivers/mfd/Kconfig
@@ -1,5 +1,9 @@
 menu MFD
 
+config MFD_ACT8846
+	depends on I2C
+	bool "ACT8846 driver"
+
 config MFD_LP3972
 	depends on I2C
 	bool "LP3972 driver"
diff --git a/drivers/mfd/Makefile b/drivers/mfd/Makefile
index 2ad766d..49b9e35 100644
--- a/drivers/mfd/Makefile
+++ b/drivers/mfd/Makefile
@@ -1,3 +1,4 @@
+obj-$(CONFIG_MFD_ACT8846)	+= act8846.o
 obj-$(CONFIG_MFD_LP3972)	+= lp3972.o
 obj-$(CONFIG_MFD_MC13XXX)	+= mc13xxx.o
 obj-$(CONFIG_MFD_MC34704)	+= mc34704.o
diff --git a/drivers/mfd/act8846.c b/drivers/mfd/act8846.c
new file mode 100644
index 0000000..60029ac
--- /dev/null
+++ b/drivers/mfd/act8846.c
@@ -0,0 +1,154 @@
+/*
+ * Copyright (C) 2007 Sascha Hauer, Pengutronix
+ *               2009 Marc Kleine-Budde <mkl@pengutronix.de>
+ *
+ * Copied from drivers/mfd/mc9sdz60.c
+ *
+ * This program is free software; you can redistribute it and/or
+ * modify it under the terms of the GNU General Public License as
+ * published by the Free Software Foundation; either version 2 of
+ * the License, or (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ *
+ */
+
+#include <common.h>
+#include <init.h>
+#include <driver.h>
+#include <xfuncs.h>
+#include <errno.h>
+
+#include <i2c/i2c.h>
+#include <mfd/act8846.h>
+
+#define DRIVERNAME		"act8846"
+
+#define to_act8846(a)		container_of(a, struct act8846, cdev)
+
+static struct act8846 *act8846_dev;
+
+struct act8846 *act8846_get(void)
+{
+	if (!act8846_dev)
+		return NULL;
+
+	return act8846_dev;
+}
+EXPORT_SYMBOL(act8846_get);
+
+int act8846_reg_read(struct act8846 *act8846, enum act8846_reg reg, u8 *val)
+{
+	int ret;
+
+	ret = i2c_read_reg(act8846->client, reg, val, 1);
+
+	return ret == 1 ? 0 : ret;
+}
+EXPORT_SYMBOL(act8846_reg_read);
+
+int act8846_reg_write(struct act8846 *act8846, enum act8846_reg reg, u8 val)
+{
+	int ret;
+
+	ret = i2c_write_reg(act8846->client, reg, &val, 1);
+
+	return ret == 1 ? 0 : ret;
+}
+EXPORT_SYMBOL(act8846_reg_write);
+
+int act8846_set_bits(struct act8846 *act8846, enum act8846_reg reg,
+		     u8 mask, u8 val)
+{
+	u8 tmp;
+	int err;
+
+	err = act8846_reg_read(act8846, reg, &tmp);
+	tmp = (tmp & ~mask) | val;
+
+	if (!err)
+		err = act8846_reg_write(act8846, reg, tmp);
+
+	return err;
+}
+EXPORT_SYMBOL(act8846_set_bits);
+
+static ssize_t act8846_read(struct cdev *cdev, void *_buf, size_t count,
+			    loff_t offset, ulong flags)
+{
+	struct act8846 *act8846 = to_act8846(cdev);
+	u8 *buf = _buf;
+	size_t i = count;
+	int err;
+
+	while (i) {
+		err = act8846_reg_read(act8846, offset, buf);
+		if (err)
+			return (ssize_t)err;
+		buf++;
+		i--;
+		offset++;
+	}
+
+	return count;
+}
+
+static ssize_t act8846_write(struct cdev *cdev, const void *_buf, size_t count,
+			     loff_t offset, ulong flags)
+{
+	struct act8846 *act8846 = to_act8846(cdev);
+	const u8 *buf = _buf;
+	size_t i = count;
+	int err;
+
+	while (i) {
+		err = act8846_reg_write(act8846, offset, *buf);
+		if (err)
+			return (ssize_t)err;
+		buf++;
+		i--;
+		offset++;
+	}
+
+	return count;
+}
+
+static struct file_operations act8846_fops = {
+	.lseek	= dev_lseek_default,
+	.read	= act8846_read,
+	.write	= act8846_write,
+};
+
+static int act8846_probe(struct device_d *dev)
+{
+	if (act8846_dev)
+		return -EBUSY;
+
+	act8846_dev = xzalloc(sizeof(struct act8846));
+	act8846_dev->cdev.name = DRIVERNAME;
+	act8846_dev->client = to_i2c_client(dev);
+	act8846_dev->cdev.size = 64;
+	act8846_dev->cdev.dev = dev;
+	act8846_dev->cdev.ops = &act8846_fops;
+
+	devfs_create(&act8846_dev->cdev);
+
+	return 0;
+}
+
+static struct driver_d act8846_driver = {
+	.name  = DRIVERNAME,
+	.probe = act8846_probe,
+};
+
+static int act8846_init(void)
+{
+	i2c_driver_register(&act8846_driver);
+	return 0;
+}
+
+device_initcall(act8846_init);
diff --git a/include/mfd/act8846.h b/include/mfd/act8846.h
new file mode 100644
index 0000000..011fe20
--- /dev/null
+++ b/include/mfd/act8846.h
@@ -0,0 +1,56 @@
+/*
+ * Copyright (C) 2009 Marc Kleine-Budde <mkl@pengutronix.de>
+ *
+ * This file is released under the GPLv2
+ *
+ * Derived from mc9sdz60.h
+ */
+
+#ifndef _ACT8846_H
+#define _ACT8846_H
+
+enum act8846_reg {
+	ACT8846_SYS_MODE	= 0x00,
+	ACT8846_SYS_CTRL	= 0x01,
+	ACT8846_DCDC1_VSET1	= 0x10,
+	ACT8846_DCDC1_CTRL	= 0x12,
+	ACT8846_DCDC2_VSET1	= 0x20,
+	ACT8846_DCDC2_VSET2	= 0x21,
+	ACT8846_DCDC2_CTRL	= 0x22,
+	ACT8846_DCDC3_VSET1	= 0x30,
+	ACT8846_DCDC3_VSET2	= 0x31,
+	ACT8846_DCDC3_CTRL	= 0x32,
+	ACT8846_DCDC4_VSET1	= 0x40,
+	ACT8846_DCDC4_VSET2	= 0x41,
+	ACT8846_DCDC4_CTRL	= 0x42,
+	ACT8846_LDO5_VSET	= 0x50,
+	ACT8846_LDO5_CTRL	= 0x51,
+	ACT8846_LDO6_VSET	= 0x58,
+	ACT8846_LDO6_CTRL	= 0x59,
+	ACT8846_LDO7_VSET	= 0x60,
+	ACT8846_LDO7_CTRL	= 0x61,
+	ACT8846_LDO8_VSET	= 0x68,
+	ACT8846_LDO8_CTRL	= 0x69,
+	ACT8846_LDO9_VSET	= 0x70,
+	ACT8846_LDO9_CTRL	= 0x71,
+	ACT8846_LDO10_VSET	= 0x80,
+	ACT8846_LDO10_CTRL	= 0x81,
+	ACT8846_LDO11_VSET	= 0x90,
+	ACT8846_LDO11_CTRL	= 0x91,
+	ACT8846_LDO12_VSET	= 0xA0,
+	ACT8846_LDO12_CTRL	= 0xA1,
+};
+
+struct act8846 {
+	struct cdev		cdev;
+	struct i2c_client	*client;
+};
+
+struct act8846 *act8846_get(void);
+
+int act8846_reg_read(struct act8846 *priv, enum act8846_reg reg, u8 *val);
+int act8846_reg_write(struct act8846 *priv, enum act8846_reg reg, u8 val);
+int act8846_set_bits(struct act8846 *priv, enum act8846_reg reg,
+		     u8 mask, u8 val);
+
+#endif /* _ACT8846_H */
-- 
1.7.10.4


_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

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

* [PATCH 03/11] ARM: add basic support for Rockchip SoCs
  2014-04-27  9:30 [PATCH 00/11] ARM: add initial support for Rockchip boards Beniamino Galvani
  2014-04-27  9:30 ` [PATCH 01/11] net: add ARC EMAC driver Beniamino Galvani
  2014-04-27  9:30 ` [PATCH 02/11] mfd: add act8846 driver Beniamino Galvani
@ 2014-04-27  9:30 ` Beniamino Galvani
  2014-04-27  9:30 ` [PATCH 04/11] ARM: rockchip: add PLL initialization function Beniamino Galvani
                   ` (8 subsequent siblings)
  11 siblings, 0 replies; 18+ messages in thread
From: Beniamino Galvani @ 2014-04-27  9:30 UTC (permalink / raw)
  To: barebox

This patch adds a basic support for the ARM-based Rockchip SoCs of the
RK3xxx family.

Signed-off-by: Beniamino Galvani <b.galvani@gmail.com>
---
 arch/arm/Kconfig                                   |    6 +++++
 arch/arm/Makefile                                  |    1 +
 arch/arm/mach-rockchip/Kconfig                     |    7 +++++
 arch/arm/mach-rockchip/Makefile                    |    1 +
 arch/arm/mach-rockchip/core.c                      |   28 ++++++++++++++++++++
 .../arm/mach-rockchip/include/mach/rockchip-regs.h |   25 +++++++++++++++++
 6 files changed, 68 insertions(+)
 create mode 100644 arch/arm/mach-rockchip/Kconfig
 create mode 100644 arch/arm/mach-rockchip/Makefile
 create mode 100644 arch/arm/mach-rockchip/core.c
 create mode 100644 arch/arm/mach-rockchip/include/mach/rockchip-regs.h

diff --git a/arch/arm/Kconfig b/arch/arm/Kconfig
index 3754646..a7db86c 100644
--- a/arch/arm/Kconfig
+++ b/arch/arm/Kconfig
@@ -125,6 +125,11 @@ config ARCH_PXA
 	select GENERIC_GPIO
 	select HAS_POWEROFF
 
+config ARCH_ROCKCHIP
+	bool "Rockchip RX3xxx"
+	select CPU_V7
+	select ARM_SMP_TWD
+
 config ARCH_SOCFPGA
 	bool "Altera SOCFPGA cyclone5"
 	select HAS_DEBUG_LL
@@ -204,6 +209,7 @@ source arch/arm/mach-netx/Kconfig
 source arch/arm/mach-nomadik/Kconfig
 source arch/arm/mach-omap/Kconfig
 source arch/arm/mach-pxa/Kconfig
+source arch/arm/mach-rockchip/Kconfig
 source arch/arm/mach-samsung/Kconfig
 source arch/arm/mach-socfpga/Kconfig
 source arch/arm/mach-versatile/Kconfig
diff --git a/arch/arm/Makefile b/arch/arm/Makefile
index c1bd836..3312a49 100644
--- a/arch/arm/Makefile
+++ b/arch/arm/Makefile
@@ -64,6 +64,7 @@ machine-$(CONFIG_ARCH_NOMADIK)		:= nomadik
 machine-$(CONFIG_ARCH_NETX)		:= netx
 machine-$(CONFIG_ARCH_OMAP)		:= omap
 machine-$(CONFIG_ARCH_PXA)		:= pxa
+machine-$(CONFIG_ARCH_ROCKCHIP)		:= rockchip
 machine-$(CONFIG_ARCH_SAMSUNG)		:= samsung
 machine-$(CONFIG_ARCH_SOCFPGA)		:= socfpga
 machine-$(CONFIG_ARCH_VERSATILE)	:= versatile
diff --git a/arch/arm/mach-rockchip/Kconfig b/arch/arm/mach-rockchip/Kconfig
new file mode 100644
index 0000000..dfaf146
--- /dev/null
+++ b/arch/arm/mach-rockchip/Kconfig
@@ -0,0 +1,7 @@
+if ARCH_ROCKCHIP
+
+config ARCH_TEXT_BASE
+	hex
+	default 0x68000000
+
+endif
diff --git a/arch/arm/mach-rockchip/Makefile b/arch/arm/mach-rockchip/Makefile
new file mode 100644
index 0000000..820eb10
--- /dev/null
+++ b/arch/arm/mach-rockchip/Makefile
@@ -0,0 +1 @@
+obj-y += core.o
diff --git a/arch/arm/mach-rockchip/core.c b/arch/arm/mach-rockchip/core.c
new file mode 100644
index 0000000..bab06df
--- /dev/null
+++ b/arch/arm/mach-rockchip/core.c
@@ -0,0 +1,28 @@
+/*
+ * Copyright (C) 2014 Beniamino Galvani <b.galvani@gmail.com>
+ *
+ * This program is free software; you can redistribute it and/or
+ * modify it under the terms of the GNU General Public License
+ * version 2 as published by the Free Software Foundation.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ */
+
+#include <asm/io.h>
+#include <common.h>
+#include <mach/rockchip-regs.h>
+
+void __noreturn reset_cpu(unsigned long addr)
+{
+	/* Map bootrom from address 0 */
+	writel(RK_SOC_CON0_REMAP << 16, RK_GRF_BASE + RK_GRF_SOC_CON0);
+	/* Reset */
+	writel(0xeca8, RK_CRU_BASE + RK_CRU_GLB_SRST_SND);
+
+	while (1)
+		;
+}
+EXPORT_SYMBOL(reset_cpu);
diff --git a/arch/arm/mach-rockchip/include/mach/rockchip-regs.h b/arch/arm/mach-rockchip/include/mach/rockchip-regs.h
new file mode 100644
index 0000000..a6a1c64
--- /dev/null
+++ b/arch/arm/mach-rockchip/include/mach/rockchip-regs.h
@@ -0,0 +1,25 @@
+/*
+ * Copyright (C) 2014 Beniamino Galvani <b.galvani@gmail.com>
+ *
+ * This program is free software; you can redistribute it and/or
+ * modify it under the terms of the GNU General Public License
+ * version 2 as published by the Free Software Foundation.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ */
+
+#ifndef __MACH_ROCKCHIP_REGS_H
+#define __MACH_ROCKCHIP_REGS_H
+
+#define RK_CRU_BASE		0x20000000
+#define RK_GRF_BASE		0x20008000
+
+#define RK_CRU_GLB_SRST_SND	0x0104
+#define RK_GRF_SOC_CON0		0x00a0
+
+#define RK_SOC_CON0_REMAP	(1 << 12)
+
+#endif /* __MACH_ROCKCHIP_REGS_H */
-- 
1.7.10.4


_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

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

* [PATCH 04/11] ARM: rockchip: add PLL initialization function
  2014-04-27  9:30 [PATCH 00/11] ARM: add initial support for Rockchip boards Beniamino Galvani
                   ` (2 preceding siblings ...)
  2014-04-27  9:30 ` [PATCH 03/11] ARM: add basic support for Rockchip SoCs Beniamino Galvani
@ 2014-04-27  9:30 ` Beniamino Galvani
  2014-04-27  9:30 ` [PATCH 05/11] clk: gate: add flags argument to clock gate constructor Beniamino Galvani
                   ` (7 subsequent siblings)
  11 siblings, 0 replies; 18+ messages in thread
From: Beniamino Galvani @ 2014-04-27  9:30 UTC (permalink / raw)
  To: barebox


Signed-off-by: Beniamino Galvani <b.galvani@gmail.com>
---
 arch/arm/mach-rockchip/Makefile                    |    1 +
 arch/arm/mach-rockchip/include/mach/rockchip-pll.h |   26 +++++
 arch/arm/mach-rockchip/pll.c                       |  102 ++++++++++++++++++++
 3 files changed, 129 insertions(+)
 create mode 100644 arch/arm/mach-rockchip/include/mach/rockchip-pll.h
 create mode 100644 arch/arm/mach-rockchip/pll.c

diff --git a/arch/arm/mach-rockchip/Makefile b/arch/arm/mach-rockchip/Makefile
index 820eb10..6f4ec16 100644
--- a/arch/arm/mach-rockchip/Makefile
+++ b/arch/arm/mach-rockchip/Makefile
@@ -1 +1,2 @@
 obj-y += core.o
+obj-y += pll.o
\ No newline at end of file
diff --git a/arch/arm/mach-rockchip/include/mach/rockchip-pll.h b/arch/arm/mach-rockchip/include/mach/rockchip-pll.h
new file mode 100644
index 0000000..c2cd888
--- /dev/null
+++ b/arch/arm/mach-rockchip/include/mach/rockchip-pll.h
@@ -0,0 +1,26 @@
+/*
+ * Copyright (C) 2014 Beniamino Galvani <b.galvani@gmail.com>
+ *
+ * This program is free software; you can redistribute it and/or
+ * modify it under the terms of the GNU General Public License
+ * version 2 as published by the Free Software Foundation.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ */
+
+#ifndef __MACH_ROCKCHIP_PLL_H
+#define __MACH_ROCKCHIP_PLL_H
+
+enum rk3188_plls {
+	RK3188_APLL = 0,	/* ARM */
+	RK3188_DPLL,		/* DDR */
+	RK3188_CPLL,		/* Codec */
+	RK3188_GPLL,		/* General */
+};
+
+int rk3188_pll_set_parameters(int pll, int nr, int nf, int no);
+
+#endif /* __MACH_ROCKCHIP_PLL_H */
diff --git a/arch/arm/mach-rockchip/pll.c b/arch/arm/mach-rockchip/pll.c
new file mode 100644
index 0000000..fce192c
--- /dev/null
+++ b/arch/arm/mach-rockchip/pll.c
@@ -0,0 +1,102 @@
+/*
+ * Copyright (C) 2014 Beniamino Galvani <b.galvani@gmail.com>
+ *
+ * Based on Linux clk driver:
+ *  Copyright (c) 2014 MundoReader S.L.
+ *
+ * This program is free software; you can redistribute it and/or
+ * modify it under the terms of the GNU General Public License
+ * version 2 as published by the Free Software Foundation.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ */
+
+#include <asm/io.h>
+#include <common.h>
+#include <mach/rockchip-regs.h>
+
+#define RK3188_CLK_BASE		0x20000000
+#define RK3188_PLL_LOCK_REG	0x200080ac
+
+#define PLL_MODE_MASK		0x3
+#define PLL_MODE_SLOW		0x0
+#define PLL_MODE_NORM		0x1
+#define PLL_MODE_DEEP		0x2
+
+#define PLL_RESET_DELAY(nr)	((nr * 500) / 24 + 1)
+
+#define PLLCON0_OD_MASK		0xf
+#define PLLCON0_OD_SHIFT	0
+#define PLLCON0_NR_MASK		0x3f
+#define PLLCON0_NR_SHIFT	8
+
+#define PLLCON1_NF_MASK		0x1fff
+#define PLLCON1_NF_SHIFT	0
+
+#define PLLCON2_BWADJ_MASK	0xfff
+#define PLLCON2_BWADJ_SHIFT	0
+
+#define PLLCON3_RESET		(1 << 1)
+#define PLLCON3_BYPASS		(1 << 0)
+
+struct rockchip_pll_data {
+	int con_base;
+	int mode_offset;
+	int mode_shift;
+	int lock_shift;
+};
+
+struct rockchip_pll_data rk3188_plls[] = {
+	{ 0x00, 0x40, 0x00, 0x06 },
+	{ 0x10, 0x40, 0x04, 0x05 },
+	{ 0x20, 0x40, 0x08, 0x07 },
+	{ 0x30, 0x40, 0x0c, 0x08 },
+};
+
+#define HIWORD_UPDATE(val, mask, shift) \
+	((val) << (shift) | (mask) << ((shift) + 16))
+
+int rk3188_pll_set_parameters(int pll, int nr, int nf, int no)
+{
+	struct rockchip_pll_data *d = &rk3188_plls[pll];
+	int delay = 0;
+
+	debug("rk3188 pll %d: set param %d %d %d\n", pll, nr, nf, no);
+
+	/* pull pll in slow mode */
+	writel(HIWORD_UPDATE(PLL_MODE_SLOW, PLL_MODE_MASK, d->mode_shift),
+	       RK3188_CLK_BASE + d->mode_offset);
+	/* enter reset */
+	writel(HIWORD_UPDATE(PLLCON3_RESET, PLLCON3_RESET, 0),
+	       RK3188_CLK_BASE + d->con_base + 12);
+
+	/* update pll values */
+	writel(HIWORD_UPDATE(nr - 1, PLLCON0_NR_MASK, PLLCON0_NR_SHIFT) |
+	       HIWORD_UPDATE(no - 1, PLLCON0_OD_MASK, PLLCON0_OD_SHIFT),
+	       RK3188_CLK_BASE + d->con_base + 0);
+	writel(HIWORD_UPDATE(nf - 1, PLLCON1_NF_MASK, PLLCON1_NF_SHIFT),
+	       RK3188_CLK_BASE + d->con_base + 4);
+	writel(HIWORD_UPDATE(nf >> 1, PLLCON2_BWADJ_MASK, PLLCON2_BWADJ_SHIFT),
+	       RK3188_CLK_BASE + d->con_base + 8);
+
+	/* leave reset and wait the reset_delay */
+	writel(HIWORD_UPDATE(0, PLLCON3_RESET, 0),
+	       RK3188_CLK_BASE + d->con_base + 12);
+	udelay(PLL_RESET_DELAY(nr));
+
+	/* wait for the pll to lock */
+	while (delay++ < 24000000) {
+		if (readl(RK3188_PLL_LOCK_REG) & BIT(d->lock_shift))
+			break;
+	}
+
+	/* go back to normal mode */
+	writel(HIWORD_UPDATE(PLL_MODE_NORM, PLL_MODE_MASK, d->mode_shift),
+	       RK3188_CLK_BASE + d->mode_offset);
+
+	return 0;
+}
+EXPORT_SYMBOL(rk3188_pll_set_parameters);
-- 
1.7.10.4


_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

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

* [PATCH 05/11] clk: gate: add flags argument to clock gate constructor
  2014-04-27  9:30 [PATCH 00/11] ARM: add initial support for Rockchip boards Beniamino Galvani
                   ` (3 preceding siblings ...)
  2014-04-27  9:30 ` [PATCH 04/11] ARM: rockchip: add PLL initialization function Beniamino Galvani
@ 2014-04-27  9:30 ` Beniamino Galvani
  2014-04-27  9:30 ` [PATCH 06/11] clk: gate: unify enable and disable functions handling Beniamino Galvani
                   ` (6 subsequent siblings)
  11 siblings, 0 replies; 18+ messages in thread
From: Beniamino Galvani @ 2014-04-27  9:30 UTC (permalink / raw)
  To: barebox

This adds a clk_gate_flags argument to clock gate creation functions
to allow the introduction of new clock gate modifiers.

Signed-off-by: Beniamino Galvani <b.galvani@gmail.com>
---
 arch/arm/mach-imx/clk.h           |    2 +-
 arch/arm/mach-zynq/clk-zynq7000.c |    8 ++++----
 drivers/clk/clk-gate.c            |   12 +++++-------
 drivers/clk/mvebu/common.c        |    2 +-
 drivers/clk/mxs/clk-imx28.c       |    2 +-
 drivers/clk/tegra/clk-periph.c    |    2 +-
 include/linux/clk.h               |    7 +++++--
 7 files changed, 18 insertions(+), 17 deletions(-)

diff --git a/arch/arm/mach-imx/clk.h b/arch/arm/mach-imx/clk.h
index 32a02db..e2f4143 100644
--- a/arch/arm/mach-imx/clk.h
+++ b/arch/arm/mach-imx/clk.h
@@ -36,7 +36,7 @@ static inline struct clk *imx_clk_mux_p(const char *name, void __iomem *reg,
 static inline struct clk *imx_clk_gate(const char *name, const char *parent,
 		void __iomem *reg, u8 shift)
 {
-	return clk_gate(name, parent, reg, shift, CLK_SET_RATE_PARENT);
+	return clk_gate(name, parent, reg, shift, CLK_SET_RATE_PARENT, 0);
 }
 
 struct clk *imx_clk_pllv1(const char *name, const char *parent,
diff --git a/arch/arm/mach-zynq/clk-zynq7000.c b/arch/arm/mach-zynq/clk-zynq7000.c
index ea637d7..b4513a9 100644
--- a/arch/arm/mach-zynq/clk-zynq7000.c
+++ b/arch/arm/mach-zynq/clk-zynq7000.c
@@ -374,11 +374,11 @@ static int zynq_clock_probe(struct device_d *dev)
 
 	clks[uart_clk] = zynq_periph_clk("uart_clk", slcr_base + 0x154);
 
-	clks[uart0] = clk_gate("uart0", "uart_clk", slcr_base + 0x154, 0, 0);
-	clks[uart1] = clk_gate("uart1", "uart_clk", slcr_base + 0x154, 1, 0);
+	clks[uart0] = clk_gate("uart0", "uart_clk", slcr_base + 0x154, 0, 0, 0);
+	clks[uart1] = clk_gate("uart1", "uart_clk", slcr_base + 0x154, 1, 0, 0);
 
-	clks[gem0] = clk_gate("gem0", "io_pll", slcr_base + 0x140, 0, 0);
-	clks[gem1] = clk_gate("gem1", "io_pll", slcr_base + 0x144, 1, 0);
+	clks[gem0] = clk_gate("gem0", "io_pll", slcr_base + 0x140, 0, 0, 0);
+	clks[gem1] = clk_gate("gem1", "io_pll", slcr_base + 0x144, 1, 0, 0);
 
 	clks[cpu_clk] = zynq_cpu_clk("cpu_clk", slcr_base + 0x120);
 
diff --git a/drivers/clk/clk-gate.c b/drivers/clk/clk-gate.c
index b298b19..11c749a 100644
--- a/drivers/clk/clk-gate.c
+++ b/drivers/clk/clk-gate.c
@@ -25,7 +25,6 @@ struct clk_gate {
 	void __iomem *reg;
 	int shift;
 	const char *parent;
-#define CLK_GATE_INVERTED	(1 << 0)
 	unsigned flags;
 };
 
@@ -85,7 +84,7 @@ static struct clk_ops clk_gate_ops = {
 };
 
 struct clk *clk_gate_alloc(const char *name, const char *parent,
-		void __iomem *reg, u8 shift, unsigned flags)
+		void __iomem *reg, u8 shift, unsigned flags, u8 clk_gate_flags)
 {
 	struct clk_gate *g = xzalloc(sizeof(*g));
 
@@ -97,6 +96,7 @@ struct clk *clk_gate_alloc(const char *name, const char *parent,
 	g->clk.flags = flags;
 	g->clk.parent_names = &g->parent;
 	g->clk.num_parents = 1;
+	g->flags = clk_gate_flags;
 
 	return &g->clk;
 }
@@ -109,12 +109,12 @@ void clk_gate_free(struct clk *clk_gate)
 }
 
 struct clk *clk_gate(const char *name, const char *parent, void __iomem *reg,
-		u8 shift, unsigned flags)
+		u8 shift, unsigned flags, u8 clk_gate_flags)
 {
 	struct clk *g;
 	int ret;
 
-	g = clk_gate_alloc(name , parent, reg, shift, flags);
+	g = clk_gate_alloc(name , parent, reg, shift, flags, clk_gate_flags);
 
 	ret = clk_register(g);
 	if (ret) {
@@ -131,13 +131,11 @@ struct clk *clk_gate_inverted(const char *name, const char *parent,
 	struct clk *clk;
 	struct clk_gate *g;
 
-	clk = clk_gate(name, parent, reg, shift, flags);
+	clk = clk_gate(name, parent, reg, shift, flags, CLK_GATE_INVERTED);
 	if (IS_ERR(clk))
 		return clk;
 
 	g = container_of(clk, struct clk_gate, clk);
 
-	g->flags = CLK_GATE_INVERTED;
-
 	return clk;
 }
diff --git a/drivers/clk/mvebu/common.c b/drivers/clk/mvebu/common.c
index 658ce3e..f3be5f2 100644
--- a/drivers/clk/mvebu/common.c
+++ b/drivers/clk/mvebu/common.c
@@ -188,7 +188,7 @@ int mvebu_clk_gating_probe(struct device_d *dev)
 			(desc[n].parent) ? desc[n].parent : default_parent;
 		gate->bit_idx = desc[n].bit_idx;
 		gate->clk = clk_gate(desc[n].name, parent,
-				base, desc[n].bit_idx, 0);
+				base, desc[n].bit_idx, 0, 0);
 		WARN_ON(IS_ERR(gate->clk));
 	}
 
diff --git a/drivers/clk/mxs/clk-imx28.c b/drivers/clk/mxs/clk-imx28.c
index 934a194..36b71f6 100644
--- a/drivers/clk/mxs/clk-imx28.c
+++ b/drivers/clk/mxs/clk-imx28.c
@@ -128,7 +128,7 @@ int __init mx28_clocks_init(void __iomem *regs)
 	clks[fec] = mxs_clk_gate("fec", "fec_sleep", ENET, 30);
 	clks[usb0_phy] = mxs_clk_gate("usb0_phy", "pll0", PLL0CTRL0, 18);
 	clks[usb1_phy] = mxs_clk_gate("usb1_phy", "pll1", PLL1CTRL0, 18);
-	clks[enet_out] = clk_gate("enet_out", "pll2", ENET, 18, 0);
+	clks[enet_out] = clk_gate("enet_out", "pll2", ENET, 18, 0, 0);
 	clks[lcdif_comp] = mxs_clk_lcdif("lcdif_comp", clks[ref_pix],
 			clks[lcdif_div], clks[lcdif]);
 
diff --git a/drivers/clk/tegra/clk-periph.c b/drivers/clk/tegra/clk-periph.c
index 25616c8..be83955 100644
--- a/drivers/clk/tegra/clk-periph.c
+++ b/drivers/clk/tegra/clk-periph.c
@@ -150,7 +150,7 @@ struct clk *_tegra_clk_register_periph(const char *name,
 		gate_offs = 0x10 + ((id >> 3) & 0xc);
 
 	periph->gate = clk_gate_alloc(NULL, NULL, clk_base + gate_offs,
-				      id & 0x1f, 0);
+				      id & 0x1f, 0, 0);
 	if (!periph->gate)
 		goto out_gate;
 
diff --git a/include/linux/clk.h b/include/linux/clk.h
index dd9fab7..fbfdd4f 100644
--- a/include/linux/clk.h
+++ b/include/linux/clk.h
@@ -199,6 +199,8 @@ static inline int clk_set_rate(struct clk *clk, unsigned long rate)
 
 #define CLK_SET_RATE_PARENT     (1 << 0) /* propagate rate change up one level */
 
+#define CLK_GATE_INVERTED	(1 << 0)
+
 struct clk_ops {
 	int		(*enable)(struct clk *clk);
 	void		(*disable)(struct clk *clk);
@@ -267,10 +269,11 @@ struct clk *clk_mux(const char *name, void __iomem *reg,
 		unsigned flags);
 
 struct clk *clk_gate_alloc(const char *name, const char *parent,
-		void __iomem *reg, u8 shift, unsigned flags);
+		void __iomem *reg, u8 shift, unsigned flags,
+		u8 clk_gate_flags);
 void clk_gate_free(struct clk *clk_gate);
 struct clk *clk_gate(const char *name, const char *parent, void __iomem *reg,
-		u8 shift, unsigned flags);
+		u8 shift, unsigned flags, u8 clk_gate_flags);
 struct clk *clk_gate_inverted(const char *name, const char *parent, void __iomem *reg,
 		u8 shift, unsigned flags);
 int clk_is_enabled(struct clk *clk);
-- 
1.7.10.4


_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

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

* [PATCH 06/11] clk: gate: unify enable and disable functions handling
  2014-04-27  9:30 [PATCH 00/11] ARM: add initial support for Rockchip boards Beniamino Galvani
                   ` (4 preceding siblings ...)
  2014-04-27  9:30 ` [PATCH 05/11] clk: gate: add flags argument to clock gate constructor Beniamino Galvani
@ 2014-04-27  9:30 ` Beniamino Galvani
  2014-04-27  9:30 ` [PATCH 07/11] clk: gate: add CLK_GATE_HIWORD_MASK flag Beniamino Galvani
                   ` (5 subsequent siblings)
  11 siblings, 0 replies; 18+ messages in thread
From: Beniamino Galvani @ 2014-04-27  9:30 UTC (permalink / raw)
  To: barebox

To avoid code duplication and make easier to introduce new flags.

Signed-off-by: Beniamino Galvani <b.galvani@gmail.com>
---
 drivers/clk/clk-gate.c |   33 +++++++++++++++------------------
 1 file changed, 15 insertions(+), 18 deletions(-)

diff --git a/drivers/clk/clk-gate.c b/drivers/clk/clk-gate.c
index 11c749a..54489c4 100644
--- a/drivers/clk/clk-gate.c
+++ b/drivers/clk/clk-gate.c
@@ -30,36 +30,33 @@ struct clk_gate {
 
 #define to_clk_gate(_clk) container_of(_clk, struct clk_gate, clk)
 
-static int clk_gate_enable(struct clk *clk)
+static void clk_gate_endisable(struct clk *clk, int enable)
 {
-	struct clk_gate *g = container_of(clk, struct clk_gate, clk);
+	struct clk_gate *gate = container_of(clk, struct clk_gate, clk);
+	int set = gate->flags & CLK_GATE_INVERTED ? 1 : 0;
 	u32 val;
 
-	val = readl(g->reg);
+	set ^= enable;
+	val = readl(gate->reg);
 
-	if (g->flags & CLK_GATE_INVERTED)
-		val &= ~(1 << g->shift);
+	if (set)
+		val |= BIT(gate->shift);
 	else
-		val |= 1 << g->shift;
+		val &= ~BIT(gate->shift);
 
-	writel(val, g->reg);
+	writel(val, gate->reg);
+}
+
+static int clk_gate_enable(struct clk *clk)
+{
+	clk_gate_endisable(clk, 1);
 
 	return 0;
 }
 
 static void clk_gate_disable(struct clk *clk)
 {
-	struct clk_gate *g = container_of(clk, struct clk_gate, clk);
-	u32 val;
-
-	val = readl(g->reg);
-
-	if (g->flags & CLK_GATE_INVERTED)
-		val |= 1 << g->shift;
-	else
-		val &= ~(1 << g->shift);
-
-	writel(val, g->reg);
+	clk_gate_endisable(clk, 0);
 }
 
 static int clk_gate_is_enabled(struct clk *clk)
-- 
1.7.10.4


_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

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

* [PATCH 07/11] clk: gate: add CLK_GATE_HIWORD_MASK flag
  2014-04-27  9:30 [PATCH 00/11] ARM: add initial support for Rockchip boards Beniamino Galvani
                   ` (5 preceding siblings ...)
  2014-04-27  9:30 ` [PATCH 06/11] clk: gate: unify enable and disable functions handling Beniamino Galvani
@ 2014-04-27  9:30 ` Beniamino Galvani
  2014-04-27  9:30 ` [PATCH 08/11] clk: add rockchip clock gate driver Beniamino Galvani
                   ` (4 subsequent siblings)
  11 siblings, 0 replies; 18+ messages in thread
From: Beniamino Galvani @ 2014-04-27  9:30 UTC (permalink / raw)
  To: barebox

Clock gates having the CLK_GATE_HIWORD_MASK flag set use the upper 16
bits of the register as a "write enable" mask for the value in the
lower 16 bits.

Signed-off-by: Beniamino Galvani <b.galvani@gmail.com>
---
 drivers/clk/clk-gate.c |   17 ++++++++++++-----
 include/linux/clk.h    |    1 +
 2 files changed, 13 insertions(+), 5 deletions(-)

diff --git a/drivers/clk/clk-gate.c b/drivers/clk/clk-gate.c
index 54489c4..85eba3d 100644
--- a/drivers/clk/clk-gate.c
+++ b/drivers/clk/clk-gate.c
@@ -37,12 +37,19 @@ static void clk_gate_endisable(struct clk *clk, int enable)
 	u32 val;
 
 	set ^= enable;
-	val = readl(gate->reg);
 
-	if (set)
-		val |= BIT(gate->shift);
-	else
-		val &= ~BIT(gate->shift);
+	if (gate->flags & CLK_GATE_HIWORD_MASK) {
+		val = BIT(gate->shift + 16);
+		if (set)
+			val |= BIT(gate->shift);
+	} else {
+		val = readl(gate->reg);
+
+		if (set)
+			val |= BIT(gate->shift);
+		else
+			val &= ~BIT(gate->shift);
+	}
 
 	writel(val, gate->reg);
 }
diff --git a/include/linux/clk.h b/include/linux/clk.h
index fbfdd4f..49cb5a2 100644
--- a/include/linux/clk.h
+++ b/include/linux/clk.h
@@ -200,6 +200,7 @@ static inline int clk_set_rate(struct clk *clk, unsigned long rate)
 #define CLK_SET_RATE_PARENT     (1 << 0) /* propagate rate change up one level */
 
 #define CLK_GATE_INVERTED	(1 << 0)
+#define CLK_GATE_HIWORD_MASK	(1 << 1)
 
 struct clk_ops {
 	int		(*enable)(struct clk *clk);
-- 
1.7.10.4


_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

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

* [PATCH 08/11] clk: add rockchip clock gate driver
  2014-04-27  9:30 [PATCH 00/11] ARM: add initial support for Rockchip boards Beniamino Galvani
                   ` (6 preceding siblings ...)
  2014-04-27  9:30 ` [PATCH 07/11] clk: gate: add CLK_GATE_HIWORD_MASK flag Beniamino Galvani
@ 2014-04-27  9:30 ` Beniamino Galvani
  2014-04-27  9:30 ` [PATCH 09/11] pinctrl: add rockchip pinctrl and gpio drivers Beniamino Galvani
                   ` (3 subsequent siblings)
  11 siblings, 0 replies; 18+ messages in thread
From: Beniamino Galvani @ 2014-04-27  9:30 UTC (permalink / raw)
  To: barebox


Signed-off-by: Beniamino Galvani <b.galvani@gmail.com>
---
 arch/arm/Kconfig                    |    3 ++
 drivers/clk/Makefile                |    1 +
 drivers/clk/rockchip/Makefile       |    1 +
 drivers/clk/rockchip/clk-rockchip.c |   86 +++++++++++++++++++++++++++++++++++
 4 files changed, 91 insertions(+)
 create mode 100644 drivers/clk/rockchip/Makefile
 create mode 100644 drivers/clk/rockchip/clk-rockchip.c

diff --git a/arch/arm/Kconfig b/arch/arm/Kconfig
index a7db86c..580faa0 100644
--- a/arch/arm/Kconfig
+++ b/arch/arm/Kconfig
@@ -129,6 +129,9 @@ config ARCH_ROCKCHIP
 	bool "Rockchip RX3xxx"
 	select CPU_V7
 	select ARM_SMP_TWD
+	select COMMON_CLK
+	select CLKDEV_LOOKUP
+	select COMMON_CLK_OF_PROVIDER
 
 config ARCH_SOCFPGA
 	bool "Altera SOCFPGA cyclone5"
diff --git a/drivers/clk/Makefile b/drivers/clk/Makefile
index 0687b3c..fa707dd 100644
--- a/drivers/clk/Makefile
+++ b/drivers/clk/Makefile
@@ -4,6 +4,7 @@ obj-$(CONFIG_CLKDEV_LOOKUP)	+= clkdev.o
 
 obj-$(CONFIG_ARCH_MVEBU)	+= mvebu/
 obj-$(CONFIG_ARCH_MXS)		+= mxs/
+obj-$(CONFIG_ARCH_ROCKCHIP)	+= rockchip/
 obj-$(CONFIG_ARCH_TEGRA)	+= tegra/
 obj-$(CONFIG_CLK_SOCFPGA)	+= socfpga.o
 obj-$(CONFIG_MACH_MIPS_ATH79)	+= clk-ar933x.o
diff --git a/drivers/clk/rockchip/Makefile b/drivers/clk/rockchip/Makefile
new file mode 100644
index 0000000..1c5271f
--- /dev/null
+++ b/drivers/clk/rockchip/Makefile
@@ -0,0 +1 @@
+obj-y += clk-rockchip.o
\ No newline at end of file
diff --git a/drivers/clk/rockchip/clk-rockchip.c b/drivers/clk/rockchip/clk-rockchip.c
new file mode 100644
index 0000000..99f836c
--- /dev/null
+++ b/drivers/clk/rockchip/clk-rockchip.c
@@ -0,0 +1,86 @@
+/*
+ * Clock gate driver for Rockchip SoCs
+ *
+ * Based on Linux driver:
+ *   Copyright (c) 2013 MundoReader S.L.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ */
+
+#include <common.h>
+#include <init.h>
+#include <driver.h>
+#include <linux/clk.h>
+#include <linux/clkdev.h>
+#include <of_address.h>
+#include <malloc.h>
+
+static void __init rk2928_gate_clk_init(struct device_node *node)
+{
+	struct clk_onecell_data *clk_data;
+	const char *clk_parent;
+	const char *clk_name;
+	void __iomem *reg;
+	void __iomem *reg_idx;
+	int flags;
+	int qty;
+	int reg_bit;
+	int clkflags = CLK_SET_RATE_PARENT;
+	int i;
+
+	qty = of_property_count_strings(node, "clock-output-names");
+	if (qty < 0) {
+		pr_err("%s: error in clock-output-names %d\n", __func__, qty);
+		return;
+	}
+
+	if (qty == 0) {
+		pr_info("%s: nothing to do\n", __func__);
+		return;
+	}
+
+	reg = of_iomap(node, 0);
+
+	clk_data = kzalloc(sizeof(struct clk_onecell_data), GFP_KERNEL);
+	if (!clk_data)
+		return;
+
+	clk_data->clks = kzalloc(qty * sizeof(struct clk *), GFP_KERNEL);
+	if (!clk_data->clks) {
+		kfree(clk_data);
+		return;
+	}
+
+	flags = CLK_GATE_HIWORD_MASK | CLK_GATE_INVERTED;
+
+	for (i = 0; i < qty; i++) {
+		of_property_read_string_index(node, "clock-output-names",
+					      i, &clk_name);
+
+		/* ignore empty slots */
+		if (!strcmp("reserved", clk_name))
+			continue;
+
+		clk_parent = of_clk_get_parent_name(node, i);
+
+		reg_idx = reg + 4 * (i / 16);
+		reg_bit = i % 16;
+
+		clk_data->clks[i] = clk_gate(clk_name, clk_parent, reg_idx,
+					     reg_bit, clkflags, flags);
+		WARN_ON(IS_ERR(clk_data->clks[i]));
+	}
+
+	clk_data->clk_num = qty;
+
+	of_clk_add_provider(node, of_clk_src_onecell_get, clk_data);
+}
+CLK_OF_DECLARE(rk2928_gate, "rockchip,rk2928-gate-clk", rk2928_gate_clk_init);
-- 
1.7.10.4


_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

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

* [PATCH 09/11] pinctrl: add rockchip pinctrl and gpio drivers
  2014-04-27  9:30 [PATCH 00/11] ARM: add initial support for Rockchip boards Beniamino Galvani
                   ` (7 preceding siblings ...)
  2014-04-27  9:30 ` [PATCH 08/11] clk: add rockchip clock gate driver Beniamino Galvani
@ 2014-04-27  9:30 ` Beniamino Galvani
  2014-04-27  9:30 ` [PATCH 10/11] ARM: dts: add Rockchip devicetree files Beniamino Galvani
                   ` (2 subsequent siblings)
  11 siblings, 0 replies; 18+ messages in thread
From: Beniamino Galvani @ 2014-04-27  9:30 UTC (permalink / raw)
  To: barebox


Signed-off-by: Beniamino Galvani <b.galvani@gmail.com>
---
 arch/arm/Kconfig                   |    2 +
 drivers/pinctrl/Kconfig            |    7 +
 drivers/pinctrl/Makefile           |    1 +
 drivers/pinctrl/pinctrl-rockchip.c |  560 ++++++++++++++++++++++++++++++++++++
 4 files changed, 570 insertions(+)
 create mode 100644 drivers/pinctrl/pinctrl-rockchip.c

diff --git a/arch/arm/Kconfig b/arch/arm/Kconfig
index 580faa0..991a411 100644
--- a/arch/arm/Kconfig
+++ b/arch/arm/Kconfig
@@ -132,6 +132,8 @@ config ARCH_ROCKCHIP
 	select COMMON_CLK
 	select CLKDEV_LOOKUP
 	select COMMON_CLK_OF_PROVIDER
+	select GPIOLIB
+	select PINCTRL_ROCKCHIP
 
 config ARCH_SOCFPGA
 	bool "Altera SOCFPGA cyclone5"
diff --git a/drivers/pinctrl/Kconfig b/drivers/pinctrl/Kconfig
index 18adbf7..b9b66f9 100644
--- a/drivers/pinctrl/Kconfig
+++ b/drivers/pinctrl/Kconfig
@@ -24,6 +24,13 @@ config PINCTRL_IMX_IOMUX_V3
 	help
 	  This iomux controller is found on i.MX25,35,51,53,6.
 
+config PINCTRL_ROCKCHIP
+	select PINCTRL
+	select GPIO_GENERIC
+	bool
+	help
+	  The pinmux controller found on Rockchip SoCs.
+
 config PINCTRL_SINGLE
 	select PINCTRL
 	bool "pinctrl single"
diff --git a/drivers/pinctrl/Makefile b/drivers/pinctrl/Makefile
index af705ea..3978c56 100644
--- a/drivers/pinctrl/Makefile
+++ b/drivers/pinctrl/Makefile
@@ -2,6 +2,7 @@ obj-$(CONFIG_PINCTRL)	+= pinctrl.o
 obj-$(CONFIG_PINCTRL_IMX_IOMUX_V1) += imx-iomux-v1.o
 obj-$(CONFIG_PINCTRL_IMX_IOMUX_V2) += imx-iomux-v2.o
 obj-$(CONFIG_PINCTRL_IMX_IOMUX_V3) += imx-iomux-v3.o
+obj-$(CONFIG_PINCTRL_ROCKCHIP) += pinctrl-rockchip.o
 obj-$(CONFIG_PINCTRL_SINGLE) += pinctrl-single.o
 obj-$(CONFIG_PINCTRL_TEGRA20) += pinctrl-tegra20.o
 obj-$(CONFIG_PINCTRL_TEGRA30) += pinctrl-tegra30.o
diff --git a/drivers/pinctrl/pinctrl-rockchip.c b/drivers/pinctrl/pinctrl-rockchip.c
new file mode 100644
index 0000000..a71fed3
--- /dev/null
+++ b/drivers/pinctrl/pinctrl-rockchip.c
@@ -0,0 +1,560 @@
+/*
+ * Rockchip pinctrl and gpio driver for Barebox
+ *
+ * Copyright (C) 2014 Beniamino Galvani <b.galvani@gmail.com>
+ *
+ * Based on Linux pinctrl-rockchip:
+ *   Copyright (C) 2013 MundoReader S.L.
+ *   Copyright (C) 2012 Samsung Electronics Co., Ltd.
+ *   Copyright (C) 2012 Linaro Ltd
+ *   Copyright (C) 2011-2012 Jean-Christophe PLAGNIOL-VILLARD
+ *
+ * This program is free software; you can redistribute it and/or
+ * modify it under the terms of the GNU General Public License
+ * version 2 as published by the Free Software Foundation.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ */
+
+#include <common.h>
+#include <gpio.h>
+#include <init.h>
+#include <malloc.h>
+#include <of.h>
+#include <of_address.h>
+#include <pinctrl.h>
+
+#include <linux/basic_mmio_gpio.h>
+#include <linux/clk.h>
+#include <linux/err.h>
+
+enum rockchip_pinctrl_type {
+	RK2928,
+	RK3066B,
+	RK3188,
+};
+
+enum rockchip_pin_bank_type {
+	COMMON_BANK,
+	RK3188_BANK0,
+};
+
+struct rockchip_pin_bank {
+	void __iomem			*reg_base;
+	void __iomem			*reg_pull;
+	struct clk			*clk;
+	u32				pin_base;
+	u8				nr_pins;
+	char				*name;
+	u8				bank_num;
+	enum rockchip_pin_bank_type	bank_type;
+	bool				valid;
+	struct device_node		*of_node;
+	struct rockchip_pinctrl		*drvdata;
+	struct bgpio_chip		bgpio_chip;
+};
+
+#define PIN_BANK(id, pins, label)			\
+	{						\
+		.bank_num	= id,			\
+		.nr_pins	= pins,			\
+		.name		= label,		\
+	}
+
+struct rockchip_pin_ctrl {
+	struct rockchip_pin_bank	*pin_banks;
+	u32				nr_banks;
+	u32				nr_pins;
+	char				*label;
+	enum rockchip_pinctrl_type	type;
+	int				mux_offset;
+	void	(*pull_calc_reg)(struct rockchip_pin_bank *bank, int pin_num,
+				 void __iomem **reg, u8 *bit);
+};
+
+struct rockchip_pinctrl {
+	void __iomem			*reg_base;
+	void __iomem			*reg_pull;
+	struct pinctrl_device		pctl_dev;
+	struct rockchip_pin_ctrl	*ctrl;
+};
+
+enum {
+	RK_BIAS_DISABLE = 0,
+	RK_BIAS_PULL_UP,
+	RK_BIAS_PULL_DOWN,
+	RK_BIAS_BUS_HOLD,
+};
+
+/* GPIO registers */
+enum {
+	RK_GPIO_SWPORT_DR	= 0x00,
+	RK_GPIO_SWPORT_DDR	= 0x04,
+	RK_GPIO_EXT_PORT	= 0x50,
+};
+
+static int rockchip_gpiolib_register(struct device_d *dev,
+				     struct rockchip_pinctrl *info)
+{
+	struct rockchip_pin_ctrl *ctrl = info->ctrl;
+	struct rockchip_pin_bank *bank = ctrl->pin_banks;
+	void __iomem *reg_base;
+	int ret;
+	int i;
+
+	for (i = 0; i < ctrl->nr_banks; ++i, ++bank) {
+		if (!bank->valid) {
+			dev_warn(dev, "bank %s is not valid\n", bank->name);
+			continue;
+		}
+
+		reg_base = bank->reg_base;
+
+		ret = bgpio_init(&bank->bgpio_chip, dev, 4,
+				 reg_base + RK_GPIO_EXT_PORT,
+				 reg_base + RK_GPIO_SWPORT_DR, NULL,
+				 reg_base + RK_GPIO_SWPORT_DDR, NULL, 0);
+		if (ret)
+			goto fail;
+
+		bank->bgpio_chip.gc.ngpio = bank->nr_pins;
+		ret = gpiochip_add(&bank->bgpio_chip.gc);
+		if (ret) {
+			dev_err(dev, "failed to register gpio_chip %s, error code: %d\n",
+				bank->name, ret);
+			goto fail;
+		}
+
+	}
+
+	return 0;
+fail:
+	for (--i, --bank; i >= 0; --i, --bank) {
+		if (!bank->valid)
+			continue;
+
+		gpiochip_remove(&bank->bgpio_chip.gc);
+	}
+	return ret;
+}
+
+static struct rockchip_pinctrl *to_rockchip_pinctrl(struct pinctrl_device *pdev)
+{
+	return container_of(pdev, struct rockchip_pinctrl, pctl_dev);
+}
+
+static struct rockchip_pin_bank *bank_num_to_bank(struct rockchip_pinctrl *info,
+						  unsigned num)
+{
+	struct rockchip_pin_bank *b = info->ctrl->pin_banks;
+	int i;
+
+	for (i = 0; i < info->ctrl->nr_banks; i++, b++) {
+		if (b->bank_num == num)
+			return b;
+	}
+
+	return ERR_PTR(-EINVAL);
+}
+
+static int parse_bias_config(struct device_node *np)
+{
+	u32 val;
+
+	if (of_property_read_u32(np, "bias-pull-up", &val) != -EINVAL)
+		return RK_BIAS_PULL_UP;
+	else if (of_property_read_u32(np, "bias-pull-down", &val) != -EINVAL)
+		return RK_BIAS_PULL_DOWN;
+	else if (of_property_read_u32(np, "bias-bus-hold", &val) != -EINVAL)
+		return RK_BIAS_BUS_HOLD;
+	else
+		return RK_BIAS_DISABLE;
+}
+
+
+#define RK2928_PULL_OFFSET		0x118
+#define RK2928_PULL_PINS_PER_REG	16
+#define RK2928_PULL_BANK_STRIDE		8
+
+static void rk2928_calc_pull_reg_and_bit(struct rockchip_pin_bank *bank,
+					 int pin_num, void __iomem **reg,
+					 u8 *bit)
+{
+	struct rockchip_pinctrl *info = bank->drvdata;
+
+	*reg = info->reg_base + RK2928_PULL_OFFSET;
+	*reg += bank->bank_num * RK2928_PULL_BANK_STRIDE;
+	*reg += (pin_num / RK2928_PULL_PINS_PER_REG) * 4;
+
+	*bit = pin_num % RK2928_PULL_PINS_PER_REG;
+};
+
+#define RK3188_PULL_BITS_PER_PIN	2
+#define RK3188_PULL_PINS_PER_REG	8
+#define RK3188_PULL_BANK_STRIDE		16
+
+static void rk3188_calc_pull_reg_and_bit(struct rockchip_pin_bank *bank,
+					 int pin_num, void __iomem **reg,
+					 u8 *bit)
+{
+	struct rockchip_pinctrl *info = bank->drvdata;
+
+	/* The first 12 pins of the first bank are located elsewhere */
+	if (bank->bank_type == RK3188_BANK0 && pin_num < 12) {
+		*reg = bank->reg_pull +
+				((pin_num / RK3188_PULL_PINS_PER_REG) * 4);
+		*bit = pin_num % RK3188_PULL_PINS_PER_REG;
+		*bit *= RK3188_PULL_BITS_PER_PIN;
+	} else {
+		*reg = info->reg_pull - 4;
+		*reg += bank->bank_num * RK3188_PULL_BANK_STRIDE;
+		*reg += ((pin_num / RK3188_PULL_PINS_PER_REG) * 4);
+
+		/*
+		 * The bits in these registers have an inverse ordering
+		 * with the lowest pin being in bits 15:14 and the highest
+		 * pin in bits 1:0
+		 */
+		*bit = 7 - (pin_num % RK3188_PULL_PINS_PER_REG);
+		*bit *= RK3188_PULL_BITS_PER_PIN;
+	}
+}
+
+static int rockchip_pinctrl_set_func(struct rockchip_pin_bank *bank, int pin,
+				     int mux)
+{
+	struct rockchip_pinctrl *info = bank->drvdata;
+	void __iomem *reg = info->reg_base + info->ctrl->mux_offset;
+	u8 bit;
+	u32 data;
+
+	/* get basic quadruple of mux registers and the correct reg inside */
+	reg += bank->bank_num * 0x10;
+	reg += (pin / 8) * 4;
+	bit = (pin % 8) * 2;
+
+	data = 3 << (bit + 16);
+	data |= (mux & 3) << bit;
+	writel(data, reg);
+
+	return 0;
+}
+
+static int rockchip_pinctrl_set_pull(struct rockchip_pin_bank *bank,
+				     int pin_num, int pull)
+{
+	struct rockchip_pinctrl *info = bank->drvdata;
+	struct rockchip_pin_ctrl *ctrl = info->ctrl;
+	void __iomem *reg;
+	u8 bit;
+	u32 data;
+
+	dev_dbg(info->pctl_dev.dev, "setting pull of GPIO%d-%d to %d\n",
+		 bank->bank_num, pin_num, pull);
+
+	/* rk3066b doesn't support any pulls */
+	if (ctrl->type == RK3066B)
+		return pull ? -EINVAL : 0;
+
+	ctrl->pull_calc_reg(bank, pin_num, &reg, &bit);
+
+	switch (ctrl->type) {
+	case RK2928:
+		data = BIT(bit + 16);
+		if (pull == RK_BIAS_DISABLE)
+			data |= BIT(bit);
+		writel(data, reg);
+		break;
+	case RK3188:
+		data = ((1 << RK3188_PULL_BITS_PER_PIN) - 1) << (bit + 16);
+		data |= pull << bit;
+		writel(data, reg);
+		break;
+	default:
+		dev_err(info->pctl_dev.dev, "unsupported pinctrl type\n");
+		return -EINVAL;
+	}
+
+	return 0;
+}
+
+static int rockchip_pinctrl_set_state(struct pinctrl_device *pdev,
+				      struct device_node *np)
+{
+	struct rockchip_pinctrl *info = to_rockchip_pinctrl(pdev);
+	const __be32 *list;
+	int i, size;
+	int bank_num, pin_num, func;
+
+	/*
+	 * the binding format is rockchip,pins = <bank pin mux CONFIG>,
+	 * do sanity check and calculate pins number
+	 */
+	list = of_get_property(np, "rockchip,pins", &size);
+	size /= sizeof(*list);
+
+	if (!size || size % 4) {
+		dev_err(pdev->dev, "wrong pins number or pins and configs should be by 4\n");
+		return -EINVAL;
+	}
+
+	for (i = 0; i < size; i += 4) {
+		const __be32 *phandle;
+		struct device_node *np_config;
+		struct rockchip_pin_bank *bank;
+
+		bank_num = be32_to_cpu(*list++);
+		pin_num = be32_to_cpu(*list++);
+		func = be32_to_cpu(*list++);
+		phandle = list++;
+
+		if (!phandle)
+			return -EINVAL;
+
+		np_config = of_find_node_by_phandle(be32_to_cpup(phandle));
+		bank = bank_num_to_bank(info, bank_num);
+		rockchip_pinctrl_set_func(bank, pin_num, func);
+		rockchip_pinctrl_set_pull(bank, pin_num,
+					  parse_bias_config(np_config));
+	}
+
+	return 0;
+}
+
+static struct pinctrl_ops rockchip_pinctrl_ops = {
+	.set_state = rockchip_pinctrl_set_state,
+};
+
+static int rockchip_get_bank_data(struct rockchip_pin_bank *bank,
+				  struct device_d *dev)
+{
+	struct resource node_res, *res;
+
+	if (of_address_to_resource(bank->of_node, 0, &node_res)) {
+		dev_err(dev, "cannot find IO resource for bank\n");
+		return -ENOENT;
+	}
+
+	res = request_iomem_region(dev_name(dev), node_res.start, node_res.end);
+	if (!res) {
+		dev_err(dev, "cannot request iomem region %08x\n",
+			node_res.start);
+		return -ENOENT;
+	}
+
+	bank->reg_base = (void __iomem *)res->start;
+
+	/*
+	 * special case, where parts of the pull setting-registers are
+	 * part of the PMU register space
+	 */
+	if (of_device_is_compatible(bank->of_node,
+				    "rockchip,rk3188-gpio-bank0")) {
+		bank->bank_type = RK3188_BANK0;
+
+		if (of_address_to_resource(bank->of_node, 1, &node_res)) {
+			dev_err(dev, "cannot find IO resource for bank\n");
+			return -ENOENT;
+		}
+
+		res = request_iomem_region(dev_name(dev), node_res.start,
+					   node_res.end);
+		if (!res) {
+			dev_err(dev, "cannot request iomem region %08x\n",
+				node_res.start);
+			return -ENOENT;
+		}
+
+		bank->reg_pull = (void __iomem *)res->start;
+	} else {
+		bank->bank_type = COMMON_BANK;
+	}
+
+	bank->clk = of_clk_get(bank->of_node, 0);
+	if (IS_ERR(bank->clk))
+		return PTR_ERR(bank->clk);
+
+	return clk_enable(bank->clk);
+}
+
+static struct of_device_id rockchip_pinctrl_dt_match[];
+
+static struct rockchip_pin_ctrl *rockchip_pinctrl_get_soc_data(
+	struct rockchip_pinctrl *d, struct device_d *dev)
+{
+	const struct of_device_id *match;
+	struct device_node *node = dev->device_node;
+	struct device_node *np;
+	struct rockchip_pin_ctrl *ctrl;
+	struct rockchip_pin_bank *bank;
+	char *name;
+	int i;
+
+	match = of_match_node(rockchip_pinctrl_dt_match, node);
+	ctrl = (struct rockchip_pin_ctrl *)match->data;
+
+	for_each_child_of_node(node, np) {
+		if (!of_find_property(np, "gpio-controller", NULL))
+			continue;
+
+		bank = ctrl->pin_banks;
+		for (i = 0; i < ctrl->nr_banks; ++i, ++bank) {
+			name = bank->name;
+			if (!strncmp(name, np->name, strlen(name))) {
+				bank->of_node = np;
+				if (!rockchip_get_bank_data(bank, dev))
+					bank->valid = true;
+
+				break;
+			}
+		}
+	}
+
+	bank = ctrl->pin_banks;
+	for (i = 0; i < ctrl->nr_banks; ++i, ++bank) {
+		bank->drvdata = d;
+		bank->pin_base = ctrl->nr_pins;
+		ctrl->nr_pins += bank->nr_pins;
+	}
+
+	return ctrl;
+}
+
+static int rockchip_pinctrl_probe(struct device_d *dev)
+{
+	struct rockchip_pinctrl *info;
+	struct rockchip_pin_ctrl *ctrl;
+	int ret;
+
+	info = xzalloc(sizeof(struct rockchip_pinctrl));
+	if (!info)
+		return -ENOMEM;
+
+	ctrl = rockchip_pinctrl_get_soc_data(info, dev);
+	if (!ctrl) {
+		dev_err(dev, "driver data not available\n");
+		return -EINVAL;
+	}
+	info->ctrl = ctrl;
+
+	info->reg_base = dev_request_mem_region(dev, 0);
+	if (!info->reg_base) {
+		dev_err(dev, "Could not get reg_base region\n");
+		return -ENODEV;
+	}
+
+	/* The RK3188 has its pull registers in a separate place */
+	if (ctrl->type == RK3188) {
+		info->reg_pull = dev_request_mem_region(dev, 1);
+		if (!info->reg_pull) {
+			dev_err(dev, "Could not get reg_pull region\n");
+			return -ENODEV;
+		}
+	}
+
+	info->pctl_dev.dev = dev;
+	info->pctl_dev.ops = &rockchip_pinctrl_ops;
+
+	ret = rockchip_gpiolib_register(dev, info);
+	if (ret)
+		return ret;
+
+	ret = pinctrl_register(&info->pctl_dev);
+	if (ret)
+		return ret;
+
+	return 0;
+}
+
+static struct rockchip_pin_bank rk2928_pin_banks[] = {
+	PIN_BANK(0, 32, "gpio0"),
+	PIN_BANK(1, 32, "gpio1"),
+	PIN_BANK(2, 32, "gpio2"),
+	PIN_BANK(3, 32, "gpio3"),
+};
+
+static struct rockchip_pin_ctrl rk2928_pin_ctrl = {
+	.pin_banks	= rk2928_pin_banks,
+	.nr_banks	= ARRAY_SIZE(rk2928_pin_banks),
+	.type		= RK2928,
+	.mux_offset	= 0xa8,
+	.pull_calc_reg	= rk2928_calc_pull_reg_and_bit,
+};
+
+static struct rockchip_pin_bank rk3066a_pin_banks[] = {
+	PIN_BANK(0, 32, "gpio0"),
+	PIN_BANK(1, 32, "gpio1"),
+	PIN_BANK(2, 32, "gpio2"),
+	PIN_BANK(3, 32, "gpio3"),
+	PIN_BANK(4, 32, "gpio4"),
+	PIN_BANK(6, 16, "gpio6"),
+};
+
+static struct rockchip_pin_ctrl rk3066a_pin_ctrl = {
+	.pin_banks	= rk3066a_pin_banks,
+	.nr_banks	= ARRAY_SIZE(rk3066a_pin_banks),
+	.type		= RK2928,
+	.mux_offset	= 0xa8,
+	.pull_calc_reg	= rk2928_calc_pull_reg_and_bit,
+};
+
+static struct rockchip_pin_bank rk3066b_pin_banks[] = {
+	PIN_BANK(0, 32, "gpio0"),
+	PIN_BANK(1, 32, "gpio1"),
+	PIN_BANK(2, 32, "gpio2"),
+	PIN_BANK(3, 32, "gpio3"),
+};
+
+static struct rockchip_pin_ctrl rk3066b_pin_ctrl = {
+	.pin_banks	= rk3066b_pin_banks,
+	.nr_banks	= ARRAY_SIZE(rk3066b_pin_banks),
+	.type		= RK3066B,
+	.mux_offset	= 0x60,
+};
+
+static struct rockchip_pin_bank rk3188_pin_banks[] = {
+	PIN_BANK(0, 32, "gpio0"),
+	PIN_BANK(1, 32, "gpio1"),
+	PIN_BANK(2, 32, "gpio2"),
+	PIN_BANK(3, 32, "gpio3"),
+};
+
+static struct rockchip_pin_ctrl rk3188_pin_ctrl = {
+	.pin_banks	= rk3188_pin_banks,
+	.nr_banks	= ARRAY_SIZE(rk3188_pin_banks),
+	.type		= RK3188,
+	.mux_offset	= 0x60,
+	.pull_calc_reg	= rk3188_calc_pull_reg_and_bit,
+};
+
+static struct of_device_id rockchip_pinctrl_dt_match[] = {
+	{
+		.compatible = "rockchip,rk2928-pinctrl",
+		.data = (long)&rk2928_pin_ctrl,
+	},
+	{
+		.compatible = "rockchip,rk3066a-pinctrl",
+		.data = (long)&rk3066a_pin_ctrl,
+	},
+	{
+		.compatible = "rockchip,rk3066b-pinctrl",
+		.data = (long)&rk3066b_pin_ctrl,
+	},
+	{
+		.compatible = "rockchip,rk3188-pinctrl",
+		.data = (long)&rk3188_pin_ctrl,
+	}, {
+		/* sentinel */
+	}
+};
+
+static struct driver_d rockchip_pinctrl_driver = {
+	.name = "rockchip-pinctrl",
+	.probe = rockchip_pinctrl_probe,
+	.of_compatible = DRV_OF_COMPAT(rockchip_pinctrl_dt_match),
+};
+
+console_platform_driver(rockchip_pinctrl_driver);
-- 
1.7.10.4


_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

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

* [PATCH 10/11] ARM: dts: add Rockchip devicetree files
  2014-04-27  9:30 [PATCH 00/11] ARM: add initial support for Rockchip boards Beniamino Galvani
                   ` (8 preceding siblings ...)
  2014-04-27  9:30 ` [PATCH 09/11] pinctrl: add rockchip pinctrl and gpio drivers Beniamino Galvani
@ 2014-04-27  9:30 ` Beniamino Galvani
  2014-04-27  9:30 ` [PATCH 11/11] ARM: rockchip: add radxa-rock board Beniamino Galvani
  2014-04-28  7:26 ` [PATCH 00/11] ARM: add initial support for Rockchip boards Sascha Hauer
  11 siblings, 0 replies; 18+ messages in thread
From: Beniamino Galvani @ 2014-04-27  9:30 UTC (permalink / raw)
  To: barebox


Signed-off-by: Beniamino Galvani <b.galvani@gmail.com>
---
 arch/arm/dts/rk3188-clocks.dtsi        |  289 +++++++++++++++++++++++++++++++
 arch/arm/dts/rk3188-radxarock.dts      |   32 ++++
 arch/arm/dts/rk3188.dtsi               |  298 ++++++++++++++++++++++++++++++++
 arch/arm/dts/rk3xxx.dtsi               |  134 ++++++++++++++
 include/dt-bindings/pinctrl/rockchip.h |   32 ++++
 5 files changed, 785 insertions(+)
 create mode 100644 arch/arm/dts/rk3188-clocks.dtsi
 create mode 100644 arch/arm/dts/rk3188-radxarock.dts
 create mode 100644 arch/arm/dts/rk3188.dtsi
 create mode 100644 arch/arm/dts/rk3xxx.dtsi
 create mode 100644 include/dt-bindings/pinctrl/rockchip.h

diff --git a/arch/arm/dts/rk3188-clocks.dtsi b/arch/arm/dts/rk3188-clocks.dtsi
new file mode 100644
index 0000000..b1b92dc
--- /dev/null
+++ b/arch/arm/dts/rk3188-clocks.dtsi
@@ -0,0 +1,289 @@
+/*
+ * Copyright (c) 2013 MundoReader S.L.
+ * Author: Heiko Stuebner <heiko@sntech.de>
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ */
+
+/ {
+	clocks {
+		#address-cells = <1>;
+		#size-cells = <1>;
+		ranges;
+
+		/*
+		 * This is a dummy clock, to be used as placeholder on
+		 * other mux clocks when a specific parent clock is not
+		 * yet implemented. It should be dropped when the driver
+		 * is complete.
+		 */
+		dummy: dummy {
+			compatible = "fixed-clock";
+			clock-frequency = <0>;
+			#clock-cells = <0>;
+		};
+
+		xin24m: xin24m {
+			compatible = "fixed-clock";
+			clock-frequency = <24000000>;
+			#clock-cells = <0>;
+		};
+
+		dummy48m: dummy48m {
+			compatible = "fixed-clock";
+			clock-frequency = <48000000>;
+			#clock-cells = <0>;
+		};
+
+		dummy150m: dummy150m {
+			compatible = "fixed-clock";
+			clock-frequency = <150000000>;
+			#clock-cells = <0>;
+		};
+
+		clk_gates0: gate-clk@200000d0 {
+			compatible = "rockchip,rk2928-gate-clk";
+			reg = <0x200000d0 0x4>;
+			clocks = <&dummy150m>, <&dummy>,
+				 <&dummy>, <&dummy>,
+				 <&dummy>, <&dummy>,
+				 <&dummy>, <&dummy>,
+				 <&dummy>, <&dummy>,
+				 <&dummy>, <&dummy>,
+				 <&dummy>, <&dummy>,
+				 <&dummy>, <&dummy>;
+
+			clock-output-names =
+				"gate_core_periph", "gate_cpu_gpll",
+				"gate_ddrphy", "gate_aclk_cpu",
+				"gate_hclk_cpu", "gate_pclk_cpu",
+				"gate_atclk_cpu", "gate_aclk_core",
+				"reserved", "gate_i2s0",
+				"gate_i2s0_frac", "reserved",
+				"reserved", "gate_spdif",
+				"gate_spdif_frac", "gate_testclk";
+
+			#clock-cells = <1>;
+		};
+
+		clk_gates1: gate-clk@200000d4 {
+			compatible = "rockchip,rk2928-gate-clk";
+			reg = <0x200000d4 0x4>;
+			clocks = <&xin24m>, <&xin24m>,
+				 <&xin24m>, <&dummy>,
+				 <&dummy>, <&xin24m>,
+				 <&xin24m>, <&dummy>,
+				 <&xin24m>, <&dummy>,
+				 <&xin24m>, <&dummy>,
+				 <&xin24m>, <&dummy>,
+				 <&xin24m>, <&dummy>;
+
+			clock-output-names =
+				"gate_timer0", "gate_timer1",
+				"gate_timer3", "gate_jtag",
+				"gate_aclk_lcdc1_src", "gate_otgphy0",
+				"gate_otgphy1", "gate_ddr_gpll",
+				"gate_uart0", "gate_frac_uart0",
+				"gate_uart1", "gate_frac_uart1",
+				"gate_uart2", "gate_frac_uart2",
+				"gate_uart3", "gate_frac_uart3";
+
+			#clock-cells = <1>;
+		};
+
+		clk_gates2: gate-clk@200000d8 {
+			compatible = "rockchip,rk2928-gate-clk";
+			reg = <0x200000d8 0x4>;
+			clocks = <&clk_gates2 1>, <&dummy>,
+				 <&dummy>, <&dummy>,
+				 <&dummy>, <&dummy>,
+				 <&clk_gates2 3>, <&dummy>,
+				 <&dummy>, <&dummy>,
+				 <&dummy>, <&dummy48m>,
+				 <&dummy>, <&dummy48m>,
+				 <&dummy>, <&dummy>;
+
+			clock-output-names =
+				"gate_periph_src", "gate_aclk_periph",
+				"gate_hclk_periph", "gate_pclk_periph",
+				"gate_smc", "gate_mac",
+				"gate_hsadc", "gate_hsadc_frac",
+				"gate_saradc", "gate_spi0",
+				"gate_spi1", "gate_mmc0",
+				"gate_mac_lbtest", "gate_mmc1",
+				"gate_emmc", "reserved";
+
+			#clock-cells = <1>;
+		};
+
+		clk_gates3: gate-clk@200000dc {
+			compatible = "rockchip,rk2928-gate-clk";
+			reg = <0x200000dc 0x4>;
+			clocks = <&dummy>, <&dummy>,
+				 <&dummy>, <&dummy>,
+				 <&xin24m>, <&xin24m>,
+				 <&dummy>, <&dummy>,
+				 <&xin24m>, <&dummy>,
+				 <&dummy>, <&dummy>,
+				 <&dummy>, <&dummy>,
+				 <&xin24m>, <&dummy>;
+
+			clock-output-names =
+				"gate_aclk_lcdc0_src", "gate_dclk_lcdc0",
+				"gate_dclk_lcdc1", "gate_pclkin_cif0",
+				"gate_timer2", "gate_timer4",
+				"gate_hsicphy", "gate_cif0_out",
+				"gate_timer5", "gate_aclk_vepu",
+				"gate_hclk_vepu", "gate_aclk_vdpu",
+				"gate_hclk_vdpu", "reserved",
+				"gate_timer6", "gate_aclk_gpu_src";
+
+			#clock-cells = <1>;
+		};
+
+		clk_gates4: gate-clk@200000e0 {
+			compatible = "rockchip,rk2928-gate-clk";
+			reg = <0x200000e0 0x4>;
+			clocks = <&clk_gates2 2>, <&clk_gates2 3>,
+				 <&clk_gates2 1>, <&clk_gates2 1>,
+				 <&clk_gates2 1>, <&clk_gates2 2>,
+				 <&clk_gates2 2>, <&clk_gates2 2>,
+				 <&clk_gates0 4>, <&clk_gates0 4>,
+				 <&clk_gates0 3>, <&dummy>,
+				 <&clk_gates0 3>, <&dummy>,
+				 <&dummy>, <&dummy>;
+
+			clock-output-names =
+				"gate_hclk_peri_axi_matrix", "gate_pclk_peri_axi_matrix",
+				"gate_aclk_cpu_peri", "gate_aclk_peri_axi_matrix",
+				"gate_aclk_pei_niu", "gate_hclk_usb_peri",
+				"gate_hclk_peri_ahb_arbi", "gate_hclk_emem_peri",
+				"gate_hclk_cpubus", "gate_hclk_ahb2apb",
+				"gate_aclk_strc_sys", "reserved",
+				"gate_aclk_intmem", "reserved",
+				"gate_hclk_imem1", "gate_hclk_imem0";
+
+			#clock-cells = <1>;
+		};
+
+		clk_gates5: gate-clk@200000e4 {
+			compatible = "rockchip,rk2928-gate-clk";
+			reg = <0x200000e4 0x4>;
+			clocks = <&clk_gates0 3>, <&clk_gates2 1>,
+				 <&clk_gates0 5>, <&clk_gates0 5>,
+				 <&clk_gates0 5>, <&clk_gates0 5>,
+				 <&clk_gates0 4>, <&clk_gates0 5>,
+				 <&clk_gates2 1>, <&clk_gates2 2>,
+				 <&clk_gates2 2>, <&clk_gates2 2>,
+				 <&clk_gates2 2>, <&clk_gates4 5>;
+
+			clock-output-names =
+				"gate_aclk_dmac1", "gate_aclk_dmac2",
+				"gate_pclk_efuse", "gate_pclk_tzpc",
+				"gate_pclk_grf", "gate_pclk_pmu",
+				"gate_hclk_rom", "gate_pclk_ddrupctl",
+				"gate_aclk_smc", "gate_hclk_nandc",
+				"gate_hclk_mmc0", "gate_hclk_mmc1",
+				"gate_hclk_emmc", "gate_hclk_otg0";
+
+			#clock-cells = <1>;
+		};
+
+		clk_gates6: gate-clk@200000e8 {
+			compatible = "rockchip,rk2928-gate-clk";
+			reg = <0x200000e8 0x4>;
+			clocks = <&clk_gates3 0>, <&clk_gates0 4>,
+				 <&clk_gates0 4>, <&clk_gates1 4>,
+				 <&clk_gates0 4>, <&clk_gates3 0>,
+				 <&dummy>, <&dummy>,
+				 <&clk_gates3 0>, <&clk_gates0 4>,
+				 <&clk_gates0 4>, <&clk_gates1 4>,
+				 <&clk_gates0 4>, <&clk_gates3 0>;
+
+			clock-output-names =
+				"gate_aclk_lcdc0", "gate_hclk_lcdc0",
+				"gate_hclk_lcdc1", "gate_aclk_lcdc1",
+				"gate_hclk_cif0", "gate_aclk_cif0",
+				"reserved", "reserved",
+				"gate_aclk_ipp", "gate_hclk_ipp",
+				"gate_hclk_rga", "gate_aclk_rga",
+				"gate_hclk_vio_bus", "gate_aclk_vio0";
+
+			#clock-cells = <1>;
+		};
+
+		clk_gates7: gate-clk@200000ec {
+			compatible = "rockchip,rk2928-gate-clk";
+			reg = <0x200000ec 0x4>;
+			clocks = <&clk_gates2 2>, <&clk_gates0 4>,
+				 <&clk_gates0 4>, <&dummy>,
+				 <&dummy>, <&clk_gates2 2>,
+				 <&clk_gates2 2>, <&clk_gates0 5>,
+				 <&dummy>, <&clk_gates0 5>,
+				 <&clk_gates0 5>, <&clk_gates2 3>,
+				 <&clk_gates2 3>, <&clk_gates2 3>,
+				 <&clk_gates2 3>, <&clk_gates2 3>;
+
+			clock-output-names =
+				"gate_hclk_emac", "gate_hclk_spdif",
+				"gate_hclk_i2s0_2ch", "gate_hclk_otg1",
+				"gate_hclk_hsic", "gate_hclk_hsadc",
+				"gate_hclk_pidf", "gate_pclk_timer0",
+				"reserved", "gate_pclk_timer2",
+				"gate_pclk_pwm01", "gate_pclk_pwm23",
+				"gate_pclk_spi0", "gate_pclk_spi1",
+				"gate_pclk_saradc", "gate_pclk_wdt";
+
+			#clock-cells = <1>;
+		};
+
+		clk_gates8: gate-clk@200000f0 {
+			compatible = "rockchip,rk2928-gate-clk";
+			reg = <0x200000f0 0x4>;
+			clocks = <&clk_gates0 5>, <&clk_gates0 5>,
+				 <&clk_gates2 3>, <&clk_gates2 3>,
+				 <&clk_gates0 5>, <&clk_gates0 5>,
+				 <&clk_gates2 3>, <&clk_gates2 3>,
+				 <&clk_gates2 3>, <&clk_gates0 5>,
+				 <&clk_gates0 5>, <&clk_gates0 5>,
+				 <&clk_gates2 3>, <&dummy>;
+
+			clock-output-names =
+				"gate_pclk_uart0", "gate_pclk_uart1",
+				"gate_pclk_uart2", "gate_pclk_uart3",
+				"gate_pclk_i2c0", "gate_pclk_i2c1",
+				"gate_pclk_i2c2", "gate_pclk_i2c3",
+				"gate_pclk_i2c4", "gate_pclk_gpio0",
+				"gate_pclk_gpio1", "gate_pclk_gpio2",
+				"gate_pclk_gpio3", "gate_aclk_gps";
+
+			#clock-cells = <1>;
+		};
+
+		clk_gates9: gate-clk@200000f4 {
+			compatible = "rockchip,rk2928-gate-clk";
+			reg = <0x200000f4 0x4>;
+			clocks = <&dummy>, <&dummy>,
+				 <&dummy>, <&dummy>,
+				 <&dummy>, <&dummy>,
+				 <&dummy>, <&dummy>;
+
+			clock-output-names =
+				"gate_clk_core_dbg", "gate_pclk_dbg",
+				"gate_clk_trace", "gate_atclk",
+				"gate_clk_l2c", "gate_aclk_vio1",
+				"gate_pclk_publ", "gate_aclk_gpu";
+
+			#clock-cells = <1>;
+		};
+	};
+
+};
diff --git a/arch/arm/dts/rk3188-radxarock.dts b/arch/arm/dts/rk3188-radxarock.dts
new file mode 100644
index 0000000..be2a302
--- /dev/null
+++ b/arch/arm/dts/rk3188-radxarock.dts
@@ -0,0 +1,32 @@
+/*
+ * Copyright (c) 2013 Heiko Stuebner <heiko@sntech.de>
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ */
+
+/dts-v1/;
+#include "rk3188.dtsi"
+
+/ {
+	model = "Radxa Rock";
+
+	memory {
+		reg = <0x60000000 0x80000000>;
+	};
+
+	soc {
+		uart2: serial@20064000 {
+			pinctrl-names = "default";
+			pinctrl-0 = <&uart2_xfer>;
+			status = "okay";
+		};
+	};
+};
diff --git a/arch/arm/dts/rk3188.dtsi b/arch/arm/dts/rk3188.dtsi
new file mode 100644
index 0000000..838da95
--- /dev/null
+++ b/arch/arm/dts/rk3188.dtsi
@@ -0,0 +1,298 @@
+/*
+ * Copyright (c) 2013 MundoReader S.L.
+ * Author: Heiko Stuebner <heiko@sntech.de>
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ */
+
+#include <dt-bindings/gpio/gpio.h>
+#include <dt-bindings/pinctrl/rockchip.h>
+#include "rk3xxx.dtsi"
+#include "rk3188-clocks.dtsi"
+
+/ {
+	compatible = "rockchip,rk3188";
+
+	cpus {
+		#address-cells = <1>;
+		#size-cells = <0>;
+
+		cpu@0 {
+			device_type = "cpu";
+			compatible = "arm,cortex-a9";
+			next-level-cache = <&L2>;
+			reg = <0x0>;
+		};
+		cpu@1 {
+			device_type = "cpu";
+			compatible = "arm,cortex-a9";
+			next-level-cache = <&L2>;
+			reg = <0x1>;
+		};
+		cpu@2 {
+			device_type = "cpu";
+			compatible = "arm,cortex-a9";
+			next-level-cache = <&L2>;
+			reg = <0x2>;
+		};
+		cpu@3 {
+			device_type = "cpu";
+			compatible = "arm,cortex-a9";
+			next-level-cache = <&L2>;
+			reg = <0x3>;
+		};
+	};
+
+	soc {
+		global-timer@1013c200 {
+			interrupts = <GIC_PPI 11 0xf04>;
+		};
+
+		local-timer@1013c600 {
+			interrupts = <GIC_PPI 13 0xf04>;
+		};
+
+		sram: sram@10080000 {
+			compatible = "mmio-sram";
+			reg = <0x10080000 0x8000>;
+			#address-cells = <1>;
+			#size-cells = <1>;
+			ranges = <0 0x10080000 0x8000>;
+
+			smp-sram@0 {
+				compatible = "rockchip,rk3066-smp-sram";
+				reg = <0x0 0x50>;
+			};
+		};
+
+		ethernet@10204000 {
+			compatible = "snps,arc-emac";
+			reg = <0x10204000 0x100>;
+			interrupts = <GIC_SPI 19 IRQ_TYPE_LEVEL_HIGH>;
+			clock-frequency = <50000000>;
+			max-speed = <100>;
+			phy = <&phy0>;
+			pinctrl-names = "default";
+			pinctrl-0 = <&emac0_pins>;
+
+			#address-cells = <1>;
+			#size-cells = <0>;
+			phy0: ethernet-phy@0 {
+				reg = <0>;
+			};
+		};
+
+		pinctrl@20008000 {
+			compatible = "rockchip,rk3188-pinctrl";
+			reg = <0x20008000 0xa0>,
+			      <0x20008164 0x1a0>;
+			reg-names = "base", "pull";
+			#address-cells = <1>;
+			#size-cells = <1>;
+			ranges;
+
+			gpio0: gpio0@0x2000a000 {
+				compatible = "rockchip,rk3188-gpio-bank0";
+				reg = <0x2000a000 0x100>,
+				      <0x20004064 0x8>;
+				interrupts = <GIC_SPI 54 IRQ_TYPE_LEVEL_HIGH>;
+				clocks = <&clk_gates8 9>;
+
+				gpio-controller;
+				#gpio-cells = <2>;
+
+				interrupt-controller;
+				#interrupt-cells = <2>;
+			};
+
+			gpio1: gpio1@0x2003c000 {
+				compatible = "rockchip,gpio-bank";
+				reg = <0x2003c000 0x100>;
+				interrupts = <GIC_SPI 55 IRQ_TYPE_LEVEL_HIGH>;
+				clocks = <&clk_gates8 10>;
+
+				gpio-controller;
+				#gpio-cells = <2>;
+
+				interrupt-controller;
+				#interrupt-cells = <2>;
+			};
+
+			gpio2: gpio2@2003e000 {
+				compatible = "rockchip,gpio-bank";
+				reg = <0x2003e000 0x100>;
+				interrupts = <GIC_SPI 56 IRQ_TYPE_LEVEL_HIGH>;
+				clocks = <&clk_gates8 11>;
+
+				gpio-controller;
+				#gpio-cells = <2>;
+
+				interrupt-controller;
+				#interrupt-cells = <2>;
+			};
+
+			gpio3: gpio3@20080000 {
+				compatible = "rockchip,gpio-bank";
+				reg = <0x20080000 0x100>;
+				interrupts = <GIC_SPI 57 IRQ_TYPE_LEVEL_HIGH>;
+				clocks = <&clk_gates8 12>;
+
+				gpio-controller;
+				#gpio-cells = <2>;
+
+				interrupt-controller;
+				#interrupt-cells = <2>;
+			};
+
+			pcfg_pull_up: pcfg_pull_up {
+				bias-pull-up;
+			};
+
+			pcfg_pull_down: pcfg_pull_down {
+				bias-pull-down;
+			};
+
+			pcfg_pull_none: pcfg_pull_none {
+				bias-disable;
+			};
+
+			emac0 {
+				emac0_pins: emac0-pins {
+					rockchip,pins = <RK_GPIO3 16 RK_FUNC_2 &pcfg_pull_up>,
+							<RK_GPIO3 17 RK_FUNC_2 &pcfg_pull_up>,
+							<RK_GPIO3 18 RK_FUNC_2 &pcfg_pull_up>,
+							<RK_GPIO3 19 RK_FUNC_2 &pcfg_pull_up>,
+							<RK_GPIO3 20 RK_FUNC_2 &pcfg_pull_up>,
+							<RK_GPIO3 21 RK_FUNC_2 &pcfg_pull_none>,
+							<RK_GPIO3 22 RK_FUNC_2 &pcfg_pull_up>,
+							<RK_GPIO3 23 RK_FUNC_2 &pcfg_pull_up>,
+							<RK_GPIO3 24 RK_FUNC_2 &pcfg_pull_up>,
+							<RK_GPIO3 25 RK_FUNC_2 &pcfg_pull_up>;
+				};
+			};
+
+			uart0 {
+				uart0_xfer: uart0-xfer {
+					rockchip,pins = <RK_GPIO1 0 RK_FUNC_1 &pcfg_pull_none>,
+							<RK_GPIO1 1 RK_FUNC_1 &pcfg_pull_none>;
+				};
+
+				uart0_cts: uart0-cts {
+					rockchip,pins = <RK_GPIO1 2 RK_FUNC_1 &pcfg_pull_none>;
+				};
+
+				uart0_rts: uart0-rts {
+					rockchip,pins = <RK_GPIO1 3 RK_FUNC_1 &pcfg_pull_none>;
+				};
+			};
+
+			uart1 {
+				uart1_xfer: uart1-xfer {
+					rockchip,pins = <RK_GPIO1 4 RK_FUNC_1 &pcfg_pull_none>,
+							<RK_GPIO1 5 RK_FUNC_1 &pcfg_pull_none>;
+				};
+
+				uart1_cts: uart1-cts {
+					rockchip,pins = <RK_GPIO1 6 RK_FUNC_1 &pcfg_pull_none>;
+				};
+
+				uart1_rts: uart1-rts {
+					rockchip,pins = <RK_GPIO1 7 RK_FUNC_1 &pcfg_pull_none>;
+				};
+			};
+
+			uart2 {
+				uart2_xfer: uart2-xfer {
+					rockchip,pins = <RK_GPIO1 8 RK_FUNC_1 &pcfg_pull_none>,
+							<RK_GPIO1 9 RK_FUNC_1 &pcfg_pull_none>;
+				};
+				/* no rts / cts for uart2 */
+			};
+
+			uart3 {
+				uart3_xfer: uart3-xfer {
+					rockchip,pins = <RK_GPIO1 10 RK_FUNC_1 &pcfg_pull_none>,
+							<RK_GPIO1 11 RK_FUNC_1 &pcfg_pull_none>;
+				};
+
+				uart3_cts: uart3-cts {
+					rockchip,pins = <RK_GPIO1 12 RK_FUNC_1 &pcfg_pull_none>;
+				};
+
+				uart3_rts: uart3-rts {
+					rockchip,pins = <RK_GPIO1 13 RK_FUNC_1 &pcfg_pull_none>;
+				};
+			};
+
+			sd0 {
+				sd0_clk: sd0-clk {
+					rockchip,pins = <RK_GPIO3 2 RK_FUNC_1 &pcfg_pull_none>;
+				};
+
+				sd0_cmd: sd0-cmd {
+					rockchip,pins = <RK_GPIO3 3 RK_FUNC_1 &pcfg_pull_none>;
+				};
+
+				sd0_cd: sd0-cd {
+					rockchip,pins = <RK_GPIO3 8 RK_FUNC_1 &pcfg_pull_none>;
+				};
+
+				sd0_wp: sd0-wp {
+					rockchip,pins = <RK_GPIO3 9 RK_FUNC_1 &pcfg_pull_none>;
+				};
+
+				sd0_pwr: sd0-pwr {
+					rockchip,pins = <RK_GPIO3 1 RK_FUNC_1 &pcfg_pull_none>;
+				};
+
+				sd0_bus1: sd0-bus-width1 {
+					rockchip,pins = <RK_GPIO3 4 RK_FUNC_1 &pcfg_pull_none>;
+				};
+
+				sd0_bus4: sd0-bus-width4 {
+					rockchip,pins = <RK_GPIO3 4 RK_FUNC_1 &pcfg_pull_none>,
+							<RK_GPIO3 5 RK_FUNC_1 &pcfg_pull_none>,
+							<RK_GPIO3 6 RK_FUNC_1 &pcfg_pull_none>,
+							<RK_GPIO3 7 RK_FUNC_1 &pcfg_pull_none>;
+				};
+			};
+
+			sd1 {
+				sd1_clk: sd1-clk {
+					rockchip,pins = <RK_GPIO3 21 RK_FUNC_1 &pcfg_pull_none>;
+				};
+
+				sd1_cmd: sd1-cmd {
+					rockchip,pins = <RK_GPIO3 16 RK_FUNC_1 &pcfg_pull_none>;
+				};
+
+				sd1_cd: sd1-cd {
+					rockchip,pins = <RK_GPIO3 22 RK_FUNC_1 &pcfg_pull_none>;
+				};
+
+				sd1_wp: sd1-wp {
+					rockchip,pins = <RK_GPIO3 23 RK_FUNC_1 &pcfg_pull_none>;
+				};
+
+				sd1_bus1: sd1-bus-width1 {
+					rockchip,pins = <RK_GPIO3 17 RK_FUNC_1 &pcfg_pull_none>;
+				};
+
+				sd1_bus4: sd1-bus-width4 {
+					rockchip,pins = <RK_GPIO3 17 RK_FUNC_1 &pcfg_pull_none>,
+							<RK_GPIO3 18 RK_FUNC_1 &pcfg_pull_none>,
+							<RK_GPIO3 19 RK_FUNC_1 &pcfg_pull_none>,
+							<RK_GPIO3 20 RK_FUNC_1 &pcfg_pull_none>;
+				};
+			};
+		};
+	};
+};
diff --git a/arch/arm/dts/rk3xxx.dtsi b/arch/arm/dts/rk3xxx.dtsi
new file mode 100644
index 0000000..26e5a96
--- /dev/null
+++ b/arch/arm/dts/rk3xxx.dtsi
@@ -0,0 +1,134 @@
+/*
+ * Copyright (c) 2013 MundoReader S.L.
+ * Author: Heiko Stuebner <heiko@sntech.de>
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ */
+
+#include <dt-bindings/interrupt-controller/irq.h>
+#include <dt-bindings/interrupt-controller/arm-gic.h>
+#include "skeleton.dtsi"
+
+/ {
+	interrupt-parent = <&gic>;
+
+	soc {
+		#address-cells = <1>;
+		#size-cells = <1>;
+		compatible = "simple-bus";
+		ranges;
+
+		scu@1013c000 {
+			compatible = "arm,cortex-a9-scu";
+			reg = <0x1013c000 0x100>;
+		};
+
+		pmu@20004000 {
+			compatible = "rockchip,rk3066-pmu";
+			reg = <0x20004000 0x100>;
+		};
+
+		gic: interrupt-controller@1013d000 {
+			compatible = "arm,cortex-a9-gic";
+			interrupt-controller;
+			#interrupt-cells = <3>;
+			reg = <0x1013d000 0x1000>,
+			      <0x1013c100 0x0100>;
+		};
+
+		L2: l2-cache-controller@10138000 {
+			compatible = "arm,pl310-cache";
+			reg = <0x10138000 0x1000>;
+			cache-unified;
+			cache-level = <2>;
+		};
+
+		global-timer@1013c200 {
+			compatible = "arm,cortex-a9-global-timer";
+			reg = <0x1013c200 0x20>;
+			interrupts = <GIC_PPI 11 0x304>;
+			clocks = <&dummy150m>;
+		};
+
+		local-timer@1013c600 {
+			compatible = "arm,cortex-a9-twd-timer";
+			reg = <0x1013c600 0x20>;
+			interrupts = <GIC_PPI 13 0x304>;
+			clocks = <&dummy150m>;
+		};
+
+		uart0: serial@10124000 {
+			compatible = "snps,dw-apb-uart";
+			reg = <0x10124000 0x400>;
+			interrupts = <GIC_SPI 34 IRQ_TYPE_LEVEL_HIGH>;
+			reg-shift = <2>;
+			reg-io-width = <1>;
+			clocks = <&clk_gates1 8>;
+			status = "disabled";
+		};
+
+		uart1: serial@10126000 {
+			compatible = "snps,dw-apb-uart";
+			reg = <0x10126000 0x400>;
+			interrupts = <GIC_SPI 35 IRQ_TYPE_LEVEL_HIGH>;
+			reg-shift = <2>;
+			reg-io-width = <1>;
+			clocks = <&clk_gates1 10>;
+			status = "disabled";
+		};
+
+		uart2: serial@20064000 {
+			compatible = "snps,dw-apb-uart";
+			reg = <0x20064000 0x400>;
+			interrupts = <GIC_SPI 36 IRQ_TYPE_LEVEL_HIGH>;
+			reg-shift = <2>;
+			reg-io-width = <1>;
+			clocks = <&clk_gates1 12>;
+			status = "disabled";
+		};
+
+		uart3: serial@20068000 {
+			compatible = "snps,dw-apb-uart";
+			reg = <0x20068000 0x400>;
+			interrupts = <GIC_SPI 37 IRQ_TYPE_LEVEL_HIGH>;
+			reg-shift = <2>;
+			reg-io-width = <1>;
+			clocks = <&clk_gates1 14>;
+			status = "disabled";
+		};
+
+		dwmmc@10214000 {
+			compatible = "rockchip,rk2928-dw-mshc";
+			reg = <0x10214000 0x1000>;
+			interrupts = <GIC_SPI 23 IRQ_TYPE_LEVEL_HIGH>;
+			#address-cells = <1>;
+			#size-cells = <0>;
+
+			clocks = <&clk_gates5 10>, <&clk_gates2 11>;
+			clock-names = "biu", "ciu";
+
+			status = "disabled";
+		};
+
+		dwmmc@10218000 {
+			compatible = "rockchip,rk2928-dw-mshc";
+			reg = <0x10218000 0x1000>;
+			interrupts = <GIC_SPI 24 IRQ_TYPE_LEVEL_HIGH>;
+			#address-cells = <1>;
+			#size-cells = <0>;
+
+			clocks = <&clk_gates5 11>, <&clk_gates2 13>;
+			clock-names = "biu", "ciu";
+
+			status = "disabled";
+		};
+	};
+};
diff --git a/include/dt-bindings/pinctrl/rockchip.h b/include/dt-bindings/pinctrl/rockchip.h
new file mode 100644
index 0000000..cd5788b
--- /dev/null
+++ b/include/dt-bindings/pinctrl/rockchip.h
@@ -0,0 +1,32 @@
+/*
+ * Header providing constants for Rockchip pinctrl bindings.
+ *
+ * Copyright (c) 2013 MundoReader S.L.
+ * Author: Heiko Stuebner <heiko@sntech.de>
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ */
+
+#ifndef __DT_BINDINGS_ROCKCHIP_PINCTRL_H__
+#define __DT_BINDINGS_ROCKCHIP_PINCTRL_H__
+
+#define RK_GPIO0	0
+#define RK_GPIO1	1
+#define RK_GPIO2	2
+#define RK_GPIO3	3
+#define RK_GPIO4	4
+#define RK_GPIO6	6
+
+#define RK_FUNC_GPIO	0
+#define RK_FUNC_1	1
+#define RK_FUNC_2	2
+
+#endif
-- 
1.7.10.4


_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

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

* [PATCH 11/11] ARM: rockchip: add radxa-rock board
  2014-04-27  9:30 [PATCH 00/11] ARM: add initial support for Rockchip boards Beniamino Galvani
                   ` (9 preceding siblings ...)
  2014-04-27  9:30 ` [PATCH 10/11] ARM: dts: add Rockchip devicetree files Beniamino Galvani
@ 2014-04-27  9:30 ` Beniamino Galvani
  2014-04-28  7:26 ` [PATCH 00/11] ARM: add initial support for Rockchip boards Sascha Hauer
  11 siblings, 0 replies; 18+ messages in thread
From: Beniamino Galvani @ 2014-04-27  9:30 UTC (permalink / raw)
  To: barebox


Signed-off-by: Beniamino Galvani <b.galvani@gmail.com>
---
 arch/arm/boards/Makefile                    |    1 +
 arch/arm/boards/radxa-rock/Makefile         |    2 +
 arch/arm/boards/radxa-rock/board.c          |   78 +++++++++++++++++++++++++++
 arch/arm/boards/radxa-rock/env/config-board |    6 +++
 arch/arm/boards/radxa-rock/lowlevel.c       |   23 ++++++++
 arch/arm/configs/radxa-rock_defconfig       |   62 +++++++++++++++++++++
 arch/arm/mach-rockchip/Kconfig              |    8 +++
 7 files changed, 180 insertions(+)
 create mode 100644 arch/arm/boards/radxa-rock/Makefile
 create mode 100644 arch/arm/boards/radxa-rock/board.c
 create mode 100644 arch/arm/boards/radxa-rock/env/config-board
 create mode 100644 arch/arm/boards/radxa-rock/lowlevel.c
 create mode 100644 arch/arm/configs/radxa-rock_defconfig

diff --git a/arch/arm/boards/Makefile b/arch/arm/boards/Makefile
index 0c1497f..06e7f2c 100644
--- a/arch/arm/boards/Makefile
+++ b/arch/arm/boards/Makefile
@@ -74,6 +74,7 @@ obj-$(CONFIG_MACH_PM9263)			+= pm9263/
 obj-$(CONFIG_MACH_PM9G45)			+= pm9g45/
 obj-$(CONFIG_MACH_QIL_A9260)			+= qil-a926x/
 obj-$(CONFIG_MACH_QIL_A9G20)			+= qil-a926x/
+obj-$(CONFIG_MACH_RADXA_ROCK)			+= radxa-rock/
 obj-$(CONFIG_MACH_REALQ7)			+= datamodul-edm-qmx6/
 obj-$(CONFIG_MACH_RPI)				+= raspberry-pi/
 obj-$(CONFIG_MACH_SABRELITE)			+= freescale-mx6-sabrelite/
diff --git a/arch/arm/boards/radxa-rock/Makefile b/arch/arm/boards/radxa-rock/Makefile
new file mode 100644
index 0000000..79c8aec
--- /dev/null
+++ b/arch/arm/boards/radxa-rock/Makefile
@@ -0,0 +1,2 @@
+obj-$(CONFIG_MACH_RADXA_ROCK) += board.o
+lwl-y += lowlevel.o
diff --git a/arch/arm/boards/radxa-rock/board.c b/arch/arm/boards/radxa-rock/board.c
new file mode 100644
index 0000000..55b4d23
--- /dev/null
+++ b/arch/arm/boards/radxa-rock/board.c
@@ -0,0 +1,78 @@
+/*
+ * Copyright (C) 2014 Beniamino Galvani <b.galvani@gmail.com>
+ *
+ * This program is free software; you can redistribute it and/or
+ * modify it under the terms of the GNU General Public License
+ * version 2 as published by the Free Software Foundation.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ */
+
+#include <common.h>
+#include <init.h>
+#include <io.h>
+#include <i2c/i2c.h>
+#include <i2c/i2c-gpio.h>
+#include <mach/rockchip-pll.h>
+#include <mfd/act8846.h>
+
+static struct i2c_board_info radxa_rock_i2c_devices[] = {
+	{
+		I2C_BOARD_INFO("act8846", 0x5a)
+	},
+};
+
+static struct i2c_gpio_platform_data i2c_gpio_pdata = {
+	.sda_pin		= 58,
+	.scl_pin		= 59,
+	.udelay			= 5,
+};
+
+static void radxa_rock_pmic_init(void)
+{
+	struct act8846 *pmic;
+
+	pmic = act8846_get();
+	if (pmic == NULL)
+		return;
+
+	/* Power on ethernet PHY */
+	act8846_set_bits(pmic, ACT8846_LDO9_CTRL, BIT(7), BIT(7));
+}
+
+static int setup_plls(void)
+{
+	/* Codec PLL frequency: 594 MHz */
+	rk3188_pll_set_parameters(RK3188_CPLL, 2, 198, 4);
+	/* General PLL frequency: 300 MHz */
+	rk3188_pll_set_parameters(RK3188_GPLL, 1, 50, 4);
+
+	return 0;
+}
+coredevice_initcall(setup_plls);
+
+static int devices_init(void)
+{
+	i2c_register_board_info(0, radxa_rock_i2c_devices,
+				ARRAY_SIZE(radxa_rock_i2c_devices));
+	add_generic_device_res("i2c-gpio", 0, NULL, 0, &i2c_gpio_pdata);
+
+	radxa_rock_pmic_init();
+
+	/* Set mac_pll divisor to 6 (50MHz output) */
+	writel((5 << 8) | (0x1f << 24), 0x20000098);
+
+	return 0;
+}
+device_initcall(devices_init);
+
+static int hostname_init(void)
+{
+	barebox_set_hostname("radxa-rock");
+
+	return 0;
+}
+core_initcall(hostname_init);
diff --git a/arch/arm/boards/radxa-rock/env/config-board b/arch/arm/boards/radxa-rock/env/config-board
new file mode 100644
index 0000000..d986e30
--- /dev/null
+++ b/arch/arm/boards/radxa-rock/env/config-board
@@ -0,0 +1,6 @@
+#!/bin/sh
+
+# board defaults, do not change in running system. Change /env/config
+# instead
+
+global.linux.bootargs.base="console=ttyS2,115200"
\ No newline at end of file
diff --git a/arch/arm/boards/radxa-rock/lowlevel.c b/arch/arm/boards/radxa-rock/lowlevel.c
new file mode 100644
index 0000000..c68d229
--- /dev/null
+++ b/arch/arm/boards/radxa-rock/lowlevel.c
@@ -0,0 +1,23 @@
+/*
+ * Copyright (C) 2014 Beniamino Galvani <b.galvani@gmail.com>
+ *
+ * This program is free software; you can redistribute it and/or
+ * modify it under the terms of the GNU General Public License
+ * version 2 as published by the Free Software Foundation.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ */
+
+#include <common.h>
+#include <sizes.h>
+#include <asm/barebox-arm-head.h>
+#include <asm/barebox-arm.h>
+
+void __naked barebox_arm_reset_vector(void)
+{
+	arm_cpu_lowlevel_init();
+	barebox_arm_entry(0x60000000, SZ_2G, 0);
+}
diff --git a/arch/arm/configs/radxa-rock_defconfig b/arch/arm/configs/radxa-rock_defconfig
new file mode 100644
index 0000000..ab45cb9
--- /dev/null
+++ b/arch/arm/configs/radxa-rock_defconfig
@@ -0,0 +1,62 @@
+CONFIG_BUILTIN_DTB=y
+CONFIG_BUILTIN_DTB_NAME="rk3188-radxarock"
+CONFIG_ARCH_ROCKCHIP=y
+CONFIG_AEABI=y
+CONFIG_ARM_OPTIMZED_STRING_FUNCTIONS=y
+CONFIG_MALLOC_SIZE=0x4000000
+CONFIG_MALLOC_TLSF=y
+CONFIG_MMU=y
+CONFIG_DEFAULT_ENVIRONMENT_GENERIC_NEW=y
+CONFIG_DEFAULT_ENVIRONMENT_PATH="arch/arm/boards/radxa-rock/env"
+CONFIG_PROMPT="radxa-rock:"
+CONFIG_LONGHELP=y
+CONFIG_GLOB=y
+CONFIG_HUSH_FANCY_PROMPT=y
+CONFIG_CMDLINE_EDITING=y
+CONFIG_AUTO_COMPLETE=y
+CONFIG_CMD_EDIT=y
+CONFIG_CMD_SLEEP=y
+CONFIG_CMD_EXPORT=y
+CONFIG_CMD_PRINTENV=y
+CONFIG_CMD_READLINE=y
+CONFIG_CMD_ECHO_E=y
+CONFIG_CMD_LOADB=y
+CONFIG_CMD_LOADY=y
+CONFIG_CMD_MEMINFO=y
+CONFIG_CMD_IOMEM=y
+CONFIG_CMD_MM=y
+CONFIG_NET_CMD_IFUP=y
+CONFIG_CMD_BOOTM=y
+CONFIG_CMD_BOOTU=y
+CONFIG_CMD_BOOTZ=y
+CONFIG_CMD_RESET=y
+CONFIG_CMD_GO=y
+CONFIG_CMD_OFTREE=y
+CONFIG_CMD_OF_PROPERTY=y
+CONFIG_CMD_OF_NODE=y
+CONFIG_CMD_TIMEOUT=y
+CONFIG_CMD_TFTP=y
+CONFIG_CMD_PARTITION=y
+CONFIG_CMD_GPIO=y
+CONFIG_CMD_I2C=y
+CONFIG_CMD_UNCOMPRESS=y
+CONFIG_CMD_LED=y
+CONFIG_CMD_MIITOOL=y
+CONFIG_CMD_CLK=y
+CONFIG_OFDEVICE=y
+CONFIG_OF_BAREBOX_DRIVERS=y
+CONFIG_DRIVER_SERIAL_NS16550=y
+CONFIG_LED=y
+CONFIG_LED_GPIO=y
+CONFIG_LED_GPIO_OF=y
+CONFIG_NET=y
+CONFIG_NET_PING=y
+CONFIG_NET_DHCP=y
+CONFIG_PINCTRL=y
+CONFIG_PINCTRL_ROCKCHIP=y
+CONFIG_I2C=y
+CONFIG_I2C_GPIO=y
+CONFIG_MFD_ACT8846=y
+CONFIG_DRIVER_NET_ARC_EMAC=y
+CONFIG_SMSC_PHY=y
+CONFIG_FS_TFTP=y
diff --git a/arch/arm/mach-rockchip/Kconfig b/arch/arm/mach-rockchip/Kconfig
index dfaf146..9348651 100644
--- a/arch/arm/mach-rockchip/Kconfig
+++ b/arch/arm/mach-rockchip/Kconfig
@@ -4,4 +4,12 @@ config ARCH_TEXT_BASE
 	hex
 	default 0x68000000
 
+choice
+	prompt "Board type"
+
+config MACH_RADXA_ROCK
+	bool "Radxa rock board"
+
+endchoice
+
 endif
-- 
1.7.10.4


_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

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

* Re: [PATCH 00/11] ARM: add initial support for Rockchip boards
  2014-04-27  9:30 [PATCH 00/11] ARM: add initial support for Rockchip boards Beniamino Galvani
                   ` (10 preceding siblings ...)
  2014-04-27  9:30 ` [PATCH 11/11] ARM: rockchip: add radxa-rock board Beniamino Galvani
@ 2014-04-28  7:26 ` Sascha Hauer
  2014-04-28 20:54   ` Beniamino Galvani
  11 siblings, 1 reply; 18+ messages in thread
From: Sascha Hauer @ 2014-04-28  7:26 UTC (permalink / raw)
  To: Beniamino Galvani; +Cc: barebox

Hi Beniamino,

On Sun, Apr 27, 2014 at 11:30:33AM +0200, Beniamino Galvani wrote:
> This series adds an initial support for Rockchip SoCs and has been
> tested on a Radxa Rock board, on which I'm able to load a kernel from
> the network and boot it [1].
> 
> At the moment Barebox must be chainloaded from the Rockchip binary
> bootloader which performs low-level initializations and loads Barebox
> from the "boot" partition on the NAND.
> 
> Barebox should be written using the same procedure used for kernels:
> it must be prepared with the mkimage tool and then written with
> rkflashkit.
> 
> There is a u-boot code released by Rockchip [2] which probably
> includes all the low-level initializations but I'm not brave enough to
> try it.
> 
> The patchset adds ethernet and pinctrl drivers, PLL and clocks
> initialization, and code to power on the external PHY of the board
> through the PMIC.

Awesome! I'm happy to see barebox support for one of the more popular
Linux ARM architectures.

The patches look quite good and there's not much to be done to
make them ready for merging.

I'm just on the way to merge the Linux devicetree files into barebox
and use them where possible so we do not duplicate the devicetrees in
barebox. Could you post a followup once to base the rockchip dts files
on the Linux dts files once I have everything in place? I saw that you
already use the mainline dts files, but these do not contain the
ethernet nodes for example.

Also I'd like to let rockchip use the multi image mechanism. This is not
much work when you know what to do. You could change it yourself or I do
the change for you, but in this case, could you give the result a test?

Sascha

-- 
Pengutronix e.K.                           |                             |
Industrial Linux Solutions                 | http://www.pengutronix.de/  |
Peiner Str. 6-8, 31137 Hildesheim, Germany | Phone: +49-5121-206917-0    |
Amtsgericht Hildesheim, HRA 2686           | Fax:   +49-5121-206917-5555 |

_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

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

* Re: [PATCH 00/11] ARM: add initial support for Rockchip boards
  2014-04-28  7:26 ` [PATCH 00/11] ARM: add initial support for Rockchip boards Sascha Hauer
@ 2014-04-28 20:54   ` Beniamino Galvani
  2014-04-29  7:05     ` Sascha Hauer
  0 siblings, 1 reply; 18+ messages in thread
From: Beniamino Galvani @ 2014-04-28 20:54 UTC (permalink / raw)
  To: Sascha Hauer; +Cc: barebox

On Mon, Apr 28, 2014 at 09:26:27AM +0200, Sascha Hauer wrote:
> Hi Beniamino,
> 
> On Sun, Apr 27, 2014 at 11:30:33AM +0200, Beniamino Galvani wrote:
> > This series adds an initial support for Rockchip SoCs and has been
> > tested on a Radxa Rock board, on which I'm able to load a kernel from
> > the network and boot it [1].
> > 
> > At the moment Barebox must be chainloaded from the Rockchip binary
> > bootloader which performs low-level initializations and loads Barebox
> > from the "boot" partition on the NAND.
> > 
> > Barebox should be written using the same procedure used for kernels:
> > it must be prepared with the mkimage tool and then written with
> > rkflashkit.
> > 
> > There is a u-boot code released by Rockchip [2] which probably
> > includes all the low-level initializations but I'm not brave enough to
> > try it.
> > 
> > The patchset adds ethernet and pinctrl drivers, PLL and clocks
> > initialization, and code to power on the external PHY of the board
> > through the PMIC.
> 
> Awesome! I'm happy to see barebox support for one of the more popular
> Linux ARM architectures.
> 
> The patches look quite good and there's not much to be done to
> make them ready for merging.
> 
> I'm just on the way to merge the Linux devicetree files into barebox
> and use them where possible so we do not duplicate the devicetrees in
> barebox. Could you post a followup once to base the rockchip dts files
> on the Linux dts files once I have everything in place? I saw that you
> already use the mainline dts files, but these do not contain the
> ethernet nodes for example.

Ok, I will do. Just a question: my series is against -next because it
requires commit 6720ad6f16db5839a72aa8b53e89918a4f0059bd "clk: move
of_clk_get_parent_name() to common clk code", while your dts branch
derives from master and doesn't have this commit. Which branch should
I base the next version on?

> Also I'd like to let rockchip use the multi image mechanism. This is not
> much work when you know what to do. You could change it yourself or I do
> the change for you, but in this case, could you give the result a test?

I'm not familiar with multi-image support but I would be glad to try
it if you're willing to implement it.

Beniamino

_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

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

* Re: [PATCH 00/11] ARM: add initial support for Rockchip boards
  2014-04-28 20:54   ` Beniamino Galvani
@ 2014-04-29  7:05     ` Sascha Hauer
  2014-04-29 21:13       ` Beniamino Galvani
  0 siblings, 1 reply; 18+ messages in thread
From: Sascha Hauer @ 2014-04-29  7:05 UTC (permalink / raw)
  To: Beniamino Galvani; +Cc: barebox

On Mon, Apr 28, 2014 at 10:54:53PM +0200, Beniamino Galvani wrote:
> On Mon, Apr 28, 2014 at 09:26:27AM +0200, Sascha Hauer wrote:
> > Hi Beniamino,
> > 
> > On Sun, Apr 27, 2014 at 11:30:33AM +0200, Beniamino Galvani wrote:
> > > This series adds an initial support for Rockchip SoCs and has been
> > > tested on a Radxa Rock board, on which I'm able to load a kernel from
> > > the network and boot it [1].
> > > 
> > > At the moment Barebox must be chainloaded from the Rockchip binary
> > > bootloader which performs low-level initializations and loads Barebox
> > > from the "boot" partition on the NAND.
> > > 
> > > Barebox should be written using the same procedure used for kernels:
> > > it must be prepared with the mkimage tool and then written with
> > > rkflashkit.
> > > 
> > > There is a u-boot code released by Rockchip [2] which probably
> > > includes all the low-level initializations but I'm not brave enough to
> > > try it.
> > > 
> > > The patchset adds ethernet and pinctrl drivers, PLL and clocks
> > > initialization, and code to power on the external PHY of the board
> > > through the PMIC.
> > 
> > Awesome! I'm happy to see barebox support for one of the more popular
> > Linux ARM architectures.
> > 
> > The patches look quite good and there's not much to be done to
> > make them ready for merging.
> > 
> > I'm just on the way to merge the Linux devicetree files into barebox
> > and use them where possible so we do not duplicate the devicetrees in
> > barebox. Could you post a followup once to base the rockchip dts files
> > on the Linux dts files once I have everything in place? I saw that you
> > already use the mainline dts files, but these do not contain the
> > ethernet nodes for example.
> 
> Ok, I will do. Just a question: my series is against -next because it
> requires commit 6720ad6f16db5839a72aa8b53e89918a4f0059bd "clk: move
> of_clk_get_parent_name() to common clk code", while your dts branch
> derives from master and doesn't have this commit. Which branch should
> I base the next version on?

I reshuffled the patches in -next so that your patches have the correct
dependencies.

> 
> > Also I'd like to let rockchip use the multi image mechanism. This is not
> > much work when you know what to do. You could change it yourself or I do
> > the change for you, but in this case, could you give the result a test?
> 
> I'm not familiar with multi-image support but I would be glad to try
> it if you're willing to implement it.

Ok, I pushed everything to -next. The multi image conversion is in the
attached patch (also included in -next). Try building rockchip_defconfig
and start images/barebox-radxa-rock.img. If it works then we are lucky,
if not we'll have to work out a way to debug the patch.

BTW I noticed the upstream radxa rock dts file does not have a board
specific compatible. I added this in my patch, but this should be done
upstream.

Sascha

------------------------8<--------------------------------

From 903b1d430904588ef9f6b2f897b46e3e3cc4516a Mon Sep 17 00:00:00 2001
From: Sascha Hauer <s.hauer@pengutronix.de>
Date: Tue, 29 Apr 2014 08:34:54 +0200
Subject: [PATCH] ARM: Rockchip: switch to multiimage support

- Add images/Makefile.rockchip
- Allow multiple boards to be selected
- protect initcalls with appropriate of_machine_is_compatible
- rename board specific config to SoC config
- Add dtb file to compilation
- turn barebox_arm_reset_vectorto ENTRY_FUNCTION
- pass dtb to barebox_arm_entry

Signed-off-by: Sascha Hauer <s.hauer@pengutronix.de>
---
 arch/arm/Kconfig                      |  1 +
 arch/arm/boards/radxa-rock/board.c    |  9 +++++
 arch/arm/boards/radxa-rock/lowlevel.c | 11 +++++--
 arch/arm/configs/radxa-rock_defconfig | 62 -----------------------------------
 arch/arm/configs/rockchip_defconfig   | 60 +++++++++++++++++++++++++++++++++
 arch/arm/dts/Makefile                 |  2 ++
 arch/arm/dts/rk3188-radxarock.dts     |  1 +
 arch/arm/mach-rockchip/Kconfig        |  5 +--
 images/Makefile                       |  1 +
 images/Makefile.rockchip              |  9 +++++
 10 files changed, 93 insertions(+), 68 deletions(-)
 delete mode 100644 arch/arm/configs/radxa-rock_defconfig
 create mode 100644 arch/arm/configs/rockchip_defconfig
 create mode 100644 images/Makefile.rockchip

diff --git a/arch/arm/Kconfig b/arch/arm/Kconfig
index 991a411..3710eed 100644
--- a/arch/arm/Kconfig
+++ b/arch/arm/Kconfig
@@ -134,6 +134,7 @@ config ARCH_ROCKCHIP
 	select COMMON_CLK_OF_PROVIDER
 	select GPIOLIB
 	select PINCTRL_ROCKCHIP
+	select HAVE_PBL_MULTI_IMAGES
 
 config ARCH_SOCFPGA
 	bool "Altera SOCFPGA cyclone5"
diff --git a/arch/arm/boards/radxa-rock/board.c b/arch/arm/boards/radxa-rock/board.c
index 55b4d23..691f243 100644
--- a/arch/arm/boards/radxa-rock/board.c
+++ b/arch/arm/boards/radxa-rock/board.c
@@ -45,6 +45,9 @@ static void radxa_rock_pmic_init(void)
 
 static int setup_plls(void)
 {
+	if (!of_machine_is_compatible("radxa,rock"))
+		return 0;
+
 	/* Codec PLL frequency: 594 MHz */
 	rk3188_pll_set_parameters(RK3188_CPLL, 2, 198, 4);
 	/* General PLL frequency: 300 MHz */
@@ -56,6 +59,9 @@ coredevice_initcall(setup_plls);
 
 static int devices_init(void)
 {
+	if (!of_machine_is_compatible("radxa,rock"))
+		return 0;
+
 	i2c_register_board_info(0, radxa_rock_i2c_devices,
 				ARRAY_SIZE(radxa_rock_i2c_devices));
 	add_generic_device_res("i2c-gpio", 0, NULL, 0, &i2c_gpio_pdata);
@@ -71,6 +77,9 @@ device_initcall(devices_init);
 
 static int hostname_init(void)
 {
+	if (!of_machine_is_compatible("radxa,rock"))
+		return 0;
+
 	barebox_set_hostname("radxa-rock");
 
 	return 0;
diff --git a/arch/arm/boards/radxa-rock/lowlevel.c b/arch/arm/boards/radxa-rock/lowlevel.c
index c68d229..0b40f10 100644
--- a/arch/arm/boards/radxa-rock/lowlevel.c
+++ b/arch/arm/boards/radxa-rock/lowlevel.c
@@ -16,8 +16,15 @@
 #include <asm/barebox-arm-head.h>
 #include <asm/barebox-arm.h>
 
-void __naked barebox_arm_reset_vector(void)
+extern char __dtb_rk3188_radxarock_start[];
+
+ENTRY_FUNCTION(start_radxa_rock, r0, r1, r2)
 {
+	uint32_t fdt;
+
 	arm_cpu_lowlevel_init();
-	barebox_arm_entry(0x60000000, SZ_2G, 0);
+
+	fdt = (uint32_t)__dtb_rk3188_radxarock_start - get_runtime_offset();
+
+	barebox_arm_entry(0x60000000, SZ_2G, fdt);
 }
diff --git a/arch/arm/configs/radxa-rock_defconfig b/arch/arm/configs/radxa-rock_defconfig
deleted file mode 100644
index ab45cb9..0000000
--- a/arch/arm/configs/radxa-rock_defconfig
+++ /dev/null
@@ -1,62 +0,0 @@
-CONFIG_BUILTIN_DTB=y
-CONFIG_BUILTIN_DTB_NAME="rk3188-radxarock"
-CONFIG_ARCH_ROCKCHIP=y
-CONFIG_AEABI=y
-CONFIG_ARM_OPTIMZED_STRING_FUNCTIONS=y
-CONFIG_MALLOC_SIZE=0x4000000
-CONFIG_MALLOC_TLSF=y
-CONFIG_MMU=y
-CONFIG_DEFAULT_ENVIRONMENT_GENERIC_NEW=y
-CONFIG_DEFAULT_ENVIRONMENT_PATH="arch/arm/boards/radxa-rock/env"
-CONFIG_PROMPT="radxa-rock:"
-CONFIG_LONGHELP=y
-CONFIG_GLOB=y
-CONFIG_HUSH_FANCY_PROMPT=y
-CONFIG_CMDLINE_EDITING=y
-CONFIG_AUTO_COMPLETE=y
-CONFIG_CMD_EDIT=y
-CONFIG_CMD_SLEEP=y
-CONFIG_CMD_EXPORT=y
-CONFIG_CMD_PRINTENV=y
-CONFIG_CMD_READLINE=y
-CONFIG_CMD_ECHO_E=y
-CONFIG_CMD_LOADB=y
-CONFIG_CMD_LOADY=y
-CONFIG_CMD_MEMINFO=y
-CONFIG_CMD_IOMEM=y
-CONFIG_CMD_MM=y
-CONFIG_NET_CMD_IFUP=y
-CONFIG_CMD_BOOTM=y
-CONFIG_CMD_BOOTU=y
-CONFIG_CMD_BOOTZ=y
-CONFIG_CMD_RESET=y
-CONFIG_CMD_GO=y
-CONFIG_CMD_OFTREE=y
-CONFIG_CMD_OF_PROPERTY=y
-CONFIG_CMD_OF_NODE=y
-CONFIG_CMD_TIMEOUT=y
-CONFIG_CMD_TFTP=y
-CONFIG_CMD_PARTITION=y
-CONFIG_CMD_GPIO=y
-CONFIG_CMD_I2C=y
-CONFIG_CMD_UNCOMPRESS=y
-CONFIG_CMD_LED=y
-CONFIG_CMD_MIITOOL=y
-CONFIG_CMD_CLK=y
-CONFIG_OFDEVICE=y
-CONFIG_OF_BAREBOX_DRIVERS=y
-CONFIG_DRIVER_SERIAL_NS16550=y
-CONFIG_LED=y
-CONFIG_LED_GPIO=y
-CONFIG_LED_GPIO_OF=y
-CONFIG_NET=y
-CONFIG_NET_PING=y
-CONFIG_NET_DHCP=y
-CONFIG_PINCTRL=y
-CONFIG_PINCTRL_ROCKCHIP=y
-CONFIG_I2C=y
-CONFIG_I2C_GPIO=y
-CONFIG_MFD_ACT8846=y
-CONFIG_DRIVER_NET_ARC_EMAC=y
-CONFIG_SMSC_PHY=y
-CONFIG_FS_TFTP=y
diff --git a/arch/arm/configs/rockchip_defconfig b/arch/arm/configs/rockchip_defconfig
new file mode 100644
index 0000000..3bc4a80
--- /dev/null
+++ b/arch/arm/configs/rockchip_defconfig
@@ -0,0 +1,60 @@
+CONFIG_ARCH_ROCKCHIP=y
+CONFIG_MACH_RADXA_ROCK=y
+CONFIG_THUMB2_BAREBOX=y
+CONFIG_CMD_ARM_MMUINFO=y
+CONFIG_ARM_OPTIMZED_STRING_FUNCTIONS=y
+CONFIG_ARM_UNWIND=y
+CONFIG_MMU=y
+CONFIG_MALLOC_SIZE=0x4000000
+CONFIG_MALLOC_TLSF=y
+CONFIG_KALLSYMS=y
+CONFIG_RELOCATABLE=y
+CONFIG_PROMPT="radxa-rock:"
+CONFIG_LONGHELP=y
+CONFIG_HUSH_FANCY_PROMPT=y
+CONFIG_CMDLINE_EDITING=y
+CONFIG_AUTO_COMPLETE=y
+CONFIG_PARTITION=y
+CONFIG_DEFAULT_ENVIRONMENT_GENERIC_NEW=y
+CONFIG_DEFAULT_ENVIRONMENT_PATH="arch/arm/boards/radxa-rock/env"
+CONFIG_CMD_EDIT=y
+CONFIG_CMD_SLEEP=y
+CONFIG_CMD_EXPORT=y
+CONFIG_CMD_PRINTENV=y
+CONFIG_CMD_READLINE=y
+CONFIG_CMD_TFTP=y
+CONFIG_CMD_ECHO_E=y
+CONFIG_CMD_LOADB=y
+CONFIG_CMD_LOADY=y
+CONFIG_CMD_MEMINFO=y
+CONFIG_CMD_IOMEM=y
+CONFIG_CMD_MM=y
+CONFIG_CMD_BOOTZ=y
+CONFIG_CMD_RESET=y
+CONFIG_CMD_GO=y
+CONFIG_CMD_OFTREE=y
+CONFIG_CMD_OF_PROPERTY=y
+CONFIG_CMD_OF_NODE=y
+CONFIG_CMD_TIMEOUT=y
+CONFIG_CMD_PARTITION=y
+CONFIG_CMD_GPIO=y
+CONFIG_CMD_UNCOMPRESS=y
+CONFIG_CMD_I2C=y
+CONFIG_CMD_LED=y
+CONFIG_CMD_MIITOOL=y
+CONFIG_CMD_CLK=y
+CONFIG_NET=y
+CONFIG_NET_DHCP=y
+CONFIG_NET_PING=y
+CONFIG_OFDEVICE=y
+CONFIG_OF_BAREBOX_DRIVERS=y
+CONFIG_DRIVER_SERIAL_NS16550=y
+CONFIG_DRIVER_NET_ARC_EMAC=y
+CONFIG_SMSC_PHY=y
+CONFIG_I2C=y
+CONFIG_I2C_GPIO=y
+CONFIG_MFD_ACT8846=y
+CONFIG_LED=y
+CONFIG_LED_GPIO=y
+CONFIG_LED_GPIO_OF=y
+CONFIG_FS_TFTP=y
diff --git a/arch/arm/dts/Makefile b/arch/arm/dts/Makefile
index b45c174..34c5165 100644
--- a/arch/arm/dts/Makefile
+++ b/arch/arm/dts/Makefile
@@ -29,6 +29,7 @@ dtb-$(CONFIG_ARCH_IMX6) += imx6q-gk802.dtb \
 	imx6q-udoo.dtb \
 	imx6q-var-custom.dtb
 dtb-$(CONFIG_ARCH_MVEBU) += dove-cubox-bb.dtb
+dtb-$(CONFIG_ARCH_ROCKCHIP) += rk3188-radxarock.dtb
 dtb-$(CONFIG_ARCH_SOCFPGA) += socfpga_cyclone5_sockit.dtb \
 	socfpga_cyclone5_socrates.dtb
 dtb-$(CONFIG_ARCH_TEGRA) += \
@@ -54,6 +55,7 @@ pbl-$(CONFIG_MACH_TOSHIBA_AC100) += tegra20-paz00.dtb.o
 pbl-$(CONFIG_MACH_TQMA53) += imx53-mba53.dtb.o
 pbl-$(CONFIG_MACH_TQMA6X) += imx6dl-mba6x.dtb.o imx6q-mba6x.dtb.o
 pbl-$(CONFIG_MACH_TX25) += imx25-karo-tx25.dtb.o
+pbl-$(CONFIG_MACH_RADXA_ROCK) += rk3188-radxarock.dtb.o
 pbl-$(CONFIG_MACH_SOCFPGA_EBV_SOCRATES) += socfpga_cyclone5_socrates.dtb.o
 pbl-$(CONFIG_MACH_SOCFPGA_TERASIC_SOCKIT) += socfpga_cyclone5_sockit.dtb.o
 pbl-$(CONFIG_MACH_SOLIDRUN_HUMMINGBOARD) += imx6dl-hummingboard.dtb.o
diff --git a/arch/arm/dts/rk3188-radxarock.dts b/arch/arm/dts/rk3188-radxarock.dts
index be2a302..2d49d69 100644
--- a/arch/arm/dts/rk3188-radxarock.dts
+++ b/arch/arm/dts/rk3188-radxarock.dts
@@ -17,6 +17,7 @@
 
 / {
 	model = "Radxa Rock";
+	compatible = "radxa,rock", "rockchip,rk3188";
 
 	memory {
 		reg = <0x60000000 0x80000000>;
diff --git a/arch/arm/mach-rockchip/Kconfig b/arch/arm/mach-rockchip/Kconfig
index 9348651..9c9eed0 100644
--- a/arch/arm/mach-rockchip/Kconfig
+++ b/arch/arm/mach-rockchip/Kconfig
@@ -4,12 +4,9 @@ config ARCH_TEXT_BASE
 	hex
 	default 0x68000000
 
-choice
-	prompt "Board type"
+comment "select Rockchip boards:"
 
 config MACH_RADXA_ROCK
 	bool "Radxa rock board"
 
-endchoice
-
 endif
diff --git a/images/Makefile b/images/Makefile
index 8ec1791..5509a4c 100644
--- a/images/Makefile
+++ b/images/Makefile
@@ -99,6 +99,7 @@ $(obj)/%.img: $(obj)/$$(FILE_$$(@F))
 include $(srctree)/images/Makefile.am33xx
 include $(srctree)/images/Makefile.imx
 include $(srctree)/images/Makefile.mvebu
+include $(srctree)/images/Makefile.rockchip
 include $(srctree)/images/Makefile.socfpga
 include $(srctree)/images/Makefile.tegra
 
diff --git a/images/Makefile.rockchip b/images/Makefile.rockchip
new file mode 100644
index 0000000..2444433
--- /dev/null
+++ b/images/Makefile.rockchip
@@ -0,0 +1,9 @@
+#
+# barebox image generation Makefile for Rockchip images
+#
+
+board = $(srctree)/arch/$(ARCH)/boards
+
+pblx-$(CONFIG_MACH_RADXA_ROCK) += start_radxa_rock
+FILE_barebox-radxa-rock.img = start_radxa_rock.pblx
+image-$(CONFIG_MACH_RADXA_ROCK) += barebox-radxa-rock.img
-- 
1.9.1

-- 
Pengutronix e.K.                           |                             |
Industrial Linux Solutions                 | http://www.pengutronix.de/  |
Peiner Str. 6-8, 31137 Hildesheim, Germany | Phone: +49-5121-206917-0    |
Amtsgericht Hildesheim, HRA 2686           | Fax:   +49-5121-206917-5555 |

_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

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

* Re: [PATCH 00/11] ARM: add initial support for Rockchip boards
  2014-04-29  7:05     ` Sascha Hauer
@ 2014-04-29 21:13       ` Beniamino Galvani
  2014-04-29 21:59         ` Heiko Stübner
  0 siblings, 1 reply; 18+ messages in thread
From: Beniamino Galvani @ 2014-04-29 21:13 UTC (permalink / raw)
  To: Sascha Hauer; +Cc: barebox, Heiko Stuebner

On Tue, Apr 29, 2014 at 09:05:58AM +0200, Sascha Hauer wrote:
> On Mon, Apr 28, 2014 at 10:54:53PM +0200, Beniamino Galvani wrote:
> > On Mon, Apr 28, 2014 at 09:26:27AM +0200, Sascha Hauer wrote:
> > > Hi Beniamino,
> > > 
> > > On Sun, Apr 27, 2014 at 11:30:33AM +0200, Beniamino Galvani wrote:
> > > > This series adds an initial support for Rockchip SoCs and has been
> > > > tested on a Radxa Rock board, on which I'm able to load a kernel from
> > > > the network and boot it [1].
> > > > 
> > > > At the moment Barebox must be chainloaded from the Rockchip binary
> > > > bootloader which performs low-level initializations and loads Barebox
> > > > from the "boot" partition on the NAND.
> > > > 
> > > > Barebox should be written using the same procedure used for kernels:
> > > > it must be prepared with the mkimage tool and then written with
> > > > rkflashkit.
> > > > 
> > > > There is a u-boot code released by Rockchip [2] which probably
> > > > includes all the low-level initializations but I'm not brave enough to
> > > > try it.
> > > > 
> > > > The patchset adds ethernet and pinctrl drivers, PLL and clocks
> > > > initialization, and code to power on the external PHY of the board
> > > > through the PMIC.
> > > 
> > > Awesome! I'm happy to see barebox support for one of the more popular
> > > Linux ARM architectures.
> > > 
> > > The patches look quite good and there's not much to be done to
> > > make them ready for merging.
> > > 
> > > I'm just on the way to merge the Linux devicetree files into barebox
> > > and use them where possible so we do not duplicate the devicetrees in
> > > barebox. Could you post a followup once to base the rockchip dts files
> > > on the Linux dts files once I have everything in place? I saw that you
> > > already use the mainline dts files, but these do not contain the
> > > ethernet nodes for example.
> > 
> > Ok, I will do. Just a question: my series is against -next because it
> > requires commit 6720ad6f16db5839a72aa8b53e89918a4f0059bd "clk: move
> > of_clk_get_parent_name() to common clk code", while your dts branch
> > derives from master and doesn't have this commit. Which branch should
> > I base the next version on?
> 
> I reshuffled the patches in -next so that your patches have the correct
> dependencies.

Thanks.

> 
> > 
> > > Also I'd like to let rockchip use the multi image mechanism. This is not
> > > much work when you know what to do. You could change it yourself or I do
> > > the change for you, but in this case, could you give the result a test?
> > 
> > I'm not familiar with multi-image support but I would be glad to try
> > it if you're willing to implement it.
> 
> Ok, I pushed everything to -next. The multi image conversion is in the
> attached patch (also included in -next). Try building rockchip_defconfig
> and start images/barebox-radxa-rock.img. If it works then we are lucky,
> if not we'll have to work out a way to debug the patch.

The image works. There is only a small change (below) to do in board
file to postpone the call of hostname_init() until the dt root node is
set, otherwise the check on board compatible always returns false.

> 
> BTW I noticed the upstream radxa rock dts file does not have a board
> specific compatible. I added this in my patch, but this should be done
> upstream.

CC'ing Heiko, who is the Linux Rockchip maintainer.

Beniamino

-----------------------------8<-------------------------------------
From 829e4a021e537d704e49aaa2b885ea9fb5484007 Mon Sep 17 00:00:00 2001
From: Beniamino Galvani <b.galvani@gmail.com>
Date: Tue, 29 Apr 2014 20:11:46 +0200
Subject: [PATCH] ARM: radxa-rock: call hostname_init() after DT initialization

---
 arch/arm/boards/radxa-rock/board.c |    2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/arch/arm/boards/radxa-rock/board.c b/arch/arm/boards/radxa-rock/board.c
index 691f243..3d9b5be 100644
--- a/arch/arm/boards/radxa-rock/board.c
+++ b/arch/arm/boards/radxa-rock/board.c
@@ -84,4 +84,4 @@ static int hostname_init(void)
 
 	return 0;
 }
-core_initcall(hostname_init);
+postcore_initcall(hostname_init);
-- 
1.7.10.4

_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

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

* Re: [PATCH 00/11] ARM: add initial support for Rockchip boards
  2014-04-29 21:13       ` Beniamino Galvani
@ 2014-04-29 21:59         ` Heiko Stübner
  2014-05-01  7:48           ` Beniamino Galvani
  0 siblings, 1 reply; 18+ messages in thread
From: Heiko Stübner @ 2014-04-29 21:59 UTC (permalink / raw)
  To: Beniamino Galvani; +Cc: barebox

Hi Beniamino,


very cool that you're working on getting a better boot loader for us :-)

Am Dienstag, 29. April 2014, 23:13:14 schrieb Beniamino Galvani:
> On Tue, Apr 29, 2014 at 09:05:58AM +0200, Sascha Hauer wrote:
> > On Mon, Apr 28, 2014 at 10:54:53PM +0200, Beniamino Galvani wrote:
> > > On Mon, Apr 28, 2014 at 09:26:27AM +0200, Sascha Hauer wrote:
> > > > Hi Beniamino,
> > > > 
> > > > On Sun, Apr 27, 2014 at 11:30:33AM +0200, Beniamino Galvani wrote:
> > > > > This series adds an initial support for Rockchip SoCs and has been
> > > > > tested on a Radxa Rock board, on which I'm able to load a kernel
> > > > > from
> > > > > the network and boot it [1].
> > > > > 
> > > > > At the moment Barebox must be chainloaded from the Rockchip binary
> > > > > bootloader which performs low-level initializations and loads
> > > > > Barebox
> > > > > from the "boot" partition on the NAND.
> > > > > 
> > > > > Barebox should be written using the same procedure used for kernels:
> > > > > it must be prepared with the mkimage tool and then written with
> > > > > rkflashkit.
> > > > > 
> > > > > There is a u-boot code released by Rockchip [2] which probably
> > > > > includes all the low-level initializations but I'm not brave enough
> > > > > to
> > > > > try it.

hehe, that goes for me too :-)


> > BTW I noticed the upstream radxa rock dts file does not have a board
> > specific compatible. I added this in my patch, but this should be done
> > upstream.
> 
> CC'ing Heiko, who is the Linux Rockchip maintainer.

Until now I didn't give it much thought, but according to usage-model.txt the 
board-specific compatible is a required property. So we'll need to add it to 
the board dts in the kernel too.

So you could send a patch, or I'll prepare one in the next days.


Heiko

_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

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

* Re: [PATCH 00/11] ARM: add initial support for Rockchip boards
  2014-04-29 21:59         ` Heiko Stübner
@ 2014-05-01  7:48           ` Beniamino Galvani
  0 siblings, 0 replies; 18+ messages in thread
From: Beniamino Galvani @ 2014-05-01  7:48 UTC (permalink / raw)
  To: Heiko Stübner; +Cc: barebox

On Tue, Apr 29, 2014 at 11:59:22PM +0200, Heiko Stübner wrote:
> > > BTW I noticed the upstream radxa rock dts file does not have a board
> > > specific compatible. I added this in my patch, but this should be done
> > > upstream.
> > 
> > CC'ing Heiko, who is the Linux Rockchip maintainer.
> 
> Until now I didn't give it much thought, but according to usage-model.txt the 
> board-specific compatible is a required property. So we'll need to add it to 
> the board dts in the kernel too.
> 
> So you could send a patch, or I'll prepare one in the next days.

Ok, I will send a patch.

Beniamino

_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

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

end of thread, other threads:[~2014-05-01  7:49 UTC | newest]

Thread overview: 18+ messages (download: mbox.gz / follow: Atom feed)
-- links below jump to the message on this page --
2014-04-27  9:30 [PATCH 00/11] ARM: add initial support for Rockchip boards Beniamino Galvani
2014-04-27  9:30 ` [PATCH 01/11] net: add ARC EMAC driver Beniamino Galvani
2014-04-27  9:30 ` [PATCH 02/11] mfd: add act8846 driver Beniamino Galvani
2014-04-27  9:30 ` [PATCH 03/11] ARM: add basic support for Rockchip SoCs Beniamino Galvani
2014-04-27  9:30 ` [PATCH 04/11] ARM: rockchip: add PLL initialization function Beniamino Galvani
2014-04-27  9:30 ` [PATCH 05/11] clk: gate: add flags argument to clock gate constructor Beniamino Galvani
2014-04-27  9:30 ` [PATCH 06/11] clk: gate: unify enable and disable functions handling Beniamino Galvani
2014-04-27  9:30 ` [PATCH 07/11] clk: gate: add CLK_GATE_HIWORD_MASK flag Beniamino Galvani
2014-04-27  9:30 ` [PATCH 08/11] clk: add rockchip clock gate driver Beniamino Galvani
2014-04-27  9:30 ` [PATCH 09/11] pinctrl: add rockchip pinctrl and gpio drivers Beniamino Galvani
2014-04-27  9:30 ` [PATCH 10/11] ARM: dts: add Rockchip devicetree files Beniamino Galvani
2014-04-27  9:30 ` [PATCH 11/11] ARM: rockchip: add radxa-rock board Beniamino Galvani
2014-04-28  7:26 ` [PATCH 00/11] ARM: add initial support for Rockchip boards Sascha Hauer
2014-04-28 20:54   ` Beniamino Galvani
2014-04-29  7:05     ` Sascha Hauer
2014-04-29 21:13       ` Beniamino Galvani
2014-04-29 21:59         ` Heiko Stübner
2014-05-01  7:48           ` Beniamino Galvani

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