mail archive of the barebox mailing list
 help / color / mirror / Atom feed
* [PATCH 0/2] Add atmel pinctrl driver
@ 2014-08-01 13:24 Raphaël Poggi
  2014-08-01 13:24 ` [PATCH 1/2] pinctrl: at91: add " Raphaël Poggi
  2014-08-01 13:24 ` [PATCH 2/2] at91sam9g45: add device tree gpio clocks Raphaël Poggi
  0 siblings, 2 replies; 10+ messages in thread
From: Raphaël Poggi @ 2014-08-01 13:24 UTC (permalink / raw)
  To: barebox

This patchset add atmel pinctrl/gpio driver and the corresponding clocks for
the at91sam9g45 device.

The pinctrl driver also include the gpio driver (like in linux) because the gpio and pinctrl parts share same structures.

Raphaël Poggi (2) :
	(1) pinctrl: at91: add pinctrl driver
	(2) at91sam9g45: add device tree gpio clocks

arch/arm/mach-at91/at91sam9g45.c |    5 +
drivers/pinctrl/Kconfig          |    6 +
drivers/pinctrl/Makefile         |    1 +
drivers/pinctrl/pinctrl-at91.c   |  529 ++++++++++++++++++++++++++++++++++++++
drivers/pinctrl/pinctrl-at91.h   |  148 +++++++++++
5 files changed, 689 insertions(+)


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

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

* [PATCH 1/2] pinctrl: at91: add pinctrl driver
  2014-08-01 13:24 [PATCH 0/2] Add atmel pinctrl driver Raphaël Poggi
@ 2014-08-01 13:24 ` Raphaël Poggi
  2014-08-04 18:22   ` Sascha Hauer
  2014-08-04 18:26   ` Jean-Christophe PLAGNIOL-VILLARD
  2014-08-01 13:24 ` [PATCH 2/2] at91sam9g45: add device tree gpio clocks Raphaël Poggi
  1 sibling, 2 replies; 10+ messages in thread
From: Raphaël Poggi @ 2014-08-01 13:24 UTC (permalink / raw)
  To: barebox; +Cc: Raphaël Poggi

This driver is based on mach-at91/gpio.c and linux pinctrl driver.
The driver contains the gpio and pinctrl parts (like in linux) because the two parts
share some structures and logics.

Signed-off-by: Raphaël Poggi <poggi.raph@gmail.com>
---
 drivers/pinctrl/Kconfig        |    6 +
 drivers/pinctrl/Makefile       |    1 +
 drivers/pinctrl/pinctrl-at91.c |  529 ++++++++++++++++++++++++++++++++++++++++
 drivers/pinctrl/pinctrl-at91.h |  148 +++++++++++
 4 files changed, 684 insertions(+)
 create mode 100644 drivers/pinctrl/pinctrl-at91.c
 create mode 100644 drivers/pinctrl/pinctrl-at91.h

diff --git a/drivers/pinctrl/Kconfig b/drivers/pinctrl/Kconfig
index dffaa4e..ce55c7b 100644
--- a/drivers/pinctrl/Kconfig
+++ b/drivers/pinctrl/Kconfig
@@ -7,6 +7,12 @@ config PINCTRL
 	  from the devicetree. Legacy drivers here may not need this core
 	  support but instead provide their own SoC specific APIs
 
+config PINCTRL_AT91
+	select PINCTRL
+	bool
+	help
+	    The pinmux controller found on AT91 SoCs.
+
 config PINCTRL_IMX_IOMUX_V1
 	select PINCTRL if OFDEVICE
 	bool
diff --git a/drivers/pinctrl/Makefile b/drivers/pinctrl/Makefile
index 566ba11..3ea8649 100644
--- a/drivers/pinctrl/Makefile
+++ b/drivers/pinctrl/Makefile
@@ -1,4 +1,5 @@
 obj-$(CONFIG_PINCTRL)	+= pinctrl.o
+obj-$(CONFIG_PINCTRL_AT91) += pinctrl-at91.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
diff --git a/drivers/pinctrl/pinctrl-at91.c b/drivers/pinctrl/pinctrl-at91.c
new file mode 100644
index 0000000..a92a898
--- /dev/null
+++ b/drivers/pinctrl/pinctrl-at91.c
@@ -0,0 +1,529 @@
+/*
+ * Copyright (C) 2005 HP Labs
+ * Copyright (C) 2011-2012 Jean-Christophe PLAGNIOL-VILLARD <plagnioj@jcrosoft.com>
+ * Copyright (C) 2014 Raphaël Poggi
+ *
+ * See file CREDITS for list of people who contributed to this
+ * project.
+ *
+ * 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 <command.h>
+#include <complete.h>
+#include <linux/clk.h>
+#include <linux/err.h>
+#include <errno.h>
+#include <io.h>
+#include <gpio.h>
+#include <init.h>
+#include <driver.h>
+#include <getopt.h>
+
+#include <mach/at91_pio.h>
+
+#include <pinctrl.h>
+
+#include "pinctrl-at91.h"
+
+struct at91_pinctrl {
+    struct pinctrl_device pctl;
+    struct at91_pinctrl_mux_ops	*ops;
+};
+
+struct at91_gpio_chip {
+	struct gpio_chip	chip;
+	void __iomem		*regbase;	/* PIO bank virtual address */
+	struct at91_pinctrl_mux_ops *ops;	/* ops */
+};
+
+enum at91_mux {
+	AT91_MUX_GPIO = 0,
+	AT91_MUX_PERIPH_A = 1,
+	AT91_MUX_PERIPH_B = 2,
+	AT91_MUX_PERIPH_C = 3,
+	AT91_MUX_PERIPH_D = 4,
+};
+
+#define MAX_GPIO_BANKS		5
+#define to_at91_pinctrl(c) container_of(c, struct at91_pinctrl, pctl);
+#define to_at91_gpio_chip(c) container_of(c, struct at91_gpio_chip, chip)
+
+#define PULL_UP         (1 << 0)
+#define MULTI_DRIVE     (1 << 1)
+#define DEGLITCH        (1 << 2)
+#define PULL_DOWN       (1 << 3)
+#define DIS_SCHMIT      (1 << 4)
+#define DEBOUNCE        (1 << 16)
+#define DEBOUNCE_VAL_SHIFT      17
+#define DEBOUNCE_VAL    (0x3fff << DEBOUNCE_VAL_SHIFT)
+
+static int gpio_banks = 0;
+
+static struct at91_gpio_chip gpio_chip[MAX_GPIO_BANKS];
+
+static inline void __iomem *pin_to_controller(struct at91_pinctrl *info, unsigned pin)
+{
+	pin /= MAX_NB_GPIO_PER_BANK;
+	if (likely(pin < gpio_banks))
+		return gpio_chip[pin].regbase;
+
+	return NULL;
+}
+
+/**
+ * struct at91_pinctrl_mux_ops - describes an At91 mux ops group
+ * on new IP with support for periph C and D the way to mux in
+ * periph A and B has changed
+ * So provide the right call back
+ * if not present means the IP does not support it
+ * @get_periph: return the periph mode configured
+ * @mux_A_periph: mux as periph A
+ * @mux_B_periph: mux as periph B
+ * @mux_C_periph: mux as periph C
+ * @mux_D_periph: mux as periph D
+ * @set_deglitch: enable/disable deglitch
+ * @set_debounce: enable/disable debounce
+ * @set_pulldown: enable/disable pulldown
+ * @disable_schmitt_trig: disable schmitt trigger
+ */
+struct at91_pinctrl_mux_ops {
+	enum at91_mux (*get_periph)(void __iomem *pio, unsigned mask);
+	void (*mux_A_periph)(void __iomem *pio, unsigned mask);
+	void (*mux_B_periph)(void __iomem *pio, unsigned mask);
+	void (*mux_C_periph)(void __iomem *pio, unsigned mask);
+	void (*mux_D_periph)(void __iomem *pio, unsigned mask);
+	bool (*get_deglitch)(void __iomem *pio, unsigned pin);
+	void (*set_deglitch)(void __iomem *pio, unsigned mask, bool in_on);
+	bool (*get_debounce)(void __iomem *pio, unsigned pin, u32 *div);
+	void (*set_debounce)(void __iomem *pio, unsigned mask, bool in_on, u32 div);
+	bool (*get_pulldown)(void __iomem *pio, unsigned pin);
+	void (*set_pulldown)(void __iomem *pio, unsigned mask, bool in_on);
+	bool (*get_schmitt_trig)(void __iomem *pio, unsigned pin);
+	void (*disable_schmitt_trig)(void __iomem *pio, unsigned mask);
+};
+
+static enum at91_mux at91_mux_pio3_get_periph(void __iomem *pio, unsigned mask)
+{
+	unsigned select;
+
+	if (__raw_readl(pio + PIO_PSR) & mask)
+		return AT91_MUX_GPIO;
+
+	select = !!(__raw_readl(pio + PIO_ABCDSR1) & mask);
+	select |= (!!(__raw_readl(pio + PIO_ABCDSR2) & mask) << 1);
+
+	return select + 1;
+}
+
+static enum at91_mux at91_mux_get_periph(void __iomem *pio, unsigned mask)
+{
+	unsigned select;
+
+	if (__raw_readl(pio + PIO_PSR) & mask)
+		return AT91_MUX_GPIO;
+
+	select = __raw_readl(pio + PIO_ABSR) & mask;
+
+	return select + 1;
+}
+
+static bool at91_mux_get_deglitch(void __iomem *pio, unsigned pin)
+{
+	return (__raw_readl(pio + PIO_IFSR) >> pin) & 0x1;
+}
+
+static bool at91_mux_pio3_get_debounce(void __iomem *pio, unsigned pin, u32 *div)
+{
+	*div = __raw_readl(pio + PIO_SCDR);
+
+	return (__raw_readl(pio + PIO_IFSCSR) >> pin) & 0x1;
+}
+
+static bool at91_mux_pio3_get_pulldown(void __iomem *pio, unsigned pin)
+{
+	return (__raw_readl(pio + PIO_PPDSR) >> pin) & 0x1;
+}
+
+static bool at91_mux_pio3_get_schmitt_trig(void __iomem *pio, unsigned pin)
+{
+	return (__raw_readl(pio + PIO_SCHMITT) >> pin) & 0x1;
+}
+
+static struct at91_pinctrl_mux_ops at91rm9200_ops = {
+	.get_periph	= at91_mux_get_periph,
+	.mux_A_periph	= at91_mux_set_A_periph,
+	.mux_B_periph	= at91_mux_set_B_periph,
+	.get_deglitch	= at91_mux_get_deglitch,
+	.set_deglitch	= at91_mux_set_deglitch,
+};
+
+static struct at91_pinctrl_mux_ops at91sam9x5_ops = {
+	.get_periph	= at91_mux_pio3_get_periph,
+	.mux_A_periph	= at91_mux_pio3_set_A_periph,
+	.mux_B_periph	= at91_mux_pio3_set_B_periph,
+	.mux_C_periph	= at91_mux_pio3_set_C_periph,
+	.mux_D_periph	= at91_mux_pio3_set_D_periph,
+	.get_deglitch	= at91_mux_get_deglitch,
+	.set_deglitch	= at91_mux_pio3_set_deglitch,
+	.get_debounce	= at91_mux_pio3_get_debounce,
+	.set_debounce	= at91_mux_pio3_set_debounce,
+	.get_pulldown	= at91_mux_pio3_get_pulldown,
+	.set_pulldown	= at91_mux_pio3_set_pulldown,
+	.get_schmitt_trig = at91_mux_pio3_get_schmitt_trig,
+	.disable_schmitt_trig = at91_mux_pio3_disable_schmitt_trig,
+};
+
+static int at91_mux_pin(struct at91_pinctrl *info, unsigned pin, enum at91_mux mux, int use_pullup)
+{
+	void __iomem	*pio = pin_to_controller(info, pin);
+	unsigned mask = pin_to_mask(pin);
+
+	if (!info)
+		return -EINVAL;
+
+	if (!pio)
+		return -EINVAL;
+
+	at91_mux_disable_interrupt(pio, mask);
+
+	switch(mux) {
+	case AT91_MUX_GPIO:
+		at91_mux_gpio_enable(pio, mask);
+		break;
+	case AT91_MUX_PERIPH_A:
+		info->ops->mux_A_periph(pio, mask);
+		break;
+	case AT91_MUX_PERIPH_B:
+		info->ops->mux_B_periph(pio, mask);
+		break;
+	case AT91_MUX_PERIPH_C:
+		if (!info->ops->mux_C_periph)
+			return -EINVAL;
+		info->ops->mux_C_periph(pio, mask);
+		break;
+	case AT91_MUX_PERIPH_D:
+		if (!info->ops->mux_D_periph)
+			return -EINVAL;
+		info->ops->mux_D_periph(pio, mask);
+		break;
+	}
+	if (mux)
+		at91_mux_gpio_disable(pio, mask);
+
+	if (use_pullup >= 0)
+		at91_mux_set_pullup(pio, mask, use_pullup);
+
+	return 0;
+}
+
+static struct of_device_id at91_pinctrl_dt_ids[] = {
+	{
+		.compatible = "atmel,at91rm9200-pinctrl",
+		.data = (unsigned long)&at91rm9200_ops,
+	}, {
+		.compatible = "atmel,at91sam9x5-pinctrl",
+		.data = (unsigned long)&at91sam9x5_ops,
+	}, {
+		/* sentinel */
+	}
+};
+
+static struct at91_pinctrl_mux_ops *at91_pinctrl_get_driver_data(struct device_d *dev)
+{
+    struct at91_pinctrl_mux_ops *ops_data = NULL;
+    int rc;
+
+    if (dev->device_node) {
+	    const struct of_device_id *match;
+	    match = of_match_node(at91_pinctrl_dt_ids, dev->device_node);
+	    if (!match)
+			ops_data = NULL;
+	    else
+			ops_data = (struct at91_pinctrl_mux_ops *)match->data;
+    }
+    else {
+	    rc = dev_get_drvdata(dev, (unsigned long *)&ops_data);
+		if (rc)
+		ops_data = NULL;
+    }
+
+    return ops_data;
+}
+
+static int at91_pinctrl_set_conf(struct at91_pinctrl *info, unsigned int pin_num, unsigned int mux, unsigned int conf)
+{
+	unsigned int mask;
+	void __iomem *pio;
+
+	pio = pin_to_controller(info, pin_num);
+	mask = pin_to_mask(pin_num);
+
+	if (conf & PULL_UP && conf & PULL_DOWN)
+		return -EINVAL;
+
+	at91_mux_set_pullup(pio, mask, conf & PULL_UP);
+	at91_mux_set_multidrive(pio, mask, conf & MULTI_DRIVE);
+	if (info->ops->set_deglitch)
+		info->ops->set_deglitch(pio, mask, conf & DEGLITCH);
+	if (info->ops->set_debounce)
+		info->ops->set_debounce(pio, mask, conf & DEBOUNCE,
+			(conf & DEBOUNCE_VAL) >> DEBOUNCE_VAL_SHIFT);
+	if (info->ops->set_pulldown)
+		info->ops->set_pulldown(pio, mask, conf & PULL_DOWN);
+	if (info->ops->disable_schmitt_trig && conf & DIS_SCHMIT)
+		info->ops->disable_schmitt_trig(pio, mask);
+
+	return 0;
+}
+
+static int at91_pinctrl_set_state(struct pinctrl_device *pdev, struct device_node *np)
+{
+	struct at91_pinctrl *info;
+	const __be32 *list;
+	int i, size;
+	int ret = 0;
+	int bank_num, pin_num, mux, conf;
+
+	info = to_at91_pinctrl(pdev);
+
+	list = of_get_property(np, "atmel,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) {
+		bank_num = be32_to_cpu(*list++);
+		pin_num = be32_to_cpu(*list++);
+		mux = be32_to_cpu(*list++);
+		conf = be32_to_cpu(*list++);
+
+		ret = at91_mux_pin(info, pin_num, mux, conf & PULL_UP);
+		if (ret) {
+			dev_err(pdev->dev, "failed to mux pin %d\n", pin_num);
+			return ret;
+		}
+
+		ret = at91_pinctrl_set_conf(info, pin_num, mux, conf);
+		if (ret) {
+			dev_err(pdev->dev, "failed to set conf on pin %d\n", pin_num);
+			return ret;
+		}
+	}
+
+	return ret;
+}
+
+static struct pinctrl_ops at91_pinctrl_ops = {
+	.set_state = at91_pinctrl_set_state,
+};
+
+static int at91_pinctrl_probe(struct device_d *dev)
+{
+	struct at91_pinctrl *info;
+	int ret;
+
+	info = xzalloc(sizeof(struct at91_pinctrl));
+
+	info->ops = at91_pinctrl_get_driver_data(dev);
+	if (!info->ops) {
+		dev_err(dev, "failed to retrieve driver data\n");
+		return -ENODEV;
+	}
+
+	info->pctl.dev = dev;
+	info->pctl.ops = &at91_pinctrl_ops;
+
+	ret = pinctrl_register(&info->pctl);
+	if (ret)
+		return ret;
+
+	dev_info(dev, "AT91 pinctrl registred\n");
+
+	return 0;
+}
+
+static struct platform_device_id at91_pinctrl_ids[] = {
+	{
+		.name = "at91rm9200-pinctrl",
+		.driver_data = (unsigned long)&at91rm9200_ops,
+	}, {
+		.name = "at91sam9x5-pinctrl",
+		.driver_data = (unsigned long)&at91sam9x5_ops,
+	}, {
+		/* sentinel */
+	},
+};
+
+static struct driver_d at91_pinctrl_driver = {
+	.name = "pinctrl-at91",
+	.probe = at91_pinctrl_probe,
+	.id_table = at91_pinctrl_ids,
+	.of_compatible = DRV_OF_COMPAT(at91_pinctrl_dt_ids),
+};
+
+static int at91_pinctrl_init(void)
+{
+	return platform_driver_register(&at91_pinctrl_driver);
+}
+coredevice_initcall(at91_pinctrl_init);
+
+static int at91_gpio_get(struct gpio_chip *chip, unsigned offset)
+{
+	struct at91_gpio_chip *at91_gpio = to_at91_gpio_chip(chip);
+	void __iomem *pio = at91_gpio->regbase;
+	unsigned mask = 1 << offset;
+
+	return at91_mux_gpio_get(pio, mask);
+}
+
+static void at91_gpio_set(struct gpio_chip *chip, unsigned offset, int value)
+{
+	struct at91_gpio_chip *at91_gpio = to_at91_gpio_chip(chip);
+	void __iomem *pio = at91_gpio->regbase;
+	unsigned mask = 1 << offset;
+
+	at91_mux_gpio_set(pio, mask, value);
+}
+
+static int at91_gpio_direction_output(struct gpio_chip *chip, unsigned offset,
+		int value)
+{
+	struct at91_gpio_chip *at91_gpio = to_at91_gpio_chip(chip);
+	void __iomem *pio = at91_gpio->regbase;
+	unsigned mask = 1 << offset;
+
+	at91_mux_gpio_set(pio, mask, value);
+	__raw_writel(mask, pio + PIO_OER);
+
+	return 0;
+}
+
+static int at91_gpio_direction_input(struct gpio_chip *chip, unsigned offset)
+{
+	struct at91_gpio_chip *at91_gpio = to_at91_gpio_chip(chip);
+	void __iomem *pio = at91_gpio->regbase;
+	unsigned mask = 1 << offset;
+
+	__raw_writel(mask, pio + PIO_ODR);
+
+	return 0;
+}
+
+static int at91_gpio_request(struct gpio_chip *chip, unsigned offset)
+{
+	struct at91_gpio_chip *at91_gpio = to_at91_gpio_chip(chip);
+	void __iomem *pio = at91_gpio->regbase;
+	unsigned mask = 1 << offset;
+
+	dev_dbg(chip->dev, "%s:%d pio%c%d(%d)\n", __func__, __LINE__,
+		 'A' + pin_to_bank(chip->base), offset, chip->base + offset);
+	at91_mux_gpio_enable(pio, mask);
+
+	return 0;
+}
+
+static void at91_gpio_free(struct gpio_chip *chip, unsigned offset)
+{
+	dev_dbg(chip->dev, "%s:%d pio%c%d(%d)\n", __func__, __LINE__,
+		 'A' + pin_to_bank(chip->base), offset, chip->base + offset);
+}
+
+static struct gpio_ops at91_gpio_ops = {
+	.request = at91_gpio_request,
+	.free = at91_gpio_free,
+	.direction_input = at91_gpio_direction_input,
+	.direction_output = at91_gpio_direction_output,
+	.get = at91_gpio_get,
+	.set = at91_gpio_set,
+};
+
+static struct of_device_id at91_gpio_dt_ids[] = {
+	{
+		.compatible = "atmel,at91rm9200-gpio",
+	}, {
+		.compatible = "atmel,at91sam9x5-gpio",
+	}, {
+		/* sentinel */
+	},
+};
+
+static int at91_gpio_probe(struct device_d *dev)
+{
+	struct at91_gpio_chip *at91_gpio;
+	struct clk *clk;
+	int ret;
+	int alias_idx = of_alias_get_id(dev->device_node, "gpio");
+
+	BUG_ON(dev->id > MAX_GPIO_BANKS);
+
+	at91_gpio = &gpio_chip[alias_idx];
+
+	clk = clk_get(dev, NULL);
+	if (IS_ERR(clk)) {
+		ret = PTR_ERR(clk);
+		dev_err(dev, "clock not found: %d\n", ret);
+		return ret;
+	}
+
+	ret = clk_enable(clk);
+	if (ret < 0) {
+		dev_err(dev, "clock failed to enable: %d\n", ret);
+		clk_put(clk);
+		return ret;
+	}
+
+	gpio_banks = max(gpio_banks, alias_idx + 1);
+	at91_gpio->regbase = dev_request_mem_region(dev, 0);
+
+	at91_gpio->chip.ops = &at91_gpio_ops;
+	at91_gpio->chip.ngpio = MAX_NB_GPIO_PER_BANK;
+	at91_gpio->chip.dev = dev;
+	at91_gpio->chip.base = dev->id * MAX_NB_GPIO_PER_BANK;
+
+	ret = gpiochip_add(&at91_gpio->chip);
+	if (ret) {
+		dev_err(dev, "couldn't add gpiochip, ret = %d\n", ret);
+		return ret;
+	}
+
+	dev_info(dev, "AT91 gpio driver registred\n");
+
+	return 0;
+}
+
+static struct platform_device_id at91_gpio_ids[] = {
+	{
+		.name = "at91rm9200-gpio",
+	}, {
+		.name = "at91sam9x5-gpio",
+	}, {
+		/* sentinel */
+	},
+};
+
+static struct driver_d at91_gpio_driver = {
+	.name = "gpio-at91",
+	.probe = at91_gpio_probe,
+	.id_table = at91_gpio_ids,
+	.of_compatible	= DRV_OF_COMPAT(at91_gpio_dt_ids),
+};
+
+static int at91_gpio_init(void)
+{
+	return platform_driver_register(&at91_gpio_driver);
+}
+coredevice_initcall(at91_gpio_init);
diff --git a/drivers/pinctrl/pinctrl-at91.h b/drivers/pinctrl/pinctrl-at91.h
new file mode 100644
index 0000000..e719fb8
--- /dev/null
+++ b/drivers/pinctrl/pinctrl-at91.h
@@ -0,0 +1,148 @@
+/*
+ * Copyright (C) 2011-2012 Jean-Christophe PLAGNIOL-VILLARD <plagnioj@jcrosoft.com>
+ *
+ * Under GPLv2 only
+ */
+
+#ifndef __AT91_GPIO_H__
+#define __AT91_GPIO_H__
+
+#ifndef __gpio_init
+#define __gpio_init
+#endif
+
+#define MAX_NB_GPIO_PER_BANK	32
+
+static inline unsigned pin_to_bank(unsigned pin)
+{
+	return pin / MAX_NB_GPIO_PER_BANK;
+}
+
+static inline unsigned pin_to_bank_offset(unsigned pin)
+{
+	return pin % MAX_NB_GPIO_PER_BANK;
+}
+
+static inline unsigned pin_to_mask(unsigned pin)
+{
+	return 1 << pin_to_bank_offset(pin);
+}
+
+static inline void at91_mux_disable_interrupt(void __iomem *pio, unsigned mask)
+{
+	__raw_writel(mask, pio + PIO_IDR);
+}
+
+static inline void at91_mux_set_pullup(void __iomem *pio, unsigned mask, bool on)
+{
+	__raw_writel(mask, pio + (on ? PIO_PUER : PIO_PUDR));
+}
+
+static inline void at91_mux_set_multidrive(void __iomem *pio, unsigned mask, bool on)
+{
+	__raw_writel(mask, pio + (on ? PIO_MDER : PIO_MDDR));
+}
+
+static inline void at91_mux_set_A_periph(void __iomem *pio, unsigned mask)
+{
+	__raw_writel(mask, pio + PIO_ASR);
+}
+
+static inline void at91_mux_set_B_periph(void __iomem *pio, unsigned mask)
+{
+	__raw_writel(mask, pio + PIO_BSR);
+}
+
+static inline void at91_mux_pio3_set_A_periph(void __iomem *pio, unsigned mask)
+{
+
+	__raw_writel(__raw_readl(pio + PIO_ABCDSR1) & ~mask,
+						pio + PIO_ABCDSR1);
+	__raw_writel(__raw_readl(pio + PIO_ABCDSR2) & ~mask,
+						pio + PIO_ABCDSR2);
+}
+
+static inline void at91_mux_pio3_set_B_periph(void __iomem *pio, unsigned mask)
+{
+	__raw_writel(__raw_readl(pio + PIO_ABCDSR1) | mask,
+						pio + PIO_ABCDSR1);
+	__raw_writel(__raw_readl(pio + PIO_ABCDSR2) & ~mask,
+						pio + PIO_ABCDSR2);
+}
+
+static inline void at91_mux_pio3_set_C_periph(void __iomem *pio, unsigned mask)
+{
+	__raw_writel(__raw_readl(pio + PIO_ABCDSR1) & ~mask, pio + PIO_ABCDSR1);
+	__raw_writel(__raw_readl(pio + PIO_ABCDSR2) | mask, pio + PIO_ABCDSR2);
+}
+
+static inline void at91_mux_pio3_set_D_periph(void __iomem *pio, unsigned mask)
+{
+	__raw_writel(__raw_readl(pio + PIO_ABCDSR1) | mask, pio + PIO_ABCDSR1);
+	__raw_writel(__raw_readl(pio + PIO_ABCDSR2) | mask, pio + PIO_ABCDSR2);
+}
+
+static inline void at91_mux_set_deglitch(void __iomem *pio, unsigned mask, bool is_on)
+{
+	__raw_writel(mask, pio + (is_on ? PIO_IFER : PIO_IFDR));
+}
+
+static inline void at91_mux_pio3_set_deglitch(void __iomem *pio, unsigned mask, bool is_on)
+{
+	if (is_on)
+		__raw_writel(mask, pio + PIO_IFSCDR);
+	at91_mux_set_deglitch(pio, mask, is_on);
+}
+
+static inline void at91_mux_pio3_set_debounce(void __iomem *pio, unsigned mask,
+				bool is_on, u32 div)
+{
+	if (is_on) {
+		__raw_writel(mask, pio + PIO_IFSCER);
+		__raw_writel(div & PIO_SCDR_DIV, pio + PIO_SCDR);
+		__raw_writel(mask, pio + PIO_IFER);
+	} else {
+		__raw_writel(mask, pio + PIO_IFDR);
+	}
+}
+
+static inline void at91_mux_pio3_set_pulldown(void __iomem *pio, unsigned mask, bool is_on)
+{
+	__raw_writel(mask, pio + (is_on ? PIO_PPDER : PIO_PPDDR));
+}
+
+static inline void at91_mux_pio3_disable_schmitt_trig(void __iomem *pio, unsigned mask)
+{
+	__raw_writel(__raw_readl(pio + PIO_SCHMITT) | mask, pio + PIO_SCHMITT);
+}
+
+static inline void at91_mux_gpio_disable(void __iomem *pio, unsigned mask)
+{
+	__raw_writel(mask, pio + PIO_PDR);
+}
+
+static inline void at91_mux_gpio_enable(void __iomem *pio, unsigned mask)
+{
+	__raw_writel(mask, pio + PIO_PER);
+}
+
+static inline void at91_mux_gpio_input(void __iomem *pio, unsigned mask, bool input)
+{
+	__raw_writel(mask, pio + (input ? PIO_ODR : PIO_OER));
+}
+
+static inline void at91_mux_gpio_set(void __iomem *pio, unsigned mask,
+int value)
+{
+	__raw_writel(mask, pio + (value ? PIO_SODR : PIO_CODR));
+}
+
+static inline int at91_mux_gpio_get(void __iomem *pio, unsigned mask)
+{
+       u32 pdsr;
+
+       pdsr = __raw_readl(pio + PIO_PDSR);
+       return (pdsr & mask) != 0;
+}
+
+#endif /* __AT91_GPIO_H__ */
-- 
1.7.9.5


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

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

* [PATCH 2/2] at91sam9g45: add device tree gpio clocks
  2014-08-01 13:24 [PATCH 0/2] Add atmel pinctrl driver Raphaël Poggi
  2014-08-01 13:24 ` [PATCH 1/2] pinctrl: at91: add " Raphaël Poggi
@ 2014-08-01 13:24 ` Raphaël Poggi
  1 sibling, 0 replies; 10+ messages in thread
From: Raphaël Poggi @ 2014-08-01 13:24 UTC (permalink / raw)
  To: barebox; +Cc: Raphaël Poggi

Signed-off-by: Raphaël Poggi <poggi.raph@gmail.com>
---
 arch/arm/mach-at91/at91sam9g45.c |    5 +++++
 1 file changed, 5 insertions(+)

diff --git a/arch/arm/mach-at91/at91sam9g45.c b/arch/arm/mach-at91/at91sam9g45.c
index 9a50deb..f6031f0 100644
--- a/arch/arm/mach-at91/at91sam9g45.c
+++ b/arch/arm/mach-at91/at91sam9g45.c
@@ -197,6 +197,11 @@ static struct clk_lookup periph_clocks_lookups[] = {
 	CLKDEV_DEV_ID("at91rm9200-gpio2", &pioC_clk),
 	CLKDEV_DEV_ID("at91rm9200-gpio3", &pioDE_clk),
 	CLKDEV_DEV_ID("at91rm9200-gpio4", &pioDE_clk),
+	CLKDEV_CON_DEV_ID(NULL, "fffff200.gpio", &pioA_clk),
+	CLKDEV_CON_DEV_ID(NULL, "fffff400.gpio", &pioB_clk),
+	CLKDEV_CON_DEV_ID(NULL, "fffff600.gpio", &pioC_clk),
+	CLKDEV_CON_DEV_ID(NULL, "fffff800.gpio", &pioDE_clk),
+	CLKDEV_CON_DEV_ID(NULL, "fffffa00.gpio", &pioDE_clk),
 	CLKDEV_DEV_ID("at91-pit", &mck),
 	CLKDEV_CON_DEV_ID("hck1", "atmel_lcdfb", &lcdc_clk),
 };
-- 
1.7.9.5


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

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

* Re: [PATCH 1/2] pinctrl: at91: add pinctrl driver
  2014-08-01 13:24 ` [PATCH 1/2] pinctrl: at91: add " Raphaël Poggi
@ 2014-08-04 18:22   ` Sascha Hauer
  2014-08-04 18:26   ` Jean-Christophe PLAGNIOL-VILLARD
  1 sibling, 0 replies; 10+ messages in thread
From: Sascha Hauer @ 2014-08-04 18:22 UTC (permalink / raw)
  To: Raphaël Poggi; +Cc: barebox

Looks mostly fine.

On Fri, Aug 01, 2014 at 03:24:23PM +0200, Raphaël Poggi wrote:
> This driver is based on mach-at91/gpio.c and linux pinctrl driver.
> The driver contains the gpio and pinctrl parts (like in linux) because the two parts
> share some structures and logics.
> 
> Signed-off-by: Raphaël Poggi <poggi.raph@gmail.com>
> ---
> +static struct at91_pinctrl_mux_ops *at91_pinctrl_get_driver_data(struct device_d *dev)
> +{
> +    struct at91_pinctrl_mux_ops *ops_data = NULL;
> +    int rc;
> +
> +    if (dev->device_node) {
> +	    const struct of_device_id *match;
> +	    match = of_match_node(at91_pinctrl_dt_ids, dev->device_node);
> +	    if (!match)
> +			ops_data = NULL;
> +	    else
> +			ops_data = (struct at91_pinctrl_mux_ops *)match->data;
> +    }
> +    else {
> +	    rc = dev_get_drvdata(dev, (unsigned long *)&ops_data);
> +		if (rc)
> +		ops_data = NULL;
> +    }

Indentation looks garbled in this function.

> +
> +	ret = pinctrl_register(&info->pctl);
> +	if (ret)
> +		return ret;
> +
> +	dev_info(dev, "AT91 pinctrl registred\n");

s/registred/registered/

> +
> +	ret = gpiochip_add(&at91_gpio->chip);
> +	if (ret) {
> +		dev_err(dev, "couldn't add gpiochip, ret = %d\n", ret);
> +		return ret;
> +	}
> +
> +	dev_info(dev, "AT91 gpio driver registred\n");

here aswell.

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] 10+ messages in thread

* Re: [PATCH 1/2] pinctrl: at91: add pinctrl driver
  2014-08-01 13:24 ` [PATCH 1/2] pinctrl: at91: add " Raphaël Poggi
  2014-08-04 18:22   ` Sascha Hauer
@ 2014-08-04 18:26   ` Jean-Christophe PLAGNIOL-VILLARD
  2014-08-04 18:37     ` Raphaël Poggi
  1 sibling, 1 reply; 10+ messages in thread
From: Jean-Christophe PLAGNIOL-VILLARD @ 2014-08-04 18:26 UTC (permalink / raw)
  To: Raphaël Poggi; +Cc: barebox

why do we need it on barebox?

this driver was design for dt-only in linux

Best Regards,
J.
On Aug 1, 2014, at 9:24 PM, Raphaël Poggi <poggi.raph@gmail.com> wrote:

> This driver is based on mach-at91/gpio.c and linux pinctrl driver.
> The driver contains the gpio and pinctrl parts (like in linux) because the two parts
> share some structures and logics.
> 
> Signed-off-by: Raphaël Poggi <poggi.raph@gmail.com>
> ---
> drivers/pinctrl/Kconfig        |    6 +
> drivers/pinctrl/Makefile       |    1 +
> drivers/pinctrl/pinctrl-at91.c |  529 ++++++++++++++++++++++++++++++++++++++++
> drivers/pinctrl/pinctrl-at91.h |  148 +++++++++++
> 4 files changed, 684 insertions(+)
> create mode 100644 drivers/pinctrl/pinctrl-at91.c
> create mode 100644 drivers/pinctrl/pinctrl-at91.h
> 
> diff --git a/drivers/pinctrl/Kconfig b/drivers/pinctrl/Kconfig
> index dffaa4e..ce55c7b 100644
> --- a/drivers/pinctrl/Kconfig
> +++ b/drivers/pinctrl/Kconfig
> @@ -7,6 +7,12 @@ config PINCTRL
> 	  from the devicetree. Legacy drivers here may not need this core
> 	  support but instead provide their own SoC specific APIs
> 
> +config PINCTRL_AT91
> +	select PINCTRL
> +	bool
> +	help
> +	    The pinmux controller found on AT91 SoCs.
> +
> config PINCTRL_IMX_IOMUX_V1
> 	select PINCTRL if OFDEVICE
> 	bool
> diff --git a/drivers/pinctrl/Makefile b/drivers/pinctrl/Makefile
> index 566ba11..3ea8649 100644
> --- a/drivers/pinctrl/Makefile
> +++ b/drivers/pinctrl/Makefile
> @@ -1,4 +1,5 @@
> obj-$(CONFIG_PINCTRL)	+= pinctrl.o
> +obj-$(CONFIG_PINCTRL_AT91) += pinctrl-at91.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
> diff --git a/drivers/pinctrl/pinctrl-at91.c b/drivers/pinctrl/pinctrl-at91.c
> new file mode 100644
> index 0000000..a92a898
> --- /dev/null
> +++ b/drivers/pinctrl/pinctrl-at91.c
> @@ -0,0 +1,529 @@
> +/*
> + * Copyright (C) 2005 HP Labs
> + * Copyright (C) 2011-2012 Jean-Christophe PLAGNIOL-VILLARD <plagnioj@jcrosoft.com>
> + * Copyright (C) 2014 Raphaël Poggi
> + *
> + * See file CREDITS for list of people who contributed to this
> + * project.
> + *
> + * 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 <command.h>
> +#include <complete.h>
> +#include <linux/clk.h>
> +#include <linux/err.h>
> +#include <errno.h>
> +#include <io.h>
> +#include <gpio.h>
> +#include <init.h>
> +#include <driver.h>
> +#include <getopt.h>
> +
> +#include <mach/at91_pio.h>
> +
> +#include <pinctrl.h>
> +
> +#include "pinctrl-at91.h"
> +
> +struct at91_pinctrl {
> +    struct pinctrl_device pctl;
> +    struct at91_pinctrl_mux_ops	*ops;
> +};
> +
> +struct at91_gpio_chip {
> +	struct gpio_chip	chip;
> +	void __iomem		*regbase;	/* PIO bank virtual address */
> +	struct at91_pinctrl_mux_ops *ops;	/* ops */
> +};
> +
> +enum at91_mux {
> +	AT91_MUX_GPIO = 0,
> +	AT91_MUX_PERIPH_A = 1,
> +	AT91_MUX_PERIPH_B = 2,
> +	AT91_MUX_PERIPH_C = 3,
> +	AT91_MUX_PERIPH_D = 4,
> +};
> +
> +#define MAX_GPIO_BANKS		5
> +#define to_at91_pinctrl(c) container_of(c, struct at91_pinctrl, pctl);
> +#define to_at91_gpio_chip(c) container_of(c, struct at91_gpio_chip, chip)
> +
> +#define PULL_UP         (1 << 0)
> +#define MULTI_DRIVE     (1 << 1)
> +#define DEGLITCH        (1 << 2)
> +#define PULL_DOWN       (1 << 3)
> +#define DIS_SCHMIT      (1 << 4)
> +#define DEBOUNCE        (1 << 16)
> +#define DEBOUNCE_VAL_SHIFT      17
> +#define DEBOUNCE_VAL    (0x3fff << DEBOUNCE_VAL_SHIFT)
> +
> +static int gpio_banks = 0;
> +
> +static struct at91_gpio_chip gpio_chip[MAX_GPIO_BANKS];
> +
> +static inline void __iomem *pin_to_controller(struct at91_pinctrl *info, unsigned pin)
> +{
> +	pin /= MAX_NB_GPIO_PER_BANK;
> +	if (likely(pin < gpio_banks))
> +		return gpio_chip[pin].regbase;
> +
> +	return NULL;
> +}
> +
> +/**
> + * struct at91_pinctrl_mux_ops - describes an At91 mux ops group
> + * on new IP with support for periph C and D the way to mux in
> + * periph A and B has changed
> + * So provide the right call back
> + * if not present means the IP does not support it
> + * @get_periph: return the periph mode configured
> + * @mux_A_periph: mux as periph A
> + * @mux_B_periph: mux as periph B
> + * @mux_C_periph: mux as periph C
> + * @mux_D_periph: mux as periph D
> + * @set_deglitch: enable/disable deglitch
> + * @set_debounce: enable/disable debounce
> + * @set_pulldown: enable/disable pulldown
> + * @disable_schmitt_trig: disable schmitt trigger
> + */
> +struct at91_pinctrl_mux_ops {
> +	enum at91_mux (*get_periph)(void __iomem *pio, unsigned mask);
> +	void (*mux_A_periph)(void __iomem *pio, unsigned mask);
> +	void (*mux_B_periph)(void __iomem *pio, unsigned mask);
> +	void (*mux_C_periph)(void __iomem *pio, unsigned mask);
> +	void (*mux_D_periph)(void __iomem *pio, unsigned mask);
> +	bool (*get_deglitch)(void __iomem *pio, unsigned pin);
> +	void (*set_deglitch)(void __iomem *pio, unsigned mask, bool in_on);
> +	bool (*get_debounce)(void __iomem *pio, unsigned pin, u32 *div);
> +	void (*set_debounce)(void __iomem *pio, unsigned mask, bool in_on, u32 div);
> +	bool (*get_pulldown)(void __iomem *pio, unsigned pin);
> +	void (*set_pulldown)(void __iomem *pio, unsigned mask, bool in_on);
> +	bool (*get_schmitt_trig)(void __iomem *pio, unsigned pin);
> +	void (*disable_schmitt_trig)(void __iomem *pio, unsigned mask);
> +};
> +
> +static enum at91_mux at91_mux_pio3_get_periph(void __iomem *pio, unsigned mask)
> +{
> +	unsigned select;
> +
> +	if (__raw_readl(pio + PIO_PSR) & mask)
> +		return AT91_MUX_GPIO;
> +
> +	select = !!(__raw_readl(pio + PIO_ABCDSR1) & mask);
> +	select |= (!!(__raw_readl(pio + PIO_ABCDSR2) & mask) << 1);
> +
> +	return select + 1;
> +}
> +
> +static enum at91_mux at91_mux_get_periph(void __iomem *pio, unsigned mask)
> +{
> +	unsigned select;
> +
> +	if (__raw_readl(pio + PIO_PSR) & mask)
> +		return AT91_MUX_GPIO;
> +
> +	select = __raw_readl(pio + PIO_ABSR) & mask;
> +
> +	return select + 1;
> +}
> +
> +static bool at91_mux_get_deglitch(void __iomem *pio, unsigned pin)
> +{
> +	return (__raw_readl(pio + PIO_IFSR) >> pin) & 0x1;
> +}
> +
> +static bool at91_mux_pio3_get_debounce(void __iomem *pio, unsigned pin, u32 *div)
> +{
> +	*div = __raw_readl(pio + PIO_SCDR);
> +
> +	return (__raw_readl(pio + PIO_IFSCSR) >> pin) & 0x1;
> +}
> +
> +static bool at91_mux_pio3_get_pulldown(void __iomem *pio, unsigned pin)
> +{
> +	return (__raw_readl(pio + PIO_PPDSR) >> pin) & 0x1;
> +}
> +
> +static bool at91_mux_pio3_get_schmitt_trig(void __iomem *pio, unsigned pin)
> +{
> +	return (__raw_readl(pio + PIO_SCHMITT) >> pin) & 0x1;
> +}
> +
> +static struct at91_pinctrl_mux_ops at91rm9200_ops = {
> +	.get_periph	= at91_mux_get_periph,
> +	.mux_A_periph	= at91_mux_set_A_periph,
> +	.mux_B_periph	= at91_mux_set_B_periph,
> +	.get_deglitch	= at91_mux_get_deglitch,
> +	.set_deglitch	= at91_mux_set_deglitch,
> +};
> +
> +static struct at91_pinctrl_mux_ops at91sam9x5_ops = {
> +	.get_periph	= at91_mux_pio3_get_periph,
> +	.mux_A_periph	= at91_mux_pio3_set_A_periph,
> +	.mux_B_periph	= at91_mux_pio3_set_B_periph,
> +	.mux_C_periph	= at91_mux_pio3_set_C_periph,
> +	.mux_D_periph	= at91_mux_pio3_set_D_periph,
> +	.get_deglitch	= at91_mux_get_deglitch,
> +	.set_deglitch	= at91_mux_pio3_set_deglitch,
> +	.get_debounce	= at91_mux_pio3_get_debounce,
> +	.set_debounce	= at91_mux_pio3_set_debounce,
> +	.get_pulldown	= at91_mux_pio3_get_pulldown,
> +	.set_pulldown	= at91_mux_pio3_set_pulldown,
> +	.get_schmitt_trig = at91_mux_pio3_get_schmitt_trig,
> +	.disable_schmitt_trig = at91_mux_pio3_disable_schmitt_trig,
> +};
> +
> +static int at91_mux_pin(struct at91_pinctrl *info, unsigned pin, enum at91_mux mux, int use_pullup)
> +{
> +	void __iomem	*pio = pin_to_controller(info, pin);
> +	unsigned mask = pin_to_mask(pin);
> +
> +	if (!info)
> +		return -EINVAL;
> +
> +	if (!pio)
> +		return -EINVAL;
> +
> +	at91_mux_disable_interrupt(pio, mask);
> +
> +	switch(mux) {
> +	case AT91_MUX_GPIO:
> +		at91_mux_gpio_enable(pio, mask);
> +		break;
> +	case AT91_MUX_PERIPH_A:
> +		info->ops->mux_A_periph(pio, mask);
> +		break;
> +	case AT91_MUX_PERIPH_B:
> +		info->ops->mux_B_periph(pio, mask);
> +		break;
> +	case AT91_MUX_PERIPH_C:
> +		if (!info->ops->mux_C_periph)
> +			return -EINVAL;
> +		info->ops->mux_C_periph(pio, mask);
> +		break;
> +	case AT91_MUX_PERIPH_D:
> +		if (!info->ops->mux_D_periph)
> +			return -EINVAL;
> +		info->ops->mux_D_periph(pio, mask);
> +		break;
> +	}
> +	if (mux)
> +		at91_mux_gpio_disable(pio, mask);
> +
> +	if (use_pullup >= 0)
> +		at91_mux_set_pullup(pio, mask, use_pullup);
> +
> +	return 0;
> +}
> +
> +static struct of_device_id at91_pinctrl_dt_ids[] = {
> +	{
> +		.compatible = "atmel,at91rm9200-pinctrl",
> +		.data = (unsigned long)&at91rm9200_ops,
> +	}, {
> +		.compatible = "atmel,at91sam9x5-pinctrl",
> +		.data = (unsigned long)&at91sam9x5_ops,
> +	}, {
> +		/* sentinel */
> +	}
> +};
> +
> +static struct at91_pinctrl_mux_ops *at91_pinctrl_get_driver_data(struct device_d *dev)
> +{
> +    struct at91_pinctrl_mux_ops *ops_data = NULL;
> +    int rc;
> +
> +    if (dev->device_node) {
> +	    const struct of_device_id *match;
> +	    match = of_match_node(at91_pinctrl_dt_ids, dev->device_node);
> +	    if (!match)
> +			ops_data = NULL;
> +	    else
> +			ops_data = (struct at91_pinctrl_mux_ops *)match->data;
> +    }
> +    else {
> +	    rc = dev_get_drvdata(dev, (unsigned long *)&ops_data);
> +		if (rc)
> +		ops_data = NULL;
> +    }
> +
> +    return ops_data;
> +}
> +
> +static int at91_pinctrl_set_conf(struct at91_pinctrl *info, unsigned int pin_num, unsigned int mux, unsigned int conf)
> +{
> +	unsigned int mask;
> +	void __iomem *pio;
> +
> +	pio = pin_to_controller(info, pin_num);
> +	mask = pin_to_mask(pin_num);
> +
> +	if (conf & PULL_UP && conf & PULL_DOWN)
> +		return -EINVAL;
> +
> +	at91_mux_set_pullup(pio, mask, conf & PULL_UP);
> +	at91_mux_set_multidrive(pio, mask, conf & MULTI_DRIVE);
> +	if (info->ops->set_deglitch)
> +		info->ops->set_deglitch(pio, mask, conf & DEGLITCH);
> +	if (info->ops->set_debounce)
> +		info->ops->set_debounce(pio, mask, conf & DEBOUNCE,
> +			(conf & DEBOUNCE_VAL) >> DEBOUNCE_VAL_SHIFT);
> +	if (info->ops->set_pulldown)
> +		info->ops->set_pulldown(pio, mask, conf & PULL_DOWN);
> +	if (info->ops->disable_schmitt_trig && conf & DIS_SCHMIT)
> +		info->ops->disable_schmitt_trig(pio, mask);
> +
> +	return 0;
> +}
> +
> +static int at91_pinctrl_set_state(struct pinctrl_device *pdev, struct device_node *np)
> +{
> +	struct at91_pinctrl *info;
> +	const __be32 *list;
> +	int i, size;
> +	int ret = 0;
> +	int bank_num, pin_num, mux, conf;
> +
> +	info = to_at91_pinctrl(pdev);
> +
> +	list = of_get_property(np, "atmel,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) {
> +		bank_num = be32_to_cpu(*list++);
> +		pin_num = be32_to_cpu(*list++);
> +		mux = be32_to_cpu(*list++);
> +		conf = be32_to_cpu(*list++);
> +
> +		ret = at91_mux_pin(info, pin_num, mux, conf & PULL_UP);
> +		if (ret) {
> +			dev_err(pdev->dev, "failed to mux pin %d\n", pin_num);
> +			return ret;
> +		}
> +
> +		ret = at91_pinctrl_set_conf(info, pin_num, mux, conf);
> +		if (ret) {
> +			dev_err(pdev->dev, "failed to set conf on pin %d\n", pin_num);
> +			return ret;
> +		}
> +	}
> +
> +	return ret;
> +}
> +
> +static struct pinctrl_ops at91_pinctrl_ops = {
> +	.set_state = at91_pinctrl_set_state,
> +};
> +
> +static int at91_pinctrl_probe(struct device_d *dev)
> +{
> +	struct at91_pinctrl *info;
> +	int ret;
> +
> +	info = xzalloc(sizeof(struct at91_pinctrl));
> +
> +	info->ops = at91_pinctrl_get_driver_data(dev);
> +	if (!info->ops) {
> +		dev_err(dev, "failed to retrieve driver data\n");
> +		return -ENODEV;
> +	}
> +
> +	info->pctl.dev = dev;
> +	info->pctl.ops = &at91_pinctrl_ops;
> +
> +	ret = pinctrl_register(&info->pctl);
> +	if (ret)
> +		return ret;
> +
> +	dev_info(dev, "AT91 pinctrl registred\n");
> +
> +	return 0;
> +}
> +
> +static struct platform_device_id at91_pinctrl_ids[] = {
> +	{
> +		.name = "at91rm9200-pinctrl",
> +		.driver_data = (unsigned long)&at91rm9200_ops,
> +	}, {
> +		.name = "at91sam9x5-pinctrl",
> +		.driver_data = (unsigned long)&at91sam9x5_ops,
> +	}, {
> +		/* sentinel */
> +	},
> +};
> +
> +static struct driver_d at91_pinctrl_driver = {
> +	.name = "pinctrl-at91",
> +	.probe = at91_pinctrl_probe,
> +	.id_table = at91_pinctrl_ids,
> +	.of_compatible = DRV_OF_COMPAT(at91_pinctrl_dt_ids),
> +};
> +
> +static int at91_pinctrl_init(void)
> +{
> +	return platform_driver_register(&at91_pinctrl_driver);
> +}
> +coredevice_initcall(at91_pinctrl_init);
> +
> +static int at91_gpio_get(struct gpio_chip *chip, unsigned offset)
> +{
> +	struct at91_gpio_chip *at91_gpio = to_at91_gpio_chip(chip);
> +	void __iomem *pio = at91_gpio->regbase;
> +	unsigned mask = 1 << offset;
> +
> +	return at91_mux_gpio_get(pio, mask);
> +}
> +
> +static void at91_gpio_set(struct gpio_chip *chip, unsigned offset, int value)
> +{
> +	struct at91_gpio_chip *at91_gpio = to_at91_gpio_chip(chip);
> +	void __iomem *pio = at91_gpio->regbase;
> +	unsigned mask = 1 << offset;
> +
> +	at91_mux_gpio_set(pio, mask, value);
> +}
> +
> +static int at91_gpio_direction_output(struct gpio_chip *chip, unsigned offset,
> +		int value)
> +{
> +	struct at91_gpio_chip *at91_gpio = to_at91_gpio_chip(chip);
> +	void __iomem *pio = at91_gpio->regbase;
> +	unsigned mask = 1 << offset;
> +
> +	at91_mux_gpio_set(pio, mask, value);
> +	__raw_writel(mask, pio + PIO_OER);
> +
> +	return 0;
> +}
> +
> +static int at91_gpio_direction_input(struct gpio_chip *chip, unsigned offset)
> +{
> +	struct at91_gpio_chip *at91_gpio = to_at91_gpio_chip(chip);
> +	void __iomem *pio = at91_gpio->regbase;
> +	unsigned mask = 1 << offset;
> +
> +	__raw_writel(mask, pio + PIO_ODR);
> +
> +	return 0;
> +}
> +
> +static int at91_gpio_request(struct gpio_chip *chip, unsigned offset)
> +{
> +	struct at91_gpio_chip *at91_gpio = to_at91_gpio_chip(chip);
> +	void __iomem *pio = at91_gpio->regbase;
> +	unsigned mask = 1 << offset;
> +
> +	dev_dbg(chip->dev, "%s:%d pio%c%d(%d)\n", __func__, __LINE__,
> +		 'A' + pin_to_bank(chip->base), offset, chip->base + offset);
> +	at91_mux_gpio_enable(pio, mask);
> +
> +	return 0;
> +}
> +
> +static void at91_gpio_free(struct gpio_chip *chip, unsigned offset)
> +{
> +	dev_dbg(chip->dev, "%s:%d pio%c%d(%d)\n", __func__, __LINE__,
> +		 'A' + pin_to_bank(chip->base), offset, chip->base + offset);
> +}
> +
> +static struct gpio_ops at91_gpio_ops = {
> +	.request = at91_gpio_request,
> +	.free = at91_gpio_free,
> +	.direction_input = at91_gpio_direction_input,
> +	.direction_output = at91_gpio_direction_output,
> +	.get = at91_gpio_get,
> +	.set = at91_gpio_set,
> +};
> +
> +static struct of_device_id at91_gpio_dt_ids[] = {
> +	{
> +		.compatible = "atmel,at91rm9200-gpio",
> +	}, {
> +		.compatible = "atmel,at91sam9x5-gpio",
> +	}, {
> +		/* sentinel */
> +	},
> +};
> +
> +static int at91_gpio_probe(struct device_d *dev)
> +{
> +	struct at91_gpio_chip *at91_gpio;
> +	struct clk *clk;
> +	int ret;
> +	int alias_idx = of_alias_get_id(dev->device_node, "gpio");
> +
> +	BUG_ON(dev->id > MAX_GPIO_BANKS);
> +
> +	at91_gpio = &gpio_chip[alias_idx];
> +
> +	clk = clk_get(dev, NULL);
> +	if (IS_ERR(clk)) {
> +		ret = PTR_ERR(clk);
> +		dev_err(dev, "clock not found: %d\n", ret);
> +		return ret;
> +	}
> +
> +	ret = clk_enable(clk);
> +	if (ret < 0) {
> +		dev_err(dev, "clock failed to enable: %d\n", ret);
> +		clk_put(clk);
> +		return ret;
> +	}
> +
> +	gpio_banks = max(gpio_banks, alias_idx + 1);
> +	at91_gpio->regbase = dev_request_mem_region(dev, 0);
> +
> +	at91_gpio->chip.ops = &at91_gpio_ops;
> +	at91_gpio->chip.ngpio = MAX_NB_GPIO_PER_BANK;
> +	at91_gpio->chip.dev = dev;
> +	at91_gpio->chip.base = dev->id * MAX_NB_GPIO_PER_BANK;
> +
> +	ret = gpiochip_add(&at91_gpio->chip);
> +	if (ret) {
> +		dev_err(dev, "couldn't add gpiochip, ret = %d\n", ret);
> +		return ret;
> +	}
> +
> +	dev_info(dev, "AT91 gpio driver registred\n");
> +
> +	return 0;
> +}
> +
> +static struct platform_device_id at91_gpio_ids[] = {
> +	{
> +		.name = "at91rm9200-gpio",
> +	}, {
> +		.name = "at91sam9x5-gpio",
> +	}, {
> +		/* sentinel */
> +	},
> +};
> +
> +static struct driver_d at91_gpio_driver = {
> +	.name = "gpio-at91",
> +	.probe = at91_gpio_probe,
> +	.id_table = at91_gpio_ids,
> +	.of_compatible	= DRV_OF_COMPAT(at91_gpio_dt_ids),
> +};
> +
> +static int at91_gpio_init(void)
> +{
> +	return platform_driver_register(&at91_gpio_driver);
> +}
> +coredevice_initcall(at91_gpio_init);
> diff --git a/drivers/pinctrl/pinctrl-at91.h b/drivers/pinctrl/pinctrl-at91.h
> new file mode 100644
> index 0000000..e719fb8
> --- /dev/null
> +++ b/drivers/pinctrl/pinctrl-at91.h
> @@ -0,0 +1,148 @@
> +/*
> + * Copyright (C) 2011-2012 Jean-Christophe PLAGNIOL-VILLARD <plagnioj@jcrosoft.com>
> + *
> + * Under GPLv2 only
> + */
> +
> +#ifndef __AT91_GPIO_H__
> +#define __AT91_GPIO_H__
> +
> +#ifndef __gpio_init
> +#define __gpio_init
> +#endif
> +
> +#define MAX_NB_GPIO_PER_BANK	32
> +
> +static inline unsigned pin_to_bank(unsigned pin)
> +{
> +	return pin / MAX_NB_GPIO_PER_BANK;
> +}
> +
> +static inline unsigned pin_to_bank_offset(unsigned pin)
> +{
> +	return pin % MAX_NB_GPIO_PER_BANK;
> +}
> +
> +static inline unsigned pin_to_mask(unsigned pin)
> +{
> +	return 1 << pin_to_bank_offset(pin);
> +}
> +
> +static inline void at91_mux_disable_interrupt(void __iomem *pio, unsigned mask)
> +{
> +	__raw_writel(mask, pio + PIO_IDR);
> +}
> +
> +static inline void at91_mux_set_pullup(void __iomem *pio, unsigned mask, bool on)
> +{
> +	__raw_writel(mask, pio + (on ? PIO_PUER : PIO_PUDR));
> +}
> +
> +static inline void at91_mux_set_multidrive(void __iomem *pio, unsigned mask, bool on)
> +{
> +	__raw_writel(mask, pio + (on ? PIO_MDER : PIO_MDDR));
> +}
> +
> +static inline void at91_mux_set_A_periph(void __iomem *pio, unsigned mask)
> +{
> +	__raw_writel(mask, pio + PIO_ASR);
> +}
> +
> +static inline void at91_mux_set_B_periph(void __iomem *pio, unsigned mask)
> +{
> +	__raw_writel(mask, pio + PIO_BSR);
> +}
> +
> +static inline void at91_mux_pio3_set_A_periph(void __iomem *pio, unsigned mask)
> +{
> +
> +	__raw_writel(__raw_readl(pio + PIO_ABCDSR1) & ~mask,
> +						pio + PIO_ABCDSR1);
> +	__raw_writel(__raw_readl(pio + PIO_ABCDSR2) & ~mask,
> +						pio + PIO_ABCDSR2);
> +}
> +
> +static inline void at91_mux_pio3_set_B_periph(void __iomem *pio, unsigned mask)
> +{
> +	__raw_writel(__raw_readl(pio + PIO_ABCDSR1) | mask,
> +						pio + PIO_ABCDSR1);
> +	__raw_writel(__raw_readl(pio + PIO_ABCDSR2) & ~mask,
> +						pio + PIO_ABCDSR2);
> +}
> +
> +static inline void at91_mux_pio3_set_C_periph(void __iomem *pio, unsigned mask)
> +{
> +	__raw_writel(__raw_readl(pio + PIO_ABCDSR1) & ~mask, pio + PIO_ABCDSR1);
> +	__raw_writel(__raw_readl(pio + PIO_ABCDSR2) | mask, pio + PIO_ABCDSR2);
> +}
> +
> +static inline void at91_mux_pio3_set_D_periph(void __iomem *pio, unsigned mask)
> +{
> +	__raw_writel(__raw_readl(pio + PIO_ABCDSR1) | mask, pio + PIO_ABCDSR1);
> +	__raw_writel(__raw_readl(pio + PIO_ABCDSR2) | mask, pio + PIO_ABCDSR2);
> +}
> +
> +static inline void at91_mux_set_deglitch(void __iomem *pio, unsigned mask, bool is_on)
> +{
> +	__raw_writel(mask, pio + (is_on ? PIO_IFER : PIO_IFDR));
> +}
> +
> +static inline void at91_mux_pio3_set_deglitch(void __iomem *pio, unsigned mask, bool is_on)
> +{
> +	if (is_on)
> +		__raw_writel(mask, pio + PIO_IFSCDR);
> +	at91_mux_set_deglitch(pio, mask, is_on);
> +}
> +
> +static inline void at91_mux_pio3_set_debounce(void __iomem *pio, unsigned mask,
> +				bool is_on, u32 div)
> +{
> +	if (is_on) {
> +		__raw_writel(mask, pio + PIO_IFSCER);
> +		__raw_writel(div & PIO_SCDR_DIV, pio + PIO_SCDR);
> +		__raw_writel(mask, pio + PIO_IFER);
> +	} else {
> +		__raw_writel(mask, pio + PIO_IFDR);
> +	}
> +}
> +
> +static inline void at91_mux_pio3_set_pulldown(void __iomem *pio, unsigned mask, bool is_on)
> +{
> +	__raw_writel(mask, pio + (is_on ? PIO_PPDER : PIO_PPDDR));
> +}
> +
> +static inline void at91_mux_pio3_disable_schmitt_trig(void __iomem *pio, unsigned mask)
> +{
> +	__raw_writel(__raw_readl(pio + PIO_SCHMITT) | mask, pio + PIO_SCHMITT);
> +}
> +
> +static inline void at91_mux_gpio_disable(void __iomem *pio, unsigned mask)
> +{
> +	__raw_writel(mask, pio + PIO_PDR);
> +}
> +
> +static inline void at91_mux_gpio_enable(void __iomem *pio, unsigned mask)
> +{
> +	__raw_writel(mask, pio + PIO_PER);
> +}
> +
> +static inline void at91_mux_gpio_input(void __iomem *pio, unsigned mask, bool input)
> +{
> +	__raw_writel(mask, pio + (input ? PIO_ODR : PIO_OER));
> +}
> +
> +static inline void at91_mux_gpio_set(void __iomem *pio, unsigned mask,
> +int value)
> +{
> +	__raw_writel(mask, pio + (value ? PIO_SODR : PIO_CODR));
> +}
> +
> +static inline int at91_mux_gpio_get(void __iomem *pio, unsigned mask)
> +{
> +       u32 pdsr;
> +
> +       pdsr = __raw_readl(pio + PIO_PDSR);
> +       return (pdsr & mask) != 0;
> +}
> +
> +#endif /* __AT91_GPIO_H__ */
> -- 
> 1.7.9.5
> 
> 
> _______________________________________________
> barebox mailing list
> barebox@lists.infradead.org
> http://lists.infradead.org/mailman/listinfo/barebox


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

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

* Re: [PATCH 1/2] pinctrl: at91: add pinctrl driver
  2014-08-04 18:26   ` Jean-Christophe PLAGNIOL-VILLARD
@ 2014-08-04 18:37     ` Raphaël Poggi
  2014-08-04 18:45       ` Sascha Hauer
  2014-08-05 10:26       ` Jean-Christophe PLAGNIOL-VILLARD
  0 siblings, 2 replies; 10+ messages in thread
From: Raphaël Poggi @ 2014-08-04 18:37 UTC (permalink / raw)
  To: Jean-Christophe PLAGNIOL-VILLARD; +Cc: barebox

I have planned to add device tree support for the AT91 port.

So I port the pinctrl driver from linux to barebox to be able to use
the pinctrl in device tree, but maybe I made a mistake and there is
another solution.

Best Regards,
Raphaël

2014-08-04 20:26 GMT+02:00 Jean-Christophe PLAGNIOL-VILLARD
<plagnioj@jcrosoft.com>:
> why do we need it on barebox?
>
> this driver was design for dt-only in linux
>
> Best Regards,
> J.
> On Aug 1, 2014, at 9:24 PM, Raphaël Poggi <poggi.raph@gmail.com> wrote:
>
>> This driver is based on mach-at91/gpio.c and linux pinctrl driver.
>> The driver contains the gpio and pinctrl parts (like in linux) because the two parts
>> share some structures and logics.
>>
>> Signed-off-by: Raphaël Poggi <poggi.raph@gmail.com>
>> ---
>> drivers/pinctrl/Kconfig        |    6 +
>> drivers/pinctrl/Makefile       |    1 +
>> drivers/pinctrl/pinctrl-at91.c |  529 ++++++++++++++++++++++++++++++++++++++++
>> drivers/pinctrl/pinctrl-at91.h |  148 +++++++++++
>> 4 files changed, 684 insertions(+)
>> create mode 100644 drivers/pinctrl/pinctrl-at91.c
>> create mode 100644 drivers/pinctrl/pinctrl-at91.h
>>
>> diff --git a/drivers/pinctrl/Kconfig b/drivers/pinctrl/Kconfig
>> index dffaa4e..ce55c7b 100644
>> --- a/drivers/pinctrl/Kconfig
>> +++ b/drivers/pinctrl/Kconfig
>> @@ -7,6 +7,12 @@ config PINCTRL
>>         from the devicetree. Legacy drivers here may not need this core
>>         support but instead provide their own SoC specific APIs
>>
>> +config PINCTRL_AT91
>> +     select PINCTRL
>> +     bool
>> +     help
>> +         The pinmux controller found on AT91 SoCs.
>> +
>> config PINCTRL_IMX_IOMUX_V1
>>       select PINCTRL if OFDEVICE
>>       bool
>> diff --git a/drivers/pinctrl/Makefile b/drivers/pinctrl/Makefile
>> index 566ba11..3ea8649 100644
>> --- a/drivers/pinctrl/Makefile
>> +++ b/drivers/pinctrl/Makefile
>> @@ -1,4 +1,5 @@
>> obj-$(CONFIG_PINCTRL) += pinctrl.o
>> +obj-$(CONFIG_PINCTRL_AT91) += pinctrl-at91.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
>> diff --git a/drivers/pinctrl/pinctrl-at91.c b/drivers/pinctrl/pinctrl-at91.c
>> new file mode 100644
>> index 0000000..a92a898
>> --- /dev/null
>> +++ b/drivers/pinctrl/pinctrl-at91.c
>> @@ -0,0 +1,529 @@
>> +/*
>> + * Copyright (C) 2005 HP Labs
>> + * Copyright (C) 2011-2012 Jean-Christophe PLAGNIOL-VILLARD <plagnioj@jcrosoft.com>
>> + * Copyright (C) 2014 Raphaël Poggi
>> + *
>> + * See file CREDITS for list of people who contributed to this
>> + * project.
>> + *
>> + * 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 <command.h>
>> +#include <complete.h>
>> +#include <linux/clk.h>
>> +#include <linux/err.h>
>> +#include <errno.h>
>> +#include <io.h>
>> +#include <gpio.h>
>> +#include <init.h>
>> +#include <driver.h>
>> +#include <getopt.h>
>> +
>> +#include <mach/at91_pio.h>
>> +
>> +#include <pinctrl.h>
>> +
>> +#include "pinctrl-at91.h"
>> +
>> +struct at91_pinctrl {
>> +    struct pinctrl_device pctl;
>> +    struct at91_pinctrl_mux_ops      *ops;
>> +};
>> +
>> +struct at91_gpio_chip {
>> +     struct gpio_chip        chip;
>> +     void __iomem            *regbase;       /* PIO bank virtual address */
>> +     struct at91_pinctrl_mux_ops *ops;       /* ops */
>> +};
>> +
>> +enum at91_mux {
>> +     AT91_MUX_GPIO = 0,
>> +     AT91_MUX_PERIPH_A = 1,
>> +     AT91_MUX_PERIPH_B = 2,
>> +     AT91_MUX_PERIPH_C = 3,
>> +     AT91_MUX_PERIPH_D = 4,
>> +};
>> +
>> +#define MAX_GPIO_BANKS               5
>> +#define to_at91_pinctrl(c) container_of(c, struct at91_pinctrl, pctl);
>> +#define to_at91_gpio_chip(c) container_of(c, struct at91_gpio_chip, chip)
>> +
>> +#define PULL_UP         (1 << 0)
>> +#define MULTI_DRIVE     (1 << 1)
>> +#define DEGLITCH        (1 << 2)
>> +#define PULL_DOWN       (1 << 3)
>> +#define DIS_SCHMIT      (1 << 4)
>> +#define DEBOUNCE        (1 << 16)
>> +#define DEBOUNCE_VAL_SHIFT      17
>> +#define DEBOUNCE_VAL    (0x3fff << DEBOUNCE_VAL_SHIFT)
>> +
>> +static int gpio_banks = 0;
>> +
>> +static struct at91_gpio_chip gpio_chip[MAX_GPIO_BANKS];
>> +
>> +static inline void __iomem *pin_to_controller(struct at91_pinctrl *info, unsigned pin)
>> +{
>> +     pin /= MAX_NB_GPIO_PER_BANK;
>> +     if (likely(pin < gpio_banks))
>> +             return gpio_chip[pin].regbase;
>> +
>> +     return NULL;
>> +}
>> +
>> +/**
>> + * struct at91_pinctrl_mux_ops - describes an At91 mux ops group
>> + * on new IP with support for periph C and D the way to mux in
>> + * periph A and B has changed
>> + * So provide the right call back
>> + * if not present means the IP does not support it
>> + * @get_periph: return the periph mode configured
>> + * @mux_A_periph: mux as periph A
>> + * @mux_B_periph: mux as periph B
>> + * @mux_C_periph: mux as periph C
>> + * @mux_D_periph: mux as periph D
>> + * @set_deglitch: enable/disable deglitch
>> + * @set_debounce: enable/disable debounce
>> + * @set_pulldown: enable/disable pulldown
>> + * @disable_schmitt_trig: disable schmitt trigger
>> + */
>> +struct at91_pinctrl_mux_ops {
>> +     enum at91_mux (*get_periph)(void __iomem *pio, unsigned mask);
>> +     void (*mux_A_periph)(void __iomem *pio, unsigned mask);
>> +     void (*mux_B_periph)(void __iomem *pio, unsigned mask);
>> +     void (*mux_C_periph)(void __iomem *pio, unsigned mask);
>> +     void (*mux_D_periph)(void __iomem *pio, unsigned mask);
>> +     bool (*get_deglitch)(void __iomem *pio, unsigned pin);
>> +     void (*set_deglitch)(void __iomem *pio, unsigned mask, bool in_on);
>> +     bool (*get_debounce)(void __iomem *pio, unsigned pin, u32 *div);
>> +     void (*set_debounce)(void __iomem *pio, unsigned mask, bool in_on, u32 div);
>> +     bool (*get_pulldown)(void __iomem *pio, unsigned pin);
>> +     void (*set_pulldown)(void __iomem *pio, unsigned mask, bool in_on);
>> +     bool (*get_schmitt_trig)(void __iomem *pio, unsigned pin);
>> +     void (*disable_schmitt_trig)(void __iomem *pio, unsigned mask);
>> +};
>> +
>> +static enum at91_mux at91_mux_pio3_get_periph(void __iomem *pio, unsigned mask)
>> +{
>> +     unsigned select;
>> +
>> +     if (__raw_readl(pio + PIO_PSR) & mask)
>> +             return AT91_MUX_GPIO;
>> +
>> +     select = !!(__raw_readl(pio + PIO_ABCDSR1) & mask);
>> +     select |= (!!(__raw_readl(pio + PIO_ABCDSR2) & mask) << 1);
>> +
>> +     return select + 1;
>> +}
>> +
>> +static enum at91_mux at91_mux_get_periph(void __iomem *pio, unsigned mask)
>> +{
>> +     unsigned select;
>> +
>> +     if (__raw_readl(pio + PIO_PSR) & mask)
>> +             return AT91_MUX_GPIO;
>> +
>> +     select = __raw_readl(pio + PIO_ABSR) & mask;
>> +
>> +     return select + 1;
>> +}
>> +
>> +static bool at91_mux_get_deglitch(void __iomem *pio, unsigned pin)
>> +{
>> +     return (__raw_readl(pio + PIO_IFSR) >> pin) & 0x1;
>> +}
>> +
>> +static bool at91_mux_pio3_get_debounce(void __iomem *pio, unsigned pin, u32 *div)
>> +{
>> +     *div = __raw_readl(pio + PIO_SCDR);
>> +
>> +     return (__raw_readl(pio + PIO_IFSCSR) >> pin) & 0x1;
>> +}
>> +
>> +static bool at91_mux_pio3_get_pulldown(void __iomem *pio, unsigned pin)
>> +{
>> +     return (__raw_readl(pio + PIO_PPDSR) >> pin) & 0x1;
>> +}
>> +
>> +static bool at91_mux_pio3_get_schmitt_trig(void __iomem *pio, unsigned pin)
>> +{
>> +     return (__raw_readl(pio + PIO_SCHMITT) >> pin) & 0x1;
>> +}
>> +
>> +static struct at91_pinctrl_mux_ops at91rm9200_ops = {
>> +     .get_periph     = at91_mux_get_periph,
>> +     .mux_A_periph   = at91_mux_set_A_periph,
>> +     .mux_B_periph   = at91_mux_set_B_periph,
>> +     .get_deglitch   = at91_mux_get_deglitch,
>> +     .set_deglitch   = at91_mux_set_deglitch,
>> +};
>> +
>> +static struct at91_pinctrl_mux_ops at91sam9x5_ops = {
>> +     .get_periph     = at91_mux_pio3_get_periph,
>> +     .mux_A_periph   = at91_mux_pio3_set_A_periph,
>> +     .mux_B_periph   = at91_mux_pio3_set_B_periph,
>> +     .mux_C_periph   = at91_mux_pio3_set_C_periph,
>> +     .mux_D_periph   = at91_mux_pio3_set_D_periph,
>> +     .get_deglitch   = at91_mux_get_deglitch,
>> +     .set_deglitch   = at91_mux_pio3_set_deglitch,
>> +     .get_debounce   = at91_mux_pio3_get_debounce,
>> +     .set_debounce   = at91_mux_pio3_set_debounce,
>> +     .get_pulldown   = at91_mux_pio3_get_pulldown,
>> +     .set_pulldown   = at91_mux_pio3_set_pulldown,
>> +     .get_schmitt_trig = at91_mux_pio3_get_schmitt_trig,
>> +     .disable_schmitt_trig = at91_mux_pio3_disable_schmitt_trig,
>> +};
>> +
>> +static int at91_mux_pin(struct at91_pinctrl *info, unsigned pin, enum at91_mux mux, int use_pullup)
>> +{
>> +     void __iomem    *pio = pin_to_controller(info, pin);
>> +     unsigned mask = pin_to_mask(pin);
>> +
>> +     if (!info)
>> +             return -EINVAL;
>> +
>> +     if (!pio)
>> +             return -EINVAL;
>> +
>> +     at91_mux_disable_interrupt(pio, mask);
>> +
>> +     switch(mux) {
>> +     case AT91_MUX_GPIO:
>> +             at91_mux_gpio_enable(pio, mask);
>> +             break;
>> +     case AT91_MUX_PERIPH_A:
>> +             info->ops->mux_A_periph(pio, mask);
>> +             break;
>> +     case AT91_MUX_PERIPH_B:
>> +             info->ops->mux_B_periph(pio, mask);
>> +             break;
>> +     case AT91_MUX_PERIPH_C:
>> +             if (!info->ops->mux_C_periph)
>> +                     return -EINVAL;
>> +             info->ops->mux_C_periph(pio, mask);
>> +             break;
>> +     case AT91_MUX_PERIPH_D:
>> +             if (!info->ops->mux_D_periph)
>> +                     return -EINVAL;
>> +             info->ops->mux_D_periph(pio, mask);
>> +             break;
>> +     }
>> +     if (mux)
>> +             at91_mux_gpio_disable(pio, mask);
>> +
>> +     if (use_pullup >= 0)
>> +             at91_mux_set_pullup(pio, mask, use_pullup);
>> +
>> +     return 0;
>> +}
>> +
>> +static struct of_device_id at91_pinctrl_dt_ids[] = {
>> +     {
>> +             .compatible = "atmel,at91rm9200-pinctrl",
>> +             .data = (unsigned long)&at91rm9200_ops,
>> +     }, {
>> +             .compatible = "atmel,at91sam9x5-pinctrl",
>> +             .data = (unsigned long)&at91sam9x5_ops,
>> +     }, {
>> +             /* sentinel */
>> +     }
>> +};
>> +
>> +static struct at91_pinctrl_mux_ops *at91_pinctrl_get_driver_data(struct device_d *dev)
>> +{
>> +    struct at91_pinctrl_mux_ops *ops_data = NULL;
>> +    int rc;
>> +
>> +    if (dev->device_node) {
>> +         const struct of_device_id *match;
>> +         match = of_match_node(at91_pinctrl_dt_ids, dev->device_node);
>> +         if (!match)
>> +                     ops_data = NULL;
>> +         else
>> +                     ops_data = (struct at91_pinctrl_mux_ops *)match->data;
>> +    }
>> +    else {
>> +         rc = dev_get_drvdata(dev, (unsigned long *)&ops_data);
>> +             if (rc)
>> +             ops_data = NULL;
>> +    }
>> +
>> +    return ops_data;
>> +}
>> +
>> +static int at91_pinctrl_set_conf(struct at91_pinctrl *info, unsigned int pin_num, unsigned int mux, unsigned int conf)
>> +{
>> +     unsigned int mask;
>> +     void __iomem *pio;
>> +
>> +     pio = pin_to_controller(info, pin_num);
>> +     mask = pin_to_mask(pin_num);
>> +
>> +     if (conf & PULL_UP && conf & PULL_DOWN)
>> +             return -EINVAL;
>> +
>> +     at91_mux_set_pullup(pio, mask, conf & PULL_UP);
>> +     at91_mux_set_multidrive(pio, mask, conf & MULTI_DRIVE);
>> +     if (info->ops->set_deglitch)
>> +             info->ops->set_deglitch(pio, mask, conf & DEGLITCH);
>> +     if (info->ops->set_debounce)
>> +             info->ops->set_debounce(pio, mask, conf & DEBOUNCE,
>> +                     (conf & DEBOUNCE_VAL) >> DEBOUNCE_VAL_SHIFT);
>> +     if (info->ops->set_pulldown)
>> +             info->ops->set_pulldown(pio, mask, conf & PULL_DOWN);
>> +     if (info->ops->disable_schmitt_trig && conf & DIS_SCHMIT)
>> +             info->ops->disable_schmitt_trig(pio, mask);
>> +
>> +     return 0;
>> +}
>> +
>> +static int at91_pinctrl_set_state(struct pinctrl_device *pdev, struct device_node *np)
>> +{
>> +     struct at91_pinctrl *info;
>> +     const __be32 *list;
>> +     int i, size;
>> +     int ret = 0;
>> +     int bank_num, pin_num, mux, conf;
>> +
>> +     info = to_at91_pinctrl(pdev);
>> +
>> +     list = of_get_property(np, "atmel,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) {
>> +             bank_num = be32_to_cpu(*list++);
>> +             pin_num = be32_to_cpu(*list++);
>> +             mux = be32_to_cpu(*list++);
>> +             conf = be32_to_cpu(*list++);
>> +
>> +             ret = at91_mux_pin(info, pin_num, mux, conf & PULL_UP);
>> +             if (ret) {
>> +                     dev_err(pdev->dev, "failed to mux pin %d\n", pin_num);
>> +                     return ret;
>> +             }
>> +
>> +             ret = at91_pinctrl_set_conf(info, pin_num, mux, conf);
>> +             if (ret) {
>> +                     dev_err(pdev->dev, "failed to set conf on pin %d\n", pin_num);
>> +                     return ret;
>> +             }
>> +     }
>> +
>> +     return ret;
>> +}
>> +
>> +static struct pinctrl_ops at91_pinctrl_ops = {
>> +     .set_state = at91_pinctrl_set_state,
>> +};
>> +
>> +static int at91_pinctrl_probe(struct device_d *dev)
>> +{
>> +     struct at91_pinctrl *info;
>> +     int ret;
>> +
>> +     info = xzalloc(sizeof(struct at91_pinctrl));
>> +
>> +     info->ops = at91_pinctrl_get_driver_data(dev);
>> +     if (!info->ops) {
>> +             dev_err(dev, "failed to retrieve driver data\n");
>> +             return -ENODEV;
>> +     }
>> +
>> +     info->pctl.dev = dev;
>> +     info->pctl.ops = &at91_pinctrl_ops;
>> +
>> +     ret = pinctrl_register(&info->pctl);
>> +     if (ret)
>> +             return ret;
>> +
>> +     dev_info(dev, "AT91 pinctrl registred\n");
>> +
>> +     return 0;
>> +}
>> +
>> +static struct platform_device_id at91_pinctrl_ids[] = {
>> +     {
>> +             .name = "at91rm9200-pinctrl",
>> +             .driver_data = (unsigned long)&at91rm9200_ops,
>> +     }, {
>> +             .name = "at91sam9x5-pinctrl",
>> +             .driver_data = (unsigned long)&at91sam9x5_ops,
>> +     }, {
>> +             /* sentinel */
>> +     },
>> +};
>> +
>> +static struct driver_d at91_pinctrl_driver = {
>> +     .name = "pinctrl-at91",
>> +     .probe = at91_pinctrl_probe,
>> +     .id_table = at91_pinctrl_ids,
>> +     .of_compatible = DRV_OF_COMPAT(at91_pinctrl_dt_ids),
>> +};
>> +
>> +static int at91_pinctrl_init(void)
>> +{
>> +     return platform_driver_register(&at91_pinctrl_driver);
>> +}
>> +coredevice_initcall(at91_pinctrl_init);
>> +
>> +static int at91_gpio_get(struct gpio_chip *chip, unsigned offset)
>> +{
>> +     struct at91_gpio_chip *at91_gpio = to_at91_gpio_chip(chip);
>> +     void __iomem *pio = at91_gpio->regbase;
>> +     unsigned mask = 1 << offset;
>> +
>> +     return at91_mux_gpio_get(pio, mask);
>> +}
>> +
>> +static void at91_gpio_set(struct gpio_chip *chip, unsigned offset, int value)
>> +{
>> +     struct at91_gpio_chip *at91_gpio = to_at91_gpio_chip(chip);
>> +     void __iomem *pio = at91_gpio->regbase;
>> +     unsigned mask = 1 << offset;
>> +
>> +     at91_mux_gpio_set(pio, mask, value);
>> +}
>> +
>> +static int at91_gpio_direction_output(struct gpio_chip *chip, unsigned offset,
>> +             int value)
>> +{
>> +     struct at91_gpio_chip *at91_gpio = to_at91_gpio_chip(chip);
>> +     void __iomem *pio = at91_gpio->regbase;
>> +     unsigned mask = 1 << offset;
>> +
>> +     at91_mux_gpio_set(pio, mask, value);
>> +     __raw_writel(mask, pio + PIO_OER);
>> +
>> +     return 0;
>> +}
>> +
>> +static int at91_gpio_direction_input(struct gpio_chip *chip, unsigned offset)
>> +{
>> +     struct at91_gpio_chip *at91_gpio = to_at91_gpio_chip(chip);
>> +     void __iomem *pio = at91_gpio->regbase;
>> +     unsigned mask = 1 << offset;
>> +
>> +     __raw_writel(mask, pio + PIO_ODR);
>> +
>> +     return 0;
>> +}
>> +
>> +static int at91_gpio_request(struct gpio_chip *chip, unsigned offset)
>> +{
>> +     struct at91_gpio_chip *at91_gpio = to_at91_gpio_chip(chip);
>> +     void __iomem *pio = at91_gpio->regbase;
>> +     unsigned mask = 1 << offset;
>> +
>> +     dev_dbg(chip->dev, "%s:%d pio%c%d(%d)\n", __func__, __LINE__,
>> +              'A' + pin_to_bank(chip->base), offset, chip->base + offset);
>> +     at91_mux_gpio_enable(pio, mask);
>> +
>> +     return 0;
>> +}
>> +
>> +static void at91_gpio_free(struct gpio_chip *chip, unsigned offset)
>> +{
>> +     dev_dbg(chip->dev, "%s:%d pio%c%d(%d)\n", __func__, __LINE__,
>> +              'A' + pin_to_bank(chip->base), offset, chip->base + offset);
>> +}
>> +
>> +static struct gpio_ops at91_gpio_ops = {
>> +     .request = at91_gpio_request,
>> +     .free = at91_gpio_free,
>> +     .direction_input = at91_gpio_direction_input,
>> +     .direction_output = at91_gpio_direction_output,
>> +     .get = at91_gpio_get,
>> +     .set = at91_gpio_set,
>> +};
>> +
>> +static struct of_device_id at91_gpio_dt_ids[] = {
>> +     {
>> +             .compatible = "atmel,at91rm9200-gpio",
>> +     }, {
>> +             .compatible = "atmel,at91sam9x5-gpio",
>> +     }, {
>> +             /* sentinel */
>> +     },
>> +};
>> +
>> +static int at91_gpio_probe(struct device_d *dev)
>> +{
>> +     struct at91_gpio_chip *at91_gpio;
>> +     struct clk *clk;
>> +     int ret;
>> +     int alias_idx = of_alias_get_id(dev->device_node, "gpio");
>> +
>> +     BUG_ON(dev->id > MAX_GPIO_BANKS);
>> +
>> +     at91_gpio = &gpio_chip[alias_idx];
>> +
>> +     clk = clk_get(dev, NULL);
>> +     if (IS_ERR(clk)) {
>> +             ret = PTR_ERR(clk);
>> +             dev_err(dev, "clock not found: %d\n", ret);
>> +             return ret;
>> +     }
>> +
>> +     ret = clk_enable(clk);
>> +     if (ret < 0) {
>> +             dev_err(dev, "clock failed to enable: %d\n", ret);
>> +             clk_put(clk);
>> +             return ret;
>> +     }
>> +
>> +     gpio_banks = max(gpio_banks, alias_idx + 1);
>> +     at91_gpio->regbase = dev_request_mem_region(dev, 0);
>> +
>> +     at91_gpio->chip.ops = &at91_gpio_ops;
>> +     at91_gpio->chip.ngpio = MAX_NB_GPIO_PER_BANK;
>> +     at91_gpio->chip.dev = dev;
>> +     at91_gpio->chip.base = dev->id * MAX_NB_GPIO_PER_BANK;
>> +
>> +     ret = gpiochip_add(&at91_gpio->chip);
>> +     if (ret) {
>> +             dev_err(dev, "couldn't add gpiochip, ret = %d\n", ret);
>> +             return ret;
>> +     }
>> +
>> +     dev_info(dev, "AT91 gpio driver registred\n");
>> +
>> +     return 0;
>> +}
>> +
>> +static struct platform_device_id at91_gpio_ids[] = {
>> +     {
>> +             .name = "at91rm9200-gpio",
>> +     }, {
>> +             .name = "at91sam9x5-gpio",
>> +     }, {
>> +             /* sentinel */
>> +     },
>> +};
>> +
>> +static struct driver_d at91_gpio_driver = {
>> +     .name = "gpio-at91",
>> +     .probe = at91_gpio_probe,
>> +     .id_table = at91_gpio_ids,
>> +     .of_compatible  = DRV_OF_COMPAT(at91_gpio_dt_ids),
>> +};
>> +
>> +static int at91_gpio_init(void)
>> +{
>> +     return platform_driver_register(&at91_gpio_driver);
>> +}
>> +coredevice_initcall(at91_gpio_init);
>> diff --git a/drivers/pinctrl/pinctrl-at91.h b/drivers/pinctrl/pinctrl-at91.h
>> new file mode 100644
>> index 0000000..e719fb8
>> --- /dev/null
>> +++ b/drivers/pinctrl/pinctrl-at91.h
>> @@ -0,0 +1,148 @@
>> +/*
>> + * Copyright (C) 2011-2012 Jean-Christophe PLAGNIOL-VILLARD <plagnioj@jcrosoft.com>
>> + *
>> + * Under GPLv2 only
>> + */
>> +
>> +#ifndef __AT91_GPIO_H__
>> +#define __AT91_GPIO_H__
>> +
>> +#ifndef __gpio_init
>> +#define __gpio_init
>> +#endif
>> +
>> +#define MAX_NB_GPIO_PER_BANK 32
>> +
>> +static inline unsigned pin_to_bank(unsigned pin)
>> +{
>> +     return pin / MAX_NB_GPIO_PER_BANK;
>> +}
>> +
>> +static inline unsigned pin_to_bank_offset(unsigned pin)
>> +{
>> +     return pin % MAX_NB_GPIO_PER_BANK;
>> +}
>> +
>> +static inline unsigned pin_to_mask(unsigned pin)
>> +{
>> +     return 1 << pin_to_bank_offset(pin);
>> +}
>> +
>> +static inline void at91_mux_disable_interrupt(void __iomem *pio, unsigned mask)
>> +{
>> +     __raw_writel(mask, pio + PIO_IDR);
>> +}
>> +
>> +static inline void at91_mux_set_pullup(void __iomem *pio, unsigned mask, bool on)
>> +{
>> +     __raw_writel(mask, pio + (on ? PIO_PUER : PIO_PUDR));
>> +}
>> +
>> +static inline void at91_mux_set_multidrive(void __iomem *pio, unsigned mask, bool on)
>> +{
>> +     __raw_writel(mask, pio + (on ? PIO_MDER : PIO_MDDR));
>> +}
>> +
>> +static inline void at91_mux_set_A_periph(void __iomem *pio, unsigned mask)
>> +{
>> +     __raw_writel(mask, pio + PIO_ASR);
>> +}
>> +
>> +static inline void at91_mux_set_B_periph(void __iomem *pio, unsigned mask)
>> +{
>> +     __raw_writel(mask, pio + PIO_BSR);
>> +}
>> +
>> +static inline void at91_mux_pio3_set_A_periph(void __iomem *pio, unsigned mask)
>> +{
>> +
>> +     __raw_writel(__raw_readl(pio + PIO_ABCDSR1) & ~mask,
>> +                                             pio + PIO_ABCDSR1);
>> +     __raw_writel(__raw_readl(pio + PIO_ABCDSR2) & ~mask,
>> +                                             pio + PIO_ABCDSR2);
>> +}
>> +
>> +static inline void at91_mux_pio3_set_B_periph(void __iomem *pio, unsigned mask)
>> +{
>> +     __raw_writel(__raw_readl(pio + PIO_ABCDSR1) | mask,
>> +                                             pio + PIO_ABCDSR1);
>> +     __raw_writel(__raw_readl(pio + PIO_ABCDSR2) & ~mask,
>> +                                             pio + PIO_ABCDSR2);
>> +}
>> +
>> +static inline void at91_mux_pio3_set_C_periph(void __iomem *pio, unsigned mask)
>> +{
>> +     __raw_writel(__raw_readl(pio + PIO_ABCDSR1) & ~mask, pio + PIO_ABCDSR1);
>> +     __raw_writel(__raw_readl(pio + PIO_ABCDSR2) | mask, pio + PIO_ABCDSR2);
>> +}
>> +
>> +static inline void at91_mux_pio3_set_D_periph(void __iomem *pio, unsigned mask)
>> +{
>> +     __raw_writel(__raw_readl(pio + PIO_ABCDSR1) | mask, pio + PIO_ABCDSR1);
>> +     __raw_writel(__raw_readl(pio + PIO_ABCDSR2) | mask, pio + PIO_ABCDSR2);
>> +}
>> +
>> +static inline void at91_mux_set_deglitch(void __iomem *pio, unsigned mask, bool is_on)
>> +{
>> +     __raw_writel(mask, pio + (is_on ? PIO_IFER : PIO_IFDR));
>> +}
>> +
>> +static inline void at91_mux_pio3_set_deglitch(void __iomem *pio, unsigned mask, bool is_on)
>> +{
>> +     if (is_on)
>> +             __raw_writel(mask, pio + PIO_IFSCDR);
>> +     at91_mux_set_deglitch(pio, mask, is_on);
>> +}
>> +
>> +static inline void at91_mux_pio3_set_debounce(void __iomem *pio, unsigned mask,
>> +                             bool is_on, u32 div)
>> +{
>> +     if (is_on) {
>> +             __raw_writel(mask, pio + PIO_IFSCER);
>> +             __raw_writel(div & PIO_SCDR_DIV, pio + PIO_SCDR);
>> +             __raw_writel(mask, pio + PIO_IFER);
>> +     } else {
>> +             __raw_writel(mask, pio + PIO_IFDR);
>> +     }
>> +}
>> +
>> +static inline void at91_mux_pio3_set_pulldown(void __iomem *pio, unsigned mask, bool is_on)
>> +{
>> +     __raw_writel(mask, pio + (is_on ? PIO_PPDER : PIO_PPDDR));
>> +}
>> +
>> +static inline void at91_mux_pio3_disable_schmitt_trig(void __iomem *pio, unsigned mask)
>> +{
>> +     __raw_writel(__raw_readl(pio + PIO_SCHMITT) | mask, pio + PIO_SCHMITT);
>> +}
>> +
>> +static inline void at91_mux_gpio_disable(void __iomem *pio, unsigned mask)
>> +{
>> +     __raw_writel(mask, pio + PIO_PDR);
>> +}
>> +
>> +static inline void at91_mux_gpio_enable(void __iomem *pio, unsigned mask)
>> +{
>> +     __raw_writel(mask, pio + PIO_PER);
>> +}
>> +
>> +static inline void at91_mux_gpio_input(void __iomem *pio, unsigned mask, bool input)
>> +{
>> +     __raw_writel(mask, pio + (input ? PIO_ODR : PIO_OER));
>> +}
>> +
>> +static inline void at91_mux_gpio_set(void __iomem *pio, unsigned mask,
>> +int value)
>> +{
>> +     __raw_writel(mask, pio + (value ? PIO_SODR : PIO_CODR));
>> +}
>> +
>> +static inline int at91_mux_gpio_get(void __iomem *pio, unsigned mask)
>> +{
>> +       u32 pdsr;
>> +
>> +       pdsr = __raw_readl(pio + PIO_PDSR);
>> +       return (pdsr & mask) != 0;
>> +}
>> +
>> +#endif /* __AT91_GPIO_H__ */
>> --
>> 1.7.9.5
>>
>>
>> _______________________________________________
>> barebox mailing list
>> barebox@lists.infradead.org
>> http://lists.infradead.org/mailman/listinfo/barebox
>
>
> _______________________________________________
> barebox mailing list
> barebox@lists.infradead.org
> http://lists.infradead.org/mailman/listinfo/barebox

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

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

* Re: [PATCH 1/2] pinctrl: at91: add pinctrl driver
  2014-08-04 18:37     ` Raphaël Poggi
@ 2014-08-04 18:45       ` Sascha Hauer
  2014-08-05 10:26       ` Jean-Christophe PLAGNIOL-VILLARD
  1 sibling, 0 replies; 10+ messages in thread
From: Sascha Hauer @ 2014-08-04 18:45 UTC (permalink / raw)
  To: Raphaël Poggi; +Cc: barebox

On Mon, Aug 04, 2014 at 08:37:35PM +0200, Raphaël Poggi wrote:
> I have planned to add device tree support for the AT91 port.
> 
> So I port the pinctrl driver from linux to barebox to be able to use
> the pinctrl in device tree, but maybe I made a mistake and there is
> another solution.

Nope. When you want to add device tree support for AT91 that's exactly
the way to go.
I'm unsure about the duplication of at91_mux_set_A_periph() and friends
here. We already have them in the tree.

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] 10+ messages in thread

* Re: [PATCH 1/2] pinctrl: at91: add pinctrl driver
  2014-08-04 18:37     ` Raphaël Poggi
  2014-08-04 18:45       ` Sascha Hauer
@ 2014-08-05 10:26       ` Jean-Christophe PLAGNIOL-VILLARD
  2014-08-05 11:38         ` Raphaël Poggi
  1 sibling, 1 reply; 10+ messages in thread
From: Jean-Christophe PLAGNIOL-VILLARD @ 2014-08-05 10:26 UTC (permalink / raw)
  To: Raphaël Poggi; +Cc: barebox


On Aug 5, 2014, at 2:37 AM, Raphaël Poggi <raphio98@gmail.com> wrote:

> 
> I have planned to add device tree support for the AT91 port.
> 
> So I port the pinctrl driver from linux to barebox to be able to use
> the pinctrl in device tree, but maybe I made a mistake and there is
> another solution.
> 

I’ve a version already that I need to update and send

Best Regards,
J.
> Best Regards,
> Raphaël
> 
> 2014-08-04 20:26 GMT+02:00 Jean-Christophe PLAGNIOL-VILLARD
> <plagnioj@jcrosoft.com>:
>> why do we need it on barebox?
>> 
>> this driver was design for dt-only in linux
>> 
>> Best Regards,
>> J.
>> On Aug 1, 2014, at 9:24 PM, Raphaël Poggi <poggi.raph@gmail.com> wrote:
>> 
>>> This driver is based on mach-at91/gpio.c and linux pinctrl driver.
>>> The driver contains the gpio and pinctrl parts (like in linux) because the two parts
>>> share some structures and logics.
>>> 
>>> Signed-off-by: Raphaël Poggi <poggi.raph@gmail.com>
>>> ---
>>> drivers/pinctrl/Kconfig        |    6 +
>>> drivers/pinctrl/Makefile       |    1 +
>>> drivers/pinctrl/pinctrl-at91.c |  529 ++++++++++++++++++++++++++++++++++++++++
>>> drivers/pinctrl/pinctrl-at91.h |  148 +++++++++++
>>> 4 files changed, 684 insertions(+)
>>> create mode 100644 drivers/pinctrl/pinctrl-at91.c
>>> create mode 100644 drivers/pinctrl/pinctrl-at91.h
>>> 
>>> diff --git a/drivers/pinctrl/Kconfig b/drivers/pinctrl/Kconfig
>>> index dffaa4e..ce55c7b 100644
>>> --- a/drivers/pinctrl/Kconfig
>>> +++ b/drivers/pinctrl/Kconfig
>>> @@ -7,6 +7,12 @@ config PINCTRL
>>>        from the devicetree. Legacy drivers here may not need this core
>>>        support but instead provide their own SoC specific APIs
>>> 
>>> +config PINCTRL_AT91
>>> +     select PINCTRL
>>> +     bool
>>> +     help
>>> +         The pinmux controller found on AT91 SoCs.
>>> +
>>> config PINCTRL_IMX_IOMUX_V1
>>>      select PINCTRL if OFDEVICE
>>>      bool
>>> diff --git a/drivers/pinctrl/Makefile b/drivers/pinctrl/Makefile
>>> index 566ba11..3ea8649 100644
>>> --- a/drivers/pinctrl/Makefile
>>> +++ b/drivers/pinctrl/Makefile
>>> @@ -1,4 +1,5 @@
>>> obj-$(CONFIG_PINCTRL) += pinctrl.o
>>> +obj-$(CONFIG_PINCTRL_AT91) += pinctrl-at91.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
>>> diff --git a/drivers/pinctrl/pinctrl-at91.c b/drivers/pinctrl/pinctrl-at91.c
>>> new file mode 100644
>>> index 0000000..a92a898
>>> --- /dev/null
>>> +++ b/drivers/pinctrl/pinctrl-at91.c
>>> @@ -0,0 +1,529 @@
>>> +/*
>>> + * Copyright (C) 2005 HP Labs
>>> + * Copyright (C) 2011-2012 Jean-Christophe PLAGNIOL-VILLARD <plagnioj@jcrosoft.com>
>>> + * Copyright (C) 2014 Raphaël Poggi
>>> + *
>>> + * See file CREDITS for list of people who contributed to this
>>> + * project.
>>> + *
>>> + * 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 <command.h>
>>> +#include <complete.h>
>>> +#include <linux/clk.h>
>>> +#include <linux/err.h>
>>> +#include <errno.h>
>>> +#include <io.h>
>>> +#include <gpio.h>
>>> +#include <init.h>
>>> +#include <driver.h>
>>> +#include <getopt.h>
>>> +
>>> +#include <mach/at91_pio.h>
>>> +
>>> +#include <pinctrl.h>
>>> +
>>> +#include "pinctrl-at91.h"
>>> +
>>> +struct at91_pinctrl {
>>> +    struct pinctrl_device pctl;
>>> +    struct at91_pinctrl_mux_ops      *ops;
>>> +};
>>> +
>>> +struct at91_gpio_chip {
>>> +     struct gpio_chip        chip;
>>> +     void __iomem            *regbase;       /* PIO bank virtual address */
>>> +     struct at91_pinctrl_mux_ops *ops;       /* ops */
>>> +};
>>> +
>>> +enum at91_mux {
>>> +     AT91_MUX_GPIO = 0,
>>> +     AT91_MUX_PERIPH_A = 1,
>>> +     AT91_MUX_PERIPH_B = 2,
>>> +     AT91_MUX_PERIPH_C = 3,
>>> +     AT91_MUX_PERIPH_D = 4,
>>> +};
>>> +
>>> +#define MAX_GPIO_BANKS               5
>>> +#define to_at91_pinctrl(c) container_of(c, struct at91_pinctrl, pctl);
>>> +#define to_at91_gpio_chip(c) container_of(c, struct at91_gpio_chip, chip)
>>> +
>>> +#define PULL_UP         (1 << 0)
>>> +#define MULTI_DRIVE     (1 << 1)
>>> +#define DEGLITCH        (1 << 2)
>>> +#define PULL_DOWN       (1 << 3)
>>> +#define DIS_SCHMIT      (1 << 4)
>>> +#define DEBOUNCE        (1 << 16)
>>> +#define DEBOUNCE_VAL_SHIFT      17
>>> +#define DEBOUNCE_VAL    (0x3fff << DEBOUNCE_VAL_SHIFT)
>>> +
>>> +static int gpio_banks = 0;
>>> +
>>> +static struct at91_gpio_chip gpio_chip[MAX_GPIO_BANKS];
>>> +
>>> +static inline void __iomem *pin_to_controller(struct at91_pinctrl *info, unsigned pin)
>>> +{
>>> +     pin /= MAX_NB_GPIO_PER_BANK;
>>> +     if (likely(pin < gpio_banks))
>>> +             return gpio_chip[pin].regbase;
>>> +
>>> +     return NULL;
>>> +}
>>> +
>>> +/**
>>> + * struct at91_pinctrl_mux_ops - describes an At91 mux ops group
>>> + * on new IP with support for periph C and D the way to mux in
>>> + * periph A and B has changed
>>> + * So provide the right call back
>>> + * if not present means the IP does not support it
>>> + * @get_periph: return the periph mode configured
>>> + * @mux_A_periph: mux as periph A
>>> + * @mux_B_periph: mux as periph B
>>> + * @mux_C_periph: mux as periph C
>>> + * @mux_D_periph: mux as periph D
>>> + * @set_deglitch: enable/disable deglitch
>>> + * @set_debounce: enable/disable debounce
>>> + * @set_pulldown: enable/disable pulldown
>>> + * @disable_schmitt_trig: disable schmitt trigger
>>> + */
>>> +struct at91_pinctrl_mux_ops {
>>> +     enum at91_mux (*get_periph)(void __iomem *pio, unsigned mask);
>>> +     void (*mux_A_periph)(void __iomem *pio, unsigned mask);
>>> +     void (*mux_B_periph)(void __iomem *pio, unsigned mask);
>>> +     void (*mux_C_periph)(void __iomem *pio, unsigned mask);
>>> +     void (*mux_D_periph)(void __iomem *pio, unsigned mask);
>>> +     bool (*get_deglitch)(void __iomem *pio, unsigned pin);
>>> +     void (*set_deglitch)(void __iomem *pio, unsigned mask, bool in_on);
>>> +     bool (*get_debounce)(void __iomem *pio, unsigned pin, u32 *div);
>>> +     void (*set_debounce)(void __iomem *pio, unsigned mask, bool in_on, u32 div);
>>> +     bool (*get_pulldown)(void __iomem *pio, unsigned pin);
>>> +     void (*set_pulldown)(void __iomem *pio, unsigned mask, bool in_on);
>>> +     bool (*get_schmitt_trig)(void __iomem *pio, unsigned pin);
>>> +     void (*disable_schmitt_trig)(void __iomem *pio, unsigned mask);
>>> +};
>>> +
>>> +static enum at91_mux at91_mux_pio3_get_periph(void __iomem *pio, unsigned mask)
>>> +{
>>> +     unsigned select;
>>> +
>>> +     if (__raw_readl(pio + PIO_PSR) & mask)
>>> +             return AT91_MUX_GPIO;
>>> +
>>> +     select = !!(__raw_readl(pio + PIO_ABCDSR1) & mask);
>>> +     select |= (!!(__raw_readl(pio + PIO_ABCDSR2) & mask) << 1);
>>> +
>>> +     return select + 1;
>>> +}
>>> +
>>> +static enum at91_mux at91_mux_get_periph(void __iomem *pio, unsigned mask)
>>> +{
>>> +     unsigned select;
>>> +
>>> +     if (__raw_readl(pio + PIO_PSR) & mask)
>>> +             return AT91_MUX_GPIO;
>>> +
>>> +     select = __raw_readl(pio + PIO_ABSR) & mask;
>>> +
>>> +     return select + 1;
>>> +}
>>> +
>>> +static bool at91_mux_get_deglitch(void __iomem *pio, unsigned pin)
>>> +{
>>> +     return (__raw_readl(pio + PIO_IFSR) >> pin) & 0x1;
>>> +}
>>> +
>>> +static bool at91_mux_pio3_get_debounce(void __iomem *pio, unsigned pin, u32 *div)
>>> +{
>>> +     *div = __raw_readl(pio + PIO_SCDR);
>>> +
>>> +     return (__raw_readl(pio + PIO_IFSCSR) >> pin) & 0x1;
>>> +}
>>> +
>>> +static bool at91_mux_pio3_get_pulldown(void __iomem *pio, unsigned pin)
>>> +{
>>> +     return (__raw_readl(pio + PIO_PPDSR) >> pin) & 0x1;
>>> +}
>>> +
>>> +static bool at91_mux_pio3_get_schmitt_trig(void __iomem *pio, unsigned pin)
>>> +{
>>> +     return (__raw_readl(pio + PIO_SCHMITT) >> pin) & 0x1;
>>> +}
>>> +
>>> +static struct at91_pinctrl_mux_ops at91rm9200_ops = {
>>> +     .get_periph     = at91_mux_get_periph,
>>> +     .mux_A_periph   = at91_mux_set_A_periph,
>>> +     .mux_B_periph   = at91_mux_set_B_periph,
>>> +     .get_deglitch   = at91_mux_get_deglitch,
>>> +     .set_deglitch   = at91_mux_set_deglitch,
>>> +};
>>> +
>>> +static struct at91_pinctrl_mux_ops at91sam9x5_ops = {
>>> +     .get_periph     = at91_mux_pio3_get_periph,
>>> +     .mux_A_periph   = at91_mux_pio3_set_A_periph,
>>> +     .mux_B_periph   = at91_mux_pio3_set_B_periph,
>>> +     .mux_C_periph   = at91_mux_pio3_set_C_periph,
>>> +     .mux_D_periph   = at91_mux_pio3_set_D_periph,
>>> +     .get_deglitch   = at91_mux_get_deglitch,
>>> +     .set_deglitch   = at91_mux_pio3_set_deglitch,
>>> +     .get_debounce   = at91_mux_pio3_get_debounce,
>>> +     .set_debounce   = at91_mux_pio3_set_debounce,
>>> +     .get_pulldown   = at91_mux_pio3_get_pulldown,
>>> +     .set_pulldown   = at91_mux_pio3_set_pulldown,
>>> +     .get_schmitt_trig = at91_mux_pio3_get_schmitt_trig,
>>> +     .disable_schmitt_trig = at91_mux_pio3_disable_schmitt_trig,
>>> +};
>>> +
>>> +static int at91_mux_pin(struct at91_pinctrl *info, unsigned pin, enum at91_mux mux, int use_pullup)
>>> +{
>>> +     void __iomem    *pio = pin_to_controller(info, pin);
>>> +     unsigned mask = pin_to_mask(pin);
>>> +
>>> +     if (!info)
>>> +             return -EINVAL;
>>> +
>>> +     if (!pio)
>>> +             return -EINVAL;
>>> +
>>> +     at91_mux_disable_interrupt(pio, mask);
>>> +
>>> +     switch(mux) {
>>> +     case AT91_MUX_GPIO:
>>> +             at91_mux_gpio_enable(pio, mask);
>>> +             break;
>>> +     case AT91_MUX_PERIPH_A:
>>> +             info->ops->mux_A_periph(pio, mask);
>>> +             break;
>>> +     case AT91_MUX_PERIPH_B:
>>> +             info->ops->mux_B_periph(pio, mask);
>>> +             break;
>>> +     case AT91_MUX_PERIPH_C:
>>> +             if (!info->ops->mux_C_periph)
>>> +                     return -EINVAL;
>>> +             info->ops->mux_C_periph(pio, mask);
>>> +             break;
>>> +     case AT91_MUX_PERIPH_D:
>>> +             if (!info->ops->mux_D_periph)
>>> +                     return -EINVAL;
>>> +             info->ops->mux_D_periph(pio, mask);
>>> +             break;
>>> +     }
>>> +     if (mux)
>>> +             at91_mux_gpio_disable(pio, mask);
>>> +
>>> +     if (use_pullup >= 0)
>>> +             at91_mux_set_pullup(pio, mask, use_pullup);
>>> +
>>> +     return 0;
>>> +}
>>> +
>>> +static struct of_device_id at91_pinctrl_dt_ids[] = {
>>> +     {
>>> +             .compatible = "atmel,at91rm9200-pinctrl",
>>> +             .data = (unsigned long)&at91rm9200_ops,
>>> +     }, {
>>> +             .compatible = "atmel,at91sam9x5-pinctrl",
>>> +             .data = (unsigned long)&at91sam9x5_ops,
>>> +     }, {
>>> +             /* sentinel */
>>> +     }
>>> +};
>>> +
>>> +static struct at91_pinctrl_mux_ops *at91_pinctrl_get_driver_data(struct device_d *dev)
>>> +{
>>> +    struct at91_pinctrl_mux_ops *ops_data = NULL;
>>> +    int rc;
>>> +
>>> +    if (dev->device_node) {
>>> +         const struct of_device_id *match;
>>> +         match = of_match_node(at91_pinctrl_dt_ids, dev->device_node);
>>> +         if (!match)
>>> +                     ops_data = NULL;
>>> +         else
>>> +                     ops_data = (struct at91_pinctrl_mux_ops *)match->data;
>>> +    }
>>> +    else {
>>> +         rc = dev_get_drvdata(dev, (unsigned long *)&ops_data);
>>> +             if (rc)
>>> +             ops_data = NULL;
>>> +    }
>>> +
>>> +    return ops_data;
>>> +}
>>> +
>>> +static int at91_pinctrl_set_conf(struct at91_pinctrl *info, unsigned int pin_num, unsigned int mux, unsigned int conf)
>>> +{
>>> +     unsigned int mask;
>>> +     void __iomem *pio;
>>> +
>>> +     pio = pin_to_controller(info, pin_num);
>>> +     mask = pin_to_mask(pin_num);
>>> +
>>> +     if (conf & PULL_UP && conf & PULL_DOWN)
>>> +             return -EINVAL;
>>> +
>>> +     at91_mux_set_pullup(pio, mask, conf & PULL_UP);
>>> +     at91_mux_set_multidrive(pio, mask, conf & MULTI_DRIVE);
>>> +     if (info->ops->set_deglitch)
>>> +             info->ops->set_deglitch(pio, mask, conf & DEGLITCH);
>>> +     if (info->ops->set_debounce)
>>> +             info->ops->set_debounce(pio, mask, conf & DEBOUNCE,
>>> +                     (conf & DEBOUNCE_VAL) >> DEBOUNCE_VAL_SHIFT);
>>> +     if (info->ops->set_pulldown)
>>> +             info->ops->set_pulldown(pio, mask, conf & PULL_DOWN);
>>> +     if (info->ops->disable_schmitt_trig && conf & DIS_SCHMIT)
>>> +             info->ops->disable_schmitt_trig(pio, mask);
>>> +
>>> +     return 0;
>>> +}
>>> +
>>> +static int at91_pinctrl_set_state(struct pinctrl_device *pdev, struct device_node *np)
>>> +{
>>> +     struct at91_pinctrl *info;
>>> +     const __be32 *list;
>>> +     int i, size;
>>> +     int ret = 0;
>>> +     int bank_num, pin_num, mux, conf;
>>> +
>>> +     info = to_at91_pinctrl(pdev);
>>> +
>>> +     list = of_get_property(np, "atmel,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) {
>>> +             bank_num = be32_to_cpu(*list++);
>>> +             pin_num = be32_to_cpu(*list++);
>>> +             mux = be32_to_cpu(*list++);
>>> +             conf = be32_to_cpu(*list++);
>>> +
>>> +             ret = at91_mux_pin(info, pin_num, mux, conf & PULL_UP);
>>> +             if (ret) {
>>> +                     dev_err(pdev->dev, "failed to mux pin %d\n", pin_num);
>>> +                     return ret;
>>> +             }
>>> +
>>> +             ret = at91_pinctrl_set_conf(info, pin_num, mux, conf);
>>> +             if (ret) {
>>> +                     dev_err(pdev->dev, "failed to set conf on pin %d\n", pin_num);
>>> +                     return ret;
>>> +             }
>>> +     }
>>> +
>>> +     return ret;
>>> +}
>>> +
>>> +static struct pinctrl_ops at91_pinctrl_ops = {
>>> +     .set_state = at91_pinctrl_set_state,
>>> +};
>>> +
>>> +static int at91_pinctrl_probe(struct device_d *dev)
>>> +{
>>> +     struct at91_pinctrl *info;
>>> +     int ret;
>>> +
>>> +     info = xzalloc(sizeof(struct at91_pinctrl));
>>> +
>>> +     info->ops = at91_pinctrl_get_driver_data(dev);
>>> +     if (!info->ops) {
>>> +             dev_err(dev, "failed to retrieve driver data\n");
>>> +             return -ENODEV;
>>> +     }
>>> +
>>> +     info->pctl.dev = dev;
>>> +     info->pctl.ops = &at91_pinctrl_ops;
>>> +
>>> +     ret = pinctrl_register(&info->pctl);
>>> +     if (ret)
>>> +             return ret;
>>> +
>>> +     dev_info(dev, "AT91 pinctrl registred\n");
>>> +
>>> +     return 0;
>>> +}
>>> +
>>> +static struct platform_device_id at91_pinctrl_ids[] = {
>>> +     {
>>> +             .name = "at91rm9200-pinctrl",
>>> +             .driver_data = (unsigned long)&at91rm9200_ops,
>>> +     }, {
>>> +             .name = "at91sam9x5-pinctrl",
>>> +             .driver_data = (unsigned long)&at91sam9x5_ops,
>>> +     }, {
>>> +             /* sentinel */
>>> +     },
>>> +};
>>> +
>>> +static struct driver_d at91_pinctrl_driver = {
>>> +     .name = "pinctrl-at91",
>>> +     .probe = at91_pinctrl_probe,
>>> +     .id_table = at91_pinctrl_ids,
>>> +     .of_compatible = DRV_OF_COMPAT(at91_pinctrl_dt_ids),
>>> +};
>>> +
>>> +static int at91_pinctrl_init(void)
>>> +{
>>> +     return platform_driver_register(&at91_pinctrl_driver);
>>> +}
>>> +coredevice_initcall(at91_pinctrl_init);
>>> +
>>> +static int at91_gpio_get(struct gpio_chip *chip, unsigned offset)
>>> +{
>>> +     struct at91_gpio_chip *at91_gpio = to_at91_gpio_chip(chip);
>>> +     void __iomem *pio = at91_gpio->regbase;
>>> +     unsigned mask = 1 << offset;
>>> +
>>> +     return at91_mux_gpio_get(pio, mask);
>>> +}
>>> +
>>> +static void at91_gpio_set(struct gpio_chip *chip, unsigned offset, int value)
>>> +{
>>> +     struct at91_gpio_chip *at91_gpio = to_at91_gpio_chip(chip);
>>> +     void __iomem *pio = at91_gpio->regbase;
>>> +     unsigned mask = 1 << offset;
>>> +
>>> +     at91_mux_gpio_set(pio, mask, value);
>>> +}
>>> +
>>> +static int at91_gpio_direction_output(struct gpio_chip *chip, unsigned offset,
>>> +             int value)
>>> +{
>>> +     struct at91_gpio_chip *at91_gpio = to_at91_gpio_chip(chip);
>>> +     void __iomem *pio = at91_gpio->regbase;
>>> +     unsigned mask = 1 << offset;
>>> +
>>> +     at91_mux_gpio_set(pio, mask, value);
>>> +     __raw_writel(mask, pio + PIO_OER);
>>> +
>>> +     return 0;
>>> +}
>>> +
>>> +static int at91_gpio_direction_input(struct gpio_chip *chip, unsigned offset)
>>> +{
>>> +     struct at91_gpio_chip *at91_gpio = to_at91_gpio_chip(chip);
>>> +     void __iomem *pio = at91_gpio->regbase;
>>> +     unsigned mask = 1 << offset;
>>> +
>>> +     __raw_writel(mask, pio + PIO_ODR);
>>> +
>>> +     return 0;
>>> +}
>>> +
>>> +static int at91_gpio_request(struct gpio_chip *chip, unsigned offset)
>>> +{
>>> +     struct at91_gpio_chip *at91_gpio = to_at91_gpio_chip(chip);
>>> +     void __iomem *pio = at91_gpio->regbase;
>>> +     unsigned mask = 1 << offset;
>>> +
>>> +     dev_dbg(chip->dev, "%s:%d pio%c%d(%d)\n", __func__, __LINE__,
>>> +              'A' + pin_to_bank(chip->base), offset, chip->base + offset);
>>> +     at91_mux_gpio_enable(pio, mask);
>>> +
>>> +     return 0;
>>> +}
>>> +
>>> +static void at91_gpio_free(struct gpio_chip *chip, unsigned offset)
>>> +{
>>> +     dev_dbg(chip->dev, "%s:%d pio%c%d(%d)\n", __func__, __LINE__,
>>> +              'A' + pin_to_bank(chip->base), offset, chip->base + offset);
>>> +}
>>> +
>>> +static struct gpio_ops at91_gpio_ops = {
>>> +     .request = at91_gpio_request,
>>> +     .free = at91_gpio_free,
>>> +     .direction_input = at91_gpio_direction_input,
>>> +     .direction_output = at91_gpio_direction_output,
>>> +     .get = at91_gpio_get,
>>> +     .set = at91_gpio_set,
>>> +};
>>> +
>>> +static struct of_device_id at91_gpio_dt_ids[] = {
>>> +     {
>>> +             .compatible = "atmel,at91rm9200-gpio",
>>> +     }, {
>>> +             .compatible = "atmel,at91sam9x5-gpio",
>>> +     }, {
>>> +             /* sentinel */
>>> +     },
>>> +};
>>> +
>>> +static int at91_gpio_probe(struct device_d *dev)
>>> +{
>>> +     struct at91_gpio_chip *at91_gpio;
>>> +     struct clk *clk;
>>> +     int ret;
>>> +     int alias_idx = of_alias_get_id(dev->device_node, "gpio");
>>> +
>>> +     BUG_ON(dev->id > MAX_GPIO_BANKS);
>>> +
>>> +     at91_gpio = &gpio_chip[alias_idx];
>>> +
>>> +     clk = clk_get(dev, NULL);
>>> +     if (IS_ERR(clk)) {
>>> +             ret = PTR_ERR(clk);
>>> +             dev_err(dev, "clock not found: %d\n", ret);
>>> +             return ret;
>>> +     }
>>> +
>>> +     ret = clk_enable(clk);
>>> +     if (ret < 0) {
>>> +             dev_err(dev, "clock failed to enable: %d\n", ret);
>>> +             clk_put(clk);
>>> +             return ret;
>>> +     }
>>> +
>>> +     gpio_banks = max(gpio_banks, alias_idx + 1);
>>> +     at91_gpio->regbase = dev_request_mem_region(dev, 0);
>>> +
>>> +     at91_gpio->chip.ops = &at91_gpio_ops;
>>> +     at91_gpio->chip.ngpio = MAX_NB_GPIO_PER_BANK;
>>> +     at91_gpio->chip.dev = dev;
>>> +     at91_gpio->chip.base = dev->id * MAX_NB_GPIO_PER_BANK;
>>> +
>>> +     ret = gpiochip_add(&at91_gpio->chip);
>>> +     if (ret) {
>>> +             dev_err(dev, "couldn't add gpiochip, ret = %d\n", ret);
>>> +             return ret;
>>> +     }
>>> +
>>> +     dev_info(dev, "AT91 gpio driver registred\n");
>>> +
>>> +     return 0;
>>> +}
>>> +
>>> +static struct platform_device_id at91_gpio_ids[] = {
>>> +     {
>>> +             .name = "at91rm9200-gpio",
>>> +     }, {
>>> +             .name = "at91sam9x5-gpio",
>>> +     }, {
>>> +             /* sentinel */
>>> +     },
>>> +};
>>> +
>>> +static struct driver_d at91_gpio_driver = {
>>> +     .name = "gpio-at91",
>>> +     .probe = at91_gpio_probe,
>>> +     .id_table = at91_gpio_ids,
>>> +     .of_compatible  = DRV_OF_COMPAT(at91_gpio_dt_ids),
>>> +};
>>> +
>>> +static int at91_gpio_init(void)
>>> +{
>>> +     return platform_driver_register(&at91_gpio_driver);
>>> +}
>>> +coredevice_initcall(at91_gpio_init);
>>> diff --git a/drivers/pinctrl/pinctrl-at91.h b/drivers/pinctrl/pinctrl-at91.h
>>> new file mode 100644
>>> index 0000000..e719fb8
>>> --- /dev/null
>>> +++ b/drivers/pinctrl/pinctrl-at91.h
>>> @@ -0,0 +1,148 @@
>>> +/*
>>> + * Copyright (C) 2011-2012 Jean-Christophe PLAGNIOL-VILLARD <plagnioj@jcrosoft.com>
>>> + *
>>> + * Under GPLv2 only
>>> + */
>>> +
>>> +#ifndef __AT91_GPIO_H__
>>> +#define __AT91_GPIO_H__
>>> +
>>> +#ifndef __gpio_init
>>> +#define __gpio_init
>>> +#endif
>>> +
>>> +#define MAX_NB_GPIO_PER_BANK 32
>>> +
>>> +static inline unsigned pin_to_bank(unsigned pin)
>>> +{
>>> +     return pin / MAX_NB_GPIO_PER_BANK;
>>> +}
>>> +
>>> +static inline unsigned pin_to_bank_offset(unsigned pin)
>>> +{
>>> +     return pin % MAX_NB_GPIO_PER_BANK;
>>> +}
>>> +
>>> +static inline unsigned pin_to_mask(unsigned pin)
>>> +{
>>> +     return 1 << pin_to_bank_offset(pin);
>>> +}
>>> +
>>> +static inline void at91_mux_disable_interrupt(void __iomem *pio, unsigned mask)
>>> +{
>>> +     __raw_writel(mask, pio + PIO_IDR);
>>> +}
>>> +
>>> +static inline void at91_mux_set_pullup(void __iomem *pio, unsigned mask, bool on)
>>> +{
>>> +     __raw_writel(mask, pio + (on ? PIO_PUER : PIO_PUDR));
>>> +}
>>> +
>>> +static inline void at91_mux_set_multidrive(void __iomem *pio, unsigned mask, bool on)
>>> +{
>>> +     __raw_writel(mask, pio + (on ? PIO_MDER : PIO_MDDR));
>>> +}
>>> +
>>> +static inline void at91_mux_set_A_periph(void __iomem *pio, unsigned mask)
>>> +{
>>> +     __raw_writel(mask, pio + PIO_ASR);
>>> +}
>>> +
>>> +static inline void at91_mux_set_B_periph(void __iomem *pio, unsigned mask)
>>> +{
>>> +     __raw_writel(mask, pio + PIO_BSR);
>>> +}
>>> +
>>> +static inline void at91_mux_pio3_set_A_periph(void __iomem *pio, unsigned mask)
>>> +{
>>> +
>>> +     __raw_writel(__raw_readl(pio + PIO_ABCDSR1) & ~mask,
>>> +                                             pio + PIO_ABCDSR1);
>>> +     __raw_writel(__raw_readl(pio + PIO_ABCDSR2) & ~mask,
>>> +                                             pio + PIO_ABCDSR2);
>>> +}
>>> +
>>> +static inline void at91_mux_pio3_set_B_periph(void __iomem *pio, unsigned mask)
>>> +{
>>> +     __raw_writel(__raw_readl(pio + PIO_ABCDSR1) | mask,
>>> +                                             pio + PIO_ABCDSR1);
>>> +     __raw_writel(__raw_readl(pio + PIO_ABCDSR2) & ~mask,
>>> +                                             pio + PIO_ABCDSR2);
>>> +}
>>> +
>>> +static inline void at91_mux_pio3_set_C_periph(void __iomem *pio, unsigned mask)
>>> +{
>>> +     __raw_writel(__raw_readl(pio + PIO_ABCDSR1) & ~mask, pio + PIO_ABCDSR1);
>>> +     __raw_writel(__raw_readl(pio + PIO_ABCDSR2) | mask, pio + PIO_ABCDSR2);
>>> +}
>>> +
>>> +static inline void at91_mux_pio3_set_D_periph(void __iomem *pio, unsigned mask)
>>> +{
>>> +     __raw_writel(__raw_readl(pio + PIO_ABCDSR1) | mask, pio + PIO_ABCDSR1);
>>> +     __raw_writel(__raw_readl(pio + PIO_ABCDSR2) | mask, pio + PIO_ABCDSR2);
>>> +}
>>> +
>>> +static inline void at91_mux_set_deglitch(void __iomem *pio, unsigned mask, bool is_on)
>>> +{
>>> +     __raw_writel(mask, pio + (is_on ? PIO_IFER : PIO_IFDR));
>>> +}
>>> +
>>> +static inline void at91_mux_pio3_set_deglitch(void __iomem *pio, unsigned mask, bool is_on)
>>> +{
>>> +     if (is_on)
>>> +             __raw_writel(mask, pio + PIO_IFSCDR);
>>> +     at91_mux_set_deglitch(pio, mask, is_on);
>>> +}
>>> +
>>> +static inline void at91_mux_pio3_set_debounce(void __iomem *pio, unsigned mask,
>>> +                             bool is_on, u32 div)
>>> +{
>>> +     if (is_on) {
>>> +             __raw_writel(mask, pio + PIO_IFSCER);
>>> +             __raw_writel(div & PIO_SCDR_DIV, pio + PIO_SCDR);
>>> +             __raw_writel(mask, pio + PIO_IFER);
>>> +     } else {
>>> +             __raw_writel(mask, pio + PIO_IFDR);
>>> +     }
>>> +}
>>> +
>>> +static inline void at91_mux_pio3_set_pulldown(void __iomem *pio, unsigned mask, bool is_on)
>>> +{
>>> +     __raw_writel(mask, pio + (is_on ? PIO_PPDER : PIO_PPDDR));
>>> +}
>>> +
>>> +static inline void at91_mux_pio3_disable_schmitt_trig(void __iomem *pio, unsigned mask)
>>> +{
>>> +     __raw_writel(__raw_readl(pio + PIO_SCHMITT) | mask, pio + PIO_SCHMITT);
>>> +}
>>> +
>>> +static inline void at91_mux_gpio_disable(void __iomem *pio, unsigned mask)
>>> +{
>>> +     __raw_writel(mask, pio + PIO_PDR);
>>> +}
>>> +
>>> +static inline void at91_mux_gpio_enable(void __iomem *pio, unsigned mask)
>>> +{
>>> +     __raw_writel(mask, pio + PIO_PER);
>>> +}
>>> +
>>> +static inline void at91_mux_gpio_input(void __iomem *pio, unsigned mask, bool input)
>>> +{
>>> +     __raw_writel(mask, pio + (input ? PIO_ODR : PIO_OER));
>>> +}
>>> +
>>> +static inline void at91_mux_gpio_set(void __iomem *pio, unsigned mask,
>>> +int value)
>>> +{
>>> +     __raw_writel(mask, pio + (value ? PIO_SODR : PIO_CODR));
>>> +}
>>> +
>>> +static inline int at91_mux_gpio_get(void __iomem *pio, unsigned mask)
>>> +{
>>> +       u32 pdsr;
>>> +
>>> +       pdsr = __raw_readl(pio + PIO_PDSR);
>>> +       return (pdsr & mask) != 0;
>>> +}
>>> +
>>> +#endif /* __AT91_GPIO_H__ */
>>> --
>>> 1.7.9.5
>>> 
>>> 
>>> _______________________________________________
>>> barebox mailing list
>>> barebox@lists.infradead.org
>>> http://lists.infradead.org/mailman/listinfo/barebox
>> 
>> 
>> _______________________________________________
>> barebox mailing list
>> barebox@lists.infradead.org
>> http://lists.infradead.org/mailman/listinfo/barebox


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

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

* Re: [PATCH 1/2] pinctrl: at91: add pinctrl driver
  2014-08-05 10:26       ` Jean-Christophe PLAGNIOL-VILLARD
@ 2014-08-05 11:38         ` Raphaël Poggi
       [not found]           ` <E10FE9F3-8D18-4EFC-8470-7C2D79E7E1B4@jcrosoft.com>
  0 siblings, 1 reply; 10+ messages in thread
From: Raphaël Poggi @ 2014-08-05 11:38 UTC (permalink / raw)
  To: Jean-Christophe PLAGNIOL-VILLARD; +Cc: barebox

Ok, so I drop my patch ? Or your version is very similar of my patch
and you can review mine to improve/clean it ?

Best regards,
Raphaël Poggi

2014-08-05 12:26 GMT+02:00 Jean-Christophe PLAGNIOL-VILLARD
<plagnioj@jcrosoft.com>:
>
> On Aug 5, 2014, at 2:37 AM, Raphaël Poggi <raphio98@gmail.com> wrote:
>
>>
>> I have planned to add device tree support for the AT91 port.
>>
>> So I port the pinctrl driver from linux to barebox to be able to use
>> the pinctrl in device tree, but maybe I made a mistake and there is
>> another solution.
>>
>
> I’ve a version already that I need to update and send
>
> Best Regards,
> J.
>> Best Regards,
>> Raphaël
>>
>> 2014-08-04 20:26 GMT+02:00 Jean-Christophe PLAGNIOL-VILLARD
>> <plagnioj@jcrosoft.com>:
>>> why do we need it on barebox?
>>>
>>> this driver was design for dt-only in linux
>>>
>>> Best Regards,
>>> J.
>>> On Aug 1, 2014, at 9:24 PM, Raphaël Poggi <poggi.raph@gmail.com> wrote:
>>>
>>>> This driver is based on mach-at91/gpio.c and linux pinctrl driver.
>>>> The driver contains the gpio and pinctrl parts (like in linux) because the two parts
>>>> share some structures and logics.
>>>>
>>>> Signed-off-by: Raphaël Poggi <poggi.raph@gmail.com>
>>>> ---
>>>> drivers/pinctrl/Kconfig        |    6 +
>>>> drivers/pinctrl/Makefile       |    1 +
>>>> drivers/pinctrl/pinctrl-at91.c |  529 ++++++++++++++++++++++++++++++++++++++++
>>>> drivers/pinctrl/pinctrl-at91.h |  148 +++++++++++
>>>> 4 files changed, 684 insertions(+)
>>>> create mode 100644 drivers/pinctrl/pinctrl-at91.c
>>>> create mode 100644 drivers/pinctrl/pinctrl-at91.h
>>>>
>>>> diff --git a/drivers/pinctrl/Kconfig b/drivers/pinctrl/Kconfig
>>>> index dffaa4e..ce55c7b 100644
>>>> --- a/drivers/pinctrl/Kconfig
>>>> +++ b/drivers/pinctrl/Kconfig
>>>> @@ -7,6 +7,12 @@ config PINCTRL
>>>>        from the devicetree. Legacy drivers here may not need this core
>>>>        support but instead provide their own SoC specific APIs
>>>>
>>>> +config PINCTRL_AT91
>>>> +     select PINCTRL
>>>> +     bool
>>>> +     help
>>>> +         The pinmux controller found on AT91 SoCs.
>>>> +
>>>> config PINCTRL_IMX_IOMUX_V1
>>>>      select PINCTRL if OFDEVICE
>>>>      bool
>>>> diff --git a/drivers/pinctrl/Makefile b/drivers/pinctrl/Makefile
>>>> index 566ba11..3ea8649 100644
>>>> --- a/drivers/pinctrl/Makefile
>>>> +++ b/drivers/pinctrl/Makefile
>>>> @@ -1,4 +1,5 @@
>>>> obj-$(CONFIG_PINCTRL) += pinctrl.o
>>>> +obj-$(CONFIG_PINCTRL_AT91) += pinctrl-at91.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
>>>> diff --git a/drivers/pinctrl/pinctrl-at91.c b/drivers/pinctrl/pinctrl-at91.c
>>>> new file mode 100644
>>>> index 0000000..a92a898
>>>> --- /dev/null
>>>> +++ b/drivers/pinctrl/pinctrl-at91.c
>>>> @@ -0,0 +1,529 @@
>>>> +/*
>>>> + * Copyright (C) 2005 HP Labs
>>>> + * Copyright (C) 2011-2012 Jean-Christophe PLAGNIOL-VILLARD <plagnioj@jcrosoft.com>
>>>> + * Copyright (C) 2014 Raphaël Poggi
>>>> + *
>>>> + * See file CREDITS for list of people who contributed to this
>>>> + * project.
>>>> + *
>>>> + * 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 <command.h>
>>>> +#include <complete.h>
>>>> +#include <linux/clk.h>
>>>> +#include <linux/err.h>
>>>> +#include <errno.h>
>>>> +#include <io.h>
>>>> +#include <gpio.h>
>>>> +#include <init.h>
>>>> +#include <driver.h>
>>>> +#include <getopt.h>
>>>> +
>>>> +#include <mach/at91_pio.h>
>>>> +
>>>> +#include <pinctrl.h>
>>>> +
>>>> +#include "pinctrl-at91.h"
>>>> +
>>>> +struct at91_pinctrl {
>>>> +    struct pinctrl_device pctl;
>>>> +    struct at91_pinctrl_mux_ops      *ops;
>>>> +};
>>>> +
>>>> +struct at91_gpio_chip {
>>>> +     struct gpio_chip        chip;
>>>> +     void __iomem            *regbase;       /* PIO bank virtual address */
>>>> +     struct at91_pinctrl_mux_ops *ops;       /* ops */
>>>> +};
>>>> +
>>>> +enum at91_mux {
>>>> +     AT91_MUX_GPIO = 0,
>>>> +     AT91_MUX_PERIPH_A = 1,
>>>> +     AT91_MUX_PERIPH_B = 2,
>>>> +     AT91_MUX_PERIPH_C = 3,
>>>> +     AT91_MUX_PERIPH_D = 4,
>>>> +};
>>>> +
>>>> +#define MAX_GPIO_BANKS               5
>>>> +#define to_at91_pinctrl(c) container_of(c, struct at91_pinctrl, pctl);
>>>> +#define to_at91_gpio_chip(c) container_of(c, struct at91_gpio_chip, chip)
>>>> +
>>>> +#define PULL_UP         (1 << 0)
>>>> +#define MULTI_DRIVE     (1 << 1)
>>>> +#define DEGLITCH        (1 << 2)
>>>> +#define PULL_DOWN       (1 << 3)
>>>> +#define DIS_SCHMIT      (1 << 4)
>>>> +#define DEBOUNCE        (1 << 16)
>>>> +#define DEBOUNCE_VAL_SHIFT      17
>>>> +#define DEBOUNCE_VAL    (0x3fff << DEBOUNCE_VAL_SHIFT)
>>>> +
>>>> +static int gpio_banks = 0;
>>>> +
>>>> +static struct at91_gpio_chip gpio_chip[MAX_GPIO_BANKS];
>>>> +
>>>> +static inline void __iomem *pin_to_controller(struct at91_pinctrl *info, unsigned pin)
>>>> +{
>>>> +     pin /= MAX_NB_GPIO_PER_BANK;
>>>> +     if (likely(pin < gpio_banks))
>>>> +             return gpio_chip[pin].regbase;
>>>> +
>>>> +     return NULL;
>>>> +}
>>>> +
>>>> +/**
>>>> + * struct at91_pinctrl_mux_ops - describes an At91 mux ops group
>>>> + * on new IP with support for periph C and D the way to mux in
>>>> + * periph A and B has changed
>>>> + * So provide the right call back
>>>> + * if not present means the IP does not support it
>>>> + * @get_periph: return the periph mode configured
>>>> + * @mux_A_periph: mux as periph A
>>>> + * @mux_B_periph: mux as periph B
>>>> + * @mux_C_periph: mux as periph C
>>>> + * @mux_D_periph: mux as periph D
>>>> + * @set_deglitch: enable/disable deglitch
>>>> + * @set_debounce: enable/disable debounce
>>>> + * @set_pulldown: enable/disable pulldown
>>>> + * @disable_schmitt_trig: disable schmitt trigger
>>>> + */
>>>> +struct at91_pinctrl_mux_ops {
>>>> +     enum at91_mux (*get_periph)(void __iomem *pio, unsigned mask);
>>>> +     void (*mux_A_periph)(void __iomem *pio, unsigned mask);
>>>> +     void (*mux_B_periph)(void __iomem *pio, unsigned mask);
>>>> +     void (*mux_C_periph)(void __iomem *pio, unsigned mask);
>>>> +     void (*mux_D_periph)(void __iomem *pio, unsigned mask);
>>>> +     bool (*get_deglitch)(void __iomem *pio, unsigned pin);
>>>> +     void (*set_deglitch)(void __iomem *pio, unsigned mask, bool in_on);
>>>> +     bool (*get_debounce)(void __iomem *pio, unsigned pin, u32 *div);
>>>> +     void (*set_debounce)(void __iomem *pio, unsigned mask, bool in_on, u32 div);
>>>> +     bool (*get_pulldown)(void __iomem *pio, unsigned pin);
>>>> +     void (*set_pulldown)(void __iomem *pio, unsigned mask, bool in_on);
>>>> +     bool (*get_schmitt_trig)(void __iomem *pio, unsigned pin);
>>>> +     void (*disable_schmitt_trig)(void __iomem *pio, unsigned mask);
>>>> +};
>>>> +
>>>> +static enum at91_mux at91_mux_pio3_get_periph(void __iomem *pio, unsigned mask)
>>>> +{
>>>> +     unsigned select;
>>>> +
>>>> +     if (__raw_readl(pio + PIO_PSR) & mask)
>>>> +             return AT91_MUX_GPIO;
>>>> +
>>>> +     select = !!(__raw_readl(pio + PIO_ABCDSR1) & mask);
>>>> +     select |= (!!(__raw_readl(pio + PIO_ABCDSR2) & mask) << 1);
>>>> +
>>>> +     return select + 1;
>>>> +}
>>>> +
>>>> +static enum at91_mux at91_mux_get_periph(void __iomem *pio, unsigned mask)
>>>> +{
>>>> +     unsigned select;
>>>> +
>>>> +     if (__raw_readl(pio + PIO_PSR) & mask)
>>>> +             return AT91_MUX_GPIO;
>>>> +
>>>> +     select = __raw_readl(pio + PIO_ABSR) & mask;
>>>> +
>>>> +     return select + 1;
>>>> +}
>>>> +
>>>> +static bool at91_mux_get_deglitch(void __iomem *pio, unsigned pin)
>>>> +{
>>>> +     return (__raw_readl(pio + PIO_IFSR) >> pin) & 0x1;
>>>> +}
>>>> +
>>>> +static bool at91_mux_pio3_get_debounce(void __iomem *pio, unsigned pin, u32 *div)
>>>> +{
>>>> +     *div = __raw_readl(pio + PIO_SCDR);
>>>> +
>>>> +     return (__raw_readl(pio + PIO_IFSCSR) >> pin) & 0x1;
>>>> +}
>>>> +
>>>> +static bool at91_mux_pio3_get_pulldown(void __iomem *pio, unsigned pin)
>>>> +{
>>>> +     return (__raw_readl(pio + PIO_PPDSR) >> pin) & 0x1;
>>>> +}
>>>> +
>>>> +static bool at91_mux_pio3_get_schmitt_trig(void __iomem *pio, unsigned pin)
>>>> +{
>>>> +     return (__raw_readl(pio + PIO_SCHMITT) >> pin) & 0x1;
>>>> +}
>>>> +
>>>> +static struct at91_pinctrl_mux_ops at91rm9200_ops = {
>>>> +     .get_periph     = at91_mux_get_periph,
>>>> +     .mux_A_periph   = at91_mux_set_A_periph,
>>>> +     .mux_B_periph   = at91_mux_set_B_periph,
>>>> +     .get_deglitch   = at91_mux_get_deglitch,
>>>> +     .set_deglitch   = at91_mux_set_deglitch,
>>>> +};
>>>> +
>>>> +static struct at91_pinctrl_mux_ops at91sam9x5_ops = {
>>>> +     .get_periph     = at91_mux_pio3_get_periph,
>>>> +     .mux_A_periph   = at91_mux_pio3_set_A_periph,
>>>> +     .mux_B_periph   = at91_mux_pio3_set_B_periph,
>>>> +     .mux_C_periph   = at91_mux_pio3_set_C_periph,
>>>> +     .mux_D_periph   = at91_mux_pio3_set_D_periph,
>>>> +     .get_deglitch   = at91_mux_get_deglitch,
>>>> +     .set_deglitch   = at91_mux_pio3_set_deglitch,
>>>> +     .get_debounce   = at91_mux_pio3_get_debounce,
>>>> +     .set_debounce   = at91_mux_pio3_set_debounce,
>>>> +     .get_pulldown   = at91_mux_pio3_get_pulldown,
>>>> +     .set_pulldown   = at91_mux_pio3_set_pulldown,
>>>> +     .get_schmitt_trig = at91_mux_pio3_get_schmitt_trig,
>>>> +     .disable_schmitt_trig = at91_mux_pio3_disable_schmitt_trig,
>>>> +};
>>>> +
>>>> +static int at91_mux_pin(struct at91_pinctrl *info, unsigned pin, enum at91_mux mux, int use_pullup)
>>>> +{
>>>> +     void __iomem    *pio = pin_to_controller(info, pin);
>>>> +     unsigned mask = pin_to_mask(pin);
>>>> +
>>>> +     if (!info)
>>>> +             return -EINVAL;
>>>> +
>>>> +     if (!pio)
>>>> +             return -EINVAL;
>>>> +
>>>> +     at91_mux_disable_interrupt(pio, mask);
>>>> +
>>>> +     switch(mux) {
>>>> +     case AT91_MUX_GPIO:
>>>> +             at91_mux_gpio_enable(pio, mask);
>>>> +             break;
>>>> +     case AT91_MUX_PERIPH_A:
>>>> +             info->ops->mux_A_periph(pio, mask);
>>>> +             break;
>>>> +     case AT91_MUX_PERIPH_B:
>>>> +             info->ops->mux_B_periph(pio, mask);
>>>> +             break;
>>>> +     case AT91_MUX_PERIPH_C:
>>>> +             if (!info->ops->mux_C_periph)
>>>> +                     return -EINVAL;
>>>> +             info->ops->mux_C_periph(pio, mask);
>>>> +             break;
>>>> +     case AT91_MUX_PERIPH_D:
>>>> +             if (!info->ops->mux_D_periph)
>>>> +                     return -EINVAL;
>>>> +             info->ops->mux_D_periph(pio, mask);
>>>> +             break;
>>>> +     }
>>>> +     if (mux)
>>>> +             at91_mux_gpio_disable(pio, mask);
>>>> +
>>>> +     if (use_pullup >= 0)
>>>> +             at91_mux_set_pullup(pio, mask, use_pullup);
>>>> +
>>>> +     return 0;
>>>> +}
>>>> +
>>>> +static struct of_device_id at91_pinctrl_dt_ids[] = {
>>>> +     {
>>>> +             .compatible = "atmel,at91rm9200-pinctrl",
>>>> +             .data = (unsigned long)&at91rm9200_ops,
>>>> +     }, {
>>>> +             .compatible = "atmel,at91sam9x5-pinctrl",
>>>> +             .data = (unsigned long)&at91sam9x5_ops,
>>>> +     }, {
>>>> +             /* sentinel */
>>>> +     }
>>>> +};
>>>> +
>>>> +static struct at91_pinctrl_mux_ops *at91_pinctrl_get_driver_data(struct device_d *dev)
>>>> +{
>>>> +    struct at91_pinctrl_mux_ops *ops_data = NULL;
>>>> +    int rc;
>>>> +
>>>> +    if (dev->device_node) {
>>>> +         const struct of_device_id *match;
>>>> +         match = of_match_node(at91_pinctrl_dt_ids, dev->device_node);
>>>> +         if (!match)
>>>> +                     ops_data = NULL;
>>>> +         else
>>>> +                     ops_data = (struct at91_pinctrl_mux_ops *)match->data;
>>>> +    }
>>>> +    else {
>>>> +         rc = dev_get_drvdata(dev, (unsigned long *)&ops_data);
>>>> +             if (rc)
>>>> +             ops_data = NULL;
>>>> +    }
>>>> +
>>>> +    return ops_data;
>>>> +}
>>>> +
>>>> +static int at91_pinctrl_set_conf(struct at91_pinctrl *info, unsigned int pin_num, unsigned int mux, unsigned int conf)
>>>> +{
>>>> +     unsigned int mask;
>>>> +     void __iomem *pio;
>>>> +
>>>> +     pio = pin_to_controller(info, pin_num);
>>>> +     mask = pin_to_mask(pin_num);
>>>> +
>>>> +     if (conf & PULL_UP && conf & PULL_DOWN)
>>>> +             return -EINVAL;
>>>> +
>>>> +     at91_mux_set_pullup(pio, mask, conf & PULL_UP);
>>>> +     at91_mux_set_multidrive(pio, mask, conf & MULTI_DRIVE);
>>>> +     if (info->ops->set_deglitch)
>>>> +             info->ops->set_deglitch(pio, mask, conf & DEGLITCH);
>>>> +     if (info->ops->set_debounce)
>>>> +             info->ops->set_debounce(pio, mask, conf & DEBOUNCE,
>>>> +                     (conf & DEBOUNCE_VAL) >> DEBOUNCE_VAL_SHIFT);
>>>> +     if (info->ops->set_pulldown)
>>>> +             info->ops->set_pulldown(pio, mask, conf & PULL_DOWN);
>>>> +     if (info->ops->disable_schmitt_trig && conf & DIS_SCHMIT)
>>>> +             info->ops->disable_schmitt_trig(pio, mask);
>>>> +
>>>> +     return 0;
>>>> +}
>>>> +
>>>> +static int at91_pinctrl_set_state(struct pinctrl_device *pdev, struct device_node *np)
>>>> +{
>>>> +     struct at91_pinctrl *info;
>>>> +     const __be32 *list;
>>>> +     int i, size;
>>>> +     int ret = 0;
>>>> +     int bank_num, pin_num, mux, conf;
>>>> +
>>>> +     info = to_at91_pinctrl(pdev);
>>>> +
>>>> +     list = of_get_property(np, "atmel,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) {
>>>> +             bank_num = be32_to_cpu(*list++);
>>>> +             pin_num = be32_to_cpu(*list++);
>>>> +             mux = be32_to_cpu(*list++);
>>>> +             conf = be32_to_cpu(*list++);
>>>> +
>>>> +             ret = at91_mux_pin(info, pin_num, mux, conf & PULL_UP);
>>>> +             if (ret) {
>>>> +                     dev_err(pdev->dev, "failed to mux pin %d\n", pin_num);
>>>> +                     return ret;
>>>> +             }
>>>> +
>>>> +             ret = at91_pinctrl_set_conf(info, pin_num, mux, conf);
>>>> +             if (ret) {
>>>> +                     dev_err(pdev->dev, "failed to set conf on pin %d\n", pin_num);
>>>> +                     return ret;
>>>> +             }
>>>> +     }
>>>> +
>>>> +     return ret;
>>>> +}
>>>> +
>>>> +static struct pinctrl_ops at91_pinctrl_ops = {
>>>> +     .set_state = at91_pinctrl_set_state,
>>>> +};
>>>> +
>>>> +static int at91_pinctrl_probe(struct device_d *dev)
>>>> +{
>>>> +     struct at91_pinctrl *info;
>>>> +     int ret;
>>>> +
>>>> +     info = xzalloc(sizeof(struct at91_pinctrl));
>>>> +
>>>> +     info->ops = at91_pinctrl_get_driver_data(dev);
>>>> +     if (!info->ops) {
>>>> +             dev_err(dev, "failed to retrieve driver data\n");
>>>> +             return -ENODEV;
>>>> +     }
>>>> +
>>>> +     info->pctl.dev = dev;
>>>> +     info->pctl.ops = &at91_pinctrl_ops;
>>>> +
>>>> +     ret = pinctrl_register(&info->pctl);
>>>> +     if (ret)
>>>> +             return ret;
>>>> +
>>>> +     dev_info(dev, "AT91 pinctrl registred\n");
>>>> +
>>>> +     return 0;
>>>> +}
>>>> +
>>>> +static struct platform_device_id at91_pinctrl_ids[] = {
>>>> +     {
>>>> +             .name = "at91rm9200-pinctrl",
>>>> +             .driver_data = (unsigned long)&at91rm9200_ops,
>>>> +     }, {
>>>> +             .name = "at91sam9x5-pinctrl",
>>>> +             .driver_data = (unsigned long)&at91sam9x5_ops,
>>>> +     }, {
>>>> +             /* sentinel */
>>>> +     },
>>>> +};
>>>> +
>>>> +static struct driver_d at91_pinctrl_driver = {
>>>> +     .name = "pinctrl-at91",
>>>> +     .probe = at91_pinctrl_probe,
>>>> +     .id_table = at91_pinctrl_ids,
>>>> +     .of_compatible = DRV_OF_COMPAT(at91_pinctrl_dt_ids),
>>>> +};
>>>> +
>>>> +static int at91_pinctrl_init(void)
>>>> +{
>>>> +     return platform_driver_register(&at91_pinctrl_driver);
>>>> +}
>>>> +coredevice_initcall(at91_pinctrl_init);
>>>> +
>>>> +static int at91_gpio_get(struct gpio_chip *chip, unsigned offset)
>>>> +{
>>>> +     struct at91_gpio_chip *at91_gpio = to_at91_gpio_chip(chip);
>>>> +     void __iomem *pio = at91_gpio->regbase;
>>>> +     unsigned mask = 1 << offset;
>>>> +
>>>> +     return at91_mux_gpio_get(pio, mask);
>>>> +}
>>>> +
>>>> +static void at91_gpio_set(struct gpio_chip *chip, unsigned offset, int value)
>>>> +{
>>>> +     struct at91_gpio_chip *at91_gpio = to_at91_gpio_chip(chip);
>>>> +     void __iomem *pio = at91_gpio->regbase;
>>>> +     unsigned mask = 1 << offset;
>>>> +
>>>> +     at91_mux_gpio_set(pio, mask, value);
>>>> +}
>>>> +
>>>> +static int at91_gpio_direction_output(struct gpio_chip *chip, unsigned offset,
>>>> +             int value)
>>>> +{
>>>> +     struct at91_gpio_chip *at91_gpio = to_at91_gpio_chip(chip);
>>>> +     void __iomem *pio = at91_gpio->regbase;
>>>> +     unsigned mask = 1 << offset;
>>>> +
>>>> +     at91_mux_gpio_set(pio, mask, value);
>>>> +     __raw_writel(mask, pio + PIO_OER);
>>>> +
>>>> +     return 0;
>>>> +}
>>>> +
>>>> +static int at91_gpio_direction_input(struct gpio_chip *chip, unsigned offset)
>>>> +{
>>>> +     struct at91_gpio_chip *at91_gpio = to_at91_gpio_chip(chip);
>>>> +     void __iomem *pio = at91_gpio->regbase;
>>>> +     unsigned mask = 1 << offset;
>>>> +
>>>> +     __raw_writel(mask, pio + PIO_ODR);
>>>> +
>>>> +     return 0;
>>>> +}
>>>> +
>>>> +static int at91_gpio_request(struct gpio_chip *chip, unsigned offset)
>>>> +{
>>>> +     struct at91_gpio_chip *at91_gpio = to_at91_gpio_chip(chip);
>>>> +     void __iomem *pio = at91_gpio->regbase;
>>>> +     unsigned mask = 1 << offset;
>>>> +
>>>> +     dev_dbg(chip->dev, "%s:%d pio%c%d(%d)\n", __func__, __LINE__,
>>>> +              'A' + pin_to_bank(chip->base), offset, chip->base + offset);
>>>> +     at91_mux_gpio_enable(pio, mask);
>>>> +
>>>> +     return 0;
>>>> +}
>>>> +
>>>> +static void at91_gpio_free(struct gpio_chip *chip, unsigned offset)
>>>> +{
>>>> +     dev_dbg(chip->dev, "%s:%d pio%c%d(%d)\n", __func__, __LINE__,
>>>> +              'A' + pin_to_bank(chip->base), offset, chip->base + offset);
>>>> +}
>>>> +
>>>> +static struct gpio_ops at91_gpio_ops = {
>>>> +     .request = at91_gpio_request,
>>>> +     .free = at91_gpio_free,
>>>> +     .direction_input = at91_gpio_direction_input,
>>>> +     .direction_output = at91_gpio_direction_output,
>>>> +     .get = at91_gpio_get,
>>>> +     .set = at91_gpio_set,
>>>> +};
>>>> +
>>>> +static struct of_device_id at91_gpio_dt_ids[] = {
>>>> +     {
>>>> +             .compatible = "atmel,at91rm9200-gpio",
>>>> +     }, {
>>>> +             .compatible = "atmel,at91sam9x5-gpio",
>>>> +     }, {
>>>> +             /* sentinel */
>>>> +     },
>>>> +};
>>>> +
>>>> +static int at91_gpio_probe(struct device_d *dev)
>>>> +{
>>>> +     struct at91_gpio_chip *at91_gpio;
>>>> +     struct clk *clk;
>>>> +     int ret;
>>>> +     int alias_idx = of_alias_get_id(dev->device_node, "gpio");
>>>> +
>>>> +     BUG_ON(dev->id > MAX_GPIO_BANKS);
>>>> +
>>>> +     at91_gpio = &gpio_chip[alias_idx];
>>>> +
>>>> +     clk = clk_get(dev, NULL);
>>>> +     if (IS_ERR(clk)) {
>>>> +             ret = PTR_ERR(clk);
>>>> +             dev_err(dev, "clock not found: %d\n", ret);
>>>> +             return ret;
>>>> +     }
>>>> +
>>>> +     ret = clk_enable(clk);
>>>> +     if (ret < 0) {
>>>> +             dev_err(dev, "clock failed to enable: %d\n", ret);
>>>> +             clk_put(clk);
>>>> +             return ret;
>>>> +     }
>>>> +
>>>> +     gpio_banks = max(gpio_banks, alias_idx + 1);
>>>> +     at91_gpio->regbase = dev_request_mem_region(dev, 0);
>>>> +
>>>> +     at91_gpio->chip.ops = &at91_gpio_ops;
>>>> +     at91_gpio->chip.ngpio = MAX_NB_GPIO_PER_BANK;
>>>> +     at91_gpio->chip.dev = dev;
>>>> +     at91_gpio->chip.base = dev->id * MAX_NB_GPIO_PER_BANK;
>>>> +
>>>> +     ret = gpiochip_add(&at91_gpio->chip);
>>>> +     if (ret) {
>>>> +             dev_err(dev, "couldn't add gpiochip, ret = %d\n", ret);
>>>> +             return ret;
>>>> +     }
>>>> +
>>>> +     dev_info(dev, "AT91 gpio driver registred\n");
>>>> +
>>>> +     return 0;
>>>> +}
>>>> +
>>>> +static struct platform_device_id at91_gpio_ids[] = {
>>>> +     {
>>>> +             .name = "at91rm9200-gpio",
>>>> +     }, {
>>>> +             .name = "at91sam9x5-gpio",
>>>> +     }, {
>>>> +             /* sentinel */
>>>> +     },
>>>> +};
>>>> +
>>>> +static struct driver_d at91_gpio_driver = {
>>>> +     .name = "gpio-at91",
>>>> +     .probe = at91_gpio_probe,
>>>> +     .id_table = at91_gpio_ids,
>>>> +     .of_compatible  = DRV_OF_COMPAT(at91_gpio_dt_ids),
>>>> +};
>>>> +
>>>> +static int at91_gpio_init(void)
>>>> +{
>>>> +     return platform_driver_register(&at91_gpio_driver);
>>>> +}
>>>> +coredevice_initcall(at91_gpio_init);
>>>> diff --git a/drivers/pinctrl/pinctrl-at91.h b/drivers/pinctrl/pinctrl-at91.h
>>>> new file mode 100644
>>>> index 0000000..e719fb8
>>>> --- /dev/null
>>>> +++ b/drivers/pinctrl/pinctrl-at91.h
>>>> @@ -0,0 +1,148 @@
>>>> +/*
>>>> + * Copyright (C) 2011-2012 Jean-Christophe PLAGNIOL-VILLARD <plagnioj@jcrosoft.com>
>>>> + *
>>>> + * Under GPLv2 only
>>>> + */
>>>> +
>>>> +#ifndef __AT91_GPIO_H__
>>>> +#define __AT91_GPIO_H__
>>>> +
>>>> +#ifndef __gpio_init
>>>> +#define __gpio_init
>>>> +#endif
>>>> +
>>>> +#define MAX_NB_GPIO_PER_BANK 32
>>>> +
>>>> +static inline unsigned pin_to_bank(unsigned pin)
>>>> +{
>>>> +     return pin / MAX_NB_GPIO_PER_BANK;
>>>> +}
>>>> +
>>>> +static inline unsigned pin_to_bank_offset(unsigned pin)
>>>> +{
>>>> +     return pin % MAX_NB_GPIO_PER_BANK;
>>>> +}
>>>> +
>>>> +static inline unsigned pin_to_mask(unsigned pin)
>>>> +{
>>>> +     return 1 << pin_to_bank_offset(pin);
>>>> +}
>>>> +
>>>> +static inline void at91_mux_disable_interrupt(void __iomem *pio, unsigned mask)
>>>> +{
>>>> +     __raw_writel(mask, pio + PIO_IDR);
>>>> +}
>>>> +
>>>> +static inline void at91_mux_set_pullup(void __iomem *pio, unsigned mask, bool on)
>>>> +{
>>>> +     __raw_writel(mask, pio + (on ? PIO_PUER : PIO_PUDR));
>>>> +}
>>>> +
>>>> +static inline void at91_mux_set_multidrive(void __iomem *pio, unsigned mask, bool on)
>>>> +{
>>>> +     __raw_writel(mask, pio + (on ? PIO_MDER : PIO_MDDR));
>>>> +}
>>>> +
>>>> +static inline void at91_mux_set_A_periph(void __iomem *pio, unsigned mask)
>>>> +{
>>>> +     __raw_writel(mask, pio + PIO_ASR);
>>>> +}
>>>> +
>>>> +static inline void at91_mux_set_B_periph(void __iomem *pio, unsigned mask)
>>>> +{
>>>> +     __raw_writel(mask, pio + PIO_BSR);
>>>> +}
>>>> +
>>>> +static inline void at91_mux_pio3_set_A_periph(void __iomem *pio, unsigned mask)
>>>> +{
>>>> +
>>>> +     __raw_writel(__raw_readl(pio + PIO_ABCDSR1) & ~mask,
>>>> +                                             pio + PIO_ABCDSR1);
>>>> +     __raw_writel(__raw_readl(pio + PIO_ABCDSR2) & ~mask,
>>>> +                                             pio + PIO_ABCDSR2);
>>>> +}
>>>> +
>>>> +static inline void at91_mux_pio3_set_B_periph(void __iomem *pio, unsigned mask)
>>>> +{
>>>> +     __raw_writel(__raw_readl(pio + PIO_ABCDSR1) | mask,
>>>> +                                             pio + PIO_ABCDSR1);
>>>> +     __raw_writel(__raw_readl(pio + PIO_ABCDSR2) & ~mask,
>>>> +                                             pio + PIO_ABCDSR2);
>>>> +}
>>>> +
>>>> +static inline void at91_mux_pio3_set_C_periph(void __iomem *pio, unsigned mask)
>>>> +{
>>>> +     __raw_writel(__raw_readl(pio + PIO_ABCDSR1) & ~mask, pio + PIO_ABCDSR1);
>>>> +     __raw_writel(__raw_readl(pio + PIO_ABCDSR2) | mask, pio + PIO_ABCDSR2);
>>>> +}
>>>> +
>>>> +static inline void at91_mux_pio3_set_D_periph(void __iomem *pio, unsigned mask)
>>>> +{
>>>> +     __raw_writel(__raw_readl(pio + PIO_ABCDSR1) | mask, pio + PIO_ABCDSR1);
>>>> +     __raw_writel(__raw_readl(pio + PIO_ABCDSR2) | mask, pio + PIO_ABCDSR2);
>>>> +}
>>>> +
>>>> +static inline void at91_mux_set_deglitch(void __iomem *pio, unsigned mask, bool is_on)
>>>> +{
>>>> +     __raw_writel(mask, pio + (is_on ? PIO_IFER : PIO_IFDR));
>>>> +}
>>>> +
>>>> +static inline void at91_mux_pio3_set_deglitch(void __iomem *pio, unsigned mask, bool is_on)
>>>> +{
>>>> +     if (is_on)
>>>> +             __raw_writel(mask, pio + PIO_IFSCDR);
>>>> +     at91_mux_set_deglitch(pio, mask, is_on);
>>>> +}
>>>> +
>>>> +static inline void at91_mux_pio3_set_debounce(void __iomem *pio, unsigned mask,
>>>> +                             bool is_on, u32 div)
>>>> +{
>>>> +     if (is_on) {
>>>> +             __raw_writel(mask, pio + PIO_IFSCER);
>>>> +             __raw_writel(div & PIO_SCDR_DIV, pio + PIO_SCDR);
>>>> +             __raw_writel(mask, pio + PIO_IFER);
>>>> +     } else {
>>>> +             __raw_writel(mask, pio + PIO_IFDR);
>>>> +     }
>>>> +}
>>>> +
>>>> +static inline void at91_mux_pio3_set_pulldown(void __iomem *pio, unsigned mask, bool is_on)
>>>> +{
>>>> +     __raw_writel(mask, pio + (is_on ? PIO_PPDER : PIO_PPDDR));
>>>> +}
>>>> +
>>>> +static inline void at91_mux_pio3_disable_schmitt_trig(void __iomem *pio, unsigned mask)
>>>> +{
>>>> +     __raw_writel(__raw_readl(pio + PIO_SCHMITT) | mask, pio + PIO_SCHMITT);
>>>> +}
>>>> +
>>>> +static inline void at91_mux_gpio_disable(void __iomem *pio, unsigned mask)
>>>> +{
>>>> +     __raw_writel(mask, pio + PIO_PDR);
>>>> +}
>>>> +
>>>> +static inline void at91_mux_gpio_enable(void __iomem *pio, unsigned mask)
>>>> +{
>>>> +     __raw_writel(mask, pio + PIO_PER);
>>>> +}
>>>> +
>>>> +static inline void at91_mux_gpio_input(void __iomem *pio, unsigned mask, bool input)
>>>> +{
>>>> +     __raw_writel(mask, pio + (input ? PIO_ODR : PIO_OER));
>>>> +}
>>>> +
>>>> +static inline void at91_mux_gpio_set(void __iomem *pio, unsigned mask,
>>>> +int value)
>>>> +{
>>>> +     __raw_writel(mask, pio + (value ? PIO_SODR : PIO_CODR));
>>>> +}
>>>> +
>>>> +static inline int at91_mux_gpio_get(void __iomem *pio, unsigned mask)
>>>> +{
>>>> +       u32 pdsr;
>>>> +
>>>> +       pdsr = __raw_readl(pio + PIO_PDSR);
>>>> +       return (pdsr & mask) != 0;
>>>> +}
>>>> +
>>>> +#endif /* __AT91_GPIO_H__ */
>>>> --
>>>> 1.7.9.5
>>>>
>>>>
>>>> _______________________________________________
>>>> barebox mailing list
>>>> barebox@lists.infradead.org
>>>> http://lists.infradead.org/mailman/listinfo/barebox
>>>
>>>
>>> _______________________________________________
>>> barebox mailing list
>>> barebox@lists.infradead.org
>>> http://lists.infradead.org/mailman/listinfo/barebox
>

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

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

* Re: [PATCH 1/2] pinctrl: at91: add pinctrl driver
       [not found]             ` <CA5BE09F-18DF-49EE-83D8-65BB761BB903@jcrosoft.com>
@ 2014-08-06  7:12               ` Raphaël Poggi
  0 siblings, 0 replies; 10+ messages in thread
From: Raphaël Poggi @ 2014-08-06  7:12 UTC (permalink / raw)
  To: Jean-Christophe PLAGNIOL-VILLARD, barebox

Ok, let's do it like that

Best regards,
Raphaël Poggi

2014-08-06 5:48 GMT+02:00 Jean-Christophe PLAGNIOL-VILLARD
<plagnioj@jcrosoft.com>:
>
> On Aug 6, 2014, at 11:46 AM, Jean-Christophe PLAGNIOL-VILLARD <plagnioj@jcrosoft.com> wrote:
>
>>
>> On Aug 5, 2014, at 7:38 PM, Raphaël Poggi <raphio98@gmail.com> wrote:
>>
>>>
>>> Ok, so I drop my patch ? Or your version is very similar of my patch
>>> and you can review mine to improve/clean it ?
>>
>> I’ve a patch series to have dt on at91, my patch for the pinctrl is not finish
>>
>
> sorry I mean my patch series is not yet fully clean
>
>> give me few days to send it and we see after
>>
>> Best Regards,
>> J.
>>>
>>> Best regards,
>>> Raphaël Poggi
>>>
>>> 2014-08-05 12:26 GMT+02:00 Jean-Christophe PLAGNIOL-VILLARD
>>> <plagnioj@jcrosoft.com>:
>>>>
>>>> On Aug 5, 2014, at 2:37 AM, Raphaël Poggi <raphio98@gmail.com> wrote:
>>>>
>>>>>
>>>>> I have planned to add device tree support for the AT91 port.
>>>>>
>>>>> So I port the pinctrl driver from linux to barebox to be able to use
>>>>> the pinctrl in device tree, but maybe I made a mistake and there is
>>>>> another solution.
>>>>>
>>>>
>>>> I’ve a version already that I need to update and send
>>>>
>>>> Best Regards,
>>>> J.
>>>>> Best Regards,
>>>>> Raphaël
>>>>>
>>>>> 2014-08-04 20:26 GMT+02:00 Jean-Christophe PLAGNIOL-VILLARD
>>>>> <plagnioj@jcrosoft.com>:
>>>>>> why do we need it on barebox?
>>>>>>
>>>>>> this driver was design for dt-only in linux
>>>>>>
>>>>>> Best Regards,
>>>>>> J.
>>>>>> On Aug 1, 2014, at 9:24 PM, Raphaël Poggi <poggi.raph@gmail.com> wrote:
>>>>>>
>>>>>>> This driver is based on mach-at91/gpio.c and linux pinctrl driver.
>>>>>>> The driver contains the gpio and pinctrl parts (like in linux) because the two parts
>>>>>>> share some structures and logics.
>>>>>>>
>>>>>>> Signed-off-by: Raphaël Poggi <poggi.raph@gmail.com>
>>>>>>> ---
>>>>>>> drivers/pinctrl/Kconfig        |    6 +
>>>>>>> drivers/pinctrl/Makefile       |    1 +
>>>>>>> drivers/pinctrl/pinctrl-at91.c |  529 ++++++++++++++++++++++++++++++++++++++++
>>>>>>> drivers/pinctrl/pinctrl-at91.h |  148 +++++++++++
>>>>>>> 4 files changed, 684 insertions(+)
>>>>>>> create mode 100644 drivers/pinctrl/pinctrl-at91.c
>>>>>>> create mode 100644 drivers/pinctrl/pinctrl-at91.h
>>>>>>>
>>>>>>> diff --git a/drivers/pinctrl/Kconfig b/drivers/pinctrl/Kconfig
>>>>>>> index dffaa4e..ce55c7b 100644
>>>>>>> --- a/drivers/pinctrl/Kconfig
>>>>>>> +++ b/drivers/pinctrl/Kconfig
>>>>>>> @@ -7,6 +7,12 @@ config PINCTRL
>>>>>>>      from the devicetree. Legacy drivers here may not need this core
>>>>>>>      support but instead provide their own SoC specific APIs
>>>>>>>
>>>>>>> +config PINCTRL_AT91
>>>>>>> +     select PINCTRL
>>>>>>> +     bool
>>>>>>> +     help
>>>>>>> +         The pinmux controller found on AT91 SoCs.
>>>>>>> +
>>>>>>> config PINCTRL_IMX_IOMUX_V1
>>>>>>>    select PINCTRL if OFDEVICE
>>>>>>>    bool
>>>>>>> diff --git a/drivers/pinctrl/Makefile b/drivers/pinctrl/Makefile
>>>>>>> index 566ba11..3ea8649 100644
>>>>>>> --- a/drivers/pinctrl/Makefile
>>>>>>> +++ b/drivers/pinctrl/Makefile
>>>>>>> @@ -1,4 +1,5 @@
>>>>>>> obj-$(CONFIG_PINCTRL) += pinctrl.o
>>>>>>> +obj-$(CONFIG_PINCTRL_AT91) += pinctrl-at91.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
>>>>>>> diff --git a/drivers/pinctrl/pinctrl-at91.c b/drivers/pinctrl/pinctrl-at91.c
>>>>>>> new file mode 100644
>>>>>>> index 0000000..a92a898
>>>>>>> --- /dev/null
>>>>>>> +++ b/drivers/pinctrl/pinctrl-at91.c
>>>>>>> @@ -0,0 +1,529 @@
>>>>>>> +/*
>>>>>>> + * Copyright (C) 2005 HP Labs
>>>>>>> + * Copyright (C) 2011-2012 Jean-Christophe PLAGNIOL-VILLARD <plagnioj@jcrosoft.com>
>>>>>>> + * Copyright (C) 2014 Raphaël Poggi
>>>>>>> + *
>>>>>>> + * See file CREDITS for list of people who contributed to this
>>>>>>> + * project.
>>>>>>> + *
>>>>>>> + * 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 <command.h>
>>>>>>> +#include <complete.h>
>>>>>>> +#include <linux/clk.h>
>>>>>>> +#include <linux/err.h>
>>>>>>> +#include <errno.h>
>>>>>>> +#include <io.h>
>>>>>>> +#include <gpio.h>
>>>>>>> +#include <init.h>
>>>>>>> +#include <driver.h>
>>>>>>> +#include <getopt.h>
>>>>>>> +
>>>>>>> +#include <mach/at91_pio.h>
>>>>>>> +
>>>>>>> +#include <pinctrl.h>
>>>>>>> +
>>>>>>> +#include "pinctrl-at91.h"
>>>>>>> +
>>>>>>> +struct at91_pinctrl {
>>>>>>> +    struct pinctrl_device pctl;
>>>>>>> +    struct at91_pinctrl_mux_ops      *ops;
>>>>>>> +};
>>>>>>> +
>>>>>>> +struct at91_gpio_chip {
>>>>>>> +     struct gpio_chip        chip;
>>>>>>> +     void __iomem            *regbase;       /* PIO bank virtual address */
>>>>>>> +     struct at91_pinctrl_mux_ops *ops;       /* ops */
>>>>>>> +};
>>>>>>> +
>>>>>>> +enum at91_mux {
>>>>>>> +     AT91_MUX_GPIO = 0,
>>>>>>> +     AT91_MUX_PERIPH_A = 1,
>>>>>>> +     AT91_MUX_PERIPH_B = 2,
>>>>>>> +     AT91_MUX_PERIPH_C = 3,
>>>>>>> +     AT91_MUX_PERIPH_D = 4,
>>>>>>> +};
>>>>>>> +
>>>>>>> +#define MAX_GPIO_BANKS               5
>>>>>>> +#define to_at91_pinctrl(c) container_of(c, struct at91_pinctrl, pctl);
>>>>>>> +#define to_at91_gpio_chip(c) container_of(c, struct at91_gpio_chip, chip)
>>>>>>> +
>>>>>>> +#define PULL_UP         (1 << 0)
>>>>>>> +#define MULTI_DRIVE     (1 << 1)
>>>>>>> +#define DEGLITCH        (1 << 2)
>>>>>>> +#define PULL_DOWN       (1 << 3)
>>>>>>> +#define DIS_SCHMIT      (1 << 4)
>>>>>>> +#define DEBOUNCE        (1 << 16)
>>>>>>> +#define DEBOUNCE_VAL_SHIFT      17
>>>>>>> +#define DEBOUNCE_VAL    (0x3fff << DEBOUNCE_VAL_SHIFT)
>>>>>>> +
>>>>>>> +static int gpio_banks = 0;
>>>>>>> +
>>>>>>> +static struct at91_gpio_chip gpio_chip[MAX_GPIO_BANKS];
>>>>>>> +
>>>>>>> +static inline void __iomem *pin_to_controller(struct at91_pinctrl *info, unsigned pin)
>>>>>>> +{
>>>>>>> +     pin /= MAX_NB_GPIO_PER_BANK;
>>>>>>> +     if (likely(pin < gpio_banks))
>>>>>>> +             return gpio_chip[pin].regbase;
>>>>>>> +
>>>>>>> +     return NULL;
>>>>>>> +}
>>>>>>> +
>>>>>>> +/**
>>>>>>> + * struct at91_pinctrl_mux_ops - describes an At91 mux ops group
>>>>>>> + * on new IP with support for periph C and D the way to mux in
>>>>>>> + * periph A and B has changed
>>>>>>> + * So provide the right call back
>>>>>>> + * if not present means the IP does not support it
>>>>>>> + * @get_periph: return the periph mode configured
>>>>>>> + * @mux_A_periph: mux as periph A
>>>>>>> + * @mux_B_periph: mux as periph B
>>>>>>> + * @mux_C_periph: mux as periph C
>>>>>>> + * @mux_D_periph: mux as periph D
>>>>>>> + * @set_deglitch: enable/disable deglitch
>>>>>>> + * @set_debounce: enable/disable debounce
>>>>>>> + * @set_pulldown: enable/disable pulldown
>>>>>>> + * @disable_schmitt_trig: disable schmitt trigger
>>>>>>> + */
>>>>>>> +struct at91_pinctrl_mux_ops {
>>>>>>> +     enum at91_mux (*get_periph)(void __iomem *pio, unsigned mask);
>>>>>>> +     void (*mux_A_periph)(void __iomem *pio, unsigned mask);
>>>>>>> +     void (*mux_B_periph)(void __iomem *pio, unsigned mask);
>>>>>>> +     void (*mux_C_periph)(void __iomem *pio, unsigned mask);
>>>>>>> +     void (*mux_D_periph)(void __iomem *pio, unsigned mask);
>>>>>>> +     bool (*get_deglitch)(void __iomem *pio, unsigned pin);
>>>>>>> +     void (*set_deglitch)(void __iomem *pio, unsigned mask, bool in_on);
>>>>>>> +     bool (*get_debounce)(void __iomem *pio, unsigned pin, u32 *div);
>>>>>>> +     void (*set_debounce)(void __iomem *pio, unsigned mask, bool in_on, u32 div);
>>>>>>> +     bool (*get_pulldown)(void __iomem *pio, unsigned pin);
>>>>>>> +     void (*set_pulldown)(void __iomem *pio, unsigned mask, bool in_on);
>>>>>>> +     bool (*get_schmitt_trig)(void __iomem *pio, unsigned pin);
>>>>>>> +     void (*disable_schmitt_trig)(void __iomem *pio, unsigned mask);
>>>>>>> +};
>>>>>>> +
>>>>>>> +static enum at91_mux at91_mux_pio3_get_periph(void __iomem *pio, unsigned mask)
>>>>>>> +{
>>>>>>> +     unsigned select;
>>>>>>> +
>>>>>>> +     if (__raw_readl(pio + PIO_PSR) & mask)
>>>>>>> +             return AT91_MUX_GPIO;
>>>>>>> +
>>>>>>> +     select = !!(__raw_readl(pio + PIO_ABCDSR1) & mask);
>>>>>>> +     select |= (!!(__raw_readl(pio + PIO_ABCDSR2) & mask) << 1);
>>>>>>> +
>>>>>>> +     return select + 1;
>>>>>>> +}
>>>>>>> +
>>>>>>> +static enum at91_mux at91_mux_get_periph(void __iomem *pio, unsigned mask)
>>>>>>> +{
>>>>>>> +     unsigned select;
>>>>>>> +
>>>>>>> +     if (__raw_readl(pio + PIO_PSR) & mask)
>>>>>>> +             return AT91_MUX_GPIO;
>>>>>>> +
>>>>>>> +     select = __raw_readl(pio + PIO_ABSR) & mask;
>>>>>>> +
>>>>>>> +     return select + 1;
>>>>>>> +}
>>>>>>> +
>>>>>>> +static bool at91_mux_get_deglitch(void __iomem *pio, unsigned pin)
>>>>>>> +{
>>>>>>> +     return (__raw_readl(pio + PIO_IFSR) >> pin) & 0x1;
>>>>>>> +}
>>>>>>> +
>>>>>>> +static bool at91_mux_pio3_get_debounce(void __iomem *pio, unsigned pin, u32 *div)
>>>>>>> +{
>>>>>>> +     *div = __raw_readl(pio + PIO_SCDR);
>>>>>>> +
>>>>>>> +     return (__raw_readl(pio + PIO_IFSCSR) >> pin) & 0x1;
>>>>>>> +}
>>>>>>> +
>>>>>>> +static bool at91_mux_pio3_get_pulldown(void __iomem *pio, unsigned pin)
>>>>>>> +{
>>>>>>> +     return (__raw_readl(pio + PIO_PPDSR) >> pin) & 0x1;
>>>>>>> +}
>>>>>>> +
>>>>>>> +static bool at91_mux_pio3_get_schmitt_trig(void __iomem *pio, unsigned pin)
>>>>>>> +{
>>>>>>> +     return (__raw_readl(pio + PIO_SCHMITT) >> pin) & 0x1;
>>>>>>> +}
>>>>>>> +
>>>>>>> +static struct at91_pinctrl_mux_ops at91rm9200_ops = {
>>>>>>> +     .get_periph     = at91_mux_get_periph,
>>>>>>> +     .mux_A_periph   = at91_mux_set_A_periph,
>>>>>>> +     .mux_B_periph   = at91_mux_set_B_periph,
>>>>>>> +     .get_deglitch   = at91_mux_get_deglitch,
>>>>>>> +     .set_deglitch   = at91_mux_set_deglitch,
>>>>>>> +};
>>>>>>> +
>>>>>>> +static struct at91_pinctrl_mux_ops at91sam9x5_ops = {
>>>>>>> +     .get_periph     = at91_mux_pio3_get_periph,
>>>>>>> +     .mux_A_periph   = at91_mux_pio3_set_A_periph,
>>>>>>> +     .mux_B_periph   = at91_mux_pio3_set_B_periph,
>>>>>>> +     .mux_C_periph   = at91_mux_pio3_set_C_periph,
>>>>>>> +     .mux_D_periph   = at91_mux_pio3_set_D_periph,
>>>>>>> +     .get_deglitch   = at91_mux_get_deglitch,
>>>>>>> +     .set_deglitch   = at91_mux_pio3_set_deglitch,
>>>>>>> +     .get_debounce   = at91_mux_pio3_get_debounce,
>>>>>>> +     .set_debounce   = at91_mux_pio3_set_debounce,
>>>>>>> +     .get_pulldown   = at91_mux_pio3_get_pulldown,
>>>>>>> +     .set_pulldown   = at91_mux_pio3_set_pulldown,
>>>>>>> +     .get_schmitt_trig = at91_mux_pio3_get_schmitt_trig,
>>>>>>> +     .disable_schmitt_trig = at91_mux_pio3_disable_schmitt_trig,
>>>>>>> +};
>>>>>>> +
>>>>>>> +static int at91_mux_pin(struct at91_pinctrl *info, unsigned pin, enum at91_mux mux, int use_pullup)
>>>>>>> +{
>>>>>>> +     void __iomem    *pio = pin_to_controller(info, pin);
>>>>>>> +     unsigned mask = pin_to_mask(pin);
>>>>>>> +
>>>>>>> +     if (!info)
>>>>>>> +             return -EINVAL;
>>>>>>> +
>>>>>>> +     if (!pio)
>>>>>>> +             return -EINVAL;
>>>>>>> +
>>>>>>> +     at91_mux_disable_interrupt(pio, mask);
>>>>>>> +
>>>>>>> +     switch(mux) {
>>>>>>> +     case AT91_MUX_GPIO:
>>>>>>> +             at91_mux_gpio_enable(pio, mask);
>>>>>>> +             break;
>>>>>>> +     case AT91_MUX_PERIPH_A:
>>>>>>> +             info->ops->mux_A_periph(pio, mask);
>>>>>>> +             break;
>>>>>>> +     case AT91_MUX_PERIPH_B:
>>>>>>> +             info->ops->mux_B_periph(pio, mask);
>>>>>>> +             break;
>>>>>>> +     case AT91_MUX_PERIPH_C:
>>>>>>> +             if (!info->ops->mux_C_periph)
>>>>>>> +                     return -EINVAL;
>>>>>>> +             info->ops->mux_C_periph(pio, mask);
>>>>>>> +             break;
>>>>>>> +     case AT91_MUX_PERIPH_D:
>>>>>>> +             if (!info->ops->mux_D_periph)
>>>>>>> +                     return -EINVAL;
>>>>>>> +             info->ops->mux_D_periph(pio, mask);
>>>>>>> +             break;
>>>>>>> +     }
>>>>>>> +     if (mux)
>>>>>>> +             at91_mux_gpio_disable(pio, mask);
>>>>>>> +
>>>>>>> +     if (use_pullup >= 0)
>>>>>>> +             at91_mux_set_pullup(pio, mask, use_pullup);
>>>>>>> +
>>>>>>> +     return 0;
>>>>>>> +}
>>>>>>> +
>>>>>>> +static struct of_device_id at91_pinctrl_dt_ids[] = {
>>>>>>> +     {
>>>>>>> +             .compatible = "atmel,at91rm9200-pinctrl",
>>>>>>> +             .data = (unsigned long)&at91rm9200_ops,
>>>>>>> +     }, {
>>>>>>> +             .compatible = "atmel,at91sam9x5-pinctrl",
>>>>>>> +             .data = (unsigned long)&at91sam9x5_ops,
>>>>>>> +     }, {
>>>>>>> +             /* sentinel */
>>>>>>> +     }
>>>>>>> +};
>>>>>>> +
>>>>>>> +static struct at91_pinctrl_mux_ops *at91_pinctrl_get_driver_data(struct device_d *dev)
>>>>>>> +{
>>>>>>> +    struct at91_pinctrl_mux_ops *ops_data = NULL;
>>>>>>> +    int rc;
>>>>>>> +
>>>>>>> +    if (dev->device_node) {
>>>>>>> +         const struct of_device_id *match;
>>>>>>> +         match = of_match_node(at91_pinctrl_dt_ids, dev->device_node);
>>>>>>> +         if (!match)
>>>>>>> +                     ops_data = NULL;
>>>>>>> +         else
>>>>>>> +                     ops_data = (struct at91_pinctrl_mux_ops *)match->data;
>>>>>>> +    }
>>>>>>> +    else {
>>>>>>> +         rc = dev_get_drvdata(dev, (unsigned long *)&ops_data);
>>>>>>> +             if (rc)
>>>>>>> +             ops_data = NULL;
>>>>>>> +    }
>>>>>>> +
>>>>>>> +    return ops_data;
>>>>>>> +}
>>>>>>> +
>>>>>>> +static int at91_pinctrl_set_conf(struct at91_pinctrl *info, unsigned int pin_num, unsigned int mux, unsigned int conf)
>>>>>>> +{
>>>>>>> +     unsigned int mask;
>>>>>>> +     void __iomem *pio;
>>>>>>> +
>>>>>>> +     pio = pin_to_controller(info, pin_num);
>>>>>>> +     mask = pin_to_mask(pin_num);
>>>>>>> +
>>>>>>> +     if (conf & PULL_UP && conf & PULL_DOWN)
>>>>>>> +             return -EINVAL;
>>>>>>> +
>>>>>>> +     at91_mux_set_pullup(pio, mask, conf & PULL_UP);
>>>>>>> +     at91_mux_set_multidrive(pio, mask, conf & MULTI_DRIVE);
>>>>>>> +     if (info->ops->set_deglitch)
>>>>>>> +             info->ops->set_deglitch(pio, mask, conf & DEGLITCH);
>>>>>>> +     if (info->ops->set_debounce)
>>>>>>> +             info->ops->set_debounce(pio, mask, conf & DEBOUNCE,
>>>>>>> +                     (conf & DEBOUNCE_VAL) >> DEBOUNCE_VAL_SHIFT);
>>>>>>> +     if (info->ops->set_pulldown)
>>>>>>> +             info->ops->set_pulldown(pio, mask, conf & PULL_DOWN);
>>>>>>> +     if (info->ops->disable_schmitt_trig && conf & DIS_SCHMIT)
>>>>>>> +             info->ops->disable_schmitt_trig(pio, mask);
>>>>>>> +
>>>>>>> +     return 0;
>>>>>>> +}
>>>>>>> +
>>>>>>> +static int at91_pinctrl_set_state(struct pinctrl_device *pdev, struct device_node *np)
>>>>>>> +{
>>>>>>> +     struct at91_pinctrl *info;
>>>>>>> +     const __be32 *list;
>>>>>>> +     int i, size;
>>>>>>> +     int ret = 0;
>>>>>>> +     int bank_num, pin_num, mux, conf;
>>>>>>> +
>>>>>>> +     info = to_at91_pinctrl(pdev);
>>>>>>> +
>>>>>>> +     list = of_get_property(np, "atmel,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) {
>>>>>>> +             bank_num = be32_to_cpu(*list++);
>>>>>>> +             pin_num = be32_to_cpu(*list++);
>>>>>>> +             mux = be32_to_cpu(*list++);
>>>>>>> +             conf = be32_to_cpu(*list++);
>>>>>>> +
>>>>>>> +             ret = at91_mux_pin(info, pin_num, mux, conf & PULL_UP);
>>>>>>> +             if (ret) {
>>>>>>> +                     dev_err(pdev->dev, "failed to mux pin %d\n", pin_num);
>>>>>>> +                     return ret;
>>>>>>> +             }
>>>>>>> +
>>>>>>> +             ret = at91_pinctrl_set_conf(info, pin_num, mux, conf);
>>>>>>> +             if (ret) {
>>>>>>> +                     dev_err(pdev->dev, "failed to set conf on pin %d\n", pin_num);
>>>>>>> +                     return ret;
>>>>>>> +             }
>>>>>>> +     }
>>>>>>> +
>>>>>>> +     return ret;
>>>>>>> +}
>>>>>>> +
>>>>>>> +static struct pinctrl_ops at91_pinctrl_ops = {
>>>>>>> +     .set_state = at91_pinctrl_set_state,
>>>>>>> +};
>>>>>>> +
>>>>>>> +static int at91_pinctrl_probe(struct device_d *dev)
>>>>>>> +{
>>>>>>> +     struct at91_pinctrl *info;
>>>>>>> +     int ret;
>>>>>>> +
>>>>>>> +     info = xzalloc(sizeof(struct at91_pinctrl));
>>>>>>> +
>>>>>>> +     info->ops = at91_pinctrl_get_driver_data(dev);
>>>>>>> +     if (!info->ops) {
>>>>>>> +             dev_err(dev, "failed to retrieve driver data\n");
>>>>>>> +             return -ENODEV;
>>>>>>> +     }
>>>>>>> +
>>>>>>> +     info->pctl.dev = dev;
>>>>>>> +     info->pctl.ops = &at91_pinctrl_ops;
>>>>>>> +
>>>>>>> +     ret = pinctrl_register(&info->pctl);
>>>>>>> +     if (ret)
>>>>>>> +             return ret;
>>>>>>> +
>>>>>>> +     dev_info(dev, "AT91 pinctrl registred\n");
>>>>>>> +
>>>>>>> +     return 0;
>>>>>>> +}
>>>>>>> +
>>>>>>> +static struct platform_device_id at91_pinctrl_ids[] = {
>>>>>>> +     {
>>>>>>> +             .name = "at91rm9200-pinctrl",
>>>>>>> +             .driver_data = (unsigned long)&at91rm9200_ops,
>>>>>>> +     }, {
>>>>>>> +             .name = "at91sam9x5-pinctrl",
>>>>>>> +             .driver_data = (unsigned long)&at91sam9x5_ops,
>>>>>>> +     }, {
>>>>>>> +             /* sentinel */
>>>>>>> +     },
>>>>>>> +};
>>>>>>> +
>>>>>>> +static struct driver_d at91_pinctrl_driver = {
>>>>>>> +     .name = "pinctrl-at91",
>>>>>>> +     .probe = at91_pinctrl_probe,
>>>>>>> +     .id_table = at91_pinctrl_ids,
>>>>>>> +     .of_compatible = DRV_OF_COMPAT(at91_pinctrl_dt_ids),
>>>>>>> +};
>>>>>>> +
>>>>>>> +static int at91_pinctrl_init(void)
>>>>>>> +{
>>>>>>> +     return platform_driver_register(&at91_pinctrl_driver);
>>>>>>> +}
>>>>>>> +coredevice_initcall(at91_pinctrl_init);
>>>>>>> +
>>>>>>> +static int at91_gpio_get(struct gpio_chip *chip, unsigned offset)
>>>>>>> +{
>>>>>>> +     struct at91_gpio_chip *at91_gpio = to_at91_gpio_chip(chip);
>>>>>>> +     void __iomem *pio = at91_gpio->regbase;
>>>>>>> +     unsigned mask = 1 << offset;
>>>>>>> +
>>>>>>> +     return at91_mux_gpio_get(pio, mask);
>>>>>>> +}
>>>>>>> +
>>>>>>> +static void at91_gpio_set(struct gpio_chip *chip, unsigned offset, int value)
>>>>>>> +{
>>>>>>> +     struct at91_gpio_chip *at91_gpio = to_at91_gpio_chip(chip);
>>>>>>> +     void __iomem *pio = at91_gpio->regbase;
>>>>>>> +     unsigned mask = 1 << offset;
>>>>>>> +
>>>>>>> +     at91_mux_gpio_set(pio, mask, value);
>>>>>>> +}
>>>>>>> +
>>>>>>> +static int at91_gpio_direction_output(struct gpio_chip *chip, unsigned offset,
>>>>>>> +             int value)
>>>>>>> +{
>>>>>>> +     struct at91_gpio_chip *at91_gpio = to_at91_gpio_chip(chip);
>>>>>>> +     void __iomem *pio = at91_gpio->regbase;
>>>>>>> +     unsigned mask = 1 << offset;
>>>>>>> +
>>>>>>> +     at91_mux_gpio_set(pio, mask, value);
>>>>>>> +     __raw_writel(mask, pio + PIO_OER);
>>>>>>> +
>>>>>>> +     return 0;
>>>>>>> +}
>>>>>>> +
>>>>>>> +static int at91_gpio_direction_input(struct gpio_chip *chip, unsigned offset)
>>>>>>> +{
>>>>>>> +     struct at91_gpio_chip *at91_gpio = to_at91_gpio_chip(chip);
>>>>>>> +     void __iomem *pio = at91_gpio->regbase;
>>>>>>> +     unsigned mask = 1 << offset;
>>>>>>> +
>>>>>>> +     __raw_writel(mask, pio + PIO_ODR);
>>>>>>> +
>>>>>>> +     return 0;
>>>>>>> +}
>>>>>>> +
>>>>>>> +static int at91_gpio_request(struct gpio_chip *chip, unsigned offset)
>>>>>>> +{
>>>>>>> +     struct at91_gpio_chip *at91_gpio = to_at91_gpio_chip(chip);
>>>>>>> +     void __iomem *pio = at91_gpio->regbase;
>>>>>>> +     unsigned mask = 1 << offset;
>>>>>>> +
>>>>>>> +     dev_dbg(chip->dev, "%s:%d pio%c%d(%d)\n", __func__, __LINE__,
>>>>>>> +              'A' + pin_to_bank(chip->base), offset, chip->base + offset);
>>>>>>> +     at91_mux_gpio_enable(pio, mask);
>>>>>>> +
>>>>>>> +     return 0;
>>>>>>> +}
>>>>>>> +
>>>>>>> +static void at91_gpio_free(struct gpio_chip *chip, unsigned offset)
>>>>>>> +{
>>>>>>> +     dev_dbg(chip->dev, "%s:%d pio%c%d(%d)\n", __func__, __LINE__,
>>>>>>> +              'A' + pin_to_bank(chip->base), offset, chip->base + offset);
>>>>>>> +}
>>>>>>> +
>>>>>>> +static struct gpio_ops at91_gpio_ops = {
>>>>>>> +     .request = at91_gpio_request,
>>>>>>> +     .free = at91_gpio_free,
>>>>>>> +     .direction_input = at91_gpio_direction_input,
>>>>>>> +     .direction_output = at91_gpio_direction_output,
>>>>>>> +     .get = at91_gpio_get,
>>>>>>> +     .set = at91_gpio_set,
>>>>>>> +};
>>>>>>> +
>>>>>>> +static struct of_device_id at91_gpio_dt_ids[] = {
>>>>>>> +     {
>>>>>>> +             .compatible = "atmel,at91rm9200-gpio",
>>>>>>> +     }, {
>>>>>>> +             .compatible = "atmel,at91sam9x5-gpio",
>>>>>>> +     }, {
>>>>>>> +             /* sentinel */
>>>>>>> +     },
>>>>>>> +};
>>>>>>> +
>>>>>>> +static int at91_gpio_probe(struct device_d *dev)
>>>>>>> +{
>>>>>>> +     struct at91_gpio_chip *at91_gpio;
>>>>>>> +     struct clk *clk;
>>>>>>> +     int ret;
>>>>>>> +     int alias_idx = of_alias_get_id(dev->device_node, "gpio");
>>>>>>> +
>>>>>>> +     BUG_ON(dev->id > MAX_GPIO_BANKS);
>>>>>>> +
>>>>>>> +     at91_gpio = &gpio_chip[alias_idx];
>>>>>>> +
>>>>>>> +     clk = clk_get(dev, NULL);
>>>>>>> +     if (IS_ERR(clk)) {
>>>>>>> +             ret = PTR_ERR(clk);
>>>>>>> +             dev_err(dev, "clock not found: %d\n", ret);
>>>>>>> +             return ret;
>>>>>>> +     }
>>>>>>> +
>>>>>>> +     ret = clk_enable(clk);
>>>>>>> +     if (ret < 0) {
>>>>>>> +             dev_err(dev, "clock failed to enable: %d\n", ret);
>>>>>>> +             clk_put(clk);
>>>>>>> +             return ret;
>>>>>>> +     }
>>>>>>> +
>>>>>>> +     gpio_banks = max(gpio_banks, alias_idx + 1);
>>>>>>> +     at91_gpio->regbase = dev_request_mem_region(dev, 0);
>>>>>>> +
>>>>>>> +     at91_gpio->chip.ops = &at91_gpio_ops;
>>>>>>> +     at91_gpio->chip.ngpio = MAX_NB_GPIO_PER_BANK;
>>>>>>> +     at91_gpio->chip.dev = dev;
>>>>>>> +     at91_gpio->chip.base = dev->id * MAX_NB_GPIO_PER_BANK;
>>>>>>> +
>>>>>>> +     ret = gpiochip_add(&at91_gpio->chip);
>>>>>>> +     if (ret) {
>>>>>>> +             dev_err(dev, "couldn't add gpiochip, ret = %d\n", ret);
>>>>>>> +             return ret;
>>>>>>> +     }
>>>>>>> +
>>>>>>> +     dev_info(dev, "AT91 gpio driver registred\n");
>>>>>>> +
>>>>>>> +     return 0;
>>>>>>> +}
>>>>>>> +
>>>>>>> +static struct platform_device_id at91_gpio_ids[] = {
>>>>>>> +     {
>>>>>>> +             .name = "at91rm9200-gpio",
>>>>>>> +     }, {
>>>>>>> +             .name = "at91sam9x5-gpio",
>>>>>>> +     }, {
>>>>>>> +             /* sentinel */
>>>>>>> +     },
>>>>>>> +};
>>>>>>> +
>>>>>>> +static struct driver_d at91_gpio_driver = {
>>>>>>> +     .name = "gpio-at91",
>>>>>>> +     .probe = at91_gpio_probe,
>>>>>>> +     .id_table = at91_gpio_ids,
>>>>>>> +     .of_compatible  = DRV_OF_COMPAT(at91_gpio_dt_ids),
>>>>>>> +};
>>>>>>> +
>>>>>>> +static int at91_gpio_init(void)
>>>>>>> +{
>>>>>>> +     return platform_driver_register(&at91_gpio_driver);
>>>>>>> +}
>>>>>>> +coredevice_initcall(at91_gpio_init);
>>>>>>> diff --git a/drivers/pinctrl/pinctrl-at91.h b/drivers/pinctrl/pinctrl-at91.h
>>>>>>> new file mode 100644
>>>>>>> index 0000000..e719fb8
>>>>>>> --- /dev/null
>>>>>>> +++ b/drivers/pinctrl/pinctrl-at91.h
>>>>>>> @@ -0,0 +1,148 @@
>>>>>>> +/*
>>>>>>> + * Copyright (C) 2011-2012 Jean-Christophe PLAGNIOL-VILLARD <plagnioj@jcrosoft.com>
>>>>>>> + *
>>>>>>> + * Under GPLv2 only
>>>>>>> + */
>>>>>>> +
>>>>>>> +#ifndef __AT91_GPIO_H__
>>>>>>> +#define __AT91_GPIO_H__
>>>>>>> +
>>>>>>> +#ifndef __gpio_init
>>>>>>> +#define __gpio_init
>>>>>>> +#endif
>>>>>>> +
>>>>>>> +#define MAX_NB_GPIO_PER_BANK 32
>>>>>>> +
>>>>>>> +static inline unsigned pin_to_bank(unsigned pin)
>>>>>>> +{
>>>>>>> +     return pin / MAX_NB_GPIO_PER_BANK;
>>>>>>> +}
>>>>>>> +
>>>>>>> +static inline unsigned pin_to_bank_offset(unsigned pin)
>>>>>>> +{
>>>>>>> +     return pin % MAX_NB_GPIO_PER_BANK;
>>>>>>> +}
>>>>>>> +
>>>>>>> +static inline unsigned pin_to_mask(unsigned pin)
>>>>>>> +{
>>>>>>> +     return 1 << pin_to_bank_offset(pin);
>>>>>>> +}
>>>>>>> +
>>>>>>> +static inline void at91_mux_disable_interrupt(void __iomem *pio, unsigned mask)
>>>>>>> +{
>>>>>>> +     __raw_writel(mask, pio + PIO_IDR);
>>>>>>> +}
>>>>>>> +
>>>>>>> +static inline void at91_mux_set_pullup(void __iomem *pio, unsigned mask, bool on)
>>>>>>> +{
>>>>>>> +     __raw_writel(mask, pio + (on ? PIO_PUER : PIO_PUDR));
>>>>>>> +}
>>>>>>> +
>>>>>>> +static inline void at91_mux_set_multidrive(void __iomem *pio, unsigned mask, bool on)
>>>>>>> +{
>>>>>>> +     __raw_writel(mask, pio + (on ? PIO_MDER : PIO_MDDR));
>>>>>>> +}
>>>>>>> +
>>>>>>> +static inline void at91_mux_set_A_periph(void __iomem *pio, unsigned mask)
>>>>>>> +{
>>>>>>> +     __raw_writel(mask, pio + PIO_ASR);
>>>>>>> +}
>>>>>>> +
>>>>>>> +static inline void at91_mux_set_B_periph(void __iomem *pio, unsigned mask)
>>>>>>> +{
>>>>>>> +     __raw_writel(mask, pio + PIO_BSR);
>>>>>>> +}
>>>>>>> +
>>>>>>> +static inline void at91_mux_pio3_set_A_periph(void __iomem *pio, unsigned mask)
>>>>>>> +{
>>>>>>> +
>>>>>>> +     __raw_writel(__raw_readl(pio + PIO_ABCDSR1) & ~mask,
>>>>>>> +                                             pio + PIO_ABCDSR1);
>>>>>>> +     __raw_writel(__raw_readl(pio + PIO_ABCDSR2) & ~mask,
>>>>>>> +                                             pio + PIO_ABCDSR2);
>>>>>>> +}
>>>>>>> +
>>>>>>> +static inline void at91_mux_pio3_set_B_periph(void __iomem *pio, unsigned mask)
>>>>>>> +{
>>>>>>> +     __raw_writel(__raw_readl(pio + PIO_ABCDSR1) | mask,
>>>>>>> +                                             pio + PIO_ABCDSR1);
>>>>>>> +     __raw_writel(__raw_readl(pio + PIO_ABCDSR2) & ~mask,
>>>>>>> +                                             pio + PIO_ABCDSR2);
>>>>>>> +}
>>>>>>> +
>>>>>>> +static inline void at91_mux_pio3_set_C_periph(void __iomem *pio, unsigned mask)
>>>>>>> +{
>>>>>>> +     __raw_writel(__raw_readl(pio + PIO_ABCDSR1) & ~mask, pio + PIO_ABCDSR1);
>>>>>>> +     __raw_writel(__raw_readl(pio + PIO_ABCDSR2) | mask, pio + PIO_ABCDSR2);
>>>>>>> +}
>>>>>>> +
>>>>>>> +static inline void at91_mux_pio3_set_D_periph(void __iomem *pio, unsigned mask)
>>>>>>> +{
>>>>>>> +     __raw_writel(__raw_readl(pio + PIO_ABCDSR1) | mask, pio + PIO_ABCDSR1);
>>>>>>> +     __raw_writel(__raw_readl(pio + PIO_ABCDSR2) | mask, pio + PIO_ABCDSR2);
>>>>>>> +}
>>>>>>> +
>>>>>>> +static inline void at91_mux_set_deglitch(void __iomem *pio, unsigned mask, bool is_on)
>>>>>>> +{
>>>>>>> +     __raw_writel(mask, pio + (is_on ? PIO_IFER : PIO_IFDR));
>>>>>>> +}
>>>>>>> +
>>>>>>> +static inline void at91_mux_pio3_set_deglitch(void __iomem *pio, unsigned mask, bool is_on)
>>>>>>> +{
>>>>>>> +     if (is_on)
>>>>>>> +             __raw_writel(mask, pio + PIO_IFSCDR);
>>>>>>> +     at91_mux_set_deglitch(pio, mask, is_on);
>>>>>>> +}
>>>>>>> +
>>>>>>> +static inline void at91_mux_pio3_set_debounce(void __iomem *pio, unsigned mask,
>>>>>>> +                             bool is_on, u32 div)
>>>>>>> +{
>>>>>>> +     if (is_on) {
>>>>>>> +             __raw_writel(mask, pio + PIO_IFSCER);
>>>>>>> +             __raw_writel(div & PIO_SCDR_DIV, pio + PIO_SCDR);
>>>>>>> +             __raw_writel(mask, pio + PIO_IFER);
>>>>>>> +     } else {
>>>>>>> +             __raw_writel(mask, pio + PIO_IFDR);
>>>>>>> +     }
>>>>>>> +}
>>>>>>> +
>>>>>>> +static inline void at91_mux_pio3_set_pulldown(void __iomem *pio, unsigned mask, bool is_on)
>>>>>>> +{
>>>>>>> +     __raw_writel(mask, pio + (is_on ? PIO_PPDER : PIO_PPDDR));
>>>>>>> +}
>>>>>>> +
>>>>>>> +static inline void at91_mux_pio3_disable_schmitt_trig(void __iomem *pio, unsigned mask)
>>>>>>> +{
>>>>>>> +     __raw_writel(__raw_readl(pio + PIO_SCHMITT) | mask, pio + PIO_SCHMITT);
>>>>>>> +}
>>>>>>> +
>>>>>>> +static inline void at91_mux_gpio_disable(void __iomem *pio, unsigned mask)
>>>>>>> +{
>>>>>>> +     __raw_writel(mask, pio + PIO_PDR);
>>>>>>> +}
>>>>>>> +
>>>>>>> +static inline void at91_mux_gpio_enable(void __iomem *pio, unsigned mask)
>>>>>>> +{
>>>>>>> +     __raw_writel(mask, pio + PIO_PER);
>>>>>>> +}
>>>>>>> +
>>>>>>> +static inline void at91_mux_gpio_input(void __iomem *pio, unsigned mask, bool input)
>>>>>>> +{
>>>>>>> +     __raw_writel(mask, pio + (input ? PIO_ODR : PIO_OER));
>>>>>>> +}
>>>>>>> +
>>>>>>> +static inline void at91_mux_gpio_set(void __iomem *pio, unsigned mask,
>>>>>>> +int value)
>>>>>>> +{
>>>>>>> +     __raw_writel(mask, pio + (value ? PIO_SODR : PIO_CODR));
>>>>>>> +}
>>>>>>> +
>>>>>>> +static inline int at91_mux_gpio_get(void __iomem *pio, unsigned mask)
>>>>>>> +{
>>>>>>> +       u32 pdsr;
>>>>>>> +
>>>>>>> +       pdsr = __raw_readl(pio + PIO_PDSR);
>>>>>>> +       return (pdsr & mask) != 0;
>>>>>>> +}
>>>>>>> +
>>>>>>> +#endif /* __AT91_GPIO_H__ */
>>>>>>> --
>>>>>>> 1.7.9.5
>>>>>>>
>>>>>>>
>>>>>>> _______________________________________________
>>>>>>> barebox mailing list
>>>>>>> barebox@lists.infradead.org
>>>>>>> http://lists.infradead.org/mailman/listinfo/barebox
>>>>>>
>>>>>>
>>>>>> _______________________________________________
>>>>>> barebox mailing list
>>>>>> barebox@lists.infradead.org
>>>>>> http://lists.infradead.org/mailman/listinfo/barebox
>>>>
>>
>

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

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

end of thread, other threads:[~2014-08-06  7:13 UTC | newest]

Thread overview: 10+ messages (download: mbox.gz / follow: Atom feed)
-- links below jump to the message on this page --
2014-08-01 13:24 [PATCH 0/2] Add atmel pinctrl driver Raphaël Poggi
2014-08-01 13:24 ` [PATCH 1/2] pinctrl: at91: add " Raphaël Poggi
2014-08-04 18:22   ` Sascha Hauer
2014-08-04 18:26   ` Jean-Christophe PLAGNIOL-VILLARD
2014-08-04 18:37     ` Raphaël Poggi
2014-08-04 18:45       ` Sascha Hauer
2014-08-05 10:26       ` Jean-Christophe PLAGNIOL-VILLARD
2014-08-05 11:38         ` Raphaël Poggi
     [not found]           ` <E10FE9F3-8D18-4EFC-8470-7C2D79E7E1B4@jcrosoft.com>
     [not found]             ` <CA5BE09F-18DF-49EE-83D8-65BB761BB903@jcrosoft.com>
2014-08-06  7:12               ` Raphaël Poggi
2014-08-01 13:24 ` [PATCH 2/2] at91sam9g45: add device tree gpio clocks Raphaël Poggi

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