From 82c299159a50c72fc530abbd2210f084b5bcd938 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 23 Jan 2010 03:05:05 +0000 Subject: Misc fixes, add button support, GPIO interrupt support git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@2523 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/include/sam3u/irq.h | 127 ++++++++- nuttx/arch/arm/src/sam3u/Make.defs | 4 +- nuttx/arch/arm/src/sam3u/sam3u_gpioirq.c | 367 ++++++++++++++++++++++++++ nuttx/arch/arm/src/sam3u/sam3u_internal.h | 78 +++++- nuttx/arch/arm/src/sam3u/sam3u_irq.c | 30 ++- nuttx/arch/arm/src/sam3u/sam3u_pio.c | 2 +- nuttx/configs/sam3u-ek/README.txt | 21 +- nuttx/configs/sam3u-ek/include/board.h | 47 +++- nuttx/configs/sam3u-ek/ostest/defconfig | 8 +- nuttx/configs/sam3u-ek/src/sam3uek_internal.h | 4 + nuttx/configs/sam3u-ek/src/up_buttons.c | 83 +++++- nuttx/include/nuttx/arch.h | 2 +- nuttx/include/nuttx/irq.h | 8 +- 13 files changed, 749 insertions(+), 32 deletions(-) create mode 100755 nuttx/arch/arm/src/sam3u/sam3u_gpioirq.c diff --git a/nuttx/arch/arm/include/sam3u/irq.h b/nuttx/arch/arm/include/sam3u/irq.h index b2df14c88..d36d39a88 100755 --- a/nuttx/arch/arm/include/sam3u/irq.h +++ b/nuttx/arch/arm/include/sam3u/irq.h @@ -136,7 +136,132 @@ #define SAM3U_IRQ_ADC (SAM3U_IRQ_EXTINT+SAM3U_PID_ADC) /* 10-bit ADC Controller */ #define SAM3U_IRQ_DMAC (SAM3U_IRQ_EXTINT+SAM3U_PID_DMAC) /* DMA Controller */ #define SAM3U_IRQ_UDPHS (SAM3U_IRQ_EXTINT+SAM3U_PID_UDPHS) /* USB Device High Speed */ -#define NR_IRQS (SAM3U_IRQ_EXTINT+NR_PIDS) /* Total number of IRQ numbers */ +#define SAM3U_IRQ_NEXTINT NR_PIDS /* Total number of external interrupt numbers */ +#define SAM3U_IRQ_NIRQS (SAM3U_IRQ_EXTINT+NR_PIDS) /* The number of real IRQs */ + +/* GPIO interrupts (derived from SAM3U_IRQ_PIOA/B/C) */ + +#ifdef CONFIG_GPIOA_IRQ +# define SAM3U_IRQ_GPIOA_PINS (SAM3U_IRQ_EXTINT+SAM3U_IRQ_NEXTINT) +# define SAM3U_IRQ_PA0 (SAM3U_IRQ_GPIOA_PINS+0) /* GPIOA, PIN 0 */ +# define SAM3U_IRQ_PA1 (SAM3U_IRQ_GPIOA_PINS+1) /* GPIOA, PIN 1 */ +# define SAM3U_IRQ_PA2 (SAM3U_IRQ_GPIOA_PINS+2) /* GPIOA, PIN 2 */ +# define SAM3U_IRQ_PA3 (SAM3U_IRQ_GPIOA_PINS+3) /* GPIOA, PIN 3 */ +# define SAM3U_IRQ_PA4 (SAM3U_IRQ_GPIOA_PINS+4) /* GPIOA, PIN 4 */ +# define SAM3U_IRQ_PA5 (SAM3U_IRQ_GPIOA_PINS+5) /* GPIOA, PIN 5 */ +# define SAM3U_IRQ_PA6 (SAM3U_IRQ_GPIOA_PINS+6) /* GPIOA, PIN 6 */ +# define SAM3U_IRQ_PA7 (SAM3U_IRQ_GPIOA_PINS+7) /* GPIOA, PIN 7 */ +# define SAM3U_IRQ_PA8 (SAM3U_IRQ_GPIOA_PINS+8) /* GPIOA, PIN 8 */ +# define SAM3U_IRQ_PA9 (SAM3U_IRQ_GPIOA_PINS+9) /* GPIOA, PIN 9 */ +# define SAM3U_IRQ_PA10 (SAM3U_IRQ_GPIOA_PINS+10) /* GPIOA, PIN 10 */ +# define SAM3U_IRQ_PA11 (SAM3U_IRQ_GPIOA_PINS+11) /* GPIOA, PIN 11 */ +# define SAM3U_IRQ_PA12 (SAM3U_IRQ_GPIOA_PINS+12) /* GPIOA, PIN 12 */ +# define SAM3U_IRQ_PA13 (SAM3U_IRQ_GPIOA_PINS+13) /* GPIOA, PIN 13 */ +# define SAM3U_IRQ_PA14 (SAM3U_IRQ_GPIOA_PINS+14) /* GPIOA, PIN 14 */ +# define SAM3U_IRQ_PA15 (SAM3U_IRQ_GPIOA_PINS+15) /* GPIOA, PIN 15 */ +# define SAM3U_IRQ_PA16 (SAM3U_IRQ_GPIOA_PINS+16) /* GPIOA, PIN 16 */ +# define SAM3U_IRQ_PA17 (SAM3U_IRQ_GPIOA_PINS+17) /* GPIOA, PIN 17 */ +# define SAM3U_IRQ_PA18 (SAM3U_IRQ_GPIOA_PINS+18) /* GPIOA, PIN 18 */ +# define SAM3U_IRQ_PA19 (SAM3U_IRQ_GPIOA_PINS+19) /* GPIOA, PIN 19 */ +# define SAM3U_IRQ_PA20 (SAM3U_IRQ_GPIOA_PINS+20) /* GPIOA, PIN 20 */ +# define SAM3U_IRQ_PA21 (SAM3U_IRQ_GPIOA_PINS+21) /* GPIOA, PIN 21 */ +# define SAM3U_IRQ_PA22 (SAM3U_IRQ_GPIOA_PINS+22) /* GPIOA, PIN 22 */ +# define SAM3U_IRQ_PA23 (SAM3U_IRQ_GPIOA_PINS+23) /* GPIOA, PIN 23 */ +# define SAM3U_IRQ_PA24 (SAM3U_IRQ_GPIOA_PINS+24) /* GPIOA, PIN 24 */ +# define SAM3U_IRQ_PA25 (SAM3U_IRQ_GPIOA_PINS+25) /* GPIOA, PIN 25 */ +# define SAM3U_IRQ_PA26 (SAM3U_IRQ_GPIOA_PINS+26) /* GPIOA, PIN 26 */ +# define SAM3U_IRQ_PA27 (SAM3U_IRQ_GPIOA_PINS+27) /* GPIOA, PIN 27 */ +# define SAM3U_IRQ_PA28 (SAM3U_IRQ_GPIOA_PINS+28) /* GPIOA, PIN 28 */ +# define SAM3U_IRQ_PA29 (SAM3U_IRQ_GPIOA_PINS+29) /* GPIOA, PIN 29 */ +# define SAM3U_IRQ_PA30 (SAM3U_IRQ_GPIOA_PINS+30) /* GPIOA, PIN 30 */ +# define SAM3U_IRQ_PA31 (SAM3U_IRQ_GPIOA_PINS+31) /* GPIOA, PIN 31 */ +# define SAM3U_NGPIOAIRQS 32 +#else +# define SAM3U_NGPIOAIRQS 0 +#endif + +#ifdef CONFIG_GPIOB_IRQ +# define SAM3U_IRQ_GPIOB_PINS (SAM3U_IRQ_EXTINT+SAM3U_IRQ_NEXTINT+SAM3U_IRQ_GPIOA_PINS) +# define SAM3U_IRQ_PB0 (SAM3U_IRQ_GPIOB_PINS+0) /* GPIOB, PIN 0 */ +# define SAM3U_IRQ_PB1 (SAM3U_IRQ_GPIOB_PINS+1) /* GPIOB, PIN 1 */ +# define SAM3U_IRQ_PB2 (SAM3U_IRQ_GPIOB_PINS+2) /* GPIOB, PIN 2 */ +# define SAM3U_IRQ_PB3 (SAM3U_IRQ_GPIOB_PINS+3) /* GPIOB, PIN 3 */ +# define SAM3U_IRQ_PB4 (SAM3U_IRQ_GPIOB_PINS+4) /* GPIOB, PIN 4 */ +# define SAM3U_IRQ_PB5 (SAM3U_IRQ_GPIOB_PINS+5) /* GPIOB, PIN 5 */ +# define SAM3U_IRQ_PB6 (SAM3U_IRQ_GPIOB_PINS+6) /* GPIOB, PIN 6 */ +# define SAM3U_IRQ_PB7 (SAM3U_IRQ_GPIOB_PINS+7) /* GPIOB, PIN 7 */ +# define SAM3U_IRQ_PB8 (SAM3U_IRQ_GPIOB_PINS+8) /* GPIOB, PIN 8 */ +# define SAM3U_IRQ_PB9 (SAM3U_IRQ_GPIOB_PINS+9) /* GPIOB, PIN 9 */ +# define SAM3U_IRQ_PB10 (SAM3U_IRQ_GPIOB_PINS+10) /* GPIOB, PIN 10 */ +# define SAM3U_IRQ_PB11 (SAM3U_IRQ_GPIOB_PINS+11) /* GPIOB, PIN 11 */ +# define SAM3U_IRQ_PB12 (SAM3U_IRQ_GPIOB_PINS+12) /* GPIOB, PIN 12 */ +# define SAM3U_IRQ_PB13 (SAM3U_IRQ_GPIOB_PINS+13) /* GPIOB, PIN 13 */ +# define SAM3U_IRQ_PB14 (SAM3U_IRQ_GPIOB_PINS+14) /* GPIOB, PIN 14 */ +# define SAM3U_IRQ_PB15 (SAM3U_IRQ_GPIOB_PINS+15) /* GPIOB, PIN 15 */ +# define SAM3U_IRQ_PB16 (SAM3U_IRQ_GPIOB_PINS+16) /* GPIOB, PIN 16 */ +# define SAM3U_IRQ_PB17 (SAM3U_IRQ_GPIOB_PINS+17) /* GPIOB, PIN 17 */ +# define SAM3U_IRQ_PB18 (SAM3U_IRQ_GPIOB_PINS+18) /* GPIOB, PIN 18 */ +# define SAM3U_IRQ_PB19 (SAM3U_IRQ_GPIOB_PINS+19) /* GPIOB, PIN 19 */ +# define SAM3U_IRQ_PB20 (SAM3U_IRQ_GPIOB_PINS+20) /* GPIOB, PIN 20 */ +# define SAM3U_IRQ_PB21 (SAM3U_IRQ_GPIOB_PINS+21) /* GPIOB, PIN 21 */ +# define SAM3U_IRQ_PB22 (SAM3U_IRQ_GPIOB_PINS+22) /* GPIOB, PIN 22 */ +# define SAM3U_IRQ_PB23 (SAM3U_IRQ_GPIOB_PINS+23) /* GPIOB, PIN 23 */ +# define SAM3U_IRQ_PB24 (SAM3U_IRQ_GPIOB_PINS+24) /* GPIOB, PIN 24 */ +# define SAM3U_IRQ_PB25 (SAM3U_IRQ_GPIOB_PINS+25) /* GPIOB, PIN 25 */ +# define SAM3U_IRQ_PB26 (SAM3U_IRQ_GPIOB_PINS+26) /* GPIOB, PIN 26 */ +# define SAM3U_IRQ_PB27 (SAM3U_IRQ_GPIOB_PINS+27) /* GPIOB, PIN 27 */ +# define SAM3U_IRQ_PB28 (SAM3U_IRQ_GPIOB_PINS+28) /* GPIOB, PIN 28 */ +# define SAM3U_IRQ_PB29 (SAM3U_IRQ_GPIOB_PINS+29) /* GPIOB, PIN 29 */ +# define SAM3U_IRQ_PB30 (SAM3U_IRQ_GPIOB_PINS+30) /* GPIOB, PIN 30 */ +# define SAM3U_IRQ_PB31 (SAM3U_IRQ_GPIOB_PINS+31) /* GPIOB, PIN 31 */ +# define SAM3U_NGPIOAIRQS 32 +#else +# define SAM3U_NGPIOBIRQS 0 +#endif + +#ifdef CONFIG_GPIOC_IRQ +# define SAM3U_IRQ_GPIOC_PINS (SAM3U_IRQ_EXTINT+SAM3U_IRQ_NEXTINT+SAM3U_IRQ_GPIOA_PINS+SAM3U_IRQ_GPIOB_PINS) +# define SAM3U_IRQ_PC0 (SAM3U_IRQ_GPIOC_PINS+0) /* GPIOC, PIN 0 */ +# define SAM3U_IRQ_PC1 (SAM3U_IRQ_GPIOC_PINS+1) /* GPIOC, PIN 1 */ +# define SAM3U_IRQ_PC2 (SAM3U_IRQ_GPIOC_PINS+2) /* GPIOC, PIN 2 */ +# define SAM3U_IRQ_PC3 (SAM3U_IRQ_GPIOC_PINS+3) /* GPIOC, PIN 3 */ +# define SAM3U_IRQ_PC4 (SAM3U_IRQ_GPIOC_PINS+4) /* GPIOC, PIN 4 */ +# define SAM3U_IRQ_PC5 (SAM3U_IRQ_GPIOC_PINS+5) /* GPIOC, PIN 5 */ +# define SAM3U_IRQ_PC6 (SAM3U_IRQ_GPIOC_PINS+6) /* GPIOC, PIN 6 */ +# define SAM3U_IRQ_PC7 (SAM3U_IRQ_GPIOC_PINS+7) /* GPIOC, PIN 7 */ +# define SAM3U_IRQ_PC8 (SAM3U_IRQ_GPIOC_PINS+8) /* GPIOC, PIN 8 */ +# define SAM3U_IRQ_PC9 (SAM3U_IRQ_GPIOC_PINS+9) /* GPIOC, PIN 9 */ +# define SAM3U_IRQ_PC10 (SAM3U_IRQ_GPIOC_PINS+10) /* GPIOC, PIN 10 */ +# define SAM3U_IRQ_PC11 (SAM3U_IRQ_GPIOC_PINS+11) /* GPIOC, PIN 11 */ +# define SAM3U_IRQ_PC12 (SAM3U_IRQ_GPIOC_PINS+12) /* GPIOC, PIN 12 */ +# define SAM3U_IRQ_PC13 (SAM3U_IRQ_GPIOC_PINS+13) /* GPIOC, PIN 13 */ +# define SAM3U_IRQ_PC14 (SAM3U_IRQ_GPIOC_PINS+14) /* GPIOC, PIN 14 */ +# define SAM3U_IRQ_PC15 (SAM3U_IRQ_GPIOC_PINS+15) /* GPIOC, PIN 15 */ +# define SAM3U_IRQ_PC16 (SAM3U_IRQ_GPIOC_PINS+16) /* GPIOC, PIN 16 */ +# define SAM3U_IRQ_PC17 (SAM3U_IRQ_GPIOC_PINS+17) /* GPIOC, PIN 17 */ +# define SAM3U_IRQ_PC18 (SAM3U_IRQ_GPIOC_PINS+18) /* GPIOC, PIN 18 */ +# define SAM3U_IRQ_PC19 (SAM3U_IRQ_GPIOC_PINS+19) /* GPIOC, PIN 19 */ +# define SAM3U_IRQ_PC20 (SAM3U_IRQ_GPIOC_PINS+20) /* GPIOC, PIN 20 */ +# define SAM3U_IRQ_PC21 (SAM3U_IRQ_GPIOC_PINS+21) /* GPIOC, PIN 21 */ +# define SAM3U_IRQ_PC22 (SAM3U_IRQ_GPIOC_PINS+22) /* GPIOC, PIN 22 */ +# define SAM3U_IRQ_PC23 (SAM3U_IRQ_GPIOC_PINS+23) /* GPIOC, PIN 23 */ +# define SAM3U_IRQ_PC24 (SAM3U_IRQ_GPIOC_PINS+24) /* GPIOC, PIN 24 */ +# define SAM3U_IRQ_PC25 (SAM3U_IRQ_GPIOC_PINS+25) /* GPIOC, PIN 25 */ +# define SAM3U_IRQ_PC26 (SAM3U_IRQ_GPIOC_PINS+26) /* GPIOC, PIN 26 */ +# define SAM3U_IRQ_PC27 (SAM3U_IRQ_GPIOC_PINS+27) /* GPIOC, PIN 27 */ +# define SAM3U_IRQ_PC28 (SAM3U_IRQ_GPIOC_PINS+28) /* GPIOC, PIN 28 */ +# define SAM3U_IRQ_PC29 (SAM3U_IRQ_GPIOC_PINS+29) /* GPIOC, PIN 29 */ +# define SAM3U_IRQ_PC30 (SAM3U_IRQ_GPIOC_PINS+30) /* GPIOC, PIN 30 */ +# define SAM3U_IRQ_PC31 (SAM3U_IRQ_GPIOC_PINS+31) /* GPIOC, PIN 31 */ +# define SAM3U_NGPIOAIRQS 32 +#else +# define SAM3U_NGPIOCIRQS 0 +#endif + +/* Total number of IRQ numbers */ + +#define NR_IRQS (SAM3U_IRQ_EXTINT+SAM3U_IRQ_NEXTINT+\ + SAM3U_NGPIOAIRQS+SAM3U_NGPIOBIRQS+SAM3U_NGPIOCIRQS) /**************************************************************************************** * Public Types diff --git a/nuttx/arch/arm/src/sam3u/Make.defs b/nuttx/arch/arm/src/sam3u/Make.defs index 2e7fd965a..4c1bc0575 100755 --- a/nuttx/arch/arm/src/sam3u/Make.defs +++ b/nuttx/arch/arm/src/sam3u/Make.defs @@ -45,6 +45,6 @@ CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copystate.c \ up_usestack.c up_doirq.c up_hardfault.c up_svcall.c CHIP_ASRCS = -CHIP_CSRCS = sam3u_clockconfig.c sam3u_irq.c sam3u_lowputc.c sam3u_pio.c \ - sam3u_serial.c sam3u_start.c sam3u_timerisr.c +CHIP_CSRCS = sam3u_clockconfig.c sam3u_gpioirq.c sam3u_irq.c sam3u_lowputc.c \ + sam3u_pio.c sam3u_serial.c sam3u_start.c sam3u_timerisr.c diff --git a/nuttx/arch/arm/src/sam3u/sam3u_gpioirq.c b/nuttx/arch/arm/src/sam3u/sam3u_gpioirq.c new file mode 100755 index 000000000..bcc597b86 --- /dev/null +++ b/nuttx/arch/arm/src/sam3u/sam3u_gpioirq.c @@ -0,0 +1,367 @@ +/**************************************************************************** + * arch/arm/src/sam3u/sam3u_gpioirq.c + * arch/arm/src/chip/sam3u_gpioirq.c + * + * Copyright (C) 2010 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 + +#include +#include + +#include "up_arch.h" +#include "up_internal.h" + +#include "sam3u_internal.h" +#include "sam3u_pio.h" +#include "sam3u_pmc.h" + +#ifdef CONFIG_GPIO_IRQ + +/**************************************************************************** + * Private Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: sam3u_gpiobase + * + * Description: + * Return the base address of the GPIO register set + * + ****************************************************************************/ + +static inline uint32_t sam3u_gpiobase(uint16_t pinset) +{ + int port = (pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT; + return SAM3U_PION_BASE(port >> GPIO_PORT_SHIFT); +} + +/**************************************************************************** + * Name: sam3u_gpiopin + * + * Description: + * Returun the base address of the GPIO register set + * + ****************************************************************************/ + +static inline int sam3u_gpiopin(uint16_t pinset) +{ + return 1 << ((pinset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT); +} + +/**************************************************************************** + * Name: sam3u_irqbase + * + * Description: + * Return gpio information associated with this IRQ + * + ****************************************************************************/ + +static int sam3u_irqbase(int irq, uint32_t *base, int *pin) +{ + if (irq >= SAM3U_IRQ_NIRQS) + { +#ifdef CONFIG_GPIOA_IRQ + if (irq <= SAM3U_IRQ_PA31) + { + *base = SAM3U_PIOA_BASE; + *pin = irq - SAM3U_IRQ_PA0; + return OK; + } +#endif +#ifdef CONFIG_GPIOB_IRQ + if (irq <= SAM3U_IRQ_PB31) + { + *base = SAM3U_PIOB_BASE; + *pin = irq - SAM3U_IRQ_PB0; + return OK; + } +#endif +#ifdef CONFIG_GPIOC_IRQ + if (irq <= SAM3U_IRQ_PC31) + { + *base = SAM3U_PIOC_BASE; + *pin = irq - SAM3U_IRQ_PC0; + return OK; + } +#endif + } + return -EINVAL; +} + +/**************************************************************************** + * Name: up_gpioa/b/cinterrupt + * + * Description: + * Receive GPIOA/B/C interrupts + * + ****************************************************************************/ + +static int up_gpiointerrupt(uint32_t base, int irq0, void *context) +{ + uint32_t pending; + uint32_t bit; + int irq; + + pending = getreg32(base+SAM3U_PIO_ISR_OFFSET) & getreg32(base+SAM3U_PIO_IMR_OFFSET); + for (bit = 1, irq = irq0; pending != 0; bit <<= 1, irq++) + { + if ((pending & bit) != 0) + { + /* Re-deliver the IRQ (recurses! We got here from irq_dispatch!) */ + + irq_dispatch(irq, context); + + /* Remove this from the set of pending interrupts */ + + pending &= ~bit; + } + } + return OK; +} + +#ifdef CONFIG_GPIOA_IRQ +static int up_gpioainterrupt(int irq, void *context) +{ + return up_gpiointerrupt(SAM3U_PIOA_BASE, SAM3U_IRQ_PA0, context); +} +#endif + +#ifdef CONFIG_GPIOB_IRQ +static int up_gpiobinterrupt(int irq, void *context) +{ + return up_gpiointerrupt(SAM3U_PIOB_BASE, SAM3U_IRQ_PB0, context); +} +#endif + +#ifdef CONFIG_GPIOC_IRQ +static int up_gpiocinterrupt(int irq, void *context) +{ + return up_gpiointerrupt(SAM3U_PIOC_BASE, SAM3U_IRQ_PC0, context); +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: sam3u_gpioirqinitialize + * + * Description: + * Initialize logic to support a second level of interrupt decoding for + * GPIO pins. + * + ****************************************************************************/ + +void sam3u_gpioirqinitialize(void) +{ + uint32_t pcer; + + /* Configure GPIOA interrupts */ + +#ifdef CONFIG_GPIOA_IRQ + /* Enable GPIOA clocking */ + + pcer |= (1 << SAM3U_PID_PIOA); + putreg32(pcer, SAM3U_PMC_PCER); + + /* Clear and disable all GPIOA interrupts */ + + (void)getreg32(SAM3U_PIOA_ISR); + putreg32(0xffffffff, SAM3U_PIOA_IDR); + + /* Attach and enable the GPIOA IRQ */ + + (void)irq_attach(SAM3U_IRQ_PIOA, up_gpioainterrupt); + up_enable_irq(SAM3U_IRQ_PIOA); +#endif + + /* Configure GPIOB interrupts */ + +#ifdef CONFIG_GPIOB_IRQ + /* Enable GPIOB clocking */ + + pcer |= (1 << SAM3U_PID_PIOB); + putreg32(pcer, SAM3U_PMC_PCER); + + /* Clear and disable all GPIOB interrupts */ + + (void)getreg32(SAM3U_PIOB_ISR); + putreg32(0xffffffff, SAM3U_PIOB_IDR); + + /* Attach and enable the GPIOB IRQ */ + + (void)irq_attach(SAM3U_IRQ_PIOB, up_gpiobinterrupt); + up_enable_irq(SAM3U_IRQ_PIOB); +#endif + + /* Configure GPIOC interrupts */ + +#ifdef CONFIG_GPIOC_IRQ + /* Enable GPIOC clocking */ + + pcer |= (1 << SAM3U_PID_PIOC); + putreg32(pcer, SAM3U_PMC_PCER); + + /* Clear and disable all GPIOC interrupts */ + + (void)getreg32(SAM3U_PIOC_ISR); + putreg32(0xffffffff, SAM3U_PIOC_IDR); + + /* Attach and enable the GPIOC IRQ */ + + (void)irq_attach(SAM3U_IRQ_PIOC, up_gpioainterrupt); + up_enable_irq(SAM3U_IRQ_PIOC); +#endif +} + +/************************************************************************************ + * Name: sam3u_gpioirq + * + * Description: + * Configure an interrupt for the specified GPIO pin. + * + ************************************************************************************/ + +void sam3u_gpioirq(uint16_t pinset) +{ + uint32_t base = sam3u_gpiobase(pinset); + int pin = sam3u_gpiopin(pinset); + + /* Are any additional interrupt modes selected? */ + + if ((pinset & GPIO_INT_MASK) != 0) + { + /* Yes.. Enable additional interrupt mode */ + + putreg32(pin, base+SAM3U_PIO_AIMER_OFFSET); + + /* Level or edge detected interrupt? */ + + if ((pinset & GPIO_INT_LEVEL) != 0) + { + putreg32(pin, base+SAM3U_PIO_LSR_OFFSET); /* Level */ + } + else + { + putreg32(pin, base+SAM3U_PIO_ESR_OFFSET); /* Edge */ + } + + /* High level/rising edge or low level /falling edge? */ + + if ((pinset & GPIO_INT_HIGHLEVEL) != 0) + { + putreg32(pin, base+SAM3U_PIO_REHLSR_OFFSET); /* High level/Rising edge */ + } + else + { + putreg32(pin, base+SAM3U_PIO_FELLSR_OFFSET); /* Low level/Falling edge */ + } + } + else + { + /* No.. Disable additional interrupt mode */ + + putreg32(pin, base+SAM3U_PIO_AIMDR_OFFSET); + } +} + +/************************************************************************************ + * Name: sam3u_gpioirqenable + * + * Description: + * Enable the interrupt for specified GPIO IRQ + * + ************************************************************************************/ + +void sam3u_gpioirqenable(int irq) +{ + uint32_t base; + int pin; + + if (sam3u_irqbase(irq, &base, &pin) == OK) + { + /* Clear (all) pending interrupts and enable this pin interrupt */ + + (void)getreg32(base+SAM3U_PIO_ISR_OFFSET); + putreg32((1 << pin), base+SAM3U_PIO_IER_OFFSET); + } +} + +/************************************************************************************ + * Name: sam3u_gpioirqdisable + * + * Description: + * Disable the interrupt for specified GPIO IRQ + * + ************************************************************************************/ + +void sam3u_gpioirqdisable(int irq) +{ + uint32_t base; + int pin; + + if (sam3u_irqbase(irq, &base, &pin) == OK) + { + /* Disable this pin interrupt */ + + putreg32((1 << pin), base+SAM3U_PIO_IDR_OFFSET); + } +} + +#endif /* CONFIG_GPIO_IRQ */ \ No newline at end of file diff --git a/nuttx/arch/arm/src/sam3u/sam3u_internal.h b/nuttx/arch/arm/src/sam3u/sam3u_internal.h index d82076a79..440bcfece 100755 --- a/nuttx/arch/arm/src/sam3u/sam3u_internal.h +++ b/nuttx/arch/arm/src/sam3u/sam3u_internal.h @@ -41,6 +41,7 @@ ************************************************************************************/ #include +#include #include #include @@ -55,10 +56,16 @@ /* Configuration ********************************************************************/ +#if defined(CONFIG_GPIOA_IRQ) || defined(CONFIG_GPIOB_IRQ) || defined(CONFIG_GPIOC_IRQ) +# define CONFIG_GPIO_IRQ 1 +#else +# undef CONFIG_GPIO_IRQ +#endif + /* Bit-encoded input to sam3u_configgpio() ******************************************/ /* 16-bit Encoding: - * MMCC C... VPPB BBBB + * MMCC CII. VPPB BBBB */ /* Input/Output mode: @@ -84,6 +91,19 @@ # define GPIO_CFG_DEGLITCH (2 << GPIO_CFG_SHIFT) /* Bit 12: Internal glitch filter */ # define GPIO_CFG_OPENDRAIN (4 << GPIO_CFG_SHIFT) /* Bit 13: Open drain */ +/* Additional interrupt modes: + * .... .II. .... .... + */ + +#define GPIO_INT_SHIFT (9) /* Bits 9-10: GPIO configuration bits */ +#define GPIO_INT_MASK (3 << GPIO_INT_SHIFT) +# define GPIO_INT_LEVEL (1 << 10) /* Bit 10: Level detection interrupt */ +# define GPIO_INT_EDGE (0) /* (vs. Edge detection interrupt) */ +# define GPIO_INT_HIGHLEVEL (1 << 9) /* Bit 9: High level detection interrupt */ +# define GPIO_INT_LOWLEVEL (0) /* (vs. Low level detection interrupt) */ +# define GPIO_INT_RISING (1 << 9) /* Bit 9: Rising edge detection interrupt */ +# define GPIO_INT_FALLING (0) /* (vs. Falling edge detection interrupt) */ + /* If the pin is an GPIO output, then this identifies the initial output value: * .... .... V... .... */ @@ -323,6 +343,20 @@ EXTERN void sam3u_clockconfig(void); EXTERN void sam3u_lowsetup(void); +/************************************************************************************ + * Name: sam3u_gpioirqinitialize + * + * Description: + * Initialize logic to support a second level of interrupt decoding for GPIO pins. + * + ************************************************************************************/ + +#ifdef CONFIG_GPIO_IRQ +EXTERN void sam3u_gpioirqinitialize(void); +#else +# define sam3u_gpioirqinitialize() +#endif + /************************************************************************************ * Name: sam3u_configgpio * @@ -353,6 +387,48 @@ EXTERN void sam3u_gpiowrite(uint16_t pinset, bool value); EXTERN bool sam3u_gpioread(uint16_t pinset); +/************************************************************************************ + * Name: sam3u_gpioirq + * + * Description: + * Configure an interrupt for the specified GPIO pin. + * + ************************************************************************************/ + +#ifdef CONFIG_GPIO_IRQ +EXTERN void sam3u_gpioirq(uint16_t pinset); +#else +# define sam3u_gpioirq(pinset) +#endif + +/************************************************************************************ + * Name: sam3u_gpioirqenable + * + * Description: + * Enable the interrupt for specified GPIO IRQ + * + ************************************************************************************/ + +#ifdef CONFIG_GPIO_IRQ +EXTERN void sam3u_gpioirqenable(int irq); +#else +# define sam3u_gpioirqenable(irq) +#endif + +/************************************************************************************ + * Name: sam3u_gpioirqdisable + * + * Description: + * Disable the interrupt for specified GPIO IRQ + * + ************************************************************************************/ + +#ifdef CONFIG_GPIO_IRQ +EXTERN void sam3u_gpioirqdisable(int irq); +#else +# define sam3u_gpioirqdisable(irq) +#endif + #undef EXTERN #if defined(__cplusplus) } diff --git a/nuttx/arch/arm/src/sam3u/sam3u_irq.c b/nuttx/arch/arm/src/sam3u/sam3u_irq.c index d7be1f3d2..6ab7d2551 100755 --- a/nuttx/arch/arm/src/sam3u/sam3u_irq.c +++ b/nuttx/arch/arm/src/sam3u/sam3u_irq.c @@ -209,7 +209,7 @@ static int sam3u_irqinfo(int irq, uint32_t *regaddr, uint32_t *bit) if (irq >= SAM3U_IRQ_EXTINT) { - if (irq < NR_IRQS) + if (irq < SAM3U_IRQ_NIRQS) { *regaddr = NVIC_IRQ0_31_ENABLE; *bit = 1 << (irq - SAM3U_IRQ_EXTINT); @@ -317,7 +317,7 @@ void up_irqinitialize(void) irq_attach(SAM3U_IRQ_RESERVED, sam3u_reserved); #endif - sam3u_dumpnvic("initial", NR_IRQS); + sam3u_dumpnvic("initial", SAM3U_IRQ_NIRQS); #ifndef CONFIG_SUPPRESS_INTERRUPTS @@ -327,6 +327,14 @@ void up_irqinitialize(void) up_fiqinitialize(); #endif + /* Initialize logic to support a second level of interrupt decoding for + * GPIO pins. + */ + +#ifdef CONFIG_GPIO_IRQ + sam3u_gpioirqinitialize(); +#endif + /* And finally, enable interrupts */ setbasepri(NVIC_SYSH_PRIORITY_MAX); @@ -356,6 +364,14 @@ void up_disable_irq(int irq) regval &= ~bit; putreg32(regval, regaddr); } +#ifdef CONFIG_GPIO_IRQ + else + { + /* Maybe it is a (derived) GPIO IRQ */ + + sam3u_gpioirqdisable(irq); + } +#endif sam3u_dumpnvic("disable", irq); } @@ -381,6 +397,14 @@ void up_enable_irq(int irq) regval |= bit; putreg32(regval, regaddr); } +#ifdef CONFIG_GPIO_IRQ + else + { + /* Maybe it is a (derived) GPIO IRQ */ + + sam3u_gpioirqenable(irq); + } +#endif sam3u_dumpnvic("enable", irq); } @@ -415,7 +439,7 @@ int up_prioritize_irq(int irq, int priority) uint32_t regval; int shift; - DEBUGASSERT(irq >= SAM3U_IRQ_MPU && irq < NR_IRQS && (unsigned)priority <= NVIC_SYSH_PRIORITY_MIN); + DEBUGASSERT(irq >= SAM3U_IRQ_MPU && irq < SAM3U_IRQ_NIRQS && (unsigned)priority <= NVIC_SYSH_PRIORITY_MIN); if (irq < SAM3U_IRQ_EXTINT) { diff --git a/nuttx/arch/arm/src/sam3u/sam3u_pio.c b/nuttx/arch/arm/src/sam3u/sam3u_pio.c index 7ae1d90b4..717f00423 100755 --- a/nuttx/arch/arm/src/sam3u/sam3u_pio.c +++ b/nuttx/arch/arm/src/sam3u/sam3u_pio.c @@ -73,7 +73,7 @@ * Name: sam3u_gpiobase * * Description: - * Returun the base address of the GPIO register set + * Return the base address of the GPIO register set * ****************************************************************************/ diff --git a/nuttx/configs/sam3u-ek/README.txt b/nuttx/configs/sam3u-ek/README.txt index 50cc78dda..42cab8243 100755 --- a/nuttx/configs/sam3u-ek/README.txt +++ b/nuttx/configs/sam3u-ek/README.txt @@ -250,19 +250,22 @@ SAM3U-EK-specific Configuration Options Individual subsystems can be enabled: - CONFIG_SAM3U_UART=y - CONFIG_SAM3U_USART0=n - CONFIG_SAM3U_USART1=n - CONFIG_SAM3U_USART2=n - CONFIG_SAM3U_USART3=n + CONFIG_SAM3U_UART + CONFIG_SAM3U_USART0 + CONFIG_SAM3U_USART1 + CONFIG_SAM3U_USART2 + CONFIG_SAM3U_USART3 Some subsystems can be configured to operate in different ways. The drivers need to know how to configure the subsystem. - CONFIG_USART0_ISUART=y - CONFIG_USART1_ISUART=y - CONFIG_USART2_ISUART=y - CONFIG_USART3_ISUART=y + CONFIG_GPIOA_IRQ + CONFIG_GPIOB_IRQ + CONFIG_GPIOC_IRQ + CONFIG_USART0_ISUART + CONFIG_USART1_ISUART + CONFIG_USART2_ISUART + CONFIG_USART3_ISUART AT91SAM3U specific device driver settings diff --git a/nuttx/configs/sam3u-ek/include/board.h b/nuttx/configs/sam3u-ek/include/board.h index 2be5712da..6543acde3 100755 --- a/nuttx/configs/sam3u-ek/include/board.h +++ b/nuttx/configs/sam3u-ek/include/board.h @@ -42,12 +42,15 @@ ************************************************************************************/ #include +#include "sam3u_internal.h" + #ifndef __ASSEMBLY__ -# include +# include +# ifdef CONFIG_GPIO_IRQ +# include +# endif #endif -#include "sam3u_internal.h" - /************************************************************************************ * Definitions ************************************************************************************/ @@ -94,7 +97,12 @@ #define LED_INIRQ 4 /* LED0=XXX LED1=TOG LED2=XXX */ #define LED_SIGNAL 5 /* LED0=XXX LED1=XXX LED2=TOG */ #define LED_ASSERTION 6 /* LED0=TOG LED1=XXX LED2=XXX */ -#define LED_PANIC 7 /* LED0=TOG LED1=XXX LED2=XXX*/ +#define LED_PANIC 7 /* LED0=TOG LED1=XXX LED2=XXX */ + +/* Button definitions ***************************************************************/ + +#define BUTTON1 1 /* Bit 0: Button 1 */ +#define BUTTON2 2 /* Bit 1: Button 2 */ /************************************************************************************ * Public Data @@ -126,20 +134,47 @@ extern "C" { EXTERN void sam3u_boardinitialize(void); /************************************************************************************ - * Button support. + * Name: up_buttoninit * * Description: * up_buttoninit() must be called to initialize button resources. After that, * up_buttons() may be called to collect the state of all buttons. up_buttons() * returns an 8-bit bit set with each bit associated with a button. See the - * BUTTON_* and JOYSTICK_* definitions above for the meaning of each bit. + * BUTTON* definitions above for the meaning of each bit in the returned value. * ************************************************************************************/ #ifdef CONFIG_ARCH_BUTTONS EXTERN void up_buttoninit(void); + +/************************************************************************************ + * Name: up_buttons + * + * Description: + * After up_buttoninit() has been called, up_buttons() may be called to collect + * the state of all buttons. up_buttons() returns an 8-bit bit set with each bit + * associated with a button. See the BUTTON* definitions above for the meaning of + * each bit in the returned value. + * + ************************************************************************************/ + EXTERN uint8_t up_buttons(void); + +/************************************************************************************ + * Name: up_irqbutton1/2 + * + * Description: + * These functions may be called to register an interrupt handler that will be + * called when BUTTON1/2 is depressed. The previous interrupt handler value is + * returned (so that it may restored, if so desired). + * + ************************************************************************************/ + +#ifdef CONFIG_GPIOA_IRQ +EXTERN xcpt_t up_irqbutton1(xcpt_t irqhandler); +EXTERN xcpt_t up_irqbutton2(xcpt_t irqhandler); #endif +#endif /* CONFIG_ARCH_BUTTONS */ #undef EXTERN #if defined(__cplusplus) diff --git a/nuttx/configs/sam3u-ek/ostest/defconfig b/nuttx/configs/sam3u-ek/ostest/defconfig index ad36b1b61..96fd1cd67 100755 --- a/nuttx/configs/sam3u-ek/ostest/defconfig +++ b/nuttx/configs/sam3u-ek/ostest/defconfig @@ -74,7 +74,7 @@ CONFIG_ARCH_ARM=y CONFIG_ARCH_CORTEXM3=y CONFIG_ARCH_CHIP=sam3u CONFIG_ARCH_CHIP_AT91SAM3U4=y -CONFIG_ARCH_BOARD=sam3u_ek +CONFIG_ARCH_BOARD=sam3u-ek CONFIG_ARCH_BOARD_SAM3UEK=y CONFIG_BOARD_LOOPSPERMSEC=5483 CONFIG_DRAM_SIZE=0x00010000 @@ -85,7 +85,7 @@ CONFIG_ARCH_INTERRUPTSTACK=n CONFIG_ARCH_STACKDUMP=y CONFIG_ARCH_BOOTLOADER=n CONFIG_ARCH_LEDS=y -CONFIG_ARCH_BUTTONS=n +CONFIG_ARCH_BUTTONS=y CONFIG_ARCH_CALIBRATION=n CONFIG_ARCH_DMA=n @@ -110,6 +110,10 @@ CONFIG_SAM3U_USART3=n # Some subsystems can be configured to operate in different ways.. # The drivers need to know how to configure the subsystem. # + +CONFIG_GPIOA_IRQ=n +CONFIG_GPIOB_IRQ=n +CONFIG_GPIOC_IRQ=n CONFIG_USART0_ISUART=y CONFIG_USART1_ISUART=y CONFIG_USART2_ISUART=y diff --git a/nuttx/configs/sam3u-ek/src/sam3uek_internal.h b/nuttx/configs/sam3u-ek/src/sam3uek_internal.h index fde22f7d8..0e816204b 100755 --- a/nuttx/configs/sam3u-ek/src/sam3uek_internal.h +++ b/nuttx/configs/sam3u-ek/src/sam3uek_internal.h @@ -43,6 +43,7 @@ #include #include +#include #include /************************************************************************************ @@ -64,6 +65,9 @@ #define GPIO_BUTTON1 (GPIO_INPUT|GPIO_CFG_PULLUP|GPIO_CFG_DEGLITCH|GPIO_PORT_PIOA|GPIO_PIN18) #define GPIO_BUTTON2 (GPIO_INPUT|GPIO_CFG_PULLUP|GPIO_CFG_DEGLITCH|GPIO_PORT_PIOA|GPIO_PIN19) +#define IRQ_BUTTON1 SAM3U_IRQ_PA18 +#define IRQ_BUTTON2 SAM3U_IRQ_PA19 + /* SPI Chip Selects */ /************************************************************************************ diff --git a/nuttx/configs/sam3u-ek/src/up_buttons.c b/nuttx/configs/sam3u-ek/src/up_buttons.c index abbe502c2..ea8fe0aaf 100755 --- a/nuttx/configs/sam3u-ek/src/up_buttons.c +++ b/nuttx/configs/sam3u-ek/src/up_buttons.c @@ -1,7 +1,7 @@ /**************************************************************************** * configs/sam3u-ek/src/up_leds.c * - * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2010 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -41,7 +41,12 @@ #include +#include + +#include #include + +#include "sam3u_internal.h" #include "sam3uek_internal.h" #ifdef CONFIG_ARCH_BUTTONS @@ -54,6 +59,9 @@ * Private Data ****************************************************************************/ +static xcpt_t g_irqbutton1; +static xcpt_t g_irqbutton2; + /**************************************************************************** * Private Functions ****************************************************************************/ @@ -68,6 +76,8 @@ void up_buttoninit(void) { + (void)sam3u_configgpio(GPIO_BUTTON1); + (void)sam3u_configgpio(GPIO_BUTTON2); } /**************************************************************************** @@ -76,7 +86,76 @@ void up_buttoninit(void) uint8_t up_buttons(void) { - return 0; + uint8_t retval; + + retval = sam3u_gpioread(GPIO_BUTTON1) ? 0 : GPIO_BUTTON1; + retval |= sam3u_gpioread(GPIO_BUTTON2) ? 0 : GPIO_BUTTON2; + + return retval; +} + +/**************************************************************************** + * Name: up_irqbutton1 + ****************************************************************************/ + +#ifdef CONFIG_GPIOA_IRQ +xcpt_t up_irqbutton1(xcpt_t irqhandler) +{ + xcpt_t oldhandler; + irqstate_t flags; + + /* Disable interrupts until we are done */ + + flags = irqsave(); + + /* Get the old button interrupt handler and save the new one */ + + oldhandler = g_irqbutton1; + g_irqbutton1 = irqhandler; + + /* Configure the interrupt */ + + sam3u_gpioirq(IRQ_BUTTON1); + (void)irq_attach(IRQ_BUTTON1, irqhandler); + sam3u_gpioirqenable(IRQ_BUTTON1); + irqrestore(flags); + + /* Return the old button handler (so that it can be restored) */ + + return oldhandler; +} +#endif + +/**************************************************************************** + * Name: up_irqbutton2 + ****************************************************************************/ + +#ifdef CONFIG_GPIOA_IRQ +xcpt_t up_irqbutton2(xcpt_t irqhandler) +{ + xcpt_t oldhandler; + irqstate_t flags; + + /* Disable interrupts until we are done */ + + flags = irqsave(); + + /* Get the old button interrupt handler and save the new one */ + + oldhandler = g_irqbutton2; + g_irqbutton2 = irqhandler; + + /* Configure the interrupt */ + + sam3u_gpioirq(IRQ_BUTTON2); + (void)irq_attach(IRQ_BUTTON2, irqhandler); + sam3u_gpioirqenable(IRQ_BUTTON2); + irqrestore(flags); + + /* Return the old button handler (so that it can be restored) */ + + return oldhandler; } +#endif #endif /* CONFIG_ARCH_BUTTONS */ diff --git a/nuttx/include/nuttx/arch.h b/nuttx/include/nuttx/arch.h index e7c26970f..f7e7738aa 100644 --- a/nuttx/include/nuttx/arch.h +++ b/nuttx/include/nuttx/arch.h @@ -1,7 +1,7 @@ /**************************************************************************** * include/nuttx/arch.h * - * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2010 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without diff --git a/nuttx/include/nuttx/irq.h b/nuttx/include/nuttx/irq.h index b7ecac2d8..5c83d9587 100644 --- a/nuttx/include/nuttx/irq.h +++ b/nuttx/include/nuttx/irq.h @@ -1,7 +1,7 @@ /**************************************************************************** * include/nuttx/irq.h * - * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2010 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -33,8 +33,8 @@ * ****************************************************************************/ -#ifndef __IRQ_H -#define __IRQ_H +#ifndef __INCLUDE_NUTTX_IRQ_H +#define __INCLUDE_NUTTX_IRQ_H /**************************************************************************** * Included Files @@ -91,5 +91,5 @@ EXTERN int irq_attach(int irq, xcpt_t isr); #endif #endif -#endif /* __IRQ_H */ +#endif /* __INCLUDE_NUTTX_IRQ_H */ -- cgit v1.2.3