* [RFC 08/18] gpio: add driver for Atheros AR5312 SoC GPIO controller
[not found] <1410723213-22440-1-git-send-email-ryazanov.s.a@gmail.com>
@ 2014-09-14 19:33 ` Sergey Ryazanov
2014-09-29 9:03 ` Linus Walleij
2014-09-14 19:33 ` [RFC 09/18] " Sergey Ryazanov
1 sibling, 1 reply; 11+ messages in thread
From: Sergey Ryazanov @ 2014-09-14 19:33 UTC (permalink / raw)
To: Ralf Baechle; +Cc: Linux MIPS, Linus Walleij, Alexandre Courbot, linux-gpio
Atheros AR5312 SoC have a builtin GPIO controller, which could be accessed
via memory mapped registers. This patch adds new driver for them.
Signed-off-by: Sergey Ryazanov <ryazanov.s.a@gmail.com>
Cc: Linus Walleij <linus.walleij@linaro.org>
Cc: Alexandre Courbot <gnurou@gmail.com>
Cc: linux-gpio@vger.kernel.org
---
arch/mips/ar231x/Kconfig | 1 +
arch/mips/ar231x/ar5312.c | 19 ++++
arch/mips/include/asm/mach-ar231x/ar5312_regs.h | 2 +
drivers/gpio/Kconfig | 7 ++
drivers/gpio/Makefile | 1 +
drivers/gpio/gpio-ar5312.c | 121 ++++++++++++++++++++++++
6 files changed, 151 insertions(+)
create mode 100644 drivers/gpio/gpio-ar5312.c
diff --git a/arch/mips/ar231x/Kconfig b/arch/mips/ar231x/Kconfig
index aa0fceb..378a6e1 100644
--- a/arch/mips/ar231x/Kconfig
+++ b/arch/mips/ar231x/Kconfig
@@ -1,6 +1,7 @@
config SOC_AR5312
bool "Atheros AR5312/AR2312+ SoC support"
depends on AR231X
+ select GPIO_AR5312
default y
config SOC_AR2315
diff --git a/arch/mips/ar231x/ar5312.c b/arch/mips/ar231x/ar5312.c
index 56cb0d7..8683eb6 100644
--- a/arch/mips/ar231x/ar5312.c
+++ b/arch/mips/ar231x/ar5312.c
@@ -16,6 +16,7 @@
#include <linux/init.h>
#include <linux/kernel.h>
+#include <linux/platform_device.h>
#include <linux/reboot.h>
#include <asm/bootinfo.h>
#include <asm/reboot.h>
@@ -118,6 +119,22 @@ void __init ar5312_arch_init_irq(void)
irq_set_chained_handler(AR5312_IRQ_MISC, ar5312_misc_irq_handler);
}
+static struct resource ar5312_gpio_res[] = {
+ {
+ .name = "ar5312-gpio",
+ .flags = IORESOURCE_MEM,
+ .start = AR5312_GPIO,
+ .end = AR5312_GPIO + 0x0c - 1,
+ },
+};
+
+static struct platform_device ar5312_gpio = {
+ .name = "ar5312-gpio",
+ .id = -1,
+ .resource = ar5312_gpio_res,
+ .num_resources = ARRAY_SIZE(ar5312_gpio_res),
+};
+
static void __init ar5312_flash_init(void)
{
u32 ctl;
@@ -157,6 +174,8 @@ void __init ar5312_init_devices(void)
/* Locate board/radio config data */
ar231x_find_config(ar5312_flash_limit);
+
+ platform_device_register(&ar5312_gpio);
}
static void ar5312_restart(char *command)
diff --git a/arch/mips/include/asm/mach-ar231x/ar5312_regs.h b/arch/mips/include/asm/mach-ar231x/ar5312_regs.h
index 0b4cee8..104c558 100644
--- a/arch/mips/include/asm/mach-ar231x/ar5312_regs.h
+++ b/arch/mips/include/asm/mach-ar231x/ar5312_regs.h
@@ -210,4 +210,6 @@
#define AR5312_MEM_CFG1_AC1_M 0x00007000 /* bank 1: SDRAM addr check */
#define AR5312_MEM_CFG1_AC1_S 12
+#define AR5312_GPIO (AR5312_APBBASE + 0x2000)
+
#endif /* __ASM_MACH_AR231X_AR5312_REGS_H */
diff --git a/drivers/gpio/Kconfig b/drivers/gpio/Kconfig
index 9de1515..7ce411b 100644
--- a/drivers/gpio/Kconfig
+++ b/drivers/gpio/Kconfig
@@ -112,6 +112,13 @@ config GPIO_MAX730X
comment "Memory mapped GPIO drivers:"
+config GPIO_AR5312
+ bool "AR5312 SoC GPIO support"
+ default y if SOC_AR5312
+ depends on SOC_AR5312
+ help
+ Say yes here to enable GPIO support for Atheros AR5312/AR2312+ SoCs.
+
config GPIO_CLPS711X
tristate "CLPS711X GPIO support"
depends on ARCH_CLPS711X || COMPILE_TEST
diff --git a/drivers/gpio/Makefile b/drivers/gpio/Makefile
index 5d024e3..fae00f4 100644
--- a/drivers/gpio/Makefile
+++ b/drivers/gpio/Makefile
@@ -17,6 +17,7 @@ obj-$(CONFIG_GPIO_ADNP) += gpio-adnp.o
obj-$(CONFIG_GPIO_ADP5520) += gpio-adp5520.o
obj-$(CONFIG_GPIO_ADP5588) += gpio-adp5588.o
obj-$(CONFIG_GPIO_AMD8111) += gpio-amd8111.o
+obj-$(CONFIG_GPIO_AR5312) += gpio-ar5312.o
obj-$(CONFIG_GPIO_ARIZONA) += gpio-arizona.o
obj-$(CONFIG_GPIO_BCM_KONA) += gpio-bcm-kona.o
obj-$(CONFIG_GPIO_BT8XX) += gpio-bt8xx.o
diff --git a/drivers/gpio/gpio-ar5312.c b/drivers/gpio/gpio-ar5312.c
new file mode 100644
index 0000000..27adb61
--- /dev/null
+++ b/drivers/gpio/gpio-ar5312.c
@@ -0,0 +1,121 @@
+/*
+ * This file is subject to the terms and conditions of the GNU General Public
+ * License. See the file "COPYING" in the main directory of this archive
+ * for more details.
+ *
+ * Copyright (C) 2003 Atheros Communications, Inc., All Rights Reserved.
+ * Copyright (C) 2006 FON Technology, SL.
+ * Copyright (C) 2006 Imre Kaloz <kaloz@openwrt.org>
+ * Copyright (C) 2006-2009 Felix Fietkau <nbd@openwrt.org>
+ * Copyright (C) 2012 Alexandros C. Couloumbis <alex@ozo.com>
+ */
+
+#include <linux/kernel.h>
+#include <linux/init.h>
+#include <linux/platform_device.h>
+#include <linux/gpio.h>
+
+#define DRIVER_NAME "ar5312-gpio"
+
+#define AR5312_GPIO_DO 0x00 /* output register */
+#define AR5312_GPIO_DI 0x04 /* intput register */
+#define AR5312_GPIO_CR 0x08 /* control register */
+
+#define AR5312_GPIO_CR_M(x) (1 << (x)) /* mask for i/o */
+#define AR5312_GPIO_CR_O(x) (0 << (x)) /* mask for output */
+#define AR5312_GPIO_CR_I(x) (1 << (x)) /* mask for input */
+#define AR5312_GPIO_CR_INT(x) (1 << ((x)+8)) /* mask for interrupt */
+#define AR5312_GPIO_CR_UART(x) (1 << ((x)+16)) /* uart multiplex */
+
+#define AR5312_GPIO_NUM 8
+
+static void __iomem *ar5312_mem;
+
+static inline u32 ar5312_gpio_reg_read(unsigned reg)
+{
+ return __raw_readl(ar5312_mem + reg);
+}
+
+static inline void ar5312_gpio_reg_write(unsigned reg, u32 val)
+{
+ __raw_writel(val, ar5312_mem + reg);
+}
+
+static inline void ar5312_gpio_reg_mask(unsigned reg, u32 mask, u32 val)
+{
+ ar5312_gpio_reg_write(reg, (ar5312_gpio_reg_read(reg) & ~mask) | val);
+}
+
+static int ar5312_gpio_get_val(struct gpio_chip *chip, unsigned gpio)
+{
+ return (ar5312_gpio_reg_read(AR5312_GPIO_DI) >> gpio) & 1;
+}
+
+static void ar5312_gpio_set_val(struct gpio_chip *chip, unsigned gpio, int val)
+{
+ u32 reg = ar5312_gpio_reg_read(AR5312_GPIO_DO);
+
+ reg = val ? reg | (1 << gpio) : reg & ~(1 << gpio);
+ ar5312_gpio_reg_write(AR5312_GPIO_DO, reg);
+}
+
+static int ar5312_gpio_dir_in(struct gpio_chip *chip, unsigned gpio)
+{
+ ar5312_gpio_reg_mask(AR5312_GPIO_CR, 0, 1 << gpio);
+ return 0;
+}
+
+static int ar5312_gpio_dir_out(struct gpio_chip *chip, unsigned gpio, int val)
+{
+ ar5312_gpio_reg_mask(AR5312_GPIO_CR, 1 << gpio, 0);
+ ar5312_gpio_set_val(chip, gpio, val);
+ return 0;
+}
+
+static struct gpio_chip ar5312_gpio_chip = {
+ .label = DRIVER_NAME,
+ .direction_input = ar5312_gpio_dir_in,
+ .direction_output = ar5312_gpio_dir_out,
+ .set = ar5312_gpio_set_val,
+ .get = ar5312_gpio_get_val,
+ .base = 0,
+ .ngpio = AR5312_GPIO_NUM,
+};
+
+static int ar5312_gpio_probe(struct platform_device *pdev)
+{
+ struct device *dev = &pdev->dev;
+ struct resource *res;
+ int ret;
+
+ if (ar5312_mem)
+ return -EBUSY;
+
+ res = platform_get_resource(pdev, IORESOURCE_MEM, 0);
+ ar5312_mem = devm_ioremap_resource(dev, res);
+ if (IS_ERR(ar5312_mem))
+ return PTR_ERR(ar5312_mem);
+
+ ar5312_gpio_chip.dev = dev;
+ ret = gpiochip_add(&ar5312_gpio_chip);
+ if (ret) {
+ dev_err(dev, "failed to add gpiochip\n");
+ return ret;
+ }
+
+ return 0;
+}
+
+static struct platform_driver ar5312_gpio_driver = {
+ .probe = ar5312_gpio_probe,
+ .driver = {
+ .name = DRIVER_NAME,
+ .owner = THIS_MODULE,
+ }
+};
+
+static int __init ar5312_gpio_init(void)
+{
+ return platform_driver_register(&ar5312_gpio_driver);
+}
+subsys_initcall(ar5312_gpio_init);
--
1.8.1.5
^ permalink raw reply related [flat|nested] 11+ messages in thread
* [RFC 09/18] gpio: add driver for Atheros AR5312 SoC GPIO controller
[not found] <1410723213-22440-1-git-send-email-ryazanov.s.a@gmail.com>
2014-09-14 19:33 ` [RFC 08/18] gpio: add driver for Atheros AR5312 SoC GPIO controller Sergey Ryazanov
@ 2014-09-14 19:33 ` Sergey Ryazanov
2014-09-29 9:18 ` Linus Walleij
1 sibling, 1 reply; 11+ messages in thread
From: Sergey Ryazanov @ 2014-09-14 19:33 UTC (permalink / raw)
To: Ralf Baechle; +Cc: Linux MIPS, Linus Walleij, Alexandre Courbot, linux-gpio
Atheros AR5312 SoC have a builtin GPIO controller, which could be
accessed via memory mapped registers. This patch adds new driver
for them.
Signed-off-by: Sergey Ryazanov <ryazanov.s.a@gmail.com>
Cc: Linus Walleij <linus.walleij@linaro.org>
Cc: Alexandre Courbot <gnurou@gmail.com>
Cc: linux-gpio@vger.kernel.org
---
arch/mips/ar231x/Kconfig | 1 +
arch/mips/ar231x/ar2315.c | 49 ++++-
arch/mips/include/asm/mach-ar231x/ar2315_regs.h | 5 +
arch/mips/include/asm/mach-ar231x/ar231x.h | 1 +
drivers/gpio/Kconfig | 7 +
drivers/gpio/Makefile | 1 +
drivers/gpio/gpio-ar2315.c | 233 ++++++++++++++++++++++++
7 files changed, 294 insertions(+), 3 deletions(-)
create mode 100644 drivers/gpio/gpio-ar2315.c
diff --git a/arch/mips/ar231x/Kconfig b/arch/mips/ar231x/Kconfig
index 378a6e1..88ca061 100644
--- a/arch/mips/ar231x/Kconfig
+++ b/arch/mips/ar231x/Kconfig
@@ -7,4 +7,5 @@ config SOC_AR5312
config SOC_AR2315
bool "Atheros AR2315+ SoC support"
depends on AR231X
+ select GPIO_AR2315
default y
diff --git a/arch/mips/ar231x/ar2315.c b/arch/mips/ar231x/ar2315.c
index a766b0d..06074cb 100644
--- a/arch/mips/ar231x/ar2315.c
+++ b/arch/mips/ar231x/ar2315.c
@@ -16,7 +16,10 @@
#include <linux/init.h>
#include <linux/kernel.h>
+#include <linux/platform_device.h>
#include <linux/reboot.h>
+#include <linux/delay.h>
+#include <linux/gpio.h>
#include <asm/bootinfo.h>
#include <asm/reboot.h>
#include <asm/time.h>
@@ -53,7 +56,10 @@ static void ar2315_misc_irq_handler(unsigned irq, struct irq_desc *desc)
generic_handle_irq(AR2315_MISC_IRQ_TIMER);
else if (pending & AR2315_ISR_AHB)
generic_handle_irq(AR2315_MISC_IRQ_AHB);
- else if (pending & AR2315_ISR_UART0)
+ else if (pending & AR2315_ISR_GPIO) {
+ ar231x_write_reg(AR2315_ISR, AR2315_ISR_GPIO);
+ generic_handle_irq(AR2315_MISC_IRQ_GPIO);
+ } else if (pending & AR2315_ISR_UART0)
generic_handle_irq(AR2315_MISC_IRQ_UART0);
else
spurious_interrupt();
@@ -119,6 +125,34 @@ void __init ar2315_arch_init_irq(void)
irq_set_chained_handler(AR2315_IRQ_MISC, ar2315_misc_irq_handler);
}
+static struct resource ar2315_gpio_res[] = {
+ {
+ .name = "ar2315-gpio",
+ .flags = IORESOURCE_MEM,
+ .start = AR2315_GPIO,
+ .end = AR2315_GPIO + 0x10 - 1,
+ },
+ {
+ .name = "ar2315-gpio",
+ .flags = IORESOURCE_IRQ,
+ .start = AR2315_MISC_IRQ_GPIO,
+ .end = AR2315_MISC_IRQ_GPIO,
+ },
+ {
+ .name = "ar2315-gpio-irq-base",
+ .flags = IORESOURCE_IRQ,
+ .start = AR231X_GPIO_IRQ_BASE,
+ .end = AR231X_GPIO_IRQ_BASE,
+ }
+};
+
+static struct platform_device ar2315_gpio = {
+ .id = -1,
+ .name = "ar2315-gpio",
+ .resource = ar2315_gpio_res,
+ .num_resources = ARRAY_SIZE(ar2315_gpio_res)
+};
+
/*
* NB: We use mapping size that is larger than the actual flash size,
* but this shouldn't be a problem here, because the flash will simply
@@ -134,6 +168,8 @@ void __init ar2315_init_devices(void)
/* Find board configuration */
ar231x_find_config(ar2315_flash_limit);
+
+ platform_device_register(&ar2315_gpio);
}
static void ar2315_restart(char *command)
@@ -145,8 +181,15 @@ static void ar2315_restart(char *command)
/* try reset the system via reset control */
ar231x_write_reg(AR2315_COLD_RESET, AR2317_RESET_SYSTEM);
- /* Attempt to jump to the mips reset location - the boot loader
- * itself might be able to recover the system */
+ /* Cold reset does not work on the AR2315/6, use the GPIO reset bits
+ * a workaround. Give it some time to attempt a gpio based hardware
+ * reset (atheros reference design workaround) */
+ gpio_request_one(AR2315_RESET_GPIO, GPIOF_OUT_INIT_LOW, "Reset");
+ mdelay(100);
+
+ /* Some boards (e.g. Senao EOC-2610) don't implement the reset logic
+ * workaround. Attempt to jump to the mips reset location -
+ * the boot loader itself might be able to recover the system */
mips_reset_vec();
}
diff --git a/arch/mips/include/asm/mach-ar231x/ar2315_regs.h b/arch/mips/include/asm/mach-ar231x/ar2315_regs.h
index 27f5490..dd7df42 100644
--- a/arch/mips/include/asm/mach-ar231x/ar2315_regs.h
+++ b/arch/mips/include/asm/mach-ar231x/ar2315_regs.h
@@ -283,6 +283,11 @@
#define AR2315_AMBACLK_CLK_DIV_M 0x0000000c
#define AR2315_AMBACLK_CLK_DIV_S 2
+/* GPIO MMR base address */
+#define AR2315_GPIO (AR2315_DSLBASE + 0x0088)
+
+#define AR2315_RESET_GPIO 5
+
/*
* PCI Clock Control
*/
diff --git a/arch/mips/include/asm/mach-ar231x/ar231x.h b/arch/mips/include/asm/mach-ar231x/ar231x.h
index 69702b2..259001d 100644
--- a/arch/mips/include/asm/mach-ar231x/ar231x.h
+++ b/arch/mips/include/asm/mach-ar231x/ar231x.h
@@ -4,6 +4,7 @@
#include <linux/io.h>
#define AR231X_MISC_IRQ_BASE 0x20
+#define AR231X_GPIO_IRQ_BASE 0x30
#define AR231X_IRQ_CPU_CLOCK (MIPS_CPU_IRQ_BASE + 7) /* C0_CAUSE: 0x8000 */
diff --git a/drivers/gpio/Kconfig b/drivers/gpio/Kconfig
index 7ce411b..0ceb4ba 100644
--- a/drivers/gpio/Kconfig
+++ b/drivers/gpio/Kconfig
@@ -112,6 +112,13 @@ config GPIO_MAX730X
comment "Memory mapped GPIO drivers:"
+config GPIO_AR2315
+ bool "AR2315 SoC GPIO support"
+ default y if SOC_AR2315
+ depends on SOC_AR2315
+ help
+ Say yes here to enable GPIO support for Atheros AR2315+ SoCs.
+
config GPIO_AR5312
bool "AR5312 SoC GPIO support"
default y if SOC_AR5312
diff --git a/drivers/gpio/Makefile b/drivers/gpio/Makefile
index fae00f4..9a3a136 100644
--- a/drivers/gpio/Makefile
+++ b/drivers/gpio/Makefile
@@ -17,6 +17,7 @@ obj-$(CONFIG_GPIO_ADNP) += gpio-adnp.o
obj-$(CONFIG_GPIO_ADP5520) += gpio-adp5520.o
obj-$(CONFIG_GPIO_ADP5588) += gpio-adp5588.o
obj-$(CONFIG_GPIO_AMD8111) += gpio-amd8111.o
+obj-$(CONFIG_GPIO_AR2315) += gpio-ar2315.o
obj-$(CONFIG_GPIO_AR5312) += gpio-ar5312.o
obj-$(CONFIG_GPIO_ARIZONA) += gpio-arizona.o
obj-$(CONFIG_GPIO_BCM_KONA) += gpio-bcm-kona.o
diff --git a/drivers/gpio/gpio-ar2315.c b/drivers/gpio/gpio-ar2315.c
new file mode 100644
index 0000000..00e3101
--- /dev/null
+++ b/drivers/gpio/gpio-ar2315.c
@@ -0,0 +1,233 @@
+/*
+ * This file is subject to the terms and conditions of the GNU General Public
+ * License. See the file "COPYING" in the main directory of this archive
+ * for more details.
+ *
+ * Copyright (C) 2003 Atheros Communications, Inc., All Rights Reserved.
+ * Copyright (C) 2006 FON Technology, SL.
+ * Copyright (C) 2006 Imre Kaloz <kaloz@openwrt.org>
+ * Copyright (C) 2006 Felix Fietkau <nbd@openwrt.org>
+ * Copyright (C) 2012 Alexandros C. Couloumbis <alex@ozo.com>
+ */
+
+#include <linux/kernel.h>
+#include <linux/init.h>
+#include <linux/platform_device.h>
+#include <linux/gpio.h>
+#include <linux/irq.h>
+
+#define DRIVER_NAME "ar2315-gpio"
+
+#define AR2315_GPIO_DI 0x0000
+#define AR2315_GPIO_DO 0x0008
+#define AR2315_GPIO_DIR 0x0010
+#define AR2315_GPIO_INT 0x0018
+
+#define AR2315_GPIO_DIR_M(x) (1 << (x)) /* mask for i/o */
+#define AR2315_GPIO_DIR_O(x) (1 << (x)) /* output */
+#define AR2315_GPIO_DIR_I(x) (0) /* input */
+
+#define AR2315_GPIO_INT_NUM_M 0x3F /* mask for GPIO num */
+#define AR2315_GPIO_INT_TRIG(x) ((x) << 6) /* interrupt trigger */
+#define AR2315_GPIO_INT_TRIG_M (0x3 << 6) /* mask for int trig */
+
+#define AR2315_GPIO_INT_TRIG_OFF 0 /* Triggerring off */
+#define AR2315_GPIO_INT_TRIG_LOW 1 /* Low Level Triggered */
+#define AR2315_GPIO_INT_TRIG_HIGH 2 /* High Level Triggered */
+#define AR2315_GPIO_INT_TRIG_EDGE 3 /* Edge Triggered */
+
+#define AR2315_GPIO_NUM 22
+
+static u32 ar2315_gpio_intmask;
+static u32 ar2315_gpio_intval;
+static unsigned ar2315_gpio_irq_base;
+static void __iomem *ar2315_mem;
+
+static inline u32 ar2315_gpio_reg_read(unsigned reg)
+{
+ return __raw_readl(ar2315_mem + reg);
+}
+
+static inline void ar2315_gpio_reg_write(unsigned reg, u32 val)
+{
+ __raw_writel(val, ar2315_mem + reg);
+}
+
+static inline void ar2315_gpio_reg_mask(unsigned reg, u32 mask, u32 val)
+{
+ ar2315_gpio_reg_write(reg, (ar2315_gpio_reg_read(reg) & ~mask) | val);
+}
+
+static void ar2315_gpio_irq_handler(unsigned irq, struct irq_desc *desc)
+{
+ u32 pend;
+ int bit = -1;
+
+ /* only do one gpio interrupt at a time */
+ pend = ar2315_gpio_reg_read(AR2315_GPIO_DI);
+ pend ^= ar2315_gpio_intval;
+ pend &= ar2315_gpio_intmask;
+
+ if (pend) {
+ bit = fls(pend) - 1;
+ pend &= ~(1 << bit);
+ ar2315_gpio_intval ^= (1 << bit);
+ }
+
+ /* Enable interrupt with edge detection */
+ if ((ar2315_gpio_reg_read(AR2315_GPIO_DIR) & AR2315_GPIO_DIR_M(bit)) !=
+ AR2315_GPIO_DIR_I(bit))
+ return;
+
+ if (bit >= 0)
+ generic_handle_irq(ar2315_gpio_irq_base + bit);
+}
+
+static void ar2315_gpio_int_setup(unsigned gpio, int trig)
+{
+ u32 reg = ar2315_gpio_reg_read(AR2315_GPIO_INT);
+
+ reg &= ~(AR2315_GPIO_INT_NUM_M | AR2315_GPIO_INT_TRIG_M);
+ reg |= gpio | AR2315_GPIO_INT_TRIG(trig);
+ ar2315_gpio_reg_write(AR2315_GPIO_INT, reg);
+}
+
+static void ar2315_gpio_irq_unmask(struct irq_data *d)
+{
+ unsigned gpio = d->irq - ar2315_gpio_irq_base;
+ u32 dir = ar2315_gpio_reg_read(AR2315_GPIO_DIR);
+
+ /* Enable interrupt with edge detection */
+ if ((dir & AR2315_GPIO_DIR_M(gpio)) != AR2315_GPIO_DIR_I(gpio))
+ return;
+
+ ar2315_gpio_intmask |= (1 << gpio);
+ ar2315_gpio_int_setup(gpio, AR2315_GPIO_INT_TRIG_EDGE);
+}
+
+static void ar2315_gpio_irq_mask(struct irq_data *d)
+{
+ unsigned gpio = d->irq - ar2315_gpio_irq_base;
+
+ /* Disable interrupt */
+ ar2315_gpio_intmask &= ~(1 << gpio);
+ ar2315_gpio_int_setup(gpio, AR2315_GPIO_INT_TRIG_OFF);
+}
+
+static struct irq_chip ar2315_gpio_irq_chip = {
+ .name = DRIVER_NAME,
+ .irq_unmask = ar2315_gpio_irq_unmask,
+ .irq_mask = ar2315_gpio_irq_mask,
+};
+
+static void ar2315_gpio_irq_init(unsigned irq)
+{
+ unsigned i;
+
+ ar2315_gpio_intval = ar2315_gpio_reg_read(AR2315_GPIO_DI);
+ for (i = 0; i < AR2315_GPIO_NUM; i++) {
+ unsigned _irq = ar2315_gpio_irq_base + i;
+
+ irq_set_chip_and_handler(_irq, &ar2315_gpio_irq_chip,
+ handle_level_irq);
+ }
+ irq_set_chained_handler(irq, ar2315_gpio_irq_handler);
+}
+
+static int ar2315_gpio_get_val(struct gpio_chip *chip, unsigned gpio)
+{
+ return (ar2315_gpio_reg_read(AR2315_GPIO_DI) >> gpio) & 1;
+}
+
+static void ar2315_gpio_set_val(struct gpio_chip *chip, unsigned gpio, int val)
+{
+ u32 reg = ar2315_gpio_reg_read(AR2315_GPIO_DO);
+
+ reg = val ? reg | (1 << gpio) : reg & ~(1 << gpio);
+ ar2315_gpio_reg_write(AR2315_GPIO_DO, reg);
+}
+
+static int ar2315_gpio_dir_in(struct gpio_chip *chip, unsigned gpio)
+{
+ ar2315_gpio_reg_mask(AR2315_GPIO_DIR, 1 << gpio, 0);
+ return 0;
+}
+
+static int ar2315_gpio_dir_out(struct gpio_chip *chip, unsigned gpio, int val)
+{
+ ar2315_gpio_reg_mask(AR2315_GPIO_DIR, 0, 1 << gpio);
+ ar2315_gpio_set_val(chip, gpio, val);
+ return 0;
+}
+
+static int ar2315_gpio_to_irq(struct gpio_chip *chip, unsigned gpio)
+{
+ return ar2315_gpio_irq_base + gpio;
+}
+
+static struct gpio_chip ar2315_gpio_chip = {
+ .label = DRIVER_NAME,
+ .direction_input = ar2315_gpio_dir_in,
+ .direction_output = ar2315_gpio_dir_out,
+ .set = ar2315_gpio_set_val,
+ .get = ar2315_gpio_get_val,
+ .to_irq = ar2315_gpio_to_irq,
+ .base = 0,
+ .ngpio = AR2315_GPIO_NUM,
+};
+
+static int ar2315_gpio_probe(struct platform_device *pdev)
+{
+ struct device *dev = &pdev->dev;
+ struct resource *res;
+ unsigned irq;
+ int ret;
+
+ if (ar2315_mem)
+ return -EBUSY;
+
+ res = platform_get_resource_byname(pdev, IORESOURCE_IRQ,
+ "ar2315-gpio-irq-base");
+ if (!res) {
+ dev_err(dev, "not found GPIO IRQ base\n");
+ return -ENXIO;
+ }
+ ar2315_gpio_irq_base = res->start;
+
+ res = platform_get_resource_byname(pdev, IORESOURCE_IRQ, DRIVER_NAME);
+ if (!res) {
+ dev_err(dev, "not found IRQ number\n");
+ return -ENXIO;
+ }
+ irq = res->start;
+
+ res = platform_get_resource_byname(pdev, IORESOURCE_MEM, DRIVER_NAME);
+ ar2315_mem = devm_ioremap_resource(dev, res);
+ if (IS_ERR(ar2315_mem))
+ return PTR_ERR(ar2315_mem);
+
+ ar2315_gpio_chip.dev = dev;
+ ret = gpiochip_add(&ar2315_gpio_chip);
+ if (ret) {
+ dev_err(dev, "failed to add gpiochip\n");
+ return ret;
+ }
+
+ ar2315_gpio_irq_init(irq);
+
+ return 0;
+}
+
+static struct platform_driver ar2315_gpio_driver = {
+ .probe = ar2315_gpio_probe,
+ .driver = {
+ .name = DRIVER_NAME,
+ .owner = THIS_MODULE,
+ }
+};
+
+static int __init ar2315_gpio_init(void)
+{
+ return platform_driver_register(&ar2315_gpio_driver);
+}
+subsys_initcall(ar2315_gpio_init);
--
1.8.1.5
^ permalink raw reply related [flat|nested] 11+ messages in thread
* Re: [RFC 08/18] gpio: add driver for Atheros AR5312 SoC GPIO controller
2014-09-14 19:33 ` [RFC 08/18] gpio: add driver for Atheros AR5312 SoC GPIO controller Sergey Ryazanov
@ 2014-09-29 9:03 ` Linus Walleij
2014-09-29 9:04 ` Linus Walleij
2014-09-29 20:18 ` Sergey Ryazanov
0 siblings, 2 replies; 11+ messages in thread
From: Linus Walleij @ 2014-09-29 9:03 UTC (permalink / raw)
To: Sergey Ryazanov
Cc: Ralf Baechle, Linux MIPS, Alexandre Courbot,
linux-gpio@vger.kernel.org
On Sun, Sep 14, 2014 at 9:33 PM, Sergey Ryazanov <ryazanov.s.a@gmail.com> wrote:
> Atheros AR5312 SoC have a builtin GPIO controller, which could be accessed
> via memory mapped registers. This patch adds new driver for them.
>
> Signed-off-by: Sergey Ryazanov <ryazanov.s.a@gmail.com>
> Cc: Linus Walleij <linus.walleij@linaro.org>
> Cc: Alexandre Courbot <gnurou@gmail.com>
> Cc: linux-gpio@vger.kernel.org
(...)
> diff --git a/arch/mips/ar231x/Kconfig b/arch/mips/ar231x/Kconfig
> diff --git a/arch/mips/ar231x/ar5312.c b/arch/mips/ar231x/ar5312.c
> diff --git a/arch/mips/include/asm/mach-ar231x/ar5312_regs.h b/arch/mips/include/asm/mach-ar231x/ar5312_regs.h
Please put these MIPS-related changes into a separate patch
to be handled through the MIPS git tree.
This driver seems surplus, it's just MMIO. Use
drivers/gpio/gpio-generic.c instead.
Yours,
Linus Walleij
^ permalink raw reply [flat|nested] 11+ messages in thread
* Re: [RFC 08/18] gpio: add driver for Atheros AR5312 SoC GPIO controller
2014-09-29 9:03 ` Linus Walleij
@ 2014-09-29 9:04 ` Linus Walleij
2014-09-29 20:18 ` Sergey Ryazanov
1 sibling, 0 replies; 11+ messages in thread
From: Linus Walleij @ 2014-09-29 9:04 UTC (permalink / raw)
To: Sergey Ryazanov
Cc: Ralf Baechle, Linux MIPS, Alexandre Courbot,
linux-gpio@vger.kernel.org
On Mon, Sep 29, 2014 at 11:03 AM, Linus Walleij
<linus.walleij@linaro.org> wrote:
> This driver seems surplus, it's just MMIO. Use
> drivers/gpio/gpio-generic.c instead.
Bah, I'm talking crap. It does IRQs so it needs to be a custom
driver for sure. I'll take a second look.
Yours,
Linus Walleij
^ permalink raw reply [flat|nested] 11+ messages in thread
* Re: [RFC 09/18] gpio: add driver for Atheros AR5312 SoC GPIO controller
2014-09-14 19:33 ` [RFC 09/18] " Sergey Ryazanov
@ 2014-09-29 9:18 ` Linus Walleij
2014-09-29 9:24 ` Jonas Gorski
2014-09-29 20:43 ` Sergey Ryazanov
0 siblings, 2 replies; 11+ messages in thread
From: Linus Walleij @ 2014-09-29 9:18 UTC (permalink / raw)
To: Sergey Ryazanov
Cc: Ralf Baechle, Linux MIPS, Alexandre Courbot,
linux-gpio@vger.kernel.org
On Sun, Sep 14, 2014 at 9:33 PM, Sergey Ryazanov <ryazanov.s.a@gmail.com> wrote:
> Atheros AR5312 SoC have a builtin GPIO controller, which could be
> accessed via memory mapped registers. This patch adds new driver
> for them.
>
> Signed-off-by: Sergey Ryazanov <ryazanov.s.a@gmail.com>
> Cc: Linus Walleij <linus.walleij@linaro.org>
> Cc: Alexandre Courbot <gnurou@gmail.com>
> Cc: linux-gpio@vger.kernel.org
(...)
> - /* Attempt to jump to the mips reset location - the boot loader
> - * itself might be able to recover the system */
> + /* Cold reset does not work on the AR2315/6, use the GPIO reset bits
> + * a workaround. Give it some time to attempt a gpio based hardware
> + * reset (atheros reference design workaround) */
> + gpio_request_one(AR2315_RESET_GPIO, GPIOF_OUT_INIT_LOW, "Reset");
> + mdelay(100);
Please try to use the new GPIO descriptor API.
See Documentation/gpio/consumer.txt
(...)
> +++ b/drivers/gpio/gpio-ar2315.c
> +static u32 ar2315_gpio_intmask;
> +static u32 ar2315_gpio_intval;
> +static unsigned ar2315_gpio_irq_base;
> +static void __iomem *ar2315_mem;
Get rid of these local variables and put them into an allocated
state container, see
Documentation/driver-model/design-patterns.txt
Get rid of _gpio_irq_base altogether. (See comments below.)
(...)
> +static inline u32 ar2315_gpio_reg_read(unsigned reg)
> +{
> + return __raw_readl(ar2315_mem + reg);
> +}
Use readl_relaxed()
> +static inline void ar2315_gpio_reg_write(unsigned reg, u32 val)
> +{
> + __raw_writel(val, ar2315_mem + reg);
> +}
Use writel_relaxed()
> +static void ar2315_gpio_irq_handler(unsigned irq, struct irq_desc *desc)
> +{
> + u32 pend;
> + int bit = -1;
> +
> + /* only do one gpio interrupt at a time */
> + pend = ar2315_gpio_reg_read(AR2315_GPIO_DI);
> + pend ^= ar2315_gpio_intval;
> + pend &= ar2315_gpio_intmask;
> +
> + if (pend) {
> + bit = fls(pend) - 1;
> + pend &= ~(1 << bit);
Do this:
#include <linux/bitops.h>
pend &= ~BIT(bit);
> + ar2315_gpio_intmask |= (1 << gpio);
|= BIT(gpio);
> + ar2315_gpio_int_setup(gpio, AR2315_GPIO_INT_TRIG_EDGE);
> +}
> +
> +static void ar2315_gpio_irq_mask(struct irq_data *d)
> +{
> + unsigned gpio = d->irq - ar2315_gpio_irq_base;
Wait, no. No keeping irq bases around like that please.
unsigned offset = d->hwirq;
And call it offset rather than "gpio" everywhere please, since
it is local to this GPIO controller, not the global GPIO numberspace.
> + /* Disable interrupt */
> + ar2315_gpio_intmask &= ~(1 << gpio);
&= ~BIT(gpio);
> +static int ar2315_gpio_get_val(struct gpio_chip *chip, unsigned gpio)
> +{
> + return (ar2315_gpio_reg_read(AR2315_GPIO_DI) >> gpio) & 1;
> +}
Do this:
return !!(ar2315_gpio_reg_read(AR2315_GPIO_DI) & BIT(gpio));
> +static void ar2315_gpio_set_val(struct gpio_chip *chip, unsigned gpio, int val)
> +{
> + u32 reg = ar2315_gpio_reg_read(AR2315_GPIO_DO);
> +
> + reg = val ? reg | (1 << gpio) : reg & ~(1 << gpio);
> + ar2315_gpio_reg_write(AR2315_GPIO_DO, reg);
Convoluted, I would use an if() else construct rather than the ? operator.
> +static int ar2315_gpio_to_irq(struct gpio_chip *chip, unsigned gpio)
> +{
> + return ar2315_gpio_irq_base + gpio;
> +}
Don't implement this at all. You're using the gpiolib irqchip helpers!
It will just overrun this implementation.
Yours,
Linus Walleij
^ permalink raw reply [flat|nested] 11+ messages in thread
* Re: [RFC 09/18] gpio: add driver for Atheros AR5312 SoC GPIO controller
2014-09-29 9:18 ` Linus Walleij
@ 2014-09-29 9:24 ` Jonas Gorski
2014-09-29 20:43 ` Sergey Ryazanov
1 sibling, 0 replies; 11+ messages in thread
From: Jonas Gorski @ 2014-09-29 9:24 UTC (permalink / raw)
To: Linus Walleij
Cc: Sergey Ryazanov, Ralf Baechle, Linux MIPS, Alexandre Courbot,
linux-gpio@vger.kernel.org
On Mon, Sep 29, 2014 at 11:18 AM, Linus Walleij
<linus.walleij@linaro.org> wrote:
> On Sun, Sep 14, 2014 at 9:33 PM, Sergey Ryazanov <ryazanov.s.a@gmail.com> wrote:
>
>> Atheros AR5312 SoC have a builtin GPIO controller, which could be
>> accessed via memory mapped registers. This patch adds new driver
>> for them.
>>
>> Signed-off-by: Sergey Ryazanov <ryazanov.s.a@gmail.com>
>> Cc: Linus Walleij <linus.walleij@linaro.org>
>> Cc: Alexandre Courbot <gnurou@gmail.com>
>> Cc: linux-gpio@vger.kernel.org
> (...)
>> - /* Attempt to jump to the mips reset location - the boot loader
>> - * itself might be able to recover the system */
>> + /* Cold reset does not work on the AR2315/6, use the GPIO reset bits
>> + * a workaround. Give it some time to attempt a gpio based hardware
>> + * reset (atheros reference design workaround) */
>> + gpio_request_one(AR2315_RESET_GPIO, GPIOF_OUT_INIT_LOW, "Reset");
>> + mdelay(100);
>
> Please try to use the new GPIO descriptor API.
> See Documentation/gpio/consumer.txt
>
> (...)
>> +++ b/drivers/gpio/gpio-ar2315.c
>
>> +static u32 ar2315_gpio_intmask;
>> +static u32 ar2315_gpio_intval;
>> +static unsigned ar2315_gpio_irq_base;
>> +static void __iomem *ar2315_mem;
>
> Get rid of these local variables and put them into an allocated
> state container, see
> Documentation/driver-model/design-patterns.txt
>
> Get rid of _gpio_irq_base altogether. (See comments below.)
>
> (...)
>> +static inline u32 ar2315_gpio_reg_read(unsigned reg)
>> +{
>> + return __raw_readl(ar2315_mem + reg);
>> +}
>
> Use readl_relaxed()
ar2315/ar5312 is big endian, so readl_relaxed would mess up the byte
order. There does not seem to be a big endian equivalent for _relaxed.
Regards
Jonas
^ permalink raw reply [flat|nested] 11+ messages in thread
* Re: [RFC 08/18] gpio: add driver for Atheros AR5312 SoC GPIO controller
2014-09-29 9:03 ` Linus Walleij
2014-09-29 9:04 ` Linus Walleij
@ 2014-09-29 20:18 ` Sergey Ryazanov
1 sibling, 0 replies; 11+ messages in thread
From: Sergey Ryazanov @ 2014-09-29 20:18 UTC (permalink / raw)
To: Linus Walleij
Cc: Ralf Baechle, Linux MIPS, Alexandre Courbot,
linux-gpio@vger.kernel.org
2014-09-29 13:03 GMT+04:00 Linus Walleij <linus.walleij@linaro.org>:
> On Sun, Sep 14, 2014 at 9:33 PM, Sergey Ryazanov <ryazanov.s.a@gmail.com> wrote:
>
>> Atheros AR5312 SoC have a builtin GPIO controller, which could be accessed
>> via memory mapped registers. This patch adds new driver for them.
>>
>> Signed-off-by: Sergey Ryazanov <ryazanov.s.a@gmail.com>
>> Cc: Linus Walleij <linus.walleij@linaro.org>
>> Cc: Alexandre Courbot <gnurou@gmail.com>
>> Cc: linux-gpio@vger.kernel.org
> (...)
>
>> diff --git a/arch/mips/ar231x/Kconfig b/arch/mips/ar231x/Kconfig
>> diff --git a/arch/mips/ar231x/ar5312.c b/arch/mips/ar231x/ar5312.c
>> diff --git a/arch/mips/include/asm/mach-ar231x/ar5312_regs.h b/arch/mips/include/asm/mach-ar231x/ar5312_regs.h
>
> Please put these MIPS-related changes into a separate patch
> to be handled through the MIPS git tree.
>
Already do that in non RFC patch.
--
BR,
Sergey
^ permalink raw reply [flat|nested] 11+ messages in thread
* Re: [RFC 09/18] gpio: add driver for Atheros AR5312 SoC GPIO controller
2014-09-29 9:18 ` Linus Walleij
2014-09-29 9:24 ` Jonas Gorski
@ 2014-09-29 20:43 ` Sergey Ryazanov
2014-10-21 8:29 ` Linus Walleij
1 sibling, 1 reply; 11+ messages in thread
From: Sergey Ryazanov @ 2014-09-29 20:43 UTC (permalink / raw)
To: Linus Walleij
Cc: Ralf Baechle, Linux MIPS, Alexandre Courbot,
linux-gpio@vger.kernel.org
2014-09-29 13:18 GMT+04:00 Linus Walleij <linus.walleij@linaro.org>:
> On Sun, Sep 14, 2014 at 9:33 PM, Sergey Ryazanov <ryazanov.s.a@gmail.com> wrote:
>
>> Atheros AR5312 SoC have a builtin GPIO controller, which could be
>> accessed via memory mapped registers. This patch adds new driver
>> for them.
>>
>> Signed-off-by: Sergey Ryazanov <ryazanov.s.a@gmail.com>
>> Cc: Linus Walleij <linus.walleij@linaro.org>
>> Cc: Alexandre Courbot <gnurou@gmail.com>
>> Cc: linux-gpio@vger.kernel.org
> (...)
>> - /* Attempt to jump to the mips reset location - the boot loader
>> - * itself might be able to recover the system */
>> + /* Cold reset does not work on the AR2315/6, use the GPIO reset bits
>> + * a workaround. Give it some time to attempt a gpio based hardware
>> + * reset (atheros reference design workaround) */
>> + gpio_request_one(AR2315_RESET_GPIO, GPIOF_OUT_INIT_LOW, "Reset");
>> + mdelay(100);
>
> Please try to use the new GPIO descriptor API.
> See Documentation/gpio/consumer.txt
>
I will investigate this possibility.
> (...)
>> +++ b/drivers/gpio/gpio-ar2315.c
>
>> +static u32 ar2315_gpio_intmask;
>> +static u32 ar2315_gpio_intval;
>> +static unsigned ar2315_gpio_irq_base;
>> +static void __iomem *ar2315_mem;
>
> Get rid of these local variables and put them into an allocated
> state container, see
> Documentation/driver-model/design-patterns.txt
>
AR2315 SoC contains only one GPIO unit, so there are no reasons to
increase driver complexity. But if you insist, I will add state
container.
> Get rid of _gpio_irq_base altogether. (See comments below.)
>
> (...)
>> +static inline u32 ar2315_gpio_reg_read(unsigned reg)
>> +{
>> + return __raw_readl(ar2315_mem + reg);
>> +}
>
> Use readl_relaxed()
>
>> +static inline void ar2315_gpio_reg_write(unsigned reg, u32 val)
>> +{
>> + __raw_writel(val, ar2315_mem + reg);
>> +}
>
> Use writel_relaxed()
>
>> +static void ar2315_gpio_irq_handler(unsigned irq, struct irq_desc *desc)
>> +{
>> + u32 pend;
>> + int bit = -1;
>> +
>> + /* only do one gpio interrupt at a time */
>> + pend = ar2315_gpio_reg_read(AR2315_GPIO_DI);
>> + pend ^= ar2315_gpio_intval;
>> + pend &= ar2315_gpio_intmask;
>> +
>> + if (pend) {
>> + bit = fls(pend) - 1;
>> + pend &= ~(1 << bit);
>
> Do this:
>
> #include <linux/bitops.h>
>
> pend &= ~BIT(bit);
>
>> + ar2315_gpio_intmask |= (1 << gpio);
>
> |= BIT(gpio);
>
>> + ar2315_gpio_int_setup(gpio, AR2315_GPIO_INT_TRIG_EDGE);
>> +}
>> +
>> +static void ar2315_gpio_irq_mask(struct irq_data *d)
>> +{
>> + unsigned gpio = d->irq - ar2315_gpio_irq_base;
>
> Wait, no. No keeping irq bases around like that please.
>
> unsigned offset = d->hwirq;
>
> And call it offset rather than "gpio" everywhere please, since
> it is local to this GPIO controller, not the global GPIO numberspace.
>
Sure.
>> + /* Disable interrupt */
>> + ar2315_gpio_intmask &= ~(1 << gpio);
>
> &= ~BIT(gpio);
>
>> +static int ar2315_gpio_get_val(struct gpio_chip *chip, unsigned gpio)
>> +{
>> + return (ar2315_gpio_reg_read(AR2315_GPIO_DI) >> gpio) & 1;
>> +}
>
> Do this:
> return !!(ar2315_gpio_reg_read(AR2315_GPIO_DI) & BIT(gpio));
>
Ok.
>> +static void ar2315_gpio_set_val(struct gpio_chip *chip, unsigned gpio, int val)
>> +{
>> + u32 reg = ar2315_gpio_reg_read(AR2315_GPIO_DO);
>> +
>> + reg = val ? reg | (1 << gpio) : reg & ~(1 << gpio);
>> + ar2315_gpio_reg_write(AR2315_GPIO_DO, reg);
>
> Convoluted, I would use an if() else construct rather than the ? operator.
>
Convoluted, but 3 lines shorter :) And checkpatch has no objections.
>> +static int ar2315_gpio_to_irq(struct gpio_chip *chip, unsigned gpio)
>> +{
>> + return ar2315_gpio_irq_base + gpio;
>> +}
>
> Don't implement this at all. You're using the gpiolib irqchip helpers!
> It will just overrun this implementation.
>
Seems that I missed some new gpiolib features. I will try to rewrite this.
Thank you for detailed review!
--
BR,
Sergey
^ permalink raw reply [flat|nested] 11+ messages in thread
* Re: [RFC 09/18] gpio: add driver for Atheros AR5312 SoC GPIO controller
2014-09-29 20:43 ` Sergey Ryazanov
@ 2014-10-21 8:29 ` Linus Walleij
2014-10-21 8:59 ` Sergey Ryazanov
0 siblings, 1 reply; 11+ messages in thread
From: Linus Walleij @ 2014-10-21 8:29 UTC (permalink / raw)
To: Sergey Ryazanov
Cc: Ralf Baechle, Linux MIPS, Alexandre Courbot,
linux-gpio@vger.kernel.org
On Mon, Sep 29, 2014 at 10:43 PM, Sergey Ryazanov
<ryazanov.s.a@gmail.com> wrote:
> 2014-09-29 13:18 GMT+04:00 Linus Walleij <linus.walleij@linaro.org>:
>>> +static u32 ar2315_gpio_intmask;
>>> +static u32 ar2315_gpio_intval;
>>> +static unsigned ar2315_gpio_irq_base;
>>> +static void __iomem *ar2315_mem;
>>
>> Get rid of these local variables and put them into an allocated
>> state container, see
>> Documentation/driver-model/design-patterns.txt
>>
> AR2315 SoC contains only one GPIO unit, so there are no reasons to
> increase driver complexity. But if you insist, I will add state
> container.
I insist. It makes the driver easier to maintain if it looks like
most other drivers instead of using static locals.
>> Convoluted, I would use an if() else construct rather than the ? operator.
>>
> Convoluted, but 3 lines shorter :) And checkpatch has no objections.
True but it's me who is going to be maintaining this, not checkpatch.
Yours,
Linus Walleij
^ permalink raw reply [flat|nested] 11+ messages in thread
* Re: [RFC 09/18] gpio: add driver for Atheros AR5312 SoC GPIO controller
2014-10-21 8:29 ` Linus Walleij
@ 2014-10-21 8:59 ` Sergey Ryazanov
2014-10-28 16:12 ` Linus Walleij
0 siblings, 1 reply; 11+ messages in thread
From: Sergey Ryazanov @ 2014-10-21 8:59 UTC (permalink / raw)
To: Linus Walleij
Cc: Ralf Baechle, Linux MIPS, Alexandre Courbot,
linux-gpio@vger.kernel.org
2014-10-21 12:29 GMT+04:00 Linus Walleij <linus.walleij@linaro.org>:
> On Mon, Sep 29, 2014 at 10:43 PM, Sergey Ryazanov
> <ryazanov.s.a@gmail.com> wrote:
>> 2014-09-29 13:18 GMT+04:00 Linus Walleij <linus.walleij@linaro.org>:
>
>>>> +static u32 ar2315_gpio_intmask;
>>>> +static u32 ar2315_gpio_intval;
>>>> +static unsigned ar2315_gpio_irq_base;
>>>> +static void __iomem *ar2315_mem;
>>>
>>> Get rid of these local variables and put them into an allocated
>>> state container, see
>>> Documentation/driver-model/design-patterns.txt
>>>
>> AR2315 SoC contains only one GPIO unit, so there are no reasons to
>> increase driver complexity. But if you insist, I will add state
>> container.
>
> I insist. It makes the driver easier to maintain if it looks like
> most other drivers instead of using static locals.
>
No problem. I rewrite the driver using the state container.
>>> Convoluted, I would use an if() else construct rather than the ? operator.
>>>
>> Convoluted, but 3 lines shorter :) And checkpatch has no objections.
>
> True but it's me who is going to be maintaining this, not checkpatch.
>
I missed that. Added to my todo list.
BTW, the use of the irq_domain framework is required or I could
opencode some stuff?
> Yours,
> Linus Walleij
--
BR,
Sergey
^ permalink raw reply [flat|nested] 11+ messages in thread
* Re: [RFC 09/18] gpio: add driver for Atheros AR5312 SoC GPIO controller
2014-10-21 8:59 ` Sergey Ryazanov
@ 2014-10-28 16:12 ` Linus Walleij
0 siblings, 0 replies; 11+ messages in thread
From: Linus Walleij @ 2014-10-28 16:12 UTC (permalink / raw)
To: Sergey Ryazanov
Cc: Ralf Baechle, Linux MIPS, Alexandre Courbot,
linux-gpio@vger.kernel.org
On Tue, Oct 21, 2014 at 10:59 AM, Sergey Ryazanov
<ryazanov.s.a@gmail.com> wrote:
> BTW, the use of the irq_domain framework is required or I could
> opencode some stuff?
Whatever makes sense. If you write something that looks very
convoluted compared to doing it with irqdomain, you're doing
something wrong.
But shouldn't this driver be using GPIOLIB_IRQCHIP by the way?
That includes irqdomain handling.
Yours,
Linus Walleij
^ permalink raw reply [flat|nested] 11+ messages in thread
end of thread, other threads:[~2014-10-28 16:13 UTC | newest]
Thread overview: 11+ messages (download: mbox.gz follow: Atom feed
-- links below jump to the message on this page --
[not found] <1410723213-22440-1-git-send-email-ryazanov.s.a@gmail.com>
2014-09-14 19:33 ` [RFC 08/18] gpio: add driver for Atheros AR5312 SoC GPIO controller Sergey Ryazanov
2014-09-29 9:03 ` Linus Walleij
2014-09-29 9:04 ` Linus Walleij
2014-09-29 20:18 ` Sergey Ryazanov
2014-09-14 19:33 ` [RFC 09/18] " Sergey Ryazanov
2014-09-29 9:18 ` Linus Walleij
2014-09-29 9:24 ` Jonas Gorski
2014-09-29 20:43 ` Sergey Ryazanov
2014-10-21 8:29 ` Linus Walleij
2014-10-21 8:59 ` Sergey Ryazanov
2014-10-28 16:12 ` Linus Walleij
This is a public inbox, see mirroring instructions
for how to clone and mirror all data and code used for this inbox;
as well as URLs for NNTP newsgroup(s).