]> www.pilppa.org Git - linux-2.6-omap-h63xx.git/blobdiff - drivers/gpio/twl4030-gpio.c
twl4030-gpio irq simplification
[linux-2.6-omap-h63xx.git] / drivers / gpio / twl4030-gpio.c
index 40abcbdcd6c31d2fe044685b7c3b1764ceadcea7..582eec12f12c405a998f7d96b896322011a656e0 100644 (file)
  */
 
 #include <linux/module.h>
-#include <linux/kernel_stat.h>
 #include <linux/init.h>
-#include <linux/time.h>
 #include <linux/interrupt.h>
-#include <linux/device.h>
 #include <linux/kthread.h>
 #include <linux/irq.h>
 #include <linux/gpio.h>
 #include <linux/slab.h>
 
 #include <linux/i2c/twl4030.h>
-#include <linux/i2c/twl4030-gpio.h>
+
+
+/*
+ * The GPIO "subchip" supports 18 GPIOs which can be configured as
+ * inputs or outputs, with pullups or pulldowns on each pin.  Each
+ * GPIO can trigger interrupts on either or both edges.
+ *
+ * GPIO interrupts can be fed to either of two IRQ lines; this is
+ * intended to support multiple hosts.
+ *
+ * There are also two LED pins used sometimes as output-only GPIOs.
+ *
+ * FIXME code currently only handles the first IRQ line.
+ */
 
 
 static inline void activate_irq(int irq)
@@ -65,83 +75,10 @@ static int twl4030_gpio_irq_end;
 #define is_module()    false
 #endif
 
-/* BitField Definitions */
-
-/* Data banks : 3 banks for 8 gpios each */
-#define DATA_BANK_MAX                          8
-#define GET_GPIO_DATA_BANK(x)                  ((x)/DATA_BANK_MAX)
-#define GET_GPIO_DATA_OFF(x)                   ((x)%DATA_BANK_MAX)
-
-/* GPIODATADIR Fields each block 0-7 */
-#define BIT_GPIODATADIR_GPIOxDIR(x)            (x)
-#define MASK_GPIODATADIR_GPIOxDIR(x)           (0x01 << (x))
-
-/* GPIODATAIN Fields each block 0-7 */
-#define BIT_GPIODATAIN_GPIOxIN(x)              (x)
-#define MASK_GPIODATAIN_GPIOxIN(x)             (0x01 << (x))
-
-/* GPIODATAOUT Fields each block 0-7 */
-#define BIT_GPIODATAOUT_GPIOxOUT(x)            (x)
-#define MASK_GPIODATAOUT_GPIOxOUT(x)           (0x01 << (x))
-
-/* CLEARGPIODATAOUT Fields */
-#define BIT_CLEARGPIODATAOUT_GPIOxOUT(x)       (x)
-#define MASK_CLEARGPIODATAOUT_GPIOxOUT(x)      (0x01 << (x))
-
-/* SETGPIODATAOUT Fields */
-#define BIT_SETGPIODATAOUT_GPIOxOUT(x)         (x)
-#define MASK_SETGPIODATAOUT_GPIOxOUT(x)                (0x01 << (x))
-
-/* GPIO_DEBEN Fields */
-#define BIT_GPIO_DEBEN_GPIOxDEB(x)             (x)
-#define MASK_GPIO_DEBEN_GPIOxDEB(x)            (0x01 << (x))
-
-/* GPIO_ISR1A Fields */
-#define BIT_GPIO_ISR_GPIOxISR(x)               (x)
-#define MASK_GPIO_ISR_GPIOxISR(x)              (0x01 << (x))
-
-/* GPIO_IMR1A Fields */
-#define BIT_GPIO_IMR1A_GPIOxIMR(x)             (x)
-#define MASK_GPIO_IMR1A_GPIOxIMR(x)            (0x01 << (x))
-
-/* GPIO_SIR1 Fields */
-#define BIT_GPIO_SIR1_GPIOxSIR(x)              (x)
-#define MASK_GPIO_SIR1_GPIO0SIR                        (0x01 << (x))
-
-
-/* Control banks : 5 banks for 4 gpios each */
-#define DATA_CTL_MAX                   4
-#define GET_GPIO_CTL_BANK(x)           ((x)/DATA_CTL_MAX)
-#define GET_GPIO_CTL_OFF(x)            ((x)%DATA_CTL_MAX)
-#define GPIO_BANK_MAX                  GET_GPIO_CTL_BANK(TWL4030_GPIO_MAX)
-
-/* GPIOPUPDCTRx Fields 5 banks of 4 gpios each */
-#define BIT_GPIOPUPDCTR1_GPIOxPD(x)    (2 * (x))
-#define MASK_GPIOPUPDCTR1_GPIOxPD(x)   (0x01 << (2 * (x)))
-#define BIT_GPIOPUPDCTR1_GPIOxPU(x)    ((x) + 1)
-#define MASK_GPIOPUPDCTR1_GPIOxPU(x)   (0x01 << (((2 * (x)) + 1)))
-
-/* GPIO_EDR1 Fields */
-#define BIT_GPIO_EDR1_GPIOxFALLING(x)  (2 * (x))
-#define MASK_GPIO_EDR1_GPIOxFALLING(x) (0x01 << (2 * (x)))
-#define BIT_GPIO_EDR1_GPIOxRISING(x)   ((x) + 1)
-#define MASK_GPIO_EDR1_GPIOxRISING(x)  (0x01 << (((2 * (x)) + 1)))
-
-/* GPIO_SIH_CTRL Fields */
-#define BIT_GPIO_SIH_CTRL_EXCLEN       (0x000)
-#define MASK_GPIO_SIH_CTRL_EXCLEN      (0x00000001)
-#define BIT_GPIO_SIH_CTRL_PENDDIS      (0x001)
-#define MASK_GPIO_SIH_CTRL_PENDDIS     (0x00000002)
-#define BIT_GPIO_SIH_CTRL_COR          (0x002)
-#define MASK_GPIO_SIH_CTRL_COR         (0x00000004)
-
 /* GPIO_CTRL Fields */
-#define BIT_GPIO_CTRL_GPIO0CD1         (0x000)
-#define MASK_GPIO_CTRL_GPIO0CD1                (0x00000001)
-#define BIT_GPIO_CTRL_GPIO1CD2         (0x001)
-#define MASK_GPIO_CTRL_GPIO1CD2                (0x00000002)
-#define BIT_GPIO_CTRL_GPIO_ON          (0x002)
-#define MASK_GPIO_CTRL_GPIO_ON         (0x00000004)
+#define MASK_GPIO_CTRL_GPIO0CD1                BIT(0)
+#define MASK_GPIO_CTRL_GPIO1CD2                BIT(1)
+#define MASK_GPIO_CTRL_GPIO_ON         BIT(2)
 
 /* Mask for GPIO registers when aggregated into a 32-bit integer */
 #define GPIO_32_MASK                   0x0003ffff
@@ -152,17 +89,18 @@ static DEFINE_MUTEX(gpio_lock);
 /* store usage of each GPIO. - each bit represents one GPIO */
 static unsigned int gpio_usage_count;
 
-/* shadow the imr register */
-static unsigned int gpio_imr_shadow;
+/* protect what irq_chip modifies through its helper task */
+static DEFINE_SPINLOCK(gpio_spinlock);
 
-/* bitmask of pending requests to unmask gpio interrupts */
-static unsigned int gpio_pending_unmask;
+/* shadow the imr register; updates are delayed */
+static u32 gpio_imr_shadow;
+static bool gpio_pending_mask;
 
 /* bitmask of requests to set gpio irq trigger type */
 static unsigned int gpio_pending_trigger;
 
-/* pointer to gpio unmask thread struct */
-static struct task_struct *gpio_unmask_thread;
+/* pointer to helper thread */
+static struct task_struct *gpio_helper_thread;
 
 /*
  * Helper functions to read and write the GPIO ISR and IMR registers as
@@ -170,6 +108,9 @@ static struct task_struct *gpio_unmask_thread;
  * The caller must hold gpio_lock.
  */
 
+/* NOTE:  only the IRQ dispatcher may read ISR; reading it has
+ * side effects, because of the clear-on-read mechanism (COR=1).
+ */
 static int gpio_read_isr(unsigned int *isr)
 {
        int ret;
@@ -183,19 +124,9 @@ static int gpio_read_isr(unsigned int *isr)
        return ret;
 }
 
-static int gpio_write_isr(unsigned int isr)
-{
-       isr &= GPIO_32_MASK;
-       /*
-        * The buffer passed to the twl4030_i2c_write() routine must have an
-        * extra byte at the beginning reserved for its internal use.
-        */
-       isr <<= 8;
-       isr = cpu_to_le32(isr);
-       return twl4030_i2c_write(TWL4030_MODULE_GPIO, (u8 *) &isr,
-                               REG_GPIO_ISR1A, 3);
-}
-
+/* IMR is written only during initialization and
+ * by request of the irq_chip code.
+ */
 static int gpio_write_imr(unsigned int imr)
 {
        imr &= GPIO_32_MASK;
@@ -209,67 +140,55 @@ static int gpio_write_imr(unsigned int imr)
                                REG_GPIO_IMR1A, 3);
 }
 
-/*
- * These routines are analagous to the irqchip methods, but they are designed
- * to be called from thread context with cpu interrupts enabled and with no
- * locked spinlocks.  We call these routines from our custom IRQ handler
- * instead of the usual irqchip methods.
- */
-static void twl4030_gpio_mask_and_ack(unsigned int irq)
-{
-       int gpio = irq - twl4030_gpio_irq_base;
-
-       mutex_lock(&gpio_lock);
-       /* mask */
-       gpio_imr_shadow |= (1 << gpio);
-       gpio_write_imr(gpio_imr_shadow);
-       /* ack */
-       gpio_write_isr(1 << gpio);
-       mutex_unlock(&gpio_lock);
-}
-
-static void twl4030_gpio_unmask(unsigned int irq)
-{
-       int gpio = irq - twl4030_gpio_irq_base;
-
-       mutex_lock(&gpio_lock);
-       gpio_imr_shadow &= ~(1 << gpio);
-       gpio_write_imr(gpio_imr_shadow);
-       mutex_unlock(&gpio_lock);
-}
-
 /*
  * These are the irqchip methods for the TWL4030 GPIO interrupts.
  * Our IRQ handle method doesn't call these, but they will be called by
  * other routines such as setup_irq() and enable_irq().  They are called
- * with cpu interrupts disabled and with a lock on the irq_controller_lock
+ * with cpu interrupts disabled and with a lock on the irq_desc.lock
  * spinlock.  This complicates matters, because accessing the TWL4030 GPIO
  * interrupt controller requires I2C bus transactions that can't be initiated
  * in this context.  Our solution is to defer accessing the interrupt
- * controller to a kernel thread.  We only need to support the unmask method.
+ * controller to a kernel thread.
  */
 
-static void twl4030_gpio_irq_mask_and_ack(unsigned int irq)
+static void twl4030_gpio_irq_ack(unsigned int irq)
 {
+       /* NOP -- dispatcher acks when it reads ISR */
 }
 
 static void twl4030_gpio_irq_mask(unsigned int irq)
 {
+       int gpio = irq - twl4030_gpio_irq_base;
+       u32 mask = 1 << gpio;
+       unsigned long flags;
+
+       spin_lock_irqsave(&gpio_spinlock, flags);
+       gpio_pending_mask = true;
+       gpio_imr_shadow |= mask;
+       if (gpio_helper_thread && gpio_helper_thread->state != TASK_RUNNING)
+               wake_up_process(gpio_helper_thread);
+       spin_unlock_irqrestore(&gpio_spinlock, flags);
 }
 
 static void twl4030_gpio_irq_unmask(unsigned int irq)
 {
        int gpio = irq - twl4030_gpio_irq_base;
+       u32 mask = 1 << gpio;
+       unsigned long flags;
 
-       gpio_pending_unmask |= (1 << gpio);
-       if (gpio_unmask_thread && gpio_unmask_thread->state != TASK_RUNNING)
-               wake_up_process(gpio_unmask_thread);
+       spin_lock_irqsave(&gpio_spinlock, flags);
+       gpio_pending_mask = true;
+       gpio_imr_shadow &= ~mask;
+       if (gpio_helper_thread && gpio_helper_thread->state != TASK_RUNNING)
+               wake_up_process(gpio_helper_thread);
+       spin_unlock_irqrestore(&gpio_spinlock, flags);
 }
 
 static int twl4030_gpio_irq_set_type(unsigned int irq, unsigned trigger)
 {
        struct irq_desc *desc = irq_desc + irq;
        int gpio = irq - twl4030_gpio_irq_base;
+       unsigned long flags;
 
        trigger &= IRQ_TYPE_SENSE_MASK;
        if (trigger & ~IRQ_TYPE_EDGE_BOTH)
@@ -280,47 +199,30 @@ static int twl4030_gpio_irq_set_type(unsigned int irq, unsigned trigger)
        desc->status &= ~IRQ_TYPE_SENSE_MASK;
        desc->status |= trigger;
 
-       /* REVISIT This makes the "unmask" thread do double duty,
-        * updating IRQ trigger modes too.  Rename appropriately...
-        */
+       spin_lock_irqsave(&gpio_spinlock, flags);
        gpio_pending_trigger |= (1 << gpio);
-       if (gpio_unmask_thread && gpio_unmask_thread->state != TASK_RUNNING)
-               wake_up_process(gpio_unmask_thread);
+       if (gpio_helper_thread && gpio_helper_thread->state != TASK_RUNNING)
+               wake_up_process(gpio_helper_thread);
+       spin_unlock_irqrestore(&gpio_spinlock, flags);
 
        return 0;
 }
 
 static struct irq_chip twl4030_gpio_irq_chip = {
        .name           = "twl4030",
-       .ack            = twl4030_gpio_irq_mask_and_ack,
+       .ack            = twl4030_gpio_irq_ack,
        .mask           = twl4030_gpio_irq_mask,
        .unmask         = twl4030_gpio_irq_unmask,
        .set_type       = twl4030_gpio_irq_set_type,
 };
 
-/*
- * These are the irqchip methods for the TWL4030 PIH GPIO module interrupt.
- * The PIH module doesn't have interrupt masking capability, so these
- * methods are NULL.
- */
-static void twl4030_gpio_module_ack(unsigned int irq) {}
-static void twl4030_gpio_module_mask(unsigned int irq) {}
-static void twl4030_gpio_module_unmask(unsigned int irq) {}
-static struct irq_chip twl4030_gpio_module_irq_chip = {
-       .ack    = twl4030_gpio_module_ack,
-       .mask   = twl4030_gpio_module_mask,
-       .unmask = twl4030_gpio_module_unmask,
-};
 
 /*
  * To configure TWL4030 GPIO module registers
  */
 static inline int gpio_twl4030_write(u8 address, u8 data)
 {
-       int ret = 0;
-
-       ret = twl4030_i2c_write_u8(TWL4030_MODULE_GPIO, data, address);
-       return ret;
+       return twl4030_i2c_write_u8(TWL4030_MODULE_GPIO, data, address);
 }
 
 /*
@@ -332,9 +234,7 @@ static inline int gpio_twl4030_read(u8 address)
        int ret = 0;
 
        ret = twl4030_i2c_read_u8(TWL4030_MODULE_GPIO, &data, address);
-       if (ret >= 0)
-               ret = data;
-       return ret;
+       return (ret < 0) ? ret : data;
 }
 
 /*
@@ -352,17 +252,17 @@ int twl4030_request_gpio(int gpio)
                return ret;
 
        mutex_lock(&gpio_lock);
-       if (gpio_usage_count & (0x1 << gpio)) {
+       if (gpio_usage_count & BIT(gpio)) {
                ret = -EBUSY;
        } else {
                /* First time usage? - switch on GPIO module */
                if (!gpio_usage_count) {
                        ret = gpio_twl4030_write(REG_GPIO_CTRL,
                                        MASK_GPIO_CTRL_GPIO_ON);
-                       ret = gpio_twl4030_write(REG_GPIO_SIH_CTRL, 0x00);
+
                }
                if (!ret)
-                       gpio_usage_count |= (0x1 << gpio);
+                       gpio_usage_count |= BIT(gpio);
                else
                        gpio_free(twl_gpiochip.base + gpio);
        }
@@ -383,10 +283,10 @@ int twl4030_free_gpio(int gpio)
 
        mutex_lock(&gpio_lock);
 
-       if ((gpio_usage_count & (0x1 << gpio)) == 0) {
+       if ((gpio_usage_count & BIT(gpio)) == 0) {
                ret = -EPERM;
        } else {
-               gpio_usage_count &= ~(0x1 << gpio);
+               gpio_usage_count &= ~BIT(gpio);
                gpio_free(twl_gpiochip.base + gpio);
        }
 
@@ -399,27 +299,21 @@ int twl4030_free_gpio(int gpio)
 }
 EXPORT_SYMBOL(twl4030_free_gpio);
 
-/*
- * Set direction for TWL4030 GPIO
- */
 static int twl4030_set_gpio_direction(int gpio, int is_input)
 {
-       u8 d_bnk = GET_GPIO_DATA_BANK(gpio);
-       u8 d_msk = MASK_GPIODATADIR_GPIOxDIR(GET_GPIO_DATA_OFF(gpio));
+       u8 d_bnk = gpio >> 3;
+       u8 d_msk = BIT(gpio & 0x7);
        u8 reg = 0;
        u8 base = REG_GPIODATADIR1 + d_bnk;
        int ret = 0;
 
-       if (unlikely(!(gpio_usage_count & (0x1 << gpio))))
-               return -EPERM;
-
        mutex_lock(&gpio_lock);
        ret = gpio_twl4030_read(base);
        if (ret >= 0) {
                if (is_input)
-                       reg = (u8) ((ret) & ~(d_msk));
+                       reg = ret & ~d_msk;
                else
-                       reg = (u8) ((ret) | (d_msk));
+                       reg = ret | d_msk;
 
                ret = gpio_twl4030_write(base, reg);
        }
@@ -427,48 +321,33 @@ static int twl4030_set_gpio_direction(int gpio, int is_input)
        return ret;
 }
 
-/*
- * To enable/disable GPIO pin on TWL4030
- */
 static int twl4030_set_gpio_dataout(int gpio, int enable)
 {
-       u8 d_bnk = GET_GPIO_DATA_BANK(gpio);
-       u8 d_msk = MASK_GPIODATAOUT_GPIOxOUT(GET_GPIO_DATA_OFF(gpio));
+       u8 d_bnk = gpio >> 3;
+       u8 d_msk = BIT(gpio & 0x7);
        u8 base = 0;
-       int ret = 0;
-
-       if (unlikely(!(gpio_usage_count & (0x1 << gpio))))
-               return -EPERM;
 
        if (enable)
                base = REG_SETGPIODATAOUT1 + d_bnk;
        else
                base = REG_CLEARGPIODATAOUT1 + d_bnk;
 
-       mutex_lock(&gpio_lock);
-       ret = gpio_twl4030_write(base, d_msk);
-       mutex_unlock(&gpio_lock);
-       return ret;
+       return gpio_twl4030_write(base, d_msk);
 }
 
-/*
- * To get the status of a GPIO pin on TWL4030
- */
 int twl4030_get_gpio_datain(int gpio)
 {
-       u8 d_bnk = GET_GPIO_DATA_BANK(gpio);
-       u8 d_off = BIT_GPIODATAIN_GPIOxIN(GET_GPIO_DATA_OFF(gpio));
+       u8 d_bnk = gpio >> 3;
+       u8 d_off = gpio & 0x7;
        u8 base = 0;
        int ret = 0;
 
        if (unlikely((gpio >= TWL4030_GPIO_MAX)
-               || !(gpio_usage_count & (0x1 << gpio))))
+               || !(gpio_usage_count & BIT(gpio))))
                return -EPERM;
 
        base = REG_GPIODATAIN1 + d_bnk;
-       mutex_lock(&gpio_lock);
        ret = gpio_twl4030_read(base);
-       mutex_unlock(&gpio_lock);
        if (ret > 0)
                ret = (ret >> d_off) & 0x1;
 
@@ -476,48 +355,10 @@ int twl4030_get_gpio_datain(int gpio)
 }
 EXPORT_SYMBOL(twl4030_get_gpio_datain);
 
-#if 0
-/*
- * Configure PULL type for a GPIO pin on TWL4030
- */
-int twl4030_set_gpio_pull(int gpio, int pull_dircn)
-{
-       u8 c_bnk = GET_GPIO_CTL_BANK(gpio);
-       u8 c_off = GET_GPIO_CTL_OFF(gpio);
-       u8 c_msk = 0;
-       u8 reg = 0;
-       u8 base = 0;
-       int ret = 0;
-
-       if (unlikely((gpio >= TWL4030_GPIO_MAX) ||
-               !(gpio_usage_count & (0x1 << gpio))))
-               return -EPERM;
-
-       base = REG_GPIOPUPDCTR1 + c_bnk;
-       if (pull_dircn == TWL4030_GPIO_PULL_DOWN)
-               c_msk = MASK_GPIOPUPDCTR1_GPIOxPD(c_off);
-       else if (pull_dircn == TWL4030_GPIO_PULL_UP)
-               c_msk = MASK_GPIOPUPDCTR1_GPIOxPU(c_off);
-
-       mutex_lock(&gpio_lock);
-       ret = gpio_twl4030_read(base);
-       if (ret >= 0) {
-               /* clear the previous up/down values */
-               reg = (u8) (ret);
-               reg &= ~(MASK_GPIOPUPDCTR1_GPIOxPU(c_off) |
-                       MASK_GPIOPUPDCTR1_GPIOxPD(c_off));
-               reg |= c_msk;
-               ret = gpio_twl4030_write(base, reg);
-       }
-       mutex_unlock(&gpio_lock);
-       return ret;
-}
-#endif
-
 static int twl4030_set_gpio_edge_ctrl(int gpio, int edge)
 {
-       u8 c_bnk = GET_GPIO_CTL_BANK(gpio);
-       u8 c_off = GET_GPIO_CTL_OFF(gpio);
+       u8 c_bnk = gpio >> 2;
+       u8 c_off = (gpio & 0x3) * 2;
        u8 c_msk = 0;
        u8 reg = 0;
        u8 base = 0;
@@ -526,17 +367,16 @@ static int twl4030_set_gpio_edge_ctrl(int gpio, int edge)
        base = REG_GPIO_EDR1 + c_bnk;
 
        if (edge & IRQ_TYPE_EDGE_RISING)
-               c_msk |= MASK_GPIO_EDR1_GPIOxRISING(c_off);
+               c_msk |= BIT(c_off + 1);
        if (edge & IRQ_TYPE_EDGE_FALLING)
-               c_msk |= MASK_GPIO_EDR1_GPIOxFALLING(c_off);
+               c_msk |= BIT(c_off);
 
        mutex_lock(&gpio_lock);
        ret = gpio_twl4030_read(base);
        if (ret >= 0) {
                /* clear the previous rising/falling values */
                reg = (u8) ret;
-               reg &= ~(MASK_GPIO_EDR1_GPIOxFALLING(c_off)
-                       | MASK_GPIO_EDR1_GPIOxRISING(c_off));
+               reg &= ~(0x3 << c_off);
                reg |= c_msk;
                ret = gpio_twl4030_write(base, reg);
        }
@@ -549,14 +389,14 @@ static int twl4030_set_gpio_edge_ctrl(int gpio, int edge)
  */
 int twl4030_set_gpio_debounce(int gpio, int enable)
 {
-       u8 d_bnk = GET_GPIO_DATA_BANK(gpio);
-       u8 d_msk = MASK_GPIO_DEBEN_GPIOxDEB(GET_GPIO_DATA_OFF(gpio));
+       u8 d_bnk = gpio >> 3;
+       u8 d_msk = BIT(gpio & 0x7);
        u8 reg = 0;
        u8 base = 0;
        int ret = 0;
 
        if (unlikely((gpio >= TWL4030_GPIO_MAX)
-               || !(gpio_usage_count & (0x1 << gpio))))
+               || !(gpio_usage_count & BIT(gpio))))
                return -EPERM;
 
        base = REG_GPIO_DEBEN1 + d_bnk;
@@ -564,9 +404,9 @@ int twl4030_set_gpio_debounce(int gpio, int enable)
        ret = gpio_twl4030_read(base);
        if (ret >= 0) {
                if (enable)
-                       reg = (u8) ((ret) | (d_msk));
+                       reg = ret | d_msk;
                else
-                       reg = (u8) ((ret) & ~(d_msk));
+                       reg = ret & ~d_msk;
 
                ret = gpio_twl4030_write(base, reg);
        }
@@ -578,6 +418,9 @@ EXPORT_SYMBOL(twl4030_set_gpio_debounce);
 #if 0
 /*
  * Configure Card detect for GPIO pin on TWL4030
+ *
+ * This means:  VMMC1 or VMMC2 is enabled or disabled based
+ * on the status of GPIO-0 or GPIO-1 pins (respectively).
  */
 int twl4030_set_gpio_card_detect(int gpio, int enable)
 {
@@ -587,7 +430,7 @@ int twl4030_set_gpio_card_detect(int gpio, int enable)
 
        /* Only GPIO 0 or 1 can be used for CD feature.. */
        if (unlikely((gpio >= TWL4030_GPIO_MAX)
-               || !(gpio_usage_count & (0x1 << gpio))
+               || !(gpio_usage_count & BIT(gpio))
                || (gpio >= TWL4030_GPIO_MAX_CD))) {
                return -EPERM;
        }
@@ -610,37 +453,42 @@ int twl4030_set_gpio_card_detect(int gpio, int enable)
 /* MODULE FUNCTIONS */
 
 /*
- * gpio_unmask_thread() runs as a kernel thread.  It is awakened by the unmask
- * method for the GPIO interrupts.  It unmasks all of the GPIO interrupts
- * specified in the gpio_pending_unmask bitmask.  We have to do the unmasking
- * in a kernel thread rather than directly in the unmask method because of the
+ * gpio_helper_thread() is a kernel thread that is awakened by irq_chip
+ * methods to update IRQ masks and trigger modes.
+ *
+ * We must do this in a thread rather than in irq_chip methods because of the
  * need to access the TWL4030 via the I2C bus.  Note that we don't need to be
  * concerned about race conditions where the request to unmask a GPIO interrupt
  * has already been cancelled before this thread does the unmasking.  If a GPIO
  * interrupt is improperly unmasked, then the IRQ handler for it will mask it
  * when an interrupt occurs.
  */
-static int twl4030_gpio_unmask_thread(void *data)
+static int twl4030_gpio_helper_thread(void *dev)
 {
        current->flags |= PF_NOFREEZE;
 
        while (!kthread_should_stop()) {
                int irq;
-               unsigned int gpio_unmask;
+               bool do_mask;
+               u32 local_imr;
                unsigned int gpio_trigger;
 
-               local_irq_disable();
-               gpio_unmask = gpio_pending_unmask;
-               gpio_pending_unmask = 0;
+               spin_lock_irq(&gpio_spinlock);
+
+               do_mask = gpio_pending_mask;
+               gpio_pending_mask = false;
+               local_imr = gpio_imr_shadow;
 
                gpio_trigger = gpio_pending_trigger;
                gpio_pending_trigger = 0;
-               local_irq_enable();
 
-               for (irq = twl4030_gpio_irq_base; 0 != gpio_unmask;
-                               gpio_unmask >>= 1, irq++) {
-                       if (gpio_unmask & 0x1)
-                               twl4030_gpio_unmask(irq);
+               spin_unlock_irq(&gpio_spinlock);
+
+               if (do_mask) {
+                       int status = gpio_write_imr(local_imr);
+
+                       if (status)
+                               dev_err(dev, "write IMR err %d\n", status);
                }
 
                for (irq = twl4030_gpio_irq_base;
@@ -661,10 +509,10 @@ static int twl4030_gpio_unmask_thread(void *data)
                                        type);
                }
 
-               local_irq_disable();
-               if (!gpio_pending_unmask && !gpio_pending_trigger)
+               spin_lock_irq(&gpio_spinlock);
+               if (!gpio_pending_mask && !gpio_pending_trigger)
                        set_current_state(TASK_INTERRUPTIBLE);
-               local_irq_enable();
+               spin_unlock_irq(&gpio_spinlock);
 
                schedule();
        }
@@ -672,51 +520,6 @@ static int twl4030_gpio_unmask_thread(void *data)
        return 0;
 }
 
-/*
- * do_twl4030_gpio_irq() is the desc->handle method for each of the twl4030
- * gpio interrupts.  It executes in kernel thread context.
- * On entry, cpu interrupts are enabled.
- */
-static void do_twl4030_gpio_irq(unsigned int irq, irq_desc_t *desc)
-{
-       struct irqaction *action;
-       const unsigned int cpu = smp_processor_id();
-
-       desc->status |= IRQ_LEVEL;
-
-       /*
-        * Acknowledge, clear _AND_ disable the interrupt.
-        */
-       twl4030_gpio_mask_and_ack(irq);
-
-       if (!desc->depth) {
-               kstat_cpu(cpu).irqs[irq]++;
-
-               action = desc->action;
-               if (action) {
-                       int ret;
-                       int status = 0;
-                       int retval = 0;
-                       do {
-                               /* Call the ISR with cpu interrupts enabled. */
-                               ret = action->handler(irq, action->dev_id);
-                               if (ret == IRQ_HANDLED)
-                                       status |= action->flags;
-                               retval |= ret;
-                               action = action->next;
-                       } while (action);
-
-                       if (retval != IRQ_HANDLED)
-                               printk(KERN_ERR "ISR for TWL4030 GPIO"
-                                       " irq %d can't handle interrupt\n",
-                                       irq);
-
-                       if (!desc->depth)
-                               twl4030_gpio_unmask(irq);
-               }
-       }
-}
-
 /*
  * do_twl4030_gpio_module_irq() is the desc->handle method for the twl4030 gpio
  * module interrupt.  It executes in kernel thread context.
@@ -728,38 +531,21 @@ static void do_twl4030_gpio_irq(unsigned int irq, irq_desc_t *desc)
  */
 static void do_twl4030_gpio_module_irq(unsigned int irq, irq_desc_t *desc)
 {
-       const unsigned int cpu = smp_processor_id();
-
-       desc->status |= IRQ_LEVEL;
-       /*
-       * The desc->handle method would normally call the desc->chip->ack
-       * method here, but we won't bother since our ack method is NULL.
-       */
-       if (!desc->depth) {
-               int gpio_irq;
-               unsigned int gpio_isr;
-
-               kstat_cpu(cpu).irqs[irq]++;
-               local_irq_enable();
-
-               mutex_lock(&gpio_lock);
-               if (gpio_read_isr(&gpio_isr))
-                       gpio_isr = 0;
-               mutex_unlock(&gpio_lock);
-
-               for (gpio_irq = twl4030_gpio_irq_base; 0 != gpio_isr;
-                       gpio_isr >>= 1, gpio_irq++) {
-                       if (gpio_isr & 0x1) {
-                               irq_desc_t *d = irq_desc + gpio_irq;
-                               d->handle_irq(gpio_irq, d);
-                       }
-               }
+       int gpio_irq;
+       unsigned int gpio_isr;
 
-               local_irq_disable();
-               /*
-                * Here is where we should call the unmask method, but again we
-                * won't bother since it is NULL.
-                */
+       /* PIH irqs like this can't be individually masked or acked ...
+        * so we don't even call the PIH irq_chip stub methods.
+        */
+       local_irq_enable();
+       if (gpio_read_isr(&gpio_isr))
+               gpio_isr = 0;
+       local_irq_disable();
+
+       for (gpio_irq = twl4030_gpio_irq_base; 0 != gpio_isr;
+               gpio_isr >>= 1, gpio_irq++) {
+               if (gpio_isr & 0x1)
+                       generic_handle_irq(gpio_irq);
        }
 }
 
@@ -788,6 +574,12 @@ static void twl_set(struct gpio_chip *chip, unsigned offset, int value)
        twl4030_set_gpio_dataout(offset, value);
 }
 
+static int twl_to_irq(struct gpio_chip *chip, unsigned offset)
+{
+       /* NOTE: assumes IRQs are set up ... */
+       return twl4030_gpio_irq_base + offset;
+}
+
 static struct gpio_chip twl_gpiochip = {
        .label                  = "twl4030",
        .owner                  = THIS_MODULE,
@@ -795,11 +587,37 @@ static struct gpio_chip twl_gpiochip = {
        .get                    = twl_get,
        .direction_output       = twl_direction_out,
        .set                    = twl_set,
+       .to_irq                 = twl_to_irq,
        .can_sleep              = 1,
 };
 
 /*----------------------------------------------------------------------*/
 
+static int __devinit gpio_twl4030_pulls(u32 ups, u32 downs)
+{
+       u8              message[6];
+       unsigned        i, gpio_bit;
+
+       /* For most pins, a pulldown was enabled by default.
+        * We should have data that's specific to this board.
+        */
+       for (gpio_bit = 1, i = 1; i < 6; i++) {
+               u8              bit_mask;
+               unsigned        j;
+
+               for (bit_mask = 0, j = 0; j < 8; j += 2, gpio_bit <<= 1) {
+                       if (ups & gpio_bit)
+                               bit_mask |= 1 << (j + 1);
+                       else if (downs & gpio_bit)
+                               bit_mask |= 1 << (j + 0);
+               }
+               message[i] = bit_mask;
+       }
+
+       return twl4030_i2c_write(TWL4030_MODULE_GPIO, message,
+                               REG_GPIOPUPDCTR1, 5);
+}
+
 static int gpio_twl4030_remove(struct platform_device *pdev);
 
 static int __devinit gpio_twl4030_probe(struct platform_device *pdev)
@@ -809,7 +627,7 @@ static int __devinit gpio_twl4030_probe(struct platform_device *pdev)
        int irq = 0;
 
        /* All GPIO interrupts are initially masked */
-       gpio_pending_unmask = 0;
+       gpio_pending_mask = false;
        gpio_imr_shadow = GPIO_32_MASK;
        ret = gpio_write_imr(gpio_imr_shadow);
 
@@ -836,15 +654,14 @@ static int __devinit gpio_twl4030_probe(struct platform_device *pdev)
 
        if (!ret) {
                /*
-                * Create a kernel thread to handle deferred unmasking of gpio
+                * Create a kernel thread to handle deferred operations on gpio
                 * interrupts.
                 */
-               gpio_unmask_thread = kthread_create(twl4030_gpio_unmask_thread,
-                       NULL, "twl4030 gpio");
-               if (!gpio_unmask_thread) {
+               gpio_helper_thread = kthread_create(twl4030_gpio_helper_thread,
+                               &pdev->dev, "twl4030 gpio");
+               if (!gpio_helper_thread) {
                        dev_err(&pdev->dev,
-                               "could not create twl4030 gpio unmask"
-                               " thread!\n");
+                               "could not create helper thread!\n");
                        ret = -ENOMEM;
                }
        }
@@ -854,20 +671,26 @@ static int __devinit gpio_twl4030_probe(struct platform_device *pdev)
                for (irq = twl4030_gpio_irq_base; irq < twl4030_gpio_irq_end;
                                irq++) {
                        set_irq_chip_and_handler(irq, &twl4030_gpio_irq_chip,
-                                       do_twl4030_gpio_irq);
+                                       handle_edge_irq);
                        activate_irq(irq);
                }
 
                /* gpio module IRQ */
                irq = platform_get_irq(pdev, 0);
 
+               /* COR=1 means irqs are acked by reading ISR
+                * PENDDIS=0 means pending events enabled
+                * EXCLEN=0 means route to both irq lines
+                */
+               gpio_twl4030_write(REG_GPIO_SIH_CTRL,
+                               TWL4030_SIH_CTRL_COR_MASK);
+
                /*
                 * Install an irq handler to demultiplex the gpio module
                 * interrupt.
                 */
-               set_irq_chip(irq, &twl4030_gpio_module_irq_chip);
                set_irq_chained_handler(irq, do_twl4030_gpio_module_irq);
-               wake_up_process(gpio_unmask_thread);
+               wake_up_process(gpio_helper_thread);
 
                dev_info(&pdev->dev, "IRQ %d chains IRQs %d..%d\n", irq,
                        twl4030_gpio_irq_base, twl4030_gpio_irq_end - 1);
@@ -875,6 +698,18 @@ static int __devinit gpio_twl4030_probe(struct platform_device *pdev)
 
 no_irqs:
        if (!ret) {
+               /*
+                * NOTE:  boards may waste power if they don't set pullups
+                * and pulldowns correctly ... default for non-ULPI pins is
+                * pulldown, and some other pins may have external pullups
+                * or pulldowns.  Careful!
+                */
+               ret = gpio_twl4030_pulls(pdata->pullups, pdata->pulldowns);
+               if (ret)
+                       dev_dbg(&pdev->dev, "pullups %.05x %.05x --> %d\n",
+                                       pdata->pullups, pdata->pulldowns,
+                                       ret);
+
                twl_gpiochip.base = pdata->gpio_base;
                twl_gpiochip.ngpio = TWL4030_GPIO_MAX;
                twl_gpiochip.dev = &pdev->dev;
@@ -929,10 +764,10 @@ static int __devexit gpio_twl4030_remove(struct platform_device *pdev)
        for (irq = twl4030_gpio_irq_base; irq < twl4030_gpio_irq_end; irq++)
                set_irq_handler(irq, NULL);
 
-       /* stop the gpio unmask kernel thread */
-       if (gpio_unmask_thread) {
-               kthread_stop(gpio_unmask_thread);
-               gpio_unmask_thread = NULL;
+       /* stop the gpio helper kernel thread */
+       if (gpio_helper_thread) {
+               kthread_stop(gpio_helper_thread);
+               gpio_helper_thread = NULL;
        }
 
        return 0;