2010-06-11 19:59:09

by Gregory Bean

[permalink] [raw]
Subject: [PATCH 0/2] Add gpiolib support for MSM chips.

Hi folks:

Here is a proposed driver which adds gpio and irq support to all
currently-supported arm-msm SoCs. Feedback is greatly appreciated.

Gregory Bean (2):
gpio: msm7200a: Add gpiolib support for MSM chips.
gpio: msm7200a: Add irq support to msm-gpiolib.

MAINTAINERS | 2 +
drivers/gpio/Kconfig | 8 +
drivers/gpio/Makefile | 1 +
drivers/gpio/msm7200a-gpio.c | 398 +++++++++++++++++++++++++++++++++++++++++
include/linux/msm7200a-gpio.h | 51 ++++++
5 files changed, 460 insertions(+), 0 deletions(-)
create mode 100644 drivers/gpio/msm7200a-gpio.c
create mode 100644 include/linux/msm7200a-gpio.h

---
Employee of Qualcomm Innovation Center, Inc.
Qualcomm Innovation Center, Inc. is a member of the Code Aurora Forum.


2010-06-11 19:59:00

by Gregory Bean

[permalink] [raw]
Subject: [PATCH 2/2] gpio: msm7200a: Add irq support to msm-gpiolib.

Change-Id: Ib7f7dd05246c87096aabab12eb6cc260551c67cf
Signed-off-by: Gregory Bean <[email protected]>
---
drivers/gpio/msm7200a-gpio.c | 218 +++++++++++++++++++++++++++++++++++++++--
include/linux/msm7200a-gpio.h | 7 ++
2 files changed, 218 insertions(+), 7 deletions(-)

diff --git a/drivers/gpio/msm7200a-gpio.c b/drivers/gpio/msm7200a-gpio.c
index b31c25e..a9ea869 100644
--- a/drivers/gpio/msm7200a-gpio.c
+++ b/drivers/gpio/msm7200a-gpio.c
@@ -23,13 +23,25 @@
#include <linux/kernel.h>
#include <linux/gpio.h>
#include <linux/io.h>
+#include <linux/interrupt.h>
+#include <linux/irq.h>
#include <linux/module.h>
#include <linux/platform_device.h>
#include <linux/msm7200a-gpio.h>

+/*
+ * The INT_STATUS register latches both edge- and level-detection events,
+ * which is atypical. Turning on DONT_LATCH_LEVEL_IRQS causes level irq
+ * triggers to be forgotten across mask/unmask calls, emulating a more
+ * traditional setup.
+ */
+#define MSM_GPIO_DONT_LATCH_LEVEL_IRQS 1
+
struct msm_gpio_dev {
struct gpio_chip gpio_chip;
spinlock_t lock;
+ unsigned irq_base;
+ unsigned irq_summary;
struct msm7200a_gpio_regs regs;
};

@@ -119,12 +131,160 @@ static void gpio_chip_set(struct gpio_chip *chip, unsigned offset, int value)
spin_unlock_irqrestore(&msm_gpio->lock, irq_flags);
}

+static int gpio_chip_to_irq(struct gpio_chip *chip, unsigned offset)
+{
+ struct msm_gpio_dev *msm_gpio = TO_MSM_GPIO_DEV(chip);
+ return msm_gpio->irq_base + offset;
+}
+
+#if MSM_GPIO_DONT_LATCH_LEVEL_IRQS
+static inline void forget_level_irq(struct msm_gpio_dev *msm_gpio,
+ unsigned offset)
+{
+ unsigned v = readl(msm_gpio->regs.int_edge);
+ unsigned b = bit(offset);
+
+ if (!(v & b))
+ writel(b, msm_gpio->regs.int_clear);
+
+}
+#else
+static inline void forget_level_irq(struct msm_gpio_dev *msm, unsigned off)
+{
+}
+#endif
+
+static void msm_gpio_irq_mask(unsigned int irq)
+{
+ unsigned long irq_flags;
+ struct msm_gpio_dev *msm_gpio = get_irq_chip_data(irq);
+ unsigned offset = irq - msm_gpio->irq_base;
+
+ spin_lock_irqsave(&msm_gpio->lock, irq_flags);
+ forget_level_irq(msm_gpio, offset);
+ clr_gpio_bit(offset, msm_gpio->regs.int_en);
+ spin_unlock_irqrestore(&msm_gpio->lock, irq_flags);
+}
+
+static void msm_gpio_irq_unmask(unsigned int irq)
+{
+ unsigned long irq_flags;
+ struct msm_gpio_dev *msm_gpio = get_irq_chip_data(irq);
+ unsigned offset = irq - msm_gpio->irq_base;
+
+ spin_lock_irqsave(&msm_gpio->lock, irq_flags);
+ forget_level_irq(msm_gpio, offset);
+ set_gpio_bit(offset, msm_gpio->regs.int_en);
+ spin_unlock_irqrestore(&msm_gpio->lock, irq_flags);
+}
+
+static int msm_gpio_irq_set_type(unsigned int irq, unsigned int flow_type)
+{
+ unsigned long irq_flags;
+ struct msm_gpio_dev *msm_gpio = get_irq_chip_data(irq);
+ unsigned offset = irq - msm_gpio->irq_base;
+
+ if ((flow_type & (IRQF_TRIGGER_FALLING | IRQF_TRIGGER_RISING)) ==
+ (IRQF_TRIGGER_FALLING | IRQF_TRIGGER_RISING))
+ return -ENOTSUPP;
+
+ if ((flow_type & (IRQF_TRIGGER_HIGH | IRQF_TRIGGER_LOW)) ==
+ (IRQF_TRIGGER_HIGH | IRQF_TRIGGER_LOW))
+ return -ENOTSUPP;
+
+ spin_lock_irqsave(&msm_gpio->lock, irq_flags);
+
+ if (flow_type & (IRQF_TRIGGER_FALLING | IRQF_TRIGGER_RISING)) {
+ set_gpio_bit(offset, msm_gpio->regs.int_edge);
+ irq_desc[irq].handle_irq = handle_edge_irq;
+ } else {
+ clr_gpio_bit(offset, msm_gpio->regs.int_edge);
+ irq_desc[irq].handle_irq = handle_level_irq;
+ }
+
+ if (flow_type & (IRQF_TRIGGER_HIGH | IRQF_TRIGGER_RISING))
+ set_gpio_bit(offset, msm_gpio->regs.int_pos);
+ else
+ clr_gpio_bit(offset, msm_gpio->regs.int_pos);
+
+ spin_unlock_irqrestore(&msm_gpio->lock, irq_flags);
+
+ return 0;
+}
+
+static void msm_gpio_irq_mask_ack(unsigned int irq)
+{
+ msm_gpio_irq_mask(irq);
+}
+
+static int msm_gpio_irq_set_affinity(unsigned int irq,
+ const struct cpumask *dest)
+{
+ return -ENOTSUPP;
+}
+
+static int msm_gpio_irq_retrigger(unsigned int irq)
+{
+ return -ENOTSUPP;
+}
+
+static int msm_gpio_irq_set_wake(unsigned int irq, unsigned int on)
+{
+ return -ENOTSUPP;
+}
+
+static irqreturn_t msm_gpio_irq_handler(int irq, void *dev)
+{
+ unsigned long irq_flags;
+ int b, m;
+ unsigned e, s, v;
+
+ struct msm_gpio_dev *msm_gpio = (struct msm_gpio_dev *)dev;
+
+ /*
+ * The int_status register latches trigger events whether or not
+ * the gpio line is enabled as an interrupt source. Therefore,
+ * the set of pins which defines the interrupts which need to fire
+ * is the intersection of int_status and int_en - int_status
+ * alone provides an incomplete picture.
+ */
+ spin_lock_irqsave(&msm_gpio->lock, irq_flags);
+ s = readl(msm_gpio->regs.int_status);
+ e = readl(msm_gpio->regs.int_en);
+ v = s & e;
+ if (v)
+ writel(v, msm_gpio->regs.int_clear);
+ spin_unlock_irqrestore(&msm_gpio->lock, irq_flags);
+
+ if (!v)
+ return IRQ_NONE;
+
+ while (v) {
+ m = v & -v;
+ b = fls(m) - 1;
+ v &= ~m;
+ generic_handle_irq(msm_gpio->irq_base + b);
+ }
+ return IRQ_HANDLED;
+}
+
+static struct irq_chip msm_gpio_irq_chip = {
+ .name = "msm_gpio",
+ .mask = msm_gpio_irq_mask,
+ .mask_ack = msm_gpio_irq_mask_ack,
+ .unmask = msm_gpio_irq_unmask,
+ .set_affinity = msm_gpio_irq_set_affinity,
+ .retrigger = msm_gpio_irq_retrigger,
+ .set_type = msm_gpio_irq_set_type,
+ .set_wake = msm_gpio_irq_set_wake,
+};
+
static int msm_gpio_probe(struct platform_device *dev)
{
struct msm_gpio_dev *msm_gpio;
struct msm7200a_gpio_platform_data *pdata =
(struct msm7200a_gpio_platform_data *)dev->dev.platform_data;
- int ret;
+ int i, irq, ret;

if (!pdata)
return -EINVAL;
@@ -146,13 +306,53 @@ static int msm_gpio_probe(struct platform_device *dev)
msm_gpio->gpio_chip.direction_output = gpio_chip_direction_output;
msm_gpio->gpio_chip.get = gpio_chip_get;
msm_gpio->gpio_chip.set = gpio_chip_set;
+ msm_gpio->gpio_chip.to_irq = gpio_chip_to_irq;
+ msm_gpio->irq_base = pdata->irq_base;
+ msm_gpio->irq_summary = pdata->irq_summary;

ret = gpiochip_add(&msm_gpio->gpio_chip);
if (ret < 0)
- goto err;
+ goto err_post_malloc;
+
+ for (i = 0; i < msm_gpio->gpio_chip.ngpio; ++i) {
+ irq = msm_gpio->irq_base + i;
+ set_irq_chip_data(irq, msm_gpio);
+ set_irq_chip(irq, &msm_gpio_irq_chip);
+ set_irq_handler(irq, handle_level_irq);
+ set_irq_flags(irq, IRQF_VALID);
+ }
+
+ /*
+ * We use a level-triggered interrupt because of the nature
+ * of the shared GPIO-group interrupt.
+ *
+ * Many GPIO chips may be sharing the same group IRQ line, and
+ * it is possible for GPIO interrupt to re-occur while the system
+ * is still servicing the group interrupt associated with it.
+ * The group IRQ line would not de-assert and re-assert, and
+ * we'd get no second edge to cause the group IRQ to be handled again.
+ *
+ * Using a level interrupt guarantees that the group IRQ handlers
+ * will continue to be called as long as any GPIO chip in the group
+ * is asserting, even if the condition began while the group
+ * handler was in mid-pass.
+ */
+ ret = request_irq(msm_gpio->irq_summary,
+ msm_gpio_irq_handler,
+ IRQF_SHARED | IRQF_TRIGGER_HIGH,
+ dev->name,
+ msm_gpio);
+ if (ret < 0)
+ goto err_post_gpiochip_add;

return ret;
-err:
+err_post_gpiochip_add:
+ /*
+ * Under no circumstances should a line be held on a gpiochip
+ * which hasn't finished probing.
+ */
+ BUG_ON(gpiochip_remove(&msm_gpio->gpio_chip) < 0);
+err_post_malloc:
kfree(msm_gpio);
return ret;
}
@@ -160,12 +360,16 @@ err:
static int msm_gpio_remove(struct platform_device *dev)
{
struct msm_gpio_dev *msm_gpio = platform_get_drvdata(dev);
- int ret = gpiochip_remove(&msm_gpio->gpio_chip);
+ int ret;

- if (ret == 0)
- kfree(msm_gpio);
+ ret = gpiochip_remove(&msm_gpio->gpio_chip);
+ if (ret < 0)
+ return ret;

- return ret;
+ free_irq(msm_gpio->irq_summary, msm_gpio);
+ kfree(msm_gpio);
+
+ return 0;
}

static struct platform_driver msm_gpio_driver = {
diff --git a/include/linux/msm7200a-gpio.h b/include/linux/msm7200a-gpio.h
index 3f1ef38..7af4dd6 100644
--- a/include/linux/msm7200a-gpio.h
+++ b/include/linux/msm7200a-gpio.h
@@ -33,11 +33,18 @@ struct msm7200a_gpio_regs {
void __iomem *in;
void __iomem *out;
void __iomem *oe;
+ void __iomem *int_status;
+ void __iomem *int_clear;
+ void __iomem *int_en;
+ void __iomem *int_edge;
+ void __iomem *int_pos;
};

struct msm7200a_gpio_platform_data {
unsigned gpio_base;
unsigned ngpio;
+ unsigned irq_base;
+ unsigned irq_summary;
struct msm7200a_gpio_regs regs;
};

--
1.7.0.4

---
Employee of Qualcomm Innovation Center, Inc.
Qualcomm Innovation Center, Inc. is a member of the Code Aurora Forum.

2010-06-11 19:59:19

by Gregory Bean

[permalink] [raw]
Subject: [PATCH 1/2] gpio: msm7200a: Add gpiolib support for MSM chips.

Add support for uniprocessor MSM chips whose TLMM/GPIO design
is the same as the MSM7200A.
This includes, but is not necessarily limited to, the:
MSM7200A, MSM7x25, MSM7x27, MSM7x30, QSD8x50, QSD8x50A

Change-Id: I748d0e09f6b762f1711cde3c27a9a6e8de6d9454
Signed-off-by: Gregory Bean <[email protected]>
---
MAINTAINERS | 2 +
drivers/gpio/Kconfig | 8 ++
drivers/gpio/Makefile | 1 +
drivers/gpio/msm7200a-gpio.c | 194 +++++++++++++++++++++++++++++++++++++++++
include/linux/msm7200a-gpio.h | 44 +++++++++
5 files changed, 249 insertions(+), 0 deletions(-)
create mode 100644 drivers/gpio/msm7200a-gpio.c
create mode 100644 include/linux/msm7200a-gpio.h

diff --git a/MAINTAINERS b/MAINTAINERS
index 6d119c9..bdfd31d 100644
--- a/MAINTAINERS
+++ b/MAINTAINERS
@@ -819,6 +819,8 @@ F: drivers/mmc/host/msm_sdcc.c
F: drivers/mmc/host/msm_sdcc.h
F: drivers/serial/msm_serial.h
F: drivers/serial/msm_serial.c
+F: drivers/gpio/msm7200a-gpio.c
+F: include/linux/msm7200a-gpio.h
T: git git://codeaurora.org/quic/kernel/dwalker/linux-msm.git
S: Maintained

diff --git a/drivers/gpio/Kconfig b/drivers/gpio/Kconfig
index 724038d..557738a 100644
--- a/drivers/gpio/Kconfig
+++ b/drivers/gpio/Kconfig
@@ -76,6 +76,14 @@ config GPIO_IT8761E
help
Say yes here to support GPIO functionality of IT8761E super I/O chip.

+config GPIO_MSM7200A
+ tristate "Qualcomm MSM7200A SoC GPIO support"
+ depends on GPIOLIB
+ help
+ Say yes here to support GPIO functionality on Qualcomm's
+ MSM chipsets which descend from the MSM7200a:
+ MSM7x01(a), MSM7x25, MSM7x27, MSM7x30, QSD8x50(a).
+
config GPIO_PL061
bool "PrimeCell PL061 GPIO support"
depends on ARM_AMBA
diff --git a/drivers/gpio/Makefile b/drivers/gpio/Makefile
index 51c3cdd..2389c29 100644
--- a/drivers/gpio/Makefile
+++ b/drivers/gpio/Makefile
@@ -13,6 +13,7 @@ obj-$(CONFIG_GPIO_MAX7301) += max7301.o
obj-$(CONFIG_GPIO_MAX732X) += max732x.o
obj-$(CONFIG_GPIO_MC33880) += mc33880.o
obj-$(CONFIG_GPIO_MCP23S08) += mcp23s08.o
+obj-$(CONFIG_GPIO_MSM7200A) += msm7200a-gpio.o
obj-$(CONFIG_GPIO_PCA953X) += pca953x.o
obj-$(CONFIG_GPIO_PCF857X) += pcf857x.o
obj-$(CONFIG_GPIO_PL061) += pl061.o
diff --git a/drivers/gpio/msm7200a-gpio.c b/drivers/gpio/msm7200a-gpio.c
new file mode 100644
index 0000000..b31c25e
--- /dev/null
+++ b/drivers/gpio/msm7200a-gpio.c
@@ -0,0 +1,194 @@
+/*
+ * Driver for Qualcomm MSM7200a and related SoC GPIO.
+ * Supported chipset families include:
+ * MSM7x01(a), MSM7x25, MSM7x27, MSM7x30, QSD8x50(a)
+ *
+ * Copyright (C) 2007 Google, Inc.
+ * Copyright (c) 2010, Code Aurora Forum. All rights reserved.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 and
+ * only version 2 as published by the Free Software Foundation.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA
+ * 02110-1301, USA.
+ */
+#include <linux/kernel.h>
+#include <linux/gpio.h>
+#include <linux/io.h>
+#include <linux/module.h>
+#include <linux/platform_device.h>
+#include <linux/msm7200a-gpio.h>
+
+struct msm_gpio_dev {
+ struct gpio_chip gpio_chip;
+ spinlock_t lock;
+ struct msm7200a_gpio_regs regs;
+};
+
+#define TO_MSM_GPIO_DEV(c) container_of(c, struct msm_gpio_dev, gpio_chip)
+
+static inline unsigned bit(unsigned offset)
+{
+ BUG_ON(offset >= sizeof(unsigned) * 8);
+ return 1U << offset;
+}
+
+/*
+ * This function assumes that msm_gpio_dev::lock is held.
+ */
+static inline void set_gpio_bit(unsigned n, void __iomem *reg)
+{
+ writel(readl(reg) | bit(n), reg);
+}
+
+/*
+ * This function assumes that msm_gpio_dev::lock is held.
+ */
+static inline void clr_gpio_bit(unsigned n, void __iomem *reg)
+{
+ writel(readl(reg) & ~bit(n), reg);
+}
+
+/*
+ * This function assumes that msm_gpio_dev::lock is held.
+ */
+static inline void
+msm_gpio_write(struct msm_gpio_dev *dev, unsigned n, unsigned on)
+{
+ if (on)
+ set_gpio_bit(n, dev->regs.out);
+ else
+ clr_gpio_bit(n, dev->regs.out);
+}
+
+static int gpio_chip_direction_input(struct gpio_chip *chip, unsigned offset)
+{
+ struct msm_gpio_dev *msm_gpio = TO_MSM_GPIO_DEV(chip);
+ unsigned long irq_flags;
+
+ spin_lock_irqsave(&msm_gpio->lock, irq_flags);
+ clr_gpio_bit(offset, msm_gpio->regs.oe);
+ spin_unlock_irqrestore(&msm_gpio->lock, irq_flags);
+
+ return 0;
+}
+
+static int
+gpio_chip_direction_output(struct gpio_chip *chip, unsigned offset, int value)
+{
+ struct msm_gpio_dev *msm_gpio = TO_MSM_GPIO_DEV(chip);
+ unsigned long irq_flags;
+
+ spin_lock_irqsave(&msm_gpio->lock, irq_flags);
+
+ msm_gpio_write(msm_gpio, offset, value);
+ set_gpio_bit(offset, msm_gpio->regs.oe);
+ spin_unlock_irqrestore(&msm_gpio->lock, irq_flags);
+
+ return 0;
+}
+
+static int gpio_chip_get(struct gpio_chip *chip, unsigned offset)
+{
+ struct msm_gpio_dev *msm_gpio = TO_MSM_GPIO_DEV(chip);
+ unsigned long irq_flags;
+ int ret;
+
+ spin_lock_irqsave(&msm_gpio->lock, irq_flags);
+ ret = readl(msm_gpio->regs.in) & bit(offset) ? 1 : 0;
+ spin_unlock_irqrestore(&msm_gpio->lock, irq_flags);
+
+ return ret;
+}
+
+static void gpio_chip_set(struct gpio_chip *chip, unsigned offset, int value)
+{
+ struct msm_gpio_dev *msm_gpio = TO_MSM_GPIO_DEV(chip);
+ unsigned long irq_flags;
+
+ spin_lock_irqsave(&msm_gpio->lock, irq_flags);
+ msm_gpio_write(msm_gpio, offset, value);
+ spin_unlock_irqrestore(&msm_gpio->lock, irq_flags);
+}
+
+static int msm_gpio_probe(struct platform_device *dev)
+{
+ struct msm_gpio_dev *msm_gpio;
+ struct msm7200a_gpio_platform_data *pdata =
+ (struct msm7200a_gpio_platform_data *)dev->dev.platform_data;
+ int ret;
+
+ if (!pdata)
+ return -EINVAL;
+
+ msm_gpio = kzalloc(sizeof(struct msm_gpio_dev), GFP_KERNEL);
+ if (!msm_gpio)
+ return -ENOMEM;
+
+ spin_lock_init(&msm_gpio->lock);
+ platform_set_drvdata(dev, msm_gpio);
+ memcpy(&msm_gpio->regs,
+ &pdata->regs,
+ sizeof(struct msm7200a_gpio_regs));
+
+ msm_gpio->gpio_chip.label = dev->name;
+ msm_gpio->gpio_chip.base = pdata->gpio_base;
+ msm_gpio->gpio_chip.ngpio = pdata->ngpio;
+ msm_gpio->gpio_chip.direction_input = gpio_chip_direction_input;
+ msm_gpio->gpio_chip.direction_output = gpio_chip_direction_output;
+ msm_gpio->gpio_chip.get = gpio_chip_get;
+ msm_gpio->gpio_chip.set = gpio_chip_set;
+
+ ret = gpiochip_add(&msm_gpio->gpio_chip);
+ if (ret < 0)
+ goto err;
+
+ return ret;
+err:
+ kfree(msm_gpio);
+ return ret;
+}
+
+static int msm_gpio_remove(struct platform_device *dev)
+{
+ struct msm_gpio_dev *msm_gpio = platform_get_drvdata(dev);
+ int ret = gpiochip_remove(&msm_gpio->gpio_chip);
+
+ if (ret == 0)
+ kfree(msm_gpio);
+
+ return ret;
+}
+
+static struct platform_driver msm_gpio_driver = {
+ .probe = msm_gpio_probe,
+ .remove = msm_gpio_remove,
+ .driver = {
+ .name = "msm7200a-gpio",
+ .owner = THIS_MODULE,
+ },
+};
+
+static int __init msm_gpio_init(void)
+{
+ return platform_driver_register(&msm_gpio_driver);
+}
+
+static void __exit msm_gpio_exit(void)
+{
+ platform_driver_unregister(&msm_gpio_driver);
+}
+
+postcore_initcall(msm_gpio_init);
+module_exit(msm_gpio_exit);
+
+MODULE_DESCRIPTION("Driver for Qualcomm MSM 7200a-family SoC GPIOs");
+MODULE_LICENSE("GPLv2");
diff --git a/include/linux/msm7200a-gpio.h b/include/linux/msm7200a-gpio.h
new file mode 100644
index 0000000..3f1ef38
--- /dev/null
+++ b/include/linux/msm7200a-gpio.h
@@ -0,0 +1,44 @@
+/* Copyright (c) 2010, Code Aurora Forum. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are
+ * met:
+ * * Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * * Redistributions in binary form must reproduce the above
+ * copyright notice, this list of conditions and the following
+ * disclaimer in the documentation and/or other materials provided
+ * with the distribution.
+ * * Neither the name of Code Aurora Forum, Inc. nor the names of its
+ * contributors may be used to endorse or promote products derived
+ * from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED "AS IS" AND ANY EXPRESS OR IMPLIED
+ * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
+ * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT
+ * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS
+ * BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+ * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+ * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR
+ * BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
+ * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
+ * OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN
+ * IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ */
+#ifndef __LINUX_MSM7200A_GPIO_H
+#define __LINUX_MSM7200A_GPIO_H
+
+struct msm7200a_gpio_regs {
+ void __iomem *in;
+ void __iomem *out;
+ void __iomem *oe;
+};
+
+struct msm7200a_gpio_platform_data {
+ unsigned gpio_base;
+ unsigned ngpio;
+ struct msm7200a_gpio_regs regs;
+};
+
+#endif
--
1.7.0.4

---
Employee of Qualcomm Innovation Center, Inc.
Qualcomm Innovation Center, Inc. is a member of the Code Aurora Forum.

2010-06-11 23:12:53

by Daniel Walker

[permalink] [raw]
Subject: Re: [PATCH 2/2] gpio: msm7200a: Add irq support to msm-gpiolib.

On Fri, 2010-06-11 at 12:58 -0700, Gregory Bean wrote:

> static int msm_gpio_probe(struct platform_device *dev)
> {
> struct msm_gpio_dev *msm_gpio;
> struct msm7200a_gpio_platform_data *pdata =
> (struct msm7200a_gpio_platform_data *)dev->dev.platform_data;
> - int ret;
> + int i, irq, ret;
>
> if (!pdata)
> return -EINVAL;
> @@ -146,13 +306,53 @@ static int msm_gpio_probe(struct platform_device *dev)
> msm_gpio->gpio_chip.direction_output = gpio_chip_direction_output;
> msm_gpio->gpio_chip.get = gpio_chip_get;
> msm_gpio->gpio_chip.set = gpio_chip_set;
> + msm_gpio->gpio_chip.to_irq = gpio_chip_to_irq;
> + msm_gpio->irq_base = pdata->irq_base;
> + msm_gpio->irq_summary = pdata->irq_summary;
>
> ret = gpiochip_add(&msm_gpio->gpio_chip);
> if (ret < 0)
> - goto err;
> + goto err_post_malloc;
> +
> + for (i = 0; i < msm_gpio->gpio_chip.ngpio; ++i) {
> + irq = msm_gpio->irq_base + i;
> + set_irq_chip_data(irq, msm_gpio);
> + set_irq_chip(irq, &msm_gpio_irq_chip);
> + set_irq_handler(irq, handle_level_irq);
> + set_irq_flags(irq, IRQF_VALID);
> + }
> +
> + /*
> + * We use a level-triggered interrupt because of the nature
> + * of the shared GPIO-group interrupt.
> + *
> + * Many GPIO chips may be sharing the same group IRQ line, and
> + * it is possible for GPIO interrupt to re-occur while the system
> + * is still servicing the group interrupt associated with it.
> + * The group IRQ line would not de-assert and re-assert, and
> + * we'd get no second edge to cause the group IRQ to be handled again.
> + *
> + * Using a level interrupt guarantees that the group IRQ handlers
> + * will continue to be called as long as any GPIO chip in the group
> + * is asserting, even if the condition began while the group
> + * handler was in mid-pass.
> + */
> + ret = request_irq(msm_gpio->irq_summary,
> + msm_gpio_irq_handler,
> + IRQF_SHARED | IRQF_TRIGGER_HIGH,
> + dev->name,
> + msm_gpio);
> + if (ret < 0)
> + goto err_post_gpiochip_add;
>
> return ret;
> -err:
> +err_post_gpiochip_add:
> + /*
> + * Under no circumstances should a line be held on a gpiochip
> + * which hasn't finished probing.
> + */
> + BUG_ON(gpiochip_remove(&msm_gpio->gpio_chip) < 0);
> +err_post_malloc:

It looks like some of this should go in the prior patch. Like this
BUG_ON() above.

> kfree(msm_gpio);
> return ret;
> }
> @@ -160,12 +360,16 @@ err:
> static int msm_gpio_remove(struct platform_device *dev)
> {
> struct msm_gpio_dev *msm_gpio = platform_get_drvdata(dev);
> - int ret = gpiochip_remove(&msm_gpio->gpio_chip);
> + int ret;
>
> - if (ret == 0)
> - kfree(msm_gpio);
> + ret = gpiochip_remove(&msm_gpio->gpio_chip);
> + if (ret < 0)
> + return ret;
>
> - return ret;
> + free_irq(msm_gpio->irq_summary, msm_gpio);
> + kfree(msm_gpio);
> +
> + return 0;
> }

Also some of the code here (msm_gpio_remove) seems like it's cleaning up
the prior patch to some degree. So it should potentially get moved into
that patch.

Daniel

2010-06-11 23:23:27

by Gregory Bean

[permalink] [raw]
Subject: Re: [PATCH 2/2] gpio: msm7200a: Add irq support to msm-gpiolib.

>> + /*
>> + * Under no circumstances should a line be held on a gpiochip
>> + * which hasn't finished probing.
>> + */
>> + BUG_ON(gpiochip_remove(&msm_gpio->gpio_chip)< 0);
>> +err_post_malloc:
>
> It looks like some of this should go in the prior patch. Like this
> BUG_ON() above.

I would argue against that. If you look at the previous patch, you'll
see that the last thing that probe() does is gpiochip_add, which means
it never has a need to call gpiochip_remove(), and thus no need to
complain if gpiochip_remove behaves unexpectedly.

>> @@ -160,12 +360,16 @@ err:
>> static int msm_gpio_remove(struct platform_device *dev)
>> {
>> struct msm_gpio_dev *msm_gpio = platform_get_drvdata(dev);
>> - int ret = gpiochip_remove(&msm_gpio->gpio_chip);
>> + int ret;
>>
>> - if (ret == 0)
>> - kfree(msm_gpio);
>> + ret = gpiochip_remove(&msm_gpio->gpio_chip);
>> + if (ret< 0)
>> + return ret;
>>
>> - return ret;
>> + free_irq(msm_gpio->irq_summary, msm_gpio);
>> + kfree(msm_gpio);
>> +
>> + return 0;
>> }
>
> Also some of the code here (msm_gpio_remove) seems like it's cleaning up
> the prior patch to some degree. So it should potentially get moved into
> that patch.

Point taken. There is definitely some stuff in here that is just
"housecleaning" - I will sort that out.

---
Employee of Qualcomm Innovation Center, Inc.
Qualcomm Innovation Center, Inc. is a member of the Code Aurora Forum.

2010-06-12 02:13:19

by Ben Dooks

[permalink] [raw]
Subject: Re: [PATCH 1/2] gpio: msm7200a: Add gpiolib support for MSM chips.

On Fri, Jun 11, 2010 at 12:58:51PM -0700, Gregory Bean wrote:
> Add support for uniprocessor MSM chips whose TLMM/GPIO design
> is the same as the MSM7200A.
> This includes, but is not necessarily limited to, the:
> MSM7200A, MSM7x25, MSM7x27, MSM7x30, QSD8x50, QSD8x50A
>
> Change-Id: I748d0e09f6b762f1711cde3c27a9a6e8de6d9454
> Signed-off-by: Gregory Bean <[email protected]>
> ---
> MAINTAINERS | 2 +
> drivers/gpio/Kconfig | 8 ++
> drivers/gpio/Makefile | 1 +
> drivers/gpio/msm7200a-gpio.c | 194 +++++++++++++++++++++++++++++++++++++++++
> include/linux/msm7200a-gpio.h | 44 +++++++++
> 5 files changed, 249 insertions(+), 0 deletions(-)
> create mode 100644 drivers/gpio/msm7200a-gpio.c
> create mode 100644 include/linux/msm7200a-gpio.h
>
> diff --git a/MAINTAINERS b/MAINTAINERS
> index 6d119c9..bdfd31d 100644
> --- a/MAINTAINERS
> +++ b/MAINTAINERS
> @@ -819,6 +819,8 @@ F: drivers/mmc/host/msm_sdcc.c
> F: drivers/mmc/host/msm_sdcc.h
> F: drivers/serial/msm_serial.h
> F: drivers/serial/msm_serial.c
> +F: drivers/gpio/msm7200a-gpio.c
> +F: include/linux/msm7200a-gpio.h
> T: git git://codeaurora.org/quic/kernel/dwalker/linux-msm.git
> S: Maintained
>
> diff --git a/drivers/gpio/Kconfig b/drivers/gpio/Kconfig
> index 724038d..557738a 100644
> --- a/drivers/gpio/Kconfig
> +++ b/drivers/gpio/Kconfig
> @@ -76,6 +76,14 @@ config GPIO_IT8761E
> help
> Say yes here to support GPIO functionality of IT8761E super I/O chip.
>
> +config GPIO_MSM7200A
> + tristate "Qualcomm MSM7200A SoC GPIO support"
> + depends on GPIOLIB
> + help
> + Say yes here to support GPIO functionality on Qualcomm's
> + MSM chipsets which descend from the MSM7200a:
> + MSM7x01(a), MSM7x25, MSM7x27, MSM7x30, QSD8x50(a).
> +
> config GPIO_PL061
> bool "PrimeCell PL061 GPIO support"
> depends on ARM_AMBA
> diff --git a/drivers/gpio/Makefile b/drivers/gpio/Makefile
> index 51c3cdd..2389c29 100644
> --- a/drivers/gpio/Makefile
> +++ b/drivers/gpio/Makefile
> @@ -13,6 +13,7 @@ obj-$(CONFIG_GPIO_MAX7301) += max7301.o
> obj-$(CONFIG_GPIO_MAX732X) += max732x.o
> obj-$(CONFIG_GPIO_MC33880) += mc33880.o
> obj-$(CONFIG_GPIO_MCP23S08) += mcp23s08.o
> +obj-$(CONFIG_GPIO_MSM7200A) += msm7200a-gpio.o
> obj-$(CONFIG_GPIO_PCA953X) += pca953x.o
> obj-$(CONFIG_GPIO_PCF857X) += pcf857x.o
> obj-$(CONFIG_GPIO_PL061) += pl061.o

Why not put this under arch/arm?

> diff --git a/drivers/gpio/msm7200a-gpio.c b/drivers/gpio/msm7200a-gpio.c
> new file mode 100644
> index 0000000..b31c25e
> --- /dev/null
> +++ b/drivers/gpio/msm7200a-gpio.c
> @@ -0,0 +1,194 @@
> +/*
> + * Driver for Qualcomm MSM7200a and related SoC GPIO.
> + * Supported chipset families include:
> + * MSM7x01(a), MSM7x25, MSM7x27, MSM7x30, QSD8x50(a)
> + *
> + * Copyright (C) 2007 Google, Inc.
> + * Copyright (c) 2010, Code Aurora Forum. All rights reserved.
> + *
> + * This program is free software; you can redistribute it and/or modify
> + * it under the terms of the GNU General Public License version 2 and
> + * only version 2 as published by the Free Software Foundation.
> + *
> + * This program is distributed in the hope that it will be useful,
> + * but WITHOUT ANY WARRANTY; without even the implied warranty of
> + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
> + * GNU General Public License for more details.
> + *
> + * You should have received a copy of the GNU General Public License
> + * along with this program; if not, write to the Free Software
> + * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA
> + * 02110-1301, USA.
> + */
> +#include <linux/kernel.h>
> +#include <linux/gpio.h>
> +#include <linux/io.h>
> +#include <linux/module.h>
> +#include <linux/platform_device.h>
> +#include <linux/msm7200a-gpio.h>
> +
> +struct msm_gpio_dev {
> + struct gpio_chip gpio_chip;
> + spinlock_t lock;
> + struct msm7200a_gpio_regs regs;
> +};
> +
> +#define TO_MSM_GPIO_DEV(c) container_of(c, struct msm_gpio_dev, gpio_chip)

I'd say an inline function would be better, since it gives a typecheck
on c. also, c is a bit of a vague name for a macro argument.

> +
> +static inline unsigned bit(unsigned offset)
> +{
> + BUG_ON(offset >= sizeof(unsigned) * 8);
> + return 1U << offset;
> +}

do you really need BUG_ON(), gpiolib tends to check the parameters
that are given to it. personally i think this is silly.

> +/*
> + * This function assumes that msm_gpio_dev::lock is held.
> + */
> +static inline void set_gpio_bit(unsigned n, void __iomem *reg)
> +{
> + writel(readl(reg) | bit(n), reg);
> +}
> +
> +/*
> + * This function assumes that msm_gpio_dev::lock is held.
> + */
> +static inline void clr_gpio_bit(unsigned n, void __iomem *reg)
> +{
> + writel(readl(reg) & ~bit(n), reg);
> +}
> +
> +/*
> + * This function assumes that msm_gpio_dev::lock is held.
> + */
> +static inline void
> +msm_gpio_write(struct msm_gpio_dev *dev, unsigned n, unsigned on)
> +{
> + if (on)
> + set_gpio_bit(n, dev->regs.out);
> + else
> + clr_gpio_bit(n, dev->regs.out);
> +}

wouldn't it be easier to inline a set_to function and just role the
set and clr bit functions into it, since they pretty much do the
same thing. even better, on arm the code won't require a branch.

> +
> +static int gpio_chip_direction_input(struct gpio_chip *chip, unsigned offset)
> +{
> + struct msm_gpio_dev *msm_gpio = TO_MSM_GPIO_DEV(chip);
> + unsigned long irq_flags;
> +
> + spin_lock_irqsave(&msm_gpio->lock, irq_flags);
> + clr_gpio_bit(offset, msm_gpio->regs.oe);
> + spin_unlock_irqrestore(&msm_gpio->lock, irq_flags);
> +
> + return 0;
> +}
> +
> +static int
> +gpio_chip_direction_output(struct gpio_chip *chip, unsigned offset, int value)
> +{
> + struct msm_gpio_dev *msm_gpio = TO_MSM_GPIO_DEV(chip);
> + unsigned long irq_flags;
> +
> + spin_lock_irqsave(&msm_gpio->lock, irq_flags);
> +
> + msm_gpio_write(msm_gpio, offset, value);
> + set_gpio_bit(offset, msm_gpio->regs.oe);
> + spin_unlock_irqrestore(&msm_gpio->lock, irq_flags);
> +
> + return 0;
> +}
> +
> +static int gpio_chip_get(struct gpio_chip *chip, unsigned offset)
> +{
> + struct msm_gpio_dev *msm_gpio = TO_MSM_GPIO_DEV(chip);
> + unsigned long irq_flags;
> + int ret;
> +
> + spin_lock_irqsave(&msm_gpio->lock, irq_flags);
> + ret = readl(msm_gpio->regs.in) & bit(offset) ? 1 : 0;
> + spin_unlock_irqrestore(&msm_gpio->lock, irq_flags);

do you really need a lock to read a value?

> + return ret;
> +}
> +
> +static void gpio_chip_set(struct gpio_chip *chip, unsigned offset, int value)
> +{
> + struct msm_gpio_dev *msm_gpio = TO_MSM_GPIO_DEV(chip);
> + unsigned long irq_flags;
> +
> + spin_lock_irqsave(&msm_gpio->lock, irq_flags);
> + msm_gpio_write(msm_gpio, offset, value);
> + spin_unlock_irqrestore(&msm_gpio->lock, irq_flags);
> +}
> +
> +static int msm_gpio_probe(struct platform_device *dev)
> +{
> + struct msm_gpio_dev *msm_gpio;
> + struct msm7200a_gpio_platform_data *pdata =
> + (struct msm7200a_gpio_platform_data *)dev->dev.platform_data;

no need to cast, void* goes to any non void * easily.

> + int ret;
> +
> + if (!pdata)
> + return -EINVAL;
> +
> + msm_gpio = kzalloc(sizeof(struct msm_gpio_dev), GFP_KERNEL);
> + if (!msm_gpio)
> + return -ENOMEM;
> +
> + spin_lock_init(&msm_gpio->lock);
> + platform_set_drvdata(dev, msm_gpio);
> + memcpy(&msm_gpio->regs,
> + &pdata->regs,
> + sizeof(struct msm7200a_gpio_regs));

you could have easily done
msm_gpio->regs = *pdata->regs
and got some free type-checking into the bargin.

> + msm_gpio->gpio_chip.label = dev->name;
> + msm_gpio->gpio_chip.base = pdata->gpio_base;
> + msm_gpio->gpio_chip.ngpio = pdata->ngpio;
> + msm_gpio->gpio_chip.direction_input = gpio_chip_direction_input;
> + msm_gpio->gpio_chip.direction_output = gpio_chip_direction_output;
> + msm_gpio->gpio_chip.get = gpio_chip_get;
> + msm_gpio->gpio_chip.set = gpio_chip_set;
> +
> + ret = gpiochip_add(&msm_gpio->gpio_chip);
> + if (ret < 0)
> + goto err;
> +
> + return ret;
> +err:
> + kfree(msm_gpio);
> + return ret;
> +}
> +
> +static int msm_gpio_remove(struct platform_device *dev)
> +{
> + struct msm_gpio_dev *msm_gpio = platform_get_drvdata(dev);
> + int ret = gpiochip_remove(&msm_gpio->gpio_chip);
> +
> + if (ret == 0)
> + kfree(msm_gpio);

hmm, not sure if you really need to check the result here before
kfrree() the memory.

~> + return ret;
> +}
> +
> +static struct platform_driver msm_gpio_driver = {
> + .probe = msm_gpio_probe,
> + .remove = msm_gpio_remove,
> + .driver = {
> + .name = "msm7200a-gpio",
> + .owner = THIS_MODULE,
> + },
> +};
> +
> +static int __init msm_gpio_init(void)
> +{
> + return platform_driver_register(&msm_gpio_driver);
> +}
> +
> +static void __exit msm_gpio_exit(void)
> +{
> + platform_driver_unregister(&msm_gpio_driver);
> +}
> +
> +postcore_initcall(msm_gpio_init);
> +module_exit(msm_gpio_exit);
> +
> +MODULE_DESCRIPTION("Driver for Qualcomm MSM 7200a-family SoC GPIOs");
> +MODULE_LICENSE("GPLv2");

you left out a MODULE_ALIAS() for your platform device.
you could also do with a MODULE_AUTHOUR() line as well

> diff --git a/include/linux/msm7200a-gpio.h b/include/linux/msm7200a-gpio.h
> new file mode 100644
> index 0000000..3f1ef38
> --- /dev/null
> +++ b/include/linux/msm7200a-gpio.h
> @@ -0,0 +1,44 @@
> +/* Copyright (c) 2010, Code Aurora Forum. All rights reserved.
> + *
> + * Redistribution and use in source and binary forms, with or without
> + * modification, are permitted provided that the following conditions are
> + * met:
> + * * Redistributions of source code must retain the above copyright
> diff --git a/include/linux/msm7200a-gpio.h b/include/linux/msm7200a-gpio.h
> new file mode 100644
> index 0000000..3f1ef38
> --- /dev/null
> +++ b/include/linux/msm7200a-gpio.h
> @@ -0,0 +1,44 @@
> +/* Copyright (c) 2010, Code Aurora Forum. All rights reserved.
> + *
> + * Redistribution and use in source and binary forms, with or without
;5B> + * modification, are permitted provided that the following conditions are
> + * met:
> + * * Redistributions of source code must retain the above copyright
> + * notice, this list of conditions and the following disclaimer.
> + * * Redistributions in binary form must reproduce the above
> + * copyright notice, this list of conditions and the following
> + * disclaimer in the documentation and/or other materials provided
> + * with the distribution.
> + * * Neither the name of Code Aurora Forum, Inc. nor the names of its
> + * contributors may be used to endorse or promote products derived
> + * from this software without specific prior written permission.
> + *
> + * THIS SOFTWARE IS PROVIDED "AS IS" AND ANY EXPRESS OR IMPLIED
> + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
> + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT
> + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS
> + * BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
> + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
> + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR
> + * BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
> + * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
> + * OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN
> + * IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
> + *
> + */

Is this really GPL compatible?

> +#ifndef __LINUX_MSM7200A_GPIO_H
> +#define __LINUX_MSM7200A_GPIO_H
> +
> +struct msm7200a_gpio_regs {
> + void __iomem *in;
> + void __iomem *out;
> + void __iomem *oe;
> +};

Are the offsets of in/out/oe so different? would be nice to document
this structure and the likely offsets you would see.

> +
> +struct msm7200a_gpio_platform_data {
> + unsigned gpio_base;
> + unsigned ngpio;
> + struct msm7200a_gpio_regs regs;
> +};

again, some documentaiton of this would be nice.

--
Ben ([email protected], http://www.fluff.org/)

'a smiley only costs 4 bytes'

2010-06-12 02:24:06

by Ben Dooks

[permalink] [raw]
Subject: Re: [PATCH 2/2] gpio: msm7200a: Add irq support to msm-gpiolib.

On Fri, Jun 11, 2010 at 12:58:52PM -0700, Gregory Bean wrote:
> Change-Id: Ib7f7dd05246c87096aabab12eb6cc260551c67cf
> Signed-off-by: Gregory Bean <[email protected]>
> ---
~> drivers/gpio/msm7200a-gpio.c | 218 +++++++++++++++++++++++++++++++++++++++--
> include/linux/msm7200a-gpio.h | 7 ++
> 2 files changed, 218 insertions(+), 7 deletions(-)
>
> diff --git a/drivers/gpio/msm7200a-gpio.c b/drivers/gpio/msm7200a-gpio.c
> index b31c25e..a9ea869 100644
> --- a/drivers/gpio/msm7200a-gpio.c
> +++ b/drivers/gpio/msm7200a-gpio.c
> @@ -23,13 +23,25 @@
> #include <linux/kernel.h>
> #include <linux/gpio.h>
> #include <linux/io.h>
> +#include <linux/interrupt.h>
> +#include <linux/irq.h>
> #include <linux/module.h>
> #include <linux/platform_device.h>
> #include <linux/msm7200a-gpio.h>
>
> +/*
> + * The INT_STATUS register latches both edge- and level-detection events,
> + * which is atypical. Turning on DONT_LATCH_LEVEL_IRQS causes level irq
> + * triggers to be forgotten across mask/unmask calls, emulating a more
> + * traditional setup.
> + */
> +#define MSM_GPIO_DONT_LATCH_LEVEL_IRQS 1
> +
> struct msm_gpio_dev {
> struct gpio_chip gpio_chip;
> spinlock_t lock;
> + unsigned irq_base;
> + unsigned irq_summary;
> struct msm7200a_gpio_regs regs;
> };
>
> @@ -119,12 +131,160 @@ static void gpio_chip_set(struct gpio_chip *chip, unsigned offset, int value)
> spin_unlock_irqrestore(&msm_gpio->lock, irq_flags);
> }
>
> +static int gpio_chip_to_irq(struct gpio_chip *chip, unsigned offset)
> +{
> + struct msm_gpio_dev *msm_gpio = TO_MSM_GPIO_DEV(chip);
> + return msm_gpio->irq_base + offset;
> +}
> +
> +#if MSM_GPIO_DONT_LATCH_LEVEL_IRQS
> +static inline void forget_level_irq(struct msm_gpio_dev *msm_gpio,
> + unsigned offset)
> +{
> + unsigned v = readl(msm_gpio->regs.int_edge);
> + unsigned b = bit(offset);
> +
> + if (!(v & b))
> + writel(b, msm_gpio->regs.int_clear);
> +
> +}
> +#else
> +static inline void forget_level_irq(struct msm_gpio_dev *msm, unsigned off)
> +{
> +}
> +#endif

Hmm, that's a bit yucky, either Kconfig it or have it definable
in the platform data.

> +static void msm_gpio_irq_mask(unsigned int irq)
> +{
> + unsigned long irq_flags;
> + struct msm_gpio_dev *msm_gpio = get_irq_chip_data(irq);
> + unsigned offset = irq - msm_gpio->irq_base;
> +
> + spin_lock_irqsave(&msm_gpio->lock, irq_flags);
> + forget_level_irq(msm_gpio, offset);
> + clr_gpio_bit(offset, msm_gpio->regs.int_en);
> + spin_unlock_irqrestore(&msm_gpio->lock, irq_flags);
> +}
> +
> +static void msm_gpio_irq_unmask(unsigned int irq)
> +{
> + unsigned long irq_flags;
> + struct msm_gpio_dev *msm_gpio = get_irq_chip_data(irq);
> + unsigned offset = irq - msm_gpio->irq_base;
> +
> + spin_lock_irqsave(&msm_gpio->lock, irq_flags);
> + forget_level_irq(msm_gpio, offset);
> + set_gpio_bit(offset, msm_gpio->regs.int_en);
> + spin_unlock_irqrestore(&msm_gpio->lock, irq_flags);
> +}
> +
> +static int msm_gpio_irq_set_type(unsigned int irq, unsigned int flow_type)
> +{
> + unsigned long irq_flags;
> + struct msm_gpio_dev *msm_gpio = get_irq_chip_data(irq);
> + unsigned offset = irq - msm_gpio->irq_base;
> +
> + if ((flow_type & (IRQF_TRIGGER_FALLING | IRQF_TRIGGER_RISING)) ==
> + (IRQF_TRIGGER_FALLING | IRQF_TRIGGER_RISING))
> + return -ENOTSUPP;

Hmm, thought there was a BOTHEDGE for this, maybe worth adding
to the irq.h file at somepoint.

> + if ((flow_type & (IRQF_TRIGGER_HIGH | IRQF_TRIGGER_LOW)) ==
> + (IRQF_TRIGGER_HIGH | IRQF_TRIGGER_LOW))
> + return -ENOTSUPP;
> +
> + spin_lock_irqsave(&msm_gpio->lock, irq_flags);
> +
> + if (flow_type & (IRQF_TRIGGER_FALLING | IRQF_TRIGGER_RISING)) {
> + set_gpio_bit(offset, msm_gpio->regs.int_edge);
> + irq_desc[irq].handle_irq = handle_edge_irq;
> + } else {
> + clr_gpio_bit(offset, msm_gpio->regs.int_edge);
> + irq_desc[irq].handle_irq = handle_level_irq;
> + }
> +
> + if (flow_type & (IRQF_TRIGGER_HIGH | IRQF_TRIGGER_RISING))
> + set_gpio_bit(offset, msm_gpio->regs.int_pos);
> + else
> + clr_gpio_bit(offset, msm_gpio->regs.int_pos);
> +
> + spin_unlock_irqrestore(&msm_gpio->lock, irq_flags);
> +
> + return 0;
> +}
> +
> +static void msm_gpio_irq_mask_ack(unsigned int irq)
> +{
> + msm_gpio_irq_mask(irq);
> +}
> +
> +static int msm_gpio_irq_set_affinity(unsigned int irq,
> + const struct cpumask *dest)
> +{
> + return -ENOTSUPP;
> +}
> +
> +static int msm_gpio_irq_retrigger(unsigned int irq)
> +{
> + return -ENOTSUPP;
> +}
> +
> +static int msm_gpio_irq_set_wake(unsigned int irq, unsigned int on)
> +{
> + return -ENOTSUPP;
> +}

do you really need to define these, surely the irq layer will
do the right thing if there's no handler defined?

> +static irqreturn_t msm_gpio_irq_handler(int irq, void *dev)
> +{
> + unsigned long irq_flags;
> + int b, m;
> + unsigned e, s, v;
> +
> + struct msm_gpio_dev *msm_gpio = (struct msm_gpio_dev *)dev;

see prev. comment about casting void *, plus you seem to have a blank
line in here by accident.

would be worth organising the longest lines first.

+ /*
> + * The int_status register latches trigger events whether or not
> + * the gpio line is enabled as an interrupt source. Therefore,
> + * the set of pins which defines the interrupts which need to fire
> + * is the intersection of int_status and int_en - int_status
> + * alone provides an incomplete picture.
> + */
> + spin_lock_irqsave(&msm_gpio->lock, irq_flags);
> + s = readl(msm_gpio->regs.int_status);
> + e = readl(msm_gpio->regs.int_en);
> + v = s & e;

how about slightly less terse interrupts.

> + if (v)
> + writel(v, msm_gpio->regs.int_clear);
> + spin_unlock_irqrestore(&msm_gpio->lock, irq_flags);
> + if (!v)
> + return IRQ_NONE;
> +
> + while (v) {
> + m = v & -v;
> + b = fls(m) - 1;
> + v &= ~m;

i'm not entirely sure what you'e doing here, how aout a comment
on the m line to say what ti is up to.

> + generic_handle_irq(msm_gpio->irq_base + b);
> + }
> + return IRQ_HANDLED;
> +}
> +
> +static struct irq_chip msm_gpio_irq_chip = {
> + .name = "msm_gpio",
> + .mask = msm_gpio_irq_mask,
> + .mask_ack = msm_gpio_irq_mask_ack,
> + .unmask = msm_gpio_irq_unmask,
> + .set_affinity = msm_gpio_irq_set_affinity,
> + .retrigger = msm_gpio_irq_retrigger,
> + .set_type = msm_gpio_irq_set_type,
> + .set_wake = msm_gpio_irq_set_wake,
> +};
> +
> static int msm_gpio_probe(struct platform_device *dev)
> {
> struct msm_gpio_dev *msm_gpio;
> struct msm7200a_gpio_platform_data *pdata =
> (struct msm7200a_gpio_platform_data *)dev->dev.platform_data;
> - int ret;
> + int i, irq, ret;
>
> if (!pdata)
> return -EINVAL;
> @@ -146,13 +306,53 @@ static int msm_gpio_probe(struct platform_device *dev)
> msm_gpio->gpio_chip.direction_output = gpio_chip_direction_output;
> msm_gpio->gpio_chip.get = gpio_chip_get;
> msm_gpio->gpio_chip.set = gpio_chip_set;
> + msm_gpio->gpio_chip.to_irq = gpio_chip_to_irq;
> + msm_gpio->irq_base = pdata->irq_base;
> + msm_gpio->irq_summary = pdata->irq_summary;
>
> ret = gpiochip_add(&msm_gpio->gpio_chip);
> if (ret < 0)
> - goto err;
> + goto err_post_malloc;
> +
> + for (i = 0; i < msm_gpio->gpio_chip.ngpio; ++i) {
> + irq = msm_gpio->irq_base + i;
> + set_irq_chip_data(irq, msm_gpio);
> + set_irq_chip(irq, &msm_gpio_irq_chip);
> + set_irq_handler(irq, handle_level_irq);
> + set_irq_flags(irq, IRQF_VALID);
> + }
> +
> + /*
> + * We use a level-triggered interrupt because of the nature
> + * of the shared GPIO-group interrupt.
> + *
> + * Many GPIO chips may be sharing the same group IRQ line, and
> + * it is possible for GPIO interrupt to re-occur while the system
> + * is still servicing the group interrupt associated with it.
> + * The group IRQ line would not de-assert and re-assert, and
> + * we'd get no second edge to cause the group IRQ to be handled again.
> + *
> + * Using a level interrupt guarantees that the group IRQ handlers
> + * will continue to be called as long as any GPIO chip in the group
> + * is asserting, even if the condition began while the group
> + * handler was in mid-pass.
> + */
> + ret = request_irq(msm_gpio->irq_summary,
> + msm_gpio_irq_handler,
> + IRQF_SHARED | IRQF_TRIGGER_HIGH,
> + dev->name,
iirc, dev_name() is the correct thing to use herre.

> + msm_gpio);
> + if (ret < 0)
> + goto err_post_gpiochip_add;
>
> return ret;
> -err:
> +err_post_gpiochip_add:
> + /*
> + * Under no circumstances should a line be held on a gpiochip
> + * which hasn't finished probing.
> + */
> + BUG_ON(gpiochip_remove(&msm_gpio->gpio_chip) < 0);
> +err_post_malloc:
> kfree(msm_gpio);
> return ret;
> }
> @@ -160,12 +360,16 @@ err:
> static int msm_gpio_remove(struct platform_device *dev)
> {
> struct msm_gpio_dev *msm_gpio = platform_get_drvdata(dev);
> - int ret = gpiochip_remove(&msm_gpio->gpio_chip);
> + int ret;
>
> - if (ret == 0)
> - kfree(msm_gpio);
> + ret = gpiochip_remove(&msm_gpio->gpio_chip);
> + if (ret < 0)
> + return ret;
>
> - return ret;
> + free_irq(msm_gpio->irq_summary, msm_gpio);
> + kfree(msm_gpio);
> +
> + return 0;
> }
>
> static struct platform_driver msm_gpio_driver = {
> diff --git a/include/linux/msm7200a-gpio.h b/include/linux/msm7200a-gpio.h
> index 3f1ef38..7af4dd6 100644
> --- a/include/linux/msm7200a-gpio.h
> +++ b/include/linux/msm7200a-gpio.h
> @@ -33,11 +33,18 @@ struct msm7200a_gpio_regs {
> void __iomem *in;
> void __iomem *out;
> void __iomem *oe;
> + void __iomem *int_status;
> + void __iomem *int_clear;
> + void __iomem *int_en;
> + void __iomem *int_edge;
> + void __iomem *int_pos;
> };

see prev. comment on could we have single base and offsets?

> struct msm7200a_gpio_platform_data {
> unsigned gpio_base;~~
> unsigned ngpio;
> + unsigned irq_base;
> + unsigned irq_summary;
> struct msm7200a_gpio_regs regs;
> };
>
> --
> 1.7.0.4
>
> ---
> Employee of Qualcomm Innovation Center, Inc.
> Qualcomm Innovation Center, Inc. is a member of the Code Aurora Forum.
> --
> To unsubscribe from this list: send the line "unsubscribe linux-kernel" in
> the body of a message to [email protected]
> More majordomo info at http://vger.kernel.org/majordomo-info.html
> Please read the FAQ at http://www.tux.org/lkml/

--
Ben ([email protected], http://www.fluff.org/)

'a smiley only costs 4 bytes'

2010-06-12 02:34:04

by Bryan Huntsman

[permalink] [raw]
Subject: Re: [PATCH 1/2] gpio: msm7200a: Add gpiolib support for MSM chips.

Ben Dooks wrote:
> On Fri, Jun 11, 2010 at 12:58:51PM -0700, Gregory Bean wrote:

...snip...

>> +MODULE_DESCRIPTION("Driver for Qualcomm MSM 7200a-family SoC GPIOs");
>> +MODULE_LICENSE("GPLv2");
>
> you left out a MODULE_ALIAS() for your platform device.
> you could also do with a MODULE_AUTHOUR() line as well

Also, the string is "GPL v2". See include/linux/license.h.

>> diff --git a/include/linux/msm7200a-gpio.h b/include/linux/msm7200a-gpio.h
>> new file mode 100644
>> index 0000000..3f1ef38
>> --- /dev/null
>> +++ b/include/linux/msm7200a-gpio.h
>> @@ -0,0 +1,44 @@
>> +/* Copyright (c) 2010, Code Aurora Forum. All rights reserved.
>> + *
>> + * Redistribution and use in source and binary forms, with or without
>> + * modification, are permitted provided that the following conditions are
>> + * met:
>> + * * Redistributions of source code must retain the above copyright
>> diff --git a/include/linux/msm7200a-gpio.h b/include/linux/msm7200a-gpio.h
>> new file mode 100644
>> index 0000000..3f1ef38
>> --- /dev/null
>> +++ b/include/linux/msm7200a-gpio.h
>> @@ -0,0 +1,44 @@
>> +/* Copyright (c) 2010, Code Aurora Forum. All rights reserved.
>> + *
>> + * Redistribution and use in source and binary forms, with or without
> ;5B> + * modification, are permitted provided that the following conditions are
>> + * met:
>> + * * Redistributions of source code must retain the above copyright
>> + * notice, this list of conditions and the following disclaimer.
>> + * * Redistributions in binary form must reproduce the above
>> + * copyright notice, this list of conditions and the following
>> + * disclaimer in the documentation and/or other materials provided
>> + * with the distribution.
>> + * * Neither the name of Code Aurora Forum, Inc. nor the names of its
>> + * contributors may be used to endorse or promote products derived
>> + * from this software without specific prior written permission.
>> + *
>> + * THIS SOFTWARE IS PROVIDED "AS IS" AND ANY EXPRESS OR IMPLIED
>> + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
>> + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT
>> + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS
>> + * BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
>> + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
>> + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR
>> + * BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
>> + * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
>> + * OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN
>> + * IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
>> + *
>> + */
>
> Is this really GPL compatible?

It's BSD-style, so yes.


--
Sent by an employee of the Qualcomm Innovation Center, Inc.
The Qualcomm Innovation Center, Inc. is a member of the Code Aurora Forum.

2010-06-12 05:37:24

by Gregory Bean

[permalink] [raw]
Subject: Re: [PATCH 1/2] gpio: msm7200a: Add gpiolib support for MSM chips.

> Why not put this under arch/arm?

Is there an appropriate place for loadable device drivers under
arch/arm? I don't know of one.

>> +static inline void set_gpio_bit(unsigned n, void __iomem *reg)
>> +{
>> + writel(readl(reg) | bit(n), reg);
>> +}
>> +
>> +/*
>> + * This function assumes that msm_gpio_dev::lock is held.
>> + */
>> +static inline void clr_gpio_bit(unsigned n, void __iomem *reg)
>> +{
>> + writel(readl(reg)& ~bit(n), reg);
>> +}
>> +
>> +/*
>> + * This function assumes that msm_gpio_dev::lock is held.
>> + */
>> +static inline void
>> +msm_gpio_write(struct msm_gpio_dev *dev, unsigned n, unsigned on)
>> +{
>> + if (on)
>> + set_gpio_bit(n, dev->regs.out);
>> + else
>> + clr_gpio_bit(n, dev->regs.out);
>> +}
>
> wouldn't it be easier to inline a set_to function and just role the
> set and clr bit functions into it, since they pretty much do the
> same thing. even better, on arm the code won't require a branch.

I'm not sure I understand you. Can you clarify? set_ and clr_gpio_bit
are used in more places than just here, so they can't just be rolled
into msm_gpio_write and disappear.

>> +static int msm_gpio_remove(struct platform_device *dev)
>> +{
>> + struct msm_gpio_dev *msm_gpio = platform_get_drvdata(dev);
>> + int ret = gpiochip_remove(&msm_gpio->gpio_chip);
>> +
>> + if (ret == 0)
>> + kfree(msm_gpio);
>
> hmm, not sure if you really need to check the result here before
> kfrree() the memory.

I feel that this is important. If any clients are still holding gpio
lines, gpiochip_remove will fail. In those circumstances, is it not
important that the device not be freed (which would leave clients with
stale references) and that the remove call return a proper failure code?
--
Employee of Qualcomm Innovation Center, Inc.
Qualcomm Innovation Center, Inc. is a member of the Code Aurora Forum.

2010-06-13 05:30:26

by Ben Dooks

[permalink] [raw]
Subject: Re: [PATCH 1/2] gpio: msm7200a: Add gpiolib support for MSM chips.

On Fri, Jun 11, 2010 at 10:37:18PM -0700, Gregory Bean wrote:
>> Why not put this under arch/arm?
>
> Is there an appropriate place for loadable device drivers under
> arch/arm? I don't know of one.
>
>>> +static inline void set_gpio_bit(unsigned n, void __iomem *reg)
>>> +{
>>> + writel(readl(reg) | bit(n), reg);
>>> +}
>>> +
>>> +/*
>>> + * This function assumes that msm_gpio_dev::lock is held.
>>> + */
>>> +static inline void clr_gpio_bit(unsigned n, void __iomem *reg)
>>> +{
>>> + writel(readl(reg)& ~bit(n), reg);
>>> +}
>>> +
>>> +/*
>>> + * This function assumes that msm_gpio_dev::lock is held.
>>> + */
>>> +static inline void
>>> +msm_gpio_write(struct msm_gpio_dev *dev, unsigned n, unsigned on)
>>> +{
>>> + if (on)
>>> + set_gpio_bit(n, dev->regs.out);
>>> + else
>>> + clr_gpio_bit(n, dev->regs.out);
>>> +}
>>
>> wouldn't it be easier to inline a set_to function and just role the
>> set and clr bit functions into it, since they pretty much do the
>> same thing. even better, on arm the code won't require a branch.
>
> I'm not sure I understand you. Can you clarify? set_ and clr_gpio_bit
> are used in more places than just here, so they can't just be rolled
> into msm_gpio_write and disappear.

Hmm, thought the compiler was clever enough to inline and sort that
out, I'll have a check later into whether this is true or not for
a few versions of gcc.

>>> +static int msm_gpio_remove(struct platform_device *dev)
>>> +{
>>> + struct msm_gpio_dev *msm_gpio = platform_get_drvdata(dev);
>>> + int ret = gpiochip_remove(&msm_gpio->gpio_chip);
>>> +
>>> + if (ret == 0)
>>> + kfree(msm_gpio);
>>
>> hmm, not sure if you really need to check the result here before
>> kfrree() the memory.
>
> I feel that this is important. If any clients are still holding gpio
> lines, gpiochip_remove will fail. In those circumstances, is it not
> important that the device not be freed (which would leave clients with
> stale references) and that the remove call return a proper failure code?

Right, confused holding onto the module to holding onto the device too.

Maybe devices should be refcounted too so that holding an open gpio on
via the driver would force the driver core to refuse to remove the device.

--
Ben

Q: What's a light-year?
A: One-third less calories than a regular year.