From 6ef9860d17c1a56a82e225c2dd3828a3e36d890a Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 14 May 2009 20:50:43 +0000 Subject: Add GPIO IRQ logic git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@1779 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/include/lm3s/irq.h | 150 ++++++++++++ nuttx/arch/arm/src/lm3s/Make.defs | 3 +- nuttx/arch/arm/src/lm3s/lm3s_gpioirq.c | 394 ++++++++++++++++++++++++++++++++ nuttx/arch/arm/src/lm3s/lm3s_internal.h | 12 +- nuttx/arch/arm/src/lm3s/lm3s_irq.c | 11 + 5 files changed, 567 insertions(+), 3 deletions(-) create mode 100644 nuttx/arch/arm/src/lm3s/lm3s_gpioirq.c (limited to 'nuttx/arch/arm') diff --git a/nuttx/arch/arm/include/lm3s/irq.h b/nuttx/arch/arm/include/lm3s/irq.h index 6714c909a..68df2e4b6 100644 --- a/nuttx/arch/arm/include/lm3s/irq.h +++ b/nuttx/arch/arm/include/lm3s/irq.h @@ -46,6 +46,7 @@ #include #include +#include /************************************************************************************ * Definitions @@ -121,6 +122,124 @@ #define NR_IRQS (60) /* Really only 43 */ +/* GPIO IRQs -- Note that support for individual GPIO ports can + * be disabled in order to reduce the size of the implemenation. + */ + +#ifndef CONFIG_LM3S_DISABLE_GPIOA_IRQS +# define LM3S_IRQ_GPIOA_0 (NR_IRQS + 0) +# define LM3S_IRQ_GPIOA_1 (NR_IRQS + 1) +# define LM3S_IRQ_GPIOA_2 (NR_IRQS + 2) +# define LM3S_IRQ_GPIOA_3 (NR_IRQS + 3) +# define LM3S_IRQ_GPIOA_4 (NR_IRQS + 4) +# define LM3S_IRQ_GPIOA_5 (NR_IRQS + 5) +# define LM3S_IRQ_GPIOA_6 (NR_IRQS + 6) +# define LM3S_IRQ_GPIOA_7 (NR_IRQS + 7) +# define _NGPIOAIRQS (NR_IRQS + 8) +#else +# define _NGPIOAIRQS NR_IRQS +#endif + +#ifndef CONFIG_LM3S_DISABLE_GPIOB_IRQS +# define LM3S_IRQ_GPIOB_0 (_NGPIOAIRQS + 0) +# define LM3S_IRQ_GPIOB_1 (_NGPIOAIRQS + 1) +# define LM3S_IRQ_GPIOB_2 (_NGPIOAIRQS + 2) +# define LM3S_IRQ_GPIOB_3 (_NGPIOAIRQS + 3) +# define LM3S_IRQ_GPIOB_4 (_NGPIOAIRQS + 4) +# define LM3S_IRQ_GPIOB_5 (_NGPIOAIRQS + 5) +# define LM3S_IRQ_GPIOB_6 (_NGPIOAIRQS + 6) +# define LM3S_IRQ_GPIOB_7 (_NGPIOAIRQS + 7) +# define _NGPIOBIRQS (_NGPIOAIRQS + 8) +#else +# define _NGPIOBIRQS _NGPIOAIRQS +#endif + +#ifndef CONFIG_LM3S_DISABLE_GPIOC_IRQS +# define LM3S_IRQ_GPIOC_0 (_NGPIOBIRQS + 0) +# define LM3S_IRQ_GPIOC_1 (_NGPIOBIRQS + 1) +# define LM3S_IRQ_GPIOC_2 (_NGPIOBIRQS + 2) +# define LM3S_IRQ_GPIOC_3 (_NGPIOBIRQS + 3) +# define LM3S_IRQ_GPIOC_4 (_NGPIOBIRQS + 4) +# define LM3S_IRQ_GPIOC_5 (_NGPIOBIRQS + 5) +# define LM3S_IRQ_GPIOC_6 (_NGPIOBIRQS + 6) +# define LM3S_IRQ_GPIOC_7 (_NGPIOBIRQS + 7) +# define _NGPIOCIRQS (_NGPIOBIRQS + 8) +#else +# define _NGPIOCIRQS _NGPIOBIRQS +#endif + +#ifndef CONFIG_LM3S_DISABLE_GPIOD_IRQS +# define LM3S_IRQ_GPIOD_0 (_NGPIOCIRQS + 0) +# define LM3S_IRQ_GPIOD_1 (_NGPIOCIRQS + 1) +# define LM3S_IRQ_GPIOD_2 (_NGPIOCIRQS + 2) +# define LM3S_IRQ_GPIOD_3 (_NGPIOCIRQS + 3) +# define LM3S_IRQ_GPIOD_4 (_NGPIOCIRQS + 4) +# define LM3S_IRQ_GPIOD_5 (_NGPIOCIRQS + 5) +# define LM3S_IRQ_GPIOD_6 (_NGPIOCIRQS + 6) +# define LM3S_IRQ_GPIOD_7 (_NGPIOCIRQS + 7) +# define _NGPIODIRQS (_NGPIOCIRQS + 8) +#else +# define _NGPIODIRQS _NGPIOCIRQS +#endif + +#ifndef CONFIG_LM3S_DISABLE_GPIOE_IRQS +# define LM3S_IRQ_GPIOE_0 (_NGPIODIRQS + 0) +# define LM3S_IRQ_GPIOE_1 (_NGPIODIRQS + 1) +# define LM3S_IRQ_GPIOE_2 (_NGPIODIRQS + 2) +# define LM3S_IRQ_GPIOE_3 (_NGPIODIRQS + 3) +# define LM3S_IRQ_GPIOE_4 (_NGPIODIRQS + 4) +# define LM3S_IRQ_GPIOE_5 (_NGPIODIRQS + 5) +# define LM3S_IRQ_GPIOE_6 (_NGPIODIRQS + 6) +# define LM3S_IRQ_GPIOE_7 (_NGPIODIRQS + 7) +# define _NGPIOEIRQS (_NGPIODIRQS + 8) +#else +# define _NGPIOEIRQS _NGPIODIRQS +#endif + +#ifndef CONFIG_LM3S_DISABLE_GPIOF_IRQS +# define LM3S_IRQ_GPIOF_0 (_NGPIOEIRQS + 0) +# define LM3S_IRQ_GPIOF_1 (_NGPIOEIRQS + 1) +# define LM3S_IRQ_GPIOF_2 (_NGPIOEIRQS + 2) +# define LM3S_IRQ_GPIOF_3 (_NGPIOEIRQS + 3) +# define LM3S_IRQ_GPIOF_4 (_NGPIOEIRQS + 4) +# define LM3S_IRQ_GPIOF_5 (_NGPIOEIRQS + 5) +# define LM3S_IRQ_GPIOF_6 (_NGPIOEIRQS + 6) +# define LM3S_IRQ_GPIOF_7 (_NGPIOEIRQS + 7) +# define _NGPIOFIRQS (_NGPIOEIRQS + 8) +#else +# define _NGPIOFIRQS _NGPIOEIRQS +#endif + +#ifndef CONFIG_LM3S_DISABLE_GPIOG_IRQS +# define LM3S_IRQ_GPIOG_0 (_NGPIOFIRQS + 0) +# define LM3S_IRQ_GPIOG_1 (_NGPIOFIRQS + 1) +# define LM3S_IRQ_GPIOG_2 (_NGPIOFIRQS + 2) +# define LM3S_IRQ_GPIOG_3 (_NGPIOFIRQS + 3) +# define LM3S_IRQ_GPIOG_4 (_NGPIOFIRQS + 4) +# define LM3S_IRQ_GPIOG_5 (_NGPIOFIRQS + 5) +# define LM3S_IRQ_GPIOG_6 (_NGPIOFIRQS + 6) +# define LM3S_IRQ_GPIOG_7 (_NGPIOFIRQS + 7) +# define _NGPIOGIRQS (_NGPIOFIRQS + 8) +#else +# define _NGPIOGIRQS _NGPIOFIRQS +#endif + +#ifndef CONFIG_LM3S_DISABLE_GPIOH_IRQS +# define LM3S_IRQ_GPIOH_0 (_NGPIOGIRQS + 0) +# define LM3S_IRQ_GPIOH_1 (_NGPIOGIRQS + 1) +# define LM3S_IRQ_GPIOH_2 (_NGPIOGIRQS + 2) +# define LM3S_IRQ_GPIOH_3 (_NGPIOGIRQS + 3) +# define LM3S_IRQ_GPIOH_4 (_NGPIOGIRQS + 4) +# define LM3S_IRQ_GPIOH_5 (_NGPIOGIRQS + 5) +# define LM3S_IRQ_GPIOH_6 (_NGPIOGIRQS + 6) +# define LM3S_IRQ_GPIOH_7 (_NGPIOGIRQS + 7) +# define _NGPIOHIRQS (_NGPIOGIRQS + 8) +#else +# define _NGPIOHIRQS _NGPIOGIRQS +#endif + +#define NR_GPIO_IRQS (_NGPIOHIRQS - NR_IRQS) + /************************************************************************************ * Public Types ************************************************************************************/ @@ -141,6 +260,37 @@ extern "C" { * Public Functions ************************************************************************************/ +/**************************************************************************** + * Name: gpio_irqattach + * + * Description: + * Attach the interrupt handler 'isr' to the GPIO IRQ 'irq' + * + ****************************************************************************/ + +EXTERN int gpio_irqattach(int irq, xcpt_t isr); +#define gpio_irqdetach(isr) gpio_irqattach(isr, NULL) + +/**************************************************************************** + * Name: gpio_irqenable + * + * Description: + * Enable the GPIO IRQ specified by 'irq' + * + ****************************************************************************/ + +EXTERN void gpio_irqenable(int irq); + +/**************************************************************************** + * Name: gpio_irqdisable + * + * Description: + * Disable the GPIO IRQ specified by 'irq' + * + ****************************************************************************/ + +EXTERN void gpio_irqdisable(int irq); + #undef EXTERN #ifdef __cplusplus } diff --git a/nuttx/arch/arm/src/lm3s/Make.defs b/nuttx/arch/arm/src/lm3s/Make.defs index 9e9ea238e..f033f8826 100644 --- a/nuttx/arch/arm/src/lm3s/Make.defs +++ b/nuttx/arch/arm/src/lm3s/Make.defs @@ -47,7 +47,8 @@ CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copystate.c \ CHIP_ASRCS = lm3s_context.S CHIP_CSRCS = lm3s_start.c lm3s_syscontrol.c lm3s_irq.c lm3s_pendsv.c \ - lm3s_gpio.c lm3s_timerisr.c lm3s_lowputc.c lm3s_serial.c + lm3s_gpio.c lm3s_gpioirq.c lm3s_timerisr.c lm3s_lowputc.c \ + lm3s_serial.c ifdef CONFIG_NET CHIP_CSRCS += lm3s_ethernet.c diff --git a/nuttx/arch/arm/src/lm3s/lm3s_gpioirq.c b/nuttx/arch/arm/src/lm3s/lm3s_gpioirq.c new file mode 100644 index 000000000..590e0d753 --- /dev/null +++ b/nuttx/arch/arm/src/lm3s/lm3s_gpioirq.c @@ -0,0 +1,394 @@ +/**************************************************************************** + * arch/arm/src/lm3s/lm3s_gpioirq.c + * arch/arm/src/chip/lm3s_gpioirq.c + * + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. 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. + * 3. Neither the name NuttX 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 BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include +#include + +#include + +#include "up_arch.h" +#include "os_internal.h" +#include "irq_internal.h" +#include "lm3s_internal.h" + +/**************************************************************************** + * Private Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* A table of handlers for each GPIO interrupt */ + +static FAR xcpt_t g_gpioirqvector[NR_GPIO_IRQS]; + +/* A table that maps a GPIO group to a GPIO base address. Overly complicated + * be we support disabling interrupt support for arbitrary ports + */ + +static const uint32 g_gpiobase[] = +{ +#ifndef CONFIG_LM3S_DISABLE_GPIOA_IRQS + LM3S_GPIOA_BASE, +#endif +#ifndef CONFIG_LM3S_DISABLE_GPIOB_IRQS + LM3S_GPIOB_BASE, +#endif +#ifndef CONFIG_LM3S_DISABLE_GPIOC_IRQS + LM3S_GPIOC_BASE, +#endif +#ifndef CONFIG_LM3S_DISABLE_GPIOD_IRQS + LM3S_GPIOD_BASE, +#endif +#ifndef CONFIG_LM3S_DISABLE_GPIOE_IRQS + LM3S_GPIOE_BASE, +#endif +#ifndef CONFIG_LM3S_DISABLE_GPIOF_IRQS + LM3S_GPIOF_BASE, +#endif +#ifndef CONFIG_LM3S_DISABLE_GPIOG_IRQS + LM3S_GPIOG_BASE, +#endif +#ifndef CONFIG_LM3S_DISABLE_GPIOH_IRQS + LM3S_GPIOH_BASE, +#endif +}; + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lm3s_gpiobaseaddress + * + * Description: + * Given a GPIO enumeration value, return the base address of the + * associated GPIO registers. + * + ****************************************************************************/ + +static inline uint32 lm3s_gpiobaseaddress(unsigned int port) +{ + return g_gpiobase[port >> 3]; +} + +/**************************************************************************** + * Name: lm3s_gpio*handler + * + * Description: + * Handle interrupts on each enabled GPIO port + * + ****************************************************************************/ + +static int lm3s_gpiohandler(uint32 regbase, int irqbase, void *context) +{ + uint32 mis; + int irq; + int pin; + + /* Handle each pending GPIO interrupt. "The GPIO MIS register is the masked + * interrupt status register. Bits read High in GPIO MIS reflect the status + * of input lines triggering an interrupt. Bits read as Low indicate that + * either no interrupt has been generated, or the interrupt is masked." + */ + + mis = getreg32(regbase + LM3S_GPIO_MIS_OFFSET) & 0xff; + + /* Clear all GPIO interrupts that we are going to process. "The GPIO ICR + * register is the interrupt clear register. Writing a 1 to a bit in this + * register clears the corresponding interrupt edge detection logic register. + * Writing a 0 has no effect." + */ + + putreg32(mis, regbase + LM3S_GPIO_ICR_OFFSET); + + /* Now process each IRQ pending in the MIS */ + + for (pin = 0; pin < 8 && mis != 0; pin++, mis >>= 1) + { + if ((mis & 1) != 0) + { + irq = irqbase + pin; + g_gpioirqvector[irq - NR_IRQS](irq, context); + } + } + return OK; +} + +#ifndef CONFIG_LM3S_DISABLE_GPIOA_IRQS +static int lm3s_gpioahandler(int irq, FAR void *context) +{ + return lm3s_gpiohandler(LM3S_GPIOA_BASE, LM3S_IRQ_GPIOA_0, context); +} +#endif + +#ifndef CONFIG_LM3S_DISABLE_GPIOB_IRQS +static int lm3s_gpiobhandler(int irq, FAR void *context) +{ + return lm3s_gpiohandler(LM3S_GPIOB_BASE, LM3S_IRQ_GPIOB_0, context); +} +#endif + +#ifndef CONFIG_LM3S_DISABLE_GPIOC_IRQS +static int lm3s_gpiochandler(int irq, FAR void *context) +{ + return lm3s_gpiohandler(LM3S_GPIOC_BASE, LM3S_IRQ_GPIOC_0, context); +} +#endif + +#ifndef CONFIG_LM3S_DISABLE_GPIOD_IRQS +static int lm3s_gpiodhandler(int irq, FAR void *context) +{ + return lm3s_gpiohandler(LM3S_GPIOD_BASE, LM3S_IRQ_GPIOD_0, context); +} +#endif + +#ifndef CONFIG_LM3S_DISABLE_GPIOE_IRQS +static int lm3s_gpioehandler(int irq, FAR void *context) +{ + return lm3s_gpiohandler(LM3S_GPIOE_BASE, LM3S_IRQ_GPIOE_0, context); +} +#endif + +#ifndef CONFIG_LM3S_DISABLE_GPIOF_IRQS +static int lm3s_gpiofhandler(int irq, FAR void *context) +{ + return lm3s_gpiohandler(LM3S_GPIOF_BASE, LM3S_IRQ_GPIOF_0, context); +} +#endif + +#ifndef CONFIG_LM3S_DISABLE_GPIOG_IRQS +static int lm3s_gpioghandler(int irq, FAR void *context) +{ + return lm3s_gpiohandler(LM3S_GPIOG_BASE, LM3S_IRQ_GPIOG_0, context); +} +#endif + +#ifndef CONFIG_LM3S_DISABLE_GPIOH_IRQS +static int lm3s_gpiohhandler(int irq, FAR void *context) +{ + return lm3s_gpiohandler(LM3S_GPIOH_BASE, LM3S_IRQ_GPIOH_0, context); +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: gpio_irqinitialize + * + * Description: + * Initialize all vectors to the unexpected interrupt handler + * + ****************************************************************************/ + +int gpio_irqinitialize(void) +{ + int i; + + /* Point all interrupt vectors to the unexpected interrupt */ + + for (i = 0; i < NR_GPIO_IRQS; i++) + { + g_gpioirqvector[i] = irq_unexpected_isr; + } + + /* Then attach all GPIO interrupt handlers */ + +#ifndef CONFIG_LM3S_DISABLE_GPIOA_IRQS + irq_attach(LM3S_IRQ_GPIOA, lm3s_gpioahandler); +#endif +#ifndef CONFIG_LM3S_DISABLE_GPIOB_IRQS + irq_attach(LM3S_IRQ_GPIOB, lm3s_gpiobhandler); +#endif +#ifndef CONFIG_LM3S_DISABLE_GPIOC_IRQS + irq_attach(LM3S_IRQ_GPIOC, lm3s_gpiochandler); +#endif +#ifndef CONFIG_LM3S_DISABLE_GPIOD_IRQS + irq_attach(LM3S_IRQ_GPIOD, lm3s_gpiodhandler); +#endif +#ifndef CONFIG_LM3S_DISABLE_GPIOE_IRQS + irq_attach(LM3S_IRQ_GPIOE, lm3s_gpioehandler); +#endif +#ifndef CONFIG_LM3S_DISABLE_GPIOF_IRQS + irq_attach(LM3S_IRQ_GPIOF, lm3s_gpiofhandler); +#endif +#ifndef CONFIG_LM3S_DISABLE_GPIOG_IRQS + irq_attach(LM3S_IRQ_GPIOG, lm3s_gpioghandler); +#endif +#ifndef CONFIG_LM3S_DISABLE_GPIOH_IRQS + irq_attach(LM3S_IRQ_GPIOH, lm3s_gpiohhandler); +#endif + + return OK; +} + +/**************************************************************************** + * Name: gpio_irqattach + * + * Description: + * Attach in GPIO interrupt to the provide 'isr' + * + ****************************************************************************/ + +int gpio_irqattach(int irq, xcpt_t isr) +{ + irqstate_t flags; + int gpioirq = irq - NR_IRQS; + int ret = ERROR; + + if ((unsigned)gpioirq < NR_GPIO_IRQS) + { + flags = irqsave(); + + /* If the new ISR is NULL, then the ISR is being detached. + * In this case, disable the ISR and direct any interrupts + * to the unexpected interrupt handler. + */ + + if (isr == NULL) + { +#ifndef CONFIG_ARCH_NOINTC + gpio_irqdisable(gpioirq); +#endif + isr = irq_unexpected_isr; + } + + /* Save the new ISR in the table. */ + + g_irqvector[gpioirq] = isr; + irqrestore(flags); + ret = OK; + } + return ret; +} + +/**************************************************************************** + * Name: gpio_irqenable + * + * Description: + * Enable the GPIO IRQ specified by 'irq' + * + ****************************************************************************/ + +void gpio_irqenable(int irq) +{ + irqstate_t flags; + int gpioirq = irq - NR_IRQS; + uint32 base; + uint32 regval; + int pin; + int ret = ERROR; + + if ((unsigned)gpioirq < NR_GPIO_IRQS) + { + /* Get the base address of the GPIO module associated with this IRQ */ + + base = lm3s_gpiobaseaddress(gpioirq); + pin = (1 << (gpioirq & 7)); + + /* Disable the GPIO interrupt. "The GPIO IM register is the interrupt + * mask register. Bits set to High in GPIO IM allow the corresponding + * pins to trigger their individual interrupts and the combined GPIO INTR + * line. Clearing a bit disables interrupt triggering on that pin. All + * bits are cleared by a reset. + */ + + flags = irqsave(); + regval = getreg32(base + LM3S_GPIO_IM_OFFSET); + regval |= pin; + putreg32(regval, base + LM3S_GPIO_IM_OFFSET); + irqrestore(flags); + ret = OK; + } + return ret; +} + +/**************************************************************************** + * Name: gpio_irqdisable + * + * Description: + * Disable the GPIO IRQ specified by 'irq' + * + ****************************************************************************/ + +void gpio_irqdisable(int irq) +{ + irqstate_t flags; + int gpioirq = irq - NR_IRQS; + uint32 base; + uint32 regval; + int pin; + int ret = ERROR; + + if ((unsigned)gpioirq < NR_GPIO_IRQS) + { + /* Get the base address of the GPIO module associated with this IRQ */ + + base = lm3s_gpiobaseaddress(gpioirq); + pin = (1 << (gpioirq & 7)); + + /* Disable the GPIO interrupt. "The GPIO IM register is the interrupt + * mask register. Bits set to High in GPIO IM allow the corresponding + * pins to trigger their individual interrupts and the combined GPIO INTR + * line. Clearing a bit disables interrupt triggering on that pin. All + * bits are cleared by a reset. + */ + + flags = irqsave(); + regval = getreg32(base + LM3S_GPIO_IM_OFFSET); + regval &= ~pin; + putreg32(regval, base + LM3S_GPIO_IM_OFFSET); + irqrestore(flags); + ret = OK; + } + return ret; +} + diff --git a/nuttx/arch/arm/src/lm3s/lm3s_internal.h b/nuttx/arch/arm/src/lm3s/lm3s_internal.h index 0f48c6f23..22a69a24c 100644 --- a/nuttx/arch/arm/src/lm3s/lm3s_internal.h +++ b/nuttx/arch/arm/src/lm3s/lm3s_internal.h @@ -250,8 +250,6 @@ EXTERN void lm3s_clockconfig(uint32 newrcc, uint32 newrcc2); EXTERN void up_clockconfig(void); -/* Configure a GPIO pin */ - /**************************************************************************** * Name: lm3s_configgpio * @@ -292,6 +290,16 @@ EXTERN void lm3s_gpiowrite(uint32 pinset, boolean value); EXTERN boolean lm3s_gpioread(uint32 pinset, boolean value); +/**************************************************************************** + * Name: gpio_irqinitialize + * + * Description: + * Initialize all vectors to the unexpected interrupt handler + * + ****************************************************************************/ + +EXTERN int weak_function gpio_irqinitialize(void); + #undef EXTERN #if defined(__cplusplus) } diff --git a/nuttx/arch/arm/src/lm3s/lm3s_irq.c b/nuttx/arch/arm/src/lm3s/lm3s_irq.c index 80bb33503..def4ce391 100644 --- a/nuttx/arch/arm/src/lm3s/lm3s_irq.c +++ b/nuttx/arch/arm/src/lm3s/lm3s_irq.c @@ -175,6 +175,17 @@ void up_irqinitialize(void) current_regs = NULL; + /* Initialize support for GPIO interrupts if included in this build */ + +#ifndef CONFIG_LM3S_DISABLE_GPIO_IRQS +#ifdef CONFIG_HAVE_WEAKFUNCTIONS + if (gpio_irqinitialize != NULL) +#endif + { + gpio_irqinitialize(); + } +#endif + /* Attach the PendSV exception handler and set it to the minimum * prioirity. The PendSV exception is used for performing * context switches. -- cgit v1.2.3