]> www.pilppa.org Git - linux-2.6-omap-h63xx.git/blobdiff - drivers/gpio/twl4030-gpio.c
twl4030 MMC card detction
[linux-2.6-omap-h63xx.git] / drivers / gpio / twl4030-gpio.c
index a38a0235337247a044ab90e369f9a00f0d7f6aa3..37d3eec8730afe3f1a6f48b920cdb4ac3678d2aa 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>
  * 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)
-{
-#ifdef CONFIG_ARM
-       /* ARM requires an extra step to clear IRQ_NOREQUEST, which it
-        * sets on behalf of every irq_chip.  Also sets IRQ_NOPROBE.
-        */
-       set_irq_flags(irq, IRQF_VALID);
-#else
-       /* same effect on other architectures */
-       set_irq_noprobe(irq);
-#endif
-}
-
 static struct gpio_chip twl_gpiochip;
 static int twl4030_gpio_irq_base;
-static int twl4030_gpio_irq_end;
 
 /* genirq interfaces are not available to modules */
 #ifdef MODULE
@@ -92,160 +73,41 @@ 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;
-
-/* bitmask of pending requests to unmask gpio interrupts */
-static unsigned int gpio_pending_unmask;
-
-/* 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;
-
-/*
- * Helper functions to read and write the GPIO ISR and IMR registers as
- * 32-bit integers. Functions return 0 on success, non-zero otherwise.
- * The caller must hold gpio_lock.
- */
-
-static int gpio_read_isr(unsigned int *isr)
-{
-       int ret;
-
-       *isr = 0;
-       ret = twl4030_i2c_read(TWL4030_MODULE_GPIO, (u8 *) isr,
-                       REG_GPIO_ISR1A, 3);
-       le32_to_cpup(isr);
-       *isr &= GPIO_32_MASK;
-
-       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);
-}
-
-static int gpio_write_imr(unsigned int imr)
-{
-       imr &= 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.
-        */
-       imr <<= 8;
-       imr = cpu_to_le32(imr);
-       return twl4030_i2c_write(TWL4030_MODULE_GPIO, (u8 *) &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.
+ * To configure TWL4030 GPIO module registers
  */
-static void twl4030_gpio_mask_and_ack(unsigned int irq)
+static inline int gpio_twl4030_write(u8 address, u8 data)
 {
-       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);
+       return twl4030_i2c_write_u8(TWL4030_MODULE_GPIO, data, address);
 }
 
-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
- * 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.
+ * LED register offsets (use TWL4030_MODULE_{LED,PWMA,PWMB}))
+ * PWMs A and B are dedicated to LEDs A and B, respectively.
  */
 
-static void twl4030_gpio_irq_mask_and_ack(unsigned int irq)
-{
-}
-
-static void twl4030_gpio_irq_mask(unsigned int irq)
-{
-}
+#define TWL4030_LED_LEDEN      0x0
 
-static void twl4030_gpio_irq_unmask(unsigned int irq)
-{
-       int gpio = irq - twl4030_gpio_irq_base;
+/* LEDEN bits */
+#define LEDEN_LEDAON           BIT(0)
+#define LEDEN_LEDBON           BIT(1)
+#define LEDEN_LEDAEXT          BIT(2)
+#define LEDEN_LEDBEXT          BIT(3)
+#define LEDEN_LEDAPWM          BIT(4)
+#define LEDEN_LEDBPWM          BIT(5)
+#define LEDEN_PWM_LENGTHA      BIT(6)
+#define LEDEN_PWM_LENGTHB      BIT(7)
 
-       gpio_pending_unmask |= (1 << gpio);
-       if (gpio_unmask_thread && gpio_unmask_thread->state != TASK_RUNNING)
-               wake_up_process(gpio_unmask_thread);
-}
+#define TWL4030_PWMx_PWMxON    0x0
+#define TWL4030_PWMx_PWMxOFF   0x1
 
-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;
+#define PWMxON_LENGTH          BIT(7)
 
-       trigger &= IRQ_TYPE_SENSE_MASK;
-       if (trigger & ~IRQ_TYPE_EDGE_BOTH)
-               return -EINVAL;
-       if ((desc->status & IRQ_TYPE_SENSE_MASK) == trigger)
-               return 0;
-
-       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...
-        */
-       gpio_pending_trigger |= (1 << gpio);
-       if (gpio_unmask_thread && gpio_unmask_thread->state != TASK_RUNNING)
-               wake_up_process(gpio_unmask_thread);
-
-       return 0;
-}
-
-static struct irq_chip twl4030_gpio_irq_chip = {
-       .name           = "twl4030",
-       .ack            = twl4030_gpio_irq_mask_and_ack,
-       .mask           = twl4030_gpio_irq_mask,
-       .unmask         = twl4030_gpio_irq_unmask,
-       .set_type       = twl4030_gpio_irq_set_type,
-};
-
-
-/*
- * To configure TWL4030 GPIO module registers
- */
-static inline int gpio_twl4030_write(u8 address, u8 data)
-{
-       return twl4030_i2c_write_u8(TWL4030_MODULE_GPIO, data, address);
-}
+/*----------------------------------------------------------------------*/
 
 /*
  * To read a TWL4030 GPIO module register
@@ -259,67 +121,31 @@ static inline int gpio_twl4030_read(u8 address)
        return (ret < 0) ? ret : data;
 }
 
-/*
- * twl4030 GPIO request function
- */
-int twl4030_request_gpio(int gpio)
-{
-       int ret = 0;
-
-       if (unlikely(gpio >= TWL4030_GPIO_MAX))
-               return -EPERM;
-
-       ret = gpio_request(twl_gpiochip.base + gpio, NULL);
-       if (ret < 0)
-               return ret;
+/*----------------------------------------------------------------------*/
 
-       mutex_lock(&gpio_lock);
-       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 |= BIT(gpio);
-               else
-                       gpio_free(twl_gpiochip.base + gpio);
-       }
-       mutex_unlock(&gpio_lock);
-       return ret;
-}
-EXPORT_SYMBOL(twl4030_request_gpio);
+static u8 cached_leden;                /* protected by gpio_lock */
 
-/*
- * TWL4030 GPIO free module
+/* The LED lines are open drain outputs ... a FET pulls to GND, so an
+ * external pullup is needed.  We could also expose the integrated PWM
+ * as a LED brightness control; we initialize it as "always on".
  */
-int twl4030_free_gpio(int gpio)
+static void twl4030_led_set_value(int led, int value)
 {
-       int ret = 0;
+       u8 mask = LEDEN_LEDAON | LEDEN_LEDAPWM;
+       int status;
 
-       if (unlikely(gpio >= TWL4030_GPIO_MAX))
-               return -EPERM;
+       if (led)
+               mask <<= 1;
 
        mutex_lock(&gpio_lock);
-
-       if ((gpio_usage_count & BIT(gpio)) == 0) {
-               ret = -EPERM;
-       } else {
-               gpio_usage_count &= ~BIT(gpio);
-               gpio_free(twl_gpiochip.base + gpio);
-       }
-
-       /* Last time usage? - switch off GPIO module */
-       if (ret == 0 && !gpio_usage_count)
-               ret = gpio_twl4030_write(REG_GPIO_CTRL, 0x0);
-
+       if (value)
+               cached_leden &= ~mask;
+       else
+               cached_leden |= mask;
+       status = twl4030_i2c_write_u8(TWL4030_MODULE_LED, cached_leden,
+                       TWL4030_LED_LEDEN);
        mutex_unlock(&gpio_lock);
-       return ret;
 }
-EXPORT_SYMBOL(twl4030_free_gpio);
 
 static int twl4030_set_gpio_direction(int gpio, int is_input)
 {
@@ -357,7 +183,7 @@ static int twl4030_set_gpio_dataout(int gpio, int enable)
        return gpio_twl4030_write(base, d_msk);
 }
 
-int twl4030_get_gpio_datain(int gpio)
+static int twl4030_get_gpio_datain(int gpio)
 {
        u8 d_bnk = gpio >> 3;
        u8 d_off = gpio & 0x7;
@@ -375,36 +201,6 @@ int twl4030_get_gpio_datain(int gpio)
 
        return ret;
 }
-EXPORT_SYMBOL(twl4030_get_gpio_datain);
-
-static int twl4030_set_gpio_edge_ctrl(int gpio, int edge)
-{
-       u8 c_bnk = gpio >> 2;
-       u8 c_off = (gpio & 0x3) * 2;
-       u8 c_msk = 0;
-       u8 reg = 0;
-       u8 base = 0;
-       int ret = 0;
-
-       base = REG_GPIO_EDR1 + c_bnk;
-
-       if (edge & IRQ_TYPE_EDGE_RISING)
-               c_msk |= BIT(c_off + 1);
-       if (edge & IRQ_TYPE_EDGE_FALLING)
-               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 &= ~(0x3 << c_off);
-               reg |= c_msk;
-               ret = gpio_twl4030_write(base, reg);
-       }
-       mutex_unlock(&gpio_lock);
-       return ret;
-}
 
 /*
  * Configure debounce timing value for a GPIO pin on TWL4030
@@ -437,229 +233,148 @@ int twl4030_set_gpio_debounce(int gpio, int enable)
 }
 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)
-{
-       u8 reg = 0;
-       u8 msk = (1 << gpio);
-       int ret = 0;
-
-       /* Only GPIO 0 or 1 can be used for CD feature.. */
-       if (unlikely((gpio >= TWL4030_GPIO_MAX)
-               || !(gpio_usage_count & BIT(gpio))
-               || (gpio >= TWL4030_GPIO_MAX_CD))) {
-               return -EPERM;
-       }
-
-       mutex_lock(&gpio_lock);
-       ret = gpio_twl4030_read(REG_GPIO_CTRL);
-       if (ret >= 0) {
-               if (enable)
-                       reg = (u8) (ret | msk);
-               else
-                       reg = (u8) (ret & ~msk);
-
-               ret = gpio_twl4030_write(REG_GPIO_CTRL, reg);
-       }
-       mutex_unlock(&gpio_lock);
-       return ret;
-}
-#endif
-
-/* 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
- * 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 twl_request(struct gpio_chip *chip, unsigned offset)
 {
-       current->flags |= PF_NOFREEZE;
-
-       while (!kthread_should_stop()) {
-               int irq;
-               unsigned int gpio_unmask;
-               unsigned int gpio_trigger;
+       int status = 0;
 
-               local_irq_disable();
-               gpio_unmask = gpio_pending_unmask;
-               gpio_pending_unmask = 0;
+       mutex_lock(&gpio_lock);
 
-               gpio_trigger = gpio_pending_trigger;
-               gpio_pending_trigger = 0;
-               local_irq_enable();
+       /* Support the two LED outputs as output-only GPIOs. */
+       if (offset >= TWL4030_GPIO_MAX) {
+               u8      ledclr_mask = LEDEN_LEDAON | LEDEN_LEDAEXT
+                               | LEDEN_LEDAPWM | LEDEN_PWM_LENGTHA;
+               u8      module = TWL4030_MODULE_PWMA;
 
-               for (irq = twl4030_gpio_irq_base; 0 != gpio_unmask;
-                               gpio_unmask >>= 1, irq++) {
-                       if (gpio_unmask & 0x1)
-                               twl4030_gpio_unmask(irq);
+               offset -= TWL4030_GPIO_MAX;
+               if (offset) {
+                       ledclr_mask <<= 1;
+                       module = TWL4030_MODULE_PWMB;
                }
 
-               for (irq = twl4030_gpio_irq_base;
-                               gpio_trigger;
-                               gpio_trigger >>= 1, irq++) {
-                       struct irq_desc *desc;
-                       unsigned type;
+               /* initialize PWM to always-drive */
+               status = twl4030_i2c_write_u8(module, 0x7f,
+                               TWL4030_PWMx_PWMxOFF);
+               if (status < 0)
+                       goto done;
+               status = twl4030_i2c_write_u8(module, 0x7f,
+                               TWL4030_PWMx_PWMxON);
+               if (status < 0)
+                       goto done;
+
+               /* init LED to not-driven (high) */
+               module = TWL4030_MODULE_LED;
+               status = twl4030_i2c_read_u8(module, &cached_leden,
+                               TWL4030_LED_LEDEN);
+               if (status < 0)
+                       goto done;
+               cached_leden &= ~ledclr_mask;
+               status = twl4030_i2c_write_u8(module, cached_leden,
+                               TWL4030_LED_LEDEN);
+               if (status < 0)
+                       goto done;
+
+               status = 0;
+               goto done;
+       }
 
-                       if (!(gpio_trigger & 0x1))
-                               continue;
+       /* on first use, turn GPIO module "on" */
+       if (!gpio_usage_count) {
+               struct twl4030_gpio_platform_data *pdata;
+               u8 value = MASK_GPIO_CTRL_GPIO_ON;
 
-                       desc = irq_desc + irq;
-                       spin_lock_irq(&desc->lock);
-                       type = desc->status & IRQ_TYPE_SENSE_MASK;
-                       spin_unlock_irq(&desc->lock);
+               /* optionally have the first two GPIOs switch vMMC1
+                * and vMMC2 power supplies based on card presence.
+                */
+               pdata = chip->dev->platform_data;
+               value |= pdata->mmc_cd & 0x03;
 
-                       twl4030_set_gpio_edge_ctrl(irq - twl4030_gpio_irq_base,
-                                       type);
-               }
+               status = gpio_twl4030_write(REG_GPIO_CTRL, value);
+       }
 
-               local_irq_disable();
-               if (!gpio_pending_unmask && !gpio_pending_trigger)
-                       set_current_state(TASK_INTERRUPTIBLE);
-               local_irq_enable();
+       if (!status)
+               gpio_usage_count |= (0x1 << offset);
 
-               schedule();
-       }
-       set_current_state(TASK_RUNNING);
-       return 0;
+done:
+       mutex_unlock(&gpio_lock);
+       return status;
 }
 
-/*
- * 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)
+static void twl_free(struct gpio_chip *chip, unsigned offset)
 {
-       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);
-               }
+       if (offset >= TWL4030_GPIO_MAX) {
+               twl4030_led_set_value(offset - TWL4030_GPIO_MAX, 1);
+               return;
        }
-}
 
-/*
- * do_twl4030_gpio_module_irq() is the desc->handle method for the twl4030 gpio
- * module interrupt.  It executes in kernel thread context.
- * This is a chained interrupt, so there is no desc->action method for it.
- * We query the gpio module interrupt controller in the twl4030 to determine
- * which gpio lines are generating interrupt requests, and then call the
- * desc->handle method for each gpio that needs service.
- * On entry, cpu interrupts are disabled.
- */
-static void do_twl4030_gpio_module_irq(unsigned int irq, irq_desc_t *desc)
-{
-       const unsigned int cpu = smp_processor_id();
+       mutex_lock(&gpio_lock);
 
-       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);
-                       }
-               }
+       gpio_usage_count &= ~BIT(offset);
 
-               local_irq_disable();
-               /*
-                * Here is where we should call the unmask method, but again we
-                * won't bother since it is NULL.
-                */
-       }
-}
+       /* on last use, switch off GPIO module */
+       if (!gpio_usage_count)
+               gpio_twl4030_write(REG_GPIO_CTRL, 0x0);
 
-/*----------------------------------------------------------------------*/
+       mutex_unlock(&gpio_lock);
+}
 
 static int twl_direction_in(struct gpio_chip *chip, unsigned offset)
 {
-       return twl4030_set_gpio_direction(offset, 1);
+       return (offset < TWL4030_GPIO_MAX)
+               ? twl4030_set_gpio_direction(offset, 1)
+               : -EINVAL;
 }
 
 static int twl_get(struct gpio_chip *chip, unsigned offset)
 {
-       int status = twl4030_get_gpio_datain(offset);
+       int status = 0;
 
+       if (offset < TWL4030_GPIO_MAX)
+               status = twl4030_get_gpio_datain(offset);
+       else if (offset == TWL4030_GPIO_MAX)
+               status = cached_leden & LEDEN_LEDAON;
+       else
+               status = cached_leden & LEDEN_LEDBON;
        return (status < 0) ? 0 : status;
 }
 
 static int twl_direction_out(struct gpio_chip *chip, unsigned offset, int value)
 {
-       twl4030_set_gpio_dataout(offset, value);
-       return twl4030_set_gpio_direction(offset, 0);
+       if (offset < TWL4030_GPIO_MAX) {
+               twl4030_set_gpio_dataout(offset, value);
+               return twl4030_set_gpio_direction(offset, 0);
+       } else {
+               twl4030_led_set_value(offset - TWL4030_GPIO_MAX, value);
+               return 0;
+       }
 }
 
 static void twl_set(struct gpio_chip *chip, unsigned offset, int value)
 {
-       twl4030_set_gpio_dataout(offset, value);
+       if (offset < TWL4030_GPIO_MAX)
+               twl4030_set_gpio_dataout(offset, value);
+       else
+               twl4030_led_set_value(offset - TWL4030_GPIO_MAX, value);
+}
+
+static int twl_to_irq(struct gpio_chip *chip, unsigned offset)
+{
+       return (twl4030_gpio_irq_base && (offset < TWL4030_GPIO_MAX))
+               ? (twl4030_gpio_irq_base + offset)
+               : -EINVAL;
 }
 
 static struct gpio_chip twl_gpiochip = {
        .label                  = "twl4030",
        .owner                  = THIS_MODULE,
+       .request                = twl_request,
+       .free                   = twl_free,
        .direction_input        = twl_direction_in,
        .get                    = twl_get,
        .direction_output       = twl_direction_out,
        .set                    = twl_set,
+       .to_irq                 = twl_to_irq,
        .can_sleep              = 1,
 };
 
@@ -696,105 +411,58 @@ static int __devinit gpio_twl4030_probe(struct platform_device *pdev)
 {
        struct twl4030_gpio_platform_data *pdata = pdev->dev.platform_data;
        int ret;
-       int irq = 0;
 
-       /* All GPIO interrupts are initially masked */
-       gpio_pending_unmask = 0;
-       gpio_imr_shadow = GPIO_32_MASK;
-       ret = gpio_write_imr(gpio_imr_shadow);
-
-       twl4030_gpio_irq_base = pdata->irq_base;
-       twl4030_gpio_irq_end = pdata->irq_end;
-
-       if ((twl4030_gpio_irq_end - twl4030_gpio_irq_base) > 0) {
+       /* maybe setup IRQs */
+       if (pdata->irq_base) {
                if (is_module()) {
                        dev_err(&pdev->dev,
                                "can't dispatch IRQs from modules\n");
                        goto no_irqs;
                }
-               if (twl4030_gpio_irq_end > NR_IRQS) {
-                       dev_err(&pdev->dev,
-                               "last IRQ is too large: %d\n",
-                               twl4030_gpio_irq_end);
-                       return -EINVAL;
-               }
-       } else {
-               dev_notice(&pdev->dev,
-                       "no IRQs being dispatched\n");
-               goto no_irqs;
-       }
-
-       if (!ret) {
-               /*
-                * Create a kernel thread to handle deferred unmasking of gpio
-                * interrupts.
-                */
-               gpio_unmask_thread = kthread_create(twl4030_gpio_unmask_thread,
-                       NULL, "twl4030 gpio");
-               if (!gpio_unmask_thread) {
-                       dev_err(&pdev->dev,
-                               "could not create twl4030 gpio unmask"
-                               " thread!\n");
-                       ret = -ENOMEM;
-               }
-       }
-
-       if (!ret) {
-               /* install an irq handler for each of the gpio interrupts */
-               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);
-                       activate_irq(irq);
-               }
-
-               /* gpio module IRQ */
-               irq = platform_get_irq(pdev, 0);
-
-               /*
-                * Install an irq handler to demultiplex the gpio module
-                * interrupt.
-                */
-               set_irq_chained_handler(irq, do_twl4030_gpio_module_irq);
-               wake_up_process(gpio_unmask_thread);
-
-               dev_info(&pdev->dev, "IRQ %d chains IRQs %d..%d\n", irq,
-                       twl4030_gpio_irq_base, twl4030_gpio_irq_end - 1);
+               ret = twl4030_sih_setup(TWL4030_MODULE_GPIO);
+               if (ret < 0)
+                       return ret;
+               WARN_ON(ret != pdata->irq_base);
+               twl4030_gpio_irq_base = ret;
        }
 
 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;
-
-               ret = gpiochip_add(&twl_gpiochip);
-               if (ret < 0) {
-                       dev_err(&pdev->dev,
-                                       "could not register gpiochip, %d\n",
-                                       ret);
-                       twl_gpiochip.ngpio = 0;
-                       gpio_twl4030_remove(pdev);
-               } else if (pdata->setup) {
-                       int status;
-
-                       status = pdata->setup(&pdev->dev,
-                                       pdata->gpio_base, TWL4030_GPIO_MAX);
-                       if (status)
-                               dev_dbg(&pdev->dev, "setup --> %d\n", status);
-               }
+       /*
+        * 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;
+
+       /* NOTE: we assume VIBRA_CTL.VIBRA_EN, in MODULE_AUDIO_VOICE,
+        * is (still) clear if use_leds is set.
+        */
+       if (pdata->use_leds)
+               twl_gpiochip.ngpio += 2;
+
+       ret = gpiochip_add(&twl_gpiochip);
+       if (ret < 0) {
+               dev_err(&pdev->dev,
+                               "could not register gpiochip, %d\n",
+                               ret);
+               twl_gpiochip.ngpio = 0;
+               gpio_twl4030_remove(pdev);
+       } else if (pdata->setup) {
+               int status;
+
+               status = pdata->setup(&pdev->dev,
+                               pdata->gpio_base, TWL4030_GPIO_MAX);
+               if (status)
+                       dev_dbg(&pdev->dev, "setup --> %d\n", status);
        }
 
        return ret;
@@ -804,7 +472,6 @@ static int __devexit gpio_twl4030_remove(struct platform_device *pdev)
 {
        struct twl4030_gpio_platform_data *pdata = pdev->dev.platform_data;
        int status;
-       int irq;
 
        if (pdata->teardown) {
                status = pdata->teardown(&pdev->dev,
@@ -819,24 +486,12 @@ static int __devexit gpio_twl4030_remove(struct platform_device *pdev)
        if (status < 0)
                return status;
 
-       if (is_module() || (twl4030_gpio_irq_end - twl4030_gpio_irq_base) <= 0)
+       if (is_module())
                return 0;
 
-       /* uninstall the gpio demultiplexing interrupt handler */
-       irq = platform_get_irq(pdev, 0);
-       set_irq_handler(irq, NULL);
-
-       /* uninstall the irq handler for each of the gpio interrupts */
-       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;
-       }
-
-       return 0;
+       /* REVISIT no support yet for deregistering all the IRQs */
+       WARN_ON(1);
+       return -EIO;
 }
 
 /* Note:  this hardware lives inside an I2C-based multi-function device. */