summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2010-10-17 17:38:40 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2010-10-17 17:38:40 +0000
commit93ba4af2ff1dacc63106796eb22f294e7d9030b0 (patch)
tree4a09e894cd6f4a2f031fb8ab8f3feed67e22cce9
parent0956ec5b471ce98d3ee0bdad3d95e8f55881ccd9 (diff)
downloadpx4-nuttx-93ba4af2ff1dacc63106796eb22f294e7d9030b0.tar.gz
px4-nuttx-93ba4af2ff1dacc63106796eb22f294e7d9030b0.tar.bz2
px4-nuttx-93ba4af2ff1dacc63106796eb22f294e7d9030b0.zip
Add button logic
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3030 42af7a65-404d-4744-a932-0658087f49c3
-rwxr-xr-xnuttx/arch/avr/include/at91uc3/irq.h342
-rwxr-xr-xnuttx/arch/avr/src/at91uc3/Make.defs4
-rwxr-xr-xnuttx/arch/avr/src/at91uc3/at91uc3_config.h6
-rw-r--r--nuttx/arch/avr/src/at91uc3/at91uc3_gpioirq.c428
-rwxr-xr-xnuttx/arch/avr/src/at91uc3/at91uc3_internal.h151
-rw-r--r--nuttx/arch/avr/src/at91uc3/at91uc3_irq.c7
-rw-r--r--nuttx/arch/avr/src/at91uc3/at91uc3_lowconsole.c5
-rwxr-xr-xnuttx/arch/avr/src/at91uc3/at91uc3_pm.h30
-rwxr-xr-xnuttx/configs/avr32dev1/README.txt4
-rwxr-xr-xnuttx/configs/avr32dev1/include/board.h15
-rwxr-xr-xnuttx/configs/avr32dev1/ostest/defconfig10
-rwxr-xr-xnuttx/configs/avr32dev1/src/avr32dev1_internal.h30
-rwxr-xr-xnuttx/configs/avr32dev1/src/up_buttons.c65
13 files changed, 1026 insertions, 71 deletions
diff --git a/nuttx/arch/avr/include/at91uc3/irq.h b/nuttx/arch/avr/include/at91uc3/irq.h
index 9317f8f18..09e94dfa4 100755
--- a/nuttx/arch/avr/include/at91uc3/irq.h
+++ b/nuttx/arch/avr/include/at91uc3/irq.h
@@ -51,8 +51,20 @@
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
+
+/* Configuration ************************************************************/
+/* Configuration CONFIG_AVR32_GPIOIRQ must be selected to enable the overall
+ * GPIO IRQ feature and CONFIG_AVR32_GPIOIRQSETA and/or
+ * CONFIG_AVR32_GPIOIRQSETB must be enabled to select GPIOs to support
+ * interrupts on.
+ */
+
+#ifndef CONFIG_AVR32_GPIOIRQ
+# undef CONFIG_AVR32_GPIOIRQSETA
+# undef CONFIG_AVR32_GPIOIRQSETB
+#endif
-/* IRQ numbers */
+/* IRQ numbers **************************************************************/
/* Events. These exclude:
*
* - The Reset event which vectors directly either to 0x8000:0000 (uc3a) or
@@ -261,6 +273,334 @@
#define AVR32_IRQ_BADVECTOR 61 /* Not a real IRQ number */
#define NR_IRQS 61
+/* GPIO IRQ Numbers *********************************************************/
+/* These numbers correspond to GPIO port numbers that have interrupts
+ * enabled. These are all decoded by the AVR32_IRQ_GPIO interrupt handler.
+ * A lot of effort was made here to keep the number of IRQs to a minimum
+ * since it will correspond to various, internal table sizes.
+ */
+
+/* Up to 32 GPIO interrupts in PORTA0-31 */
+
+#define __IRQ_GPPIO_PA0 0
+
+#if (CONFIG_AVR32_GPIOIRQSETA & 0x00000001) != 0
+# define AVR32_IRQ_GPIO_PA0 __IRQ_GPPIO_PA0
+# define __IRQ_GPIO_PA1 (__IRQ_GPPIO_PA0+1)
+#else
+# define __IRQ_GPIO_PA1 __IRQ_GPPIO_PA0
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETA & 0x00000002) != 0
+# define AVR32_IRQ_GPIO_PA1 __IRQ_GPIO_PA1
+# define __IRQ_GPIO_PA2 (__IRQ_GPIO_PA1+1)
+#else
+# define __IRQ_GPIO_PA2 __IRQ_GPIO_PA1
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETA & 0x00000004) != 0
+# define AVR32_IRQ_GPIO_PA2 __IRQ_GPIO_PA2
+# define __IRQ_GPIO_PA3 (__IRQ_GPIO_PA2+1)
+#else
+# define __IRQ_GPIO_PA3 __IRQ_GPIO_PA2
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETA & 0x00000008) != 0
+# define AVR32_IRQ_GPIO_PA3 __IRQ_GPIO_PA3
+# define __IRQ_GPIO_PA4 (__IRQ_GPIO_PA3+1)
+#else
+# define __IRQ_GPIO_PA4 __IRQ_GPIO_PA3
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETA & 0x00000010) != 0
+# define AVR32_IRQ_GPIO_PA4 __IRQ_GPIO_PA4
+# define __IRQ_GPIO_PA5 (__IRQ_GPIO_PA4+1)
+#else
+# define __IRQ_GPIO_PA5 __IRQ_GPIO_PA4
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETA & 0x00000020) != 0
+# define AVR32_IRQ_GPIO_PA5 __IRQ_GPIO_PA5
+# define __IRQ_GPIO_PA6 (__IRQ_GPIO_PA5+1)
+#else
+# define __IRQ_GPIO_PA6 __IRQ_GPIO_PA5
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETA & 0x00000040) != 0
+# define AVR32_IRQ_GPIO_PA6 __IRQ_GPIO_PA6
+# define __IRQ_GPIO_PA7 (__IRQ_GPIO_PA6+1)
+#else
+# define __IRQ_GPIO_PA7 __IRQ_GPIO_PA6
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETA & 0x00000080) != 0
+# define AVR32_IRQ_GPIO_PA7 __IRQ_GPIO_PA7
+# define __IRQ_GPIO_PA8 (__IRQ_GPIO_PA7+1)
+#else
+# define __IRQ_GPIO_PA8 __IRQ_GPIO_PA7
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETA & 0x00000100) != 0
+# define AVR32_IRQ_GPIO_PA8 __IRQ_GPIO_PA8
+# define __IRQ_GPIO_PA9 (__IRQ_GPIO_PA8+1)
+#else
+# define __IRQ_GPIO_PA9 __IRQ_GPIO_PA8
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETA & 0x00000200) != 0
+# define AVR32_IRQ_GPIO_PA9 __IRQ_GPIO_PA9
+# define __IRQ_GPIO_PA10 (__IRQ_GPIO_PA9+1)
+#else
+# define __IRQ_GPIO_PA10 __IRQ_GPIO_PA9
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETA & 0x00000400) != 0
+# define AVR32_IRQ_GPIO_PA10 __IRQ_GPIO_PA10
+# define __IRQ_GPIO_PA11 (__IRQ_GPIO_PA10+1)
+#else
+# define __IRQ_GPIO_PA11 __IRQ_GPIO_PA10
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETA & 0x00000800) != 0
+# define AVR32_IRQ_GPIO_PA11 __IRQ_GPIO_PA11
+# define __IRQ_GPIO_PA12 (__IRQ_GPIO_PA11+1)
+#else
+# define __IRQ_GPIO_PA12 __IRQ_GPIO_PA11
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETA & 0x00001000) != 0
+# define AVR32_IRQ_GPIO_PA12 __IRQ_GPIO_PA12
+# define __IRQ_GPIO_PA13 (__IRQ_GPIO_PA12+1)
+#else
+# define __IRQ_GPIO_PA13 __IRQ_GPIO_PA12
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETA & 0x00002000) != 0
+# define AVR32_IRQ_GPIO_PA13 __IRQ_GPIO_PA13
+# define __IRQ_GPIO_PA14 (__IRQ_GPIO_PA13+1)
+#else
+# define __IRQ_GPIO_PA14 __IRQ_GPIO_PA13
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETA & 0x00004000) != 0
+# define AVR32_IRQ_GPIO_PA14 __IRQ_GPIO_PA14
+# define __IRQ_GPIO_PA15 (__IRQ_GPIO_PA14+1)
+#else
+# define __IRQ_GPIO_PA15 __IRQ_GPIO_PA14
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETA & 0x00008000) != 0
+# define AVR32_IRQ_GPIO_PA15 __IRQ_GPIO_PA15
+# define __IRQ_GPIO_PA16 (__IRQ_GPIO_PA15+1)
+#else
+# define __IRQ_GPIO_PA16 __IRQ_GPIO_PA15
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETA & 0x00010000) != 0
+# define AVR32_IRQ_GPIO_PA16 __IRQ_GPIO_PA16
+# define __IRQ_GPIO_PA17 (__IRQ_GPIO_PA16+1)
+#else
+# define __IRQ_GPIO_PA17 __IRQ_GPIO_PA16
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETA & 0x00020000) != 0
+# define AVR32_IRQ_GPIO_PA17 __IRQ_GPIO_PA17
+# define __IRQ_GPIO_PA18 (__IRQ_GPIO_PA17+1)
+#else
+# define __IRQ_GPIO_PA18 __IRQ_GPIO_PA17
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETA & 0x00040000) != 0
+# define AVR32_IRQ_GPIO_PA18 __IRQ_GPIO_PA18
+# define __IRQ_GPIO_PA19 (__IRQ_GPIO_PA18+1)
+#else
+# define __IRQ_GPIO_PA19 __IRQ_GPIO_PA18
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETA & 0x00080000) != 0
+# define AVR32_IRQ_GPIO_PA19 __IRQ_GPIO_PA19
+# define __IRQ_GPIO_PA20 (__IRQ_GPIO_PA19+1)
+#else
+# define __IRQ_GPIO_PA20 __IRQ_GPIO_PA19
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETA & 0x00100000) != 0
+# define AVR32_IRQ_GPIO_PA20 __IRQ_GPIO_PA20
+# define __IRQ_GPIO_PA21 (__IRQ_GPIO_PA20+1)
+#else
+# define __IRQ_GPIO_PA21 __IRQ_GPIO_PA20
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETA & 0x00200000) != 0
+# define AVR32_IRQ_GPIO_PA21 __IRQ_GPIO_PA21
+# define __IRQ_GPIO_PA22 (__IRQ_GPIO_PA21+1)
+#else
+# define __IRQ_GPIO_PA22 __IRQ_GPIO_PA21
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETA & 0x00400000) != 0
+# define AVR32_IRQ_GPIO_PA22 __IRQ_GPIO_PA22
+# define __IRQ_GPIO_PA23 (__IRQ_GPIO_PA22+1)
+#else
+# define __IRQ_GPIO_PA23 __IRQ_GPIO_PA22
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETA & 0x00800000) != 0
+# define AVR32_IRQ_GPIO_PA23 __IRQ_GPIO_PA23
+# define __IRQ_GPIO_PA24 (__IRQ_GPIO_PA23+1)
+#else
+# define __IRQ_GPIO_PA24 __IRQ_GPIO_PA23
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETA & 0x01000000) != 0
+# define AVR32_IRQ_GPIO_PA24 __IRQ_GPIO_PA24
+# define __IRQ_GPIO_PA25 (__IRQ_GPIO_PA24+1)
+#else
+# define __IRQ_GPIO_PA25 __IRQ_GPIO_PA24
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETA & 0x02000000) != 0
+# define AVR32_IRQ_GPIO_PA25 __IRQ_GPIO_PA25
+# define __IRQ_GPIO_PA26 (__IRQ_GPIO_PA25+1)
+#else
+# define __IRQ_GPIO_PA26 __IRQ_GPIO_PA25
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETA & 0x04000000) != 0
+# define AVR32_IRQ_GPIO_PA26 __IRQ_GPIO_PA26
+# define __IRQ_GPIO_PA27 (__IRQ_GPIO_PA26+1)
+#else
+# define __IRQ_GPIO_PA27 __IRQ_GPIO_PA26
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETA & 0x08000000) != 0
+# define AVR32_IRQ_GPIO_PA27 __IRQ_GPIO_PA27
+# define __IRQ_GPIO_PA28 (__IRQ_GPIO_PA27+1)
+#else
+# define __IRQ_GPIO_PA28 __IRQ_GPIO_PA27
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETA & 0x10000000) != 0
+# define AVR32_IRQ_GPIO_PA28 __IRQ_GPIO_PA28
+# define __IRQ_GPIO_PA29 (__IRQ_GPIO_PA28+1)
+#else
+# define __IRQ_GPIO_PA29 __IRQ_GPIO_PA28
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETA & 0x20000000) != 0
+# define AVR32_IRQ_GPIO_PA29 __IRQ_GPIO_PA29
+# define __IRQ_GPIO_PA30 (__IRQ_GPIO_PA29+1)
+#else
+# define __IRQ_GPIO_PA30 __IRQ_GPIO_PA29
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETA & 0x40000000) != 0
+# define AVR32_IRQ_GPIO_PA30 __IRQ_GPIO_PA30
+# define __IRQ_GPIO_PA31 (__IRQ_GPIO_PA30+1)
+#else
+# define __IRQ_GPIO_PA31 __IRQ_GPIO_PA30
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETA & 0x80000000) != 0
+# define AVR32_IRQ_GPIO_PA31 __IRQ_GPIO_PA31
+# define __IRQ_GPIO_PB0 (__IRQ_GPIO_PA31+1)
+#else
+# define __IRQ_GPIO_PB0 __IRQ_GPIO_PA31
+#endif
+
+
+/* Up to 12 GPIO interrupts in PORTB0-11 */
+
+#if (CONFIG_AVR32_GPIOIRQSETB & 0x00000001) != 0
+# define AVR32_IRQ_GPIO_PB0 __IRQ_GPIO_pb0
+# define __IRQ_GPIO_PB1 (__IRQ_GPIO_PB0+1)
+#else
+# define __IRQ_GPIO_PB1 __IRQ_GPIO_PB0
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETB & 0x00000002) != 0
+# define AVR32_IRQ_GPIO_PB1 __IRQ_GPIO_PB1
+# define __IRQ_GPIO_PB2 (__IRQ_GPIO_PB1+1)
+#else
+# define __IRQ_GPIO_PB2 __IRQ_GPIO_PB1
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETB & 0x00000004) != 0
+# define AVR32_IRQ_GPIO_PB2 __IRQ_GPIO_PB2
+# define __IRQ_GPIO_PB3 (__IRQ_GPIO_PB2+1)
+#else
+# define __IRQ_GPIO_PB3 __IRQ_GPIO_PB2
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETB & 0x00000008) != 0
+# define AVR32_IRQ_GPIO_PB3 __IRQ_GPIO_PB3
+# define __IRQ_GPIO_PB4 (__IRQ_GPIO_PB3+1)
+#else
+# define __IRQ_GPIO_PB4 __IRQ_GPIO_PB3
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETB & 0x00000010) != 0
+# define AVR32_IRQ_GPIO_PB4 __IRQ_GPIO_PB4
+# define __IRQ_GPIO_PB5 (__IRQ_GPIO_PB4+1)
+#else
+# define __IRQ_GPIO_PB5 __IRQ_GPIO_PB4
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETB & 0x00000020) != 0
+# define AVR32_IRQ_GPIO_PB5 __IRQ_GPIO_PB5
+# define __IRQ_GPIO_PB6 (__IRQ_GPIO_PB5+1)
+#else
+# define __IRQ_GPIO_PB6 __IRQ_GPIO_PB5
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETB & 0x00000040) != 0
+# define AVR32_IRQ_GPIO_PB6 __IRQ_GPIO_PB6
+# define __IRQ_GPIO_PB7 (__IRQ_GPIO_PB6+1)
+#else
+# define __IRQ_GPIO_PB7 __IRQ_GPIO_PB6
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETB & 0x00000080) != 0
+# define AVR32_IRQ_GPIO_PB7 __IRQ_GPIO_PB7
+# define __IRQ_GPIO_PB8 (__IRQ_GPIO_PB7+1)
+#else
+# define __IRQ_GPIO_PB8 __IRQ_GPIO_PB7
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETB & 0x00000100) != 0
+# define AVR32_IRQ_GPIO_PB8 __IRQ_GPIO_PB8
+# define __IRQ_GPIO_PB9 (__IRQ_GPIO_PB8+1)
+#else
+# define __IRQ_GPIO_PB9 __IRQ_GPIO_PB8
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETB & 0x00000200) != 0
+# define AVR32_IRQ_GPIO_PB9 __IRQ_GPIO_PB9
+# define __IRQ_GPIO_PB10 (__IRQ_GPIO_PB9+1)
+#else
+# define __IRQ_GPIO_PB10 __IRQ_GPIO_PB9
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETB & 0x00000400) != 0
+# define AVR32_IRQ_GPIO_PB10 __IRQ_GPIO_PB10
+# define __IRQ_GPIO_PB11 (__IRQ_GPIO_PB10+1)
+#else
+# define __IRQ_GPIO_PB11 __IRQ_GPIO_PB10
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETB & 0x00000800) != 0
+# define AVR32_IRQ_GPIO_PB11 __IRQ_GPIO_PB11
+# define __IRQ_GPIO_PB12 (__IRQ_GPIO_PB11+1)
+#else
+# define __IRQ_GPIO_PB12 __IRQ_GPIO_PB11
+#endif
+
+#ifdef CONFIG_AVR32_GPIOIRQ
+# define NR_GPIO_IRQS __IRQ_GPIO_PB12
+#else
+# define NR_GPIO_IRQS 0
+#endif
+
/****************************************************************************
* Public Types
****************************************************************************/
diff --git a/nuttx/arch/avr/src/at91uc3/Make.defs b/nuttx/arch/avr/src/at91uc3/Make.defs
index 30600515a..6e2054a2a 100755
--- a/nuttx/arch/avr/src/at91uc3/Make.defs
+++ b/nuttx/arch/avr/src/at91uc3/Make.defs
@@ -57,4 +57,8 @@ CHIP_CSRCS = at91uc3_clkinit.c at91uc3_gpio.c at91uc3_irq.c \
# Configuration-dependent AT91UC3 files
+ifeq ($(CONFIG_AVR32_GPIOIRQ),y)
+CHIP_CSRCS += at91uc3_gpioirq.c
+endif
+
diff --git a/nuttx/arch/avr/src/at91uc3/at91uc3_config.h b/nuttx/arch/avr/src/at91uc3/at91uc3_config.h
index d33ca1f1a..eed6d3f0f 100755
--- a/nuttx/arch/avr/src/at91uc3/at91uc3_config.h
+++ b/nuttx/arch/avr/src/at91uc3/at91uc3_config.h
@@ -154,6 +154,12 @@
# define CONFIG_USE_EARLYSERIALINIT 1
#endif
+/* If GPIO IRQ support is defined, then a set of GPIOs must all be included */
+
+#if CONFIG_AVR32_GPIOIRQSETA == 0 && CONFIG_AVR32_GPIOIRQSETB == 0
+# undef CONFIG_AVR32_GPIOIRQ
+#endif
+
/************************************************************************************
* Public Types
************************************************************************************/
diff --git a/nuttx/arch/avr/src/at91uc3/at91uc3_gpioirq.c b/nuttx/arch/avr/src/at91uc3/at91uc3_gpioirq.c
new file mode 100644
index 000000000..0a74225ec
--- /dev/null
+++ b/nuttx/arch/avr/src/at91uc3/at91uc3_gpioirq.c
@@ -0,0 +1,428 @@
+/****************************************************************************
+ * arch/avr/src/at91uc3/at91uc3_gpioirq.c
+ * arch/avr/src/chip/at91uc3_gpioirq.c
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 <nuttx/config.h>
+#include "at91uc3_config.h"
+
+#include <stdint.h>
+#include <string.h>
+#include <assert.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <arch/irq.h>
+
+#include "up_arch.h"
+#include "os_internal.h"
+#include "irq_internal.h"
+#include "at91uc3_internal.h"
+#include "at91uc3_gpio.h"
+
+#ifdef CONFIG_AVR32_GPIOIRQ
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/* A table of handlers for each GPIO interrupt */
+
+static FAR xcpt_t g_gpiohandler[NR_GPIO_IRQS];
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: gpio_baseaddress
+ *
+ * Input:
+ * irq - A IRQ number in the range of 0 to NR_GPIO_IRQS.
+ *
+ * Description:
+ * Given a IRQ number, return the base address of the associated GPIO
+ * registers.
+ *
+ ****************************************************************************/
+
+static inline uint32_t gpio_baseaddress(unsigned int irq)
+{
+#if CONFIG_AVR32_GPIOIRQSETA != 0
+ if (irq < __IRQ_GPIO_PB0)
+ {
+ return AVR32_GPIO0_BASE;
+ }
+ else
+#endif
+#if CONFIG_AVR32_GPIOIRQSETB != 0
+ if (irq < NR_GPIO_IRQS)
+ {
+ return AVR32_GPIO1_BASE;
+ }
+ else
+#endif
+ {
+ return 0;
+ }
+}
+
+/****************************************************************************
+ * Name: gpio_pin
+ *
+ * Input:
+ * irq - A IRQ number in the range of 0 to NR_GPIO_IRQS.
+ *
+ * Description:
+ * Given a GPIO number, return the pin number in the range of 0-31 on the
+ * corresponding port
+ *
+ ****************************************************************************/
+
+static inline int gpio_pin(unsigned int irq)
+{
+ uint32_t pinset;
+ int pinirq;
+ int pin;
+
+#if CONFIG_AVR32_GPIOIRQSETA != 0
+ if (irq < __IRQ_GPIO_PB0)
+ {
+ pinset = CONFIG_AVR32_GPIOIRQSETA;
+ pinirq = __IRQ_GPIO_PA0;
+ }
+ else
+#endif
+#if CONFIG_AVR32_GPIOIRQSETB != 0
+ if (irq < NR_GPIO_IRQS)
+ {
+ pinset = CONFIG_AVR32_GPIOIRQSETB;
+ pinirq = __IRQ_GPIO_PB0;
+ }
+ else
+#endif
+ {
+ return -EINVAL;
+ }
+
+ /* Now we have to search for the pin with matching IRQ. Yech! We made
+ * life difficult here by choosing a sparse representation of IRQs on
+ * GPIO pins.
+ */
+
+ for (pin = 0; pin < 32 && pinset != 0; pin++)
+ {
+ /* Is this pin at bit 0 configured for interrupt support? */
+
+ if ((pinset & 1) != 0)
+ {
+ /* Is it the on IRQ we are looking for? */
+
+ if (pinirq == irq)
+ {
+ /* Yes, return the associated pin number */
+
+ return pin;
+ }
+
+ /* No.. Increment the IRQ number for the next configured pin */
+
+ pinirq++;
+ }
+
+ /* Shift the next pin to position bit 0 */
+
+ pinset >>= 1;
+ }
+
+ return -EINVAL;
+}
+
+/****************************************************************************
+ * Name: gpio_porthandler
+ *
+ * Description:
+ * Dispatch GPIO interrupts on a specific GPIO port
+ *
+ ****************************************************************************/
+
+static void gpio_porthandler(uint32_t regbase, int irqbase, uint32_t irqset, void *context)
+{
+ uint32_t ifr;
+ int irq;
+ int pin;
+
+ /* Check each bit and dispatch each pending interrupt in the interrupt flag
+ * register for this port.
+ */
+
+ ifr = getreg32(regbase + AVR32_GPIO_IFR_OFFSET);
+
+ /* Dispatch each pending interrupt */
+
+ irq = irqbase;
+ for (pin = 0; pin < 32 && ifr != 0; pin++)
+ {
+ /* Is this pin configured for interrupt support? */
+
+ uint32_t bit = (1 << pin);
+ if ((irqset & bit) != 0)
+ {
+ /* Is an interrupt pending on this pin? */
+
+ if ((ifr & bit) != 0)
+ {
+ /* Yes.. Clear the pending interrupt */
+
+ putreg32(bit, regbase + AVR32_GPIO_IFRC_OFFSET);
+ ifr &= ~bit;
+
+ /* Dispatch handling for this pin */
+
+ xcpt_t handler = g_gpiohandler[irq];
+ if (handler)
+ {
+ handler(irq, context);
+ }
+ else
+ {
+ lldbg("No handler: pin=%d ifr=%08x irqset=%08x",
+ pin, ifr, irqset);
+ }
+ }
+
+ /* Increment the IRQ number on all configured pins */
+
+ irq++;
+ }
+
+ /* Not configured. An interrupt on this pin would be an error. */
+
+ else if ((ifr & bit) != 0)
+ {
+ /* Clear the pending interrupt */
+
+ putreg32(bit, regbase + AVR32_GPIO_IFRC_OFFSET);
+ ifr &= ~bit;
+
+ lldbg("IRQ on unconfigured pin: pin=%d ifr=%08x irqset=%08x",
+ pin, ifr, irqset);
+ }
+ }
+}
+
+/****************************************************************************
+ * Name: gpio0/1_interrupt
+ *
+ * Description:
+ * Handle GPIO0/1 interrupts
+ *
+ ****************************************************************************/
+
+#if CONFIG_AVR32_GPIOIRQSETA != 0
+static int gpio0_interrupt(int irq, FAR void *context)
+{
+ gpio_porthandler(AVR32_GPIO0_BASE, __IRQ_GPIO_PA0,
+ CONFIG_AVR32_GPIOIRQSETA, context);
+ return 0;
+}
+#endif
+
+#if CONFIG_AVR32_GPIOIRQSETB != 0
+static int gpio1_interrupt(int irq, FAR void *context)
+{
+ gpio_porthandler(AVR32_GPIO1_BASE, __IRQ_GPIO_PB0,
+ CONFIG_AVR32_GPIOIRQSETB, context);
+
+ return 0;
+}
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: gpio_irqinitialize
+ *
+ * Description:
+ * Initialize all vectors to the unexpected interrupt handler.
+ *
+ * Assumptions:
+ * Called during the early boot sequence before global interrupts have
+ * been enabled.
+ *
+ ****************************************************************************/
+
+void gpio_irqinitialize(void)
+{
+ int i;
+
+ /* Point all interrupt vectors to the unexpected interrupt */
+
+ for (i = 0; i < NR_GPIO_IRQS; i++)
+ {
+ g_gpiohandler[i] = irq_unexpected_isr;
+ }
+
+ /* Then attach the GPIO interrupt handlers */
+
+#if CONFIG_AVR32_GPIOIRQSETA != 0
+ irq_attach(AVR32_IRQ_GPIO0, gpio0_interrupt);
+#endif
+#if CONFIG_AVR32_GPIOIRQSETB != 0
+ irq_attach(AVR32_IRQ_GPIO1, gpio1_interrupt);
+#endif
+}
+
+/****************************************************************************
+ * Name: gpio_irqattach
+ *
+ * Description:
+ * Attach in GPIO interrupt to the provide 'isr'
+ *
+ ****************************************************************************/
+
+int gpio_irqattach(int irq, xcpt_t newisr, xcpt_t *oldisr)
+{
+ irqstate_t flags;
+ int ret = -EINVAL;
+
+ if ((unsigned)irq < NR_GPIO_IRQS)
+ {
+ /* 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.
+ */
+
+ flags = irqsave();
+ if (newisr == NULL)
+ {
+ gpio_irqdisable(irq);
+ newisr = irq_unexpected_isr;
+ }
+
+ /* Return the old ISR (in case the caller ever wants to restore it) */
+
+ if (oldisr)
+ {
+ *oldisr = g_gpiohandler[irq];
+ }
+
+ /* Then save the new ISR in the table. */
+
+ g_gpiohandler[irq] = newisr;
+ irqrestore(flags);
+ ret = OK;
+ }
+ return ret;
+}
+
+/****************************************************************************
+ * Name: gpio_irqenable
+ *
+ * Description:
+ * Enable the GPIO IRQ specified by 'irq'
+ *
+ ****************************************************************************/
+
+void gpio_irqenable(int irq)
+{
+ uint32_t base;
+ int pin;
+
+ if ((unsigned)irq < NR_GPIO_IRQS)
+ {
+ /* Get the base address of the GPIO module associated with this IRQ */
+
+ base = gpio_baseaddress(irq);
+
+ /* Get the pin number associated with this IRQ. We made life difficult
+ * here by choosing a sparse representation of IRQs on GPIO pins.
+ */
+
+ pin = gpio_pin(irq);
+ DEBUGASSERT(pin >= 0);
+
+ /* Enable the GPIO interrupt. */
+
+ putreg32((1 << pin), base + AVR32_GPIO_IERS_OFFSET);
+ }
+}
+
+/****************************************************************************
+ * Name: gpio_irqdisable
+ *
+ * Description:
+ * Disable the GPIO IRQ specified by 'irq'
+ *
+ ****************************************************************************/
+
+void gpio_irqdisable(int irq)
+{
+ uint32_t base;
+ int pin;
+
+ if ((unsigned)irq < NR_GPIO_IRQS)
+ {
+ /* Get the base address of the GPIO module associated with this IRQ */
+
+ base = gpio_baseaddress(irq);
+
+ /* Get the pin number associated with this IRQ. We made life difficult
+ * here by choosing a sparse representation of IRQs on GPIO pins.
+ */
+
+ pin = gpio_pin(irq);
+ DEBUGASSERT(pin >= 0);
+
+ /* Disable the GPIO interrupt. */
+
+ putreg32((1 << pin), base + AVR32_GPIO_IERC_OFFSET);
+ }
+}
+
+#endif /* CONFIG_AVR32_GPIOIRQ */
diff --git a/nuttx/arch/avr/src/at91uc3/at91uc3_internal.h b/nuttx/arch/avr/src/at91uc3/at91uc3_internal.h
index 45d523aed..7825fd8ee 100755
--- a/nuttx/arch/avr/src/at91uc3/at91uc3_internal.h
+++ b/nuttx/arch/avr/src/at91uc3/at91uc3_internal.h
@@ -1,4 +1,4 @@
-/************************************************************************************
+/****************************************************************************
* arch/avr/src/at91uc3b/at91uc3_internal.h
*
* Copyright (C) 2010 Gregory Nutt. All rights reserved.
@@ -31,25 +31,30 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
- ************************************************************************************/
+ ****************************************************************************/
#ifndef __ARCH_AVR_SRC_AVR32_AT91UC3_INTERNAL_H
#define __ARCH_AVR_SRC_AVR32_AT91UC3_INTERNAL_H
-/************************************************************************************
+/****************************************************************************
* Included Files
- ************************************************************************************/
+ ****************************************************************************/
#include <nuttx/config.h>
+#include "at91uc3_config.h"
+
+#ifdef CONFIG_AVR32_GPIOIRQ
+# include <nuttx/irq.h>
+#endif
#include <stdint.h>
#include <stdbool.h>
-/************************************************************************************
+/****************************************************************************
* Pre-processor Definitions
- ************************************************************************************/
+ ****************************************************************************/
-/* Bit-encoded input to at91uc3_configgpio() ****************************************/
+/* Bit-encoded input to at91uc3_configgpio() ********************************/
/* 16-bit Encoding:
* PERIPHERAL: FMMI UXXG PPPB BBBB with G=0
@@ -143,19 +148,19 @@
#define GPIO_PIN_SHIFT (0) /* Bits 0-4: Port number */
#define GPIO_PIN_MASK (0x1f << GPIO_PIN_SHIFT)
-/************************************************************************************
+/****************************************************************************
* Public Types
- ************************************************************************************/
+ ****************************************************************************/
#ifndef __ASSEMBLY__
-/************************************************************************************
+/****************************************************************************
* Inline Functions
- ************************************************************************************/
+ ****************************************************************************/
-/************************************************************************************
+/****************************************************************************
* Public Data
- ************************************************************************************/
+ ****************************************************************************/
#undef EXTERN
#if defined(__cplusplus)
@@ -165,94 +170,170 @@ extern "C" {
#define EXTERN extern
#endif
-/************************************************************************************
+/****************************************************************************
* Public Function Prototypes
- ************************************************************************************/
+ ****************************************************************************/
-/************************************************************************************
+/****************************************************************************
* Name: up_clkinit
*
* Description:
* Initialiaze clock/PLL settings per the definitions in the board.h file.
*
- ************************************************************************************/
+ ****************************************************************************/
EXTERN void up_clkinitialize(void);
-/******************************************************************************
+/****************************************************************************
* Name: usart_reset
*
* Description:
* Reset a USART.
*
- ******************************************************************************/
+ ****************************************************************************/
EXTERN void usart_reset(uintptr_t usart_base);
-/******************************************************************************
+/****************************************************************************
* Name: usart_configure
*
* Description:
* Configure a USART as a RS-232 UART.
*
- ******************************************************************************/
+ ****************************************************************************/
void usart_configure(uintptr_t usart_base, uint32_t baud, unsigned int parity,
unsigned int nbits, bool stop2);
-/************************************************************************************
+/****************************************************************************
* Name: up_consoleinit
*
* Description:
* Initialize a console for debug output. This function is called very
- * early in the intialization sequence to configure the serial console uart
- * (only).
+ * early in the intialization sequence to configure the serial console
+ * uart (only).
*
- ************************************************************************************/
+ ****************************************************************************/
EXTERN void up_consoleinit(void);
-/************************************************************************************
+/****************************************************************************
* Name: up_boardinit
*
* Description:
- * This function must be provided by the board-specific logic in the directory
- * configs/<board-name>/up_boot.c.
+ * This function must be provided by the board-specific logic in the
+ * directory configs/<board-name>/up_boot.c.
*
- ************************************************************************************/
+ ****************************************************************************/
EXTERN void up_boardinitialize(void);
-/************************************************************************************
+/****************************************************************************
* Name: at91uc3_configgpio
*
* Description:
* Configure a GPIO pin based on bit-encoded description of the pin.
*
- ************************************************************************************/
+ ****************************************************************************/
EXTERN int at91uc3_configgpio(uint16_t cfgset);
-/************************************************************************************
+/****************************************************************************
* Name: at91uc3_gpiowrite
*
* Description:
* Write one or zero to the selected GPIO pin
*
- ************************************************************************************/
+ ****************************************************************************/
EXTERN void at91uc3_gpiowrite(uint16_t pinset, bool value);
-/************************************************************************************
+/****************************************************************************
* Name: at91uc3_gpioread
*
* Description:
* Read one or zero from the selected GPIO pin
*
- ************************************************************************************/
+ ****************************************************************************/
EXTERN bool at91uc3_gpioread(uint16_t pinset);
+/****************************************************************************
+ * Name: gpio_irqinitialize
+ *
+ * Description:
+ * Initialize all vectors to the unexpected interrupt handler
+ *
+ * Configuration Notes:
+ * Configuration CONFIG_AVR32_GPIOIRQ must be selected to enable the
+ * overall GPIO IRQ feature and CONFIG_AVR32_GPIOIRQSETA and/or
+ * CONFIG_AVR32_GPIOIRQSETB must be enabled to select GPIOs to support
+ * interrupts on.
+ *
+ * Assumptions:
+ * Called during the early boot sequence before global interrupts have
+ * been enabled.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_AVR32_GPIOIRQ
+EXTERN void gpio_irqinitialize(void);
+#endif
+
+/****************************************************************************
+ * Name: gpio_irqattach
+ *
+ * Description:
+ * Attach in GPIO interrupt to the provide 'isr'
+ *
+ * Configuration Notes:
+ * Configuration CONFIG_AVR32_GPIOIRQ must be selected to enable the
+ * overall GPIO IRQ feature and CONFIG_AVR32_GPIOIRQSETA and/or
+ * CONFIG_AVR32_GPIOIRQSETB must be enabled to select GPIOs to support
+ * interrupts on.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_AVR32_GPIOIRQ
+EXTERN int gpio_irqattach(int irq, xcpt_t newisr, xcpt_t *oldisr);
+#endif
+
+/****************************************************************************
+ * Name: gpio_irqenable
+ *
+ * Description:
+ * Enable the GPIO IRQ specified by 'irq'
+ *
+ * Configuration Notes:
+ * Configuration CONFIG_AVR32_GPIOIRQ must be selected to enable the
+ * overall GPIO IRQ feature and CONFIG_AVR32_GPIOIRQSETA and/or
+ * CONFIG_AVR32_GPIOIRQSETB must be enabled to select GPIOs to support
+ * interrupts on.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_AVR32_GPIOIRQ
+EXTERN void gpio_irqenable(int irq);
+#endif
+
+/*****************************************************************************
+ * Name: gpio_irqdisable
+ *
+ * Description:
+ * Disable the GPIO IRQ specified by 'irq'
+ *
+ * Configuration Notes:
+ * Configuration CONFIG_AVR32_GPIOIRQ must be selected to enable the
+ * overall GPIO IRQ feature and CONFIG_AVR32_GPIOIRQSETA and/or
+ * CONFIG_AVR32_GPIOIRQSETB must be enabled to select GPIOs to support
+ * interrupts on.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_AVR32_GPIOIRQ
+EXTERN void gpio_irqdisable(int irq);
+#endif
+
#undef EXTERN
#if defined(__cplusplus)
}
diff --git a/nuttx/arch/avr/src/at91uc3/at91uc3_irq.c b/nuttx/arch/avr/src/at91uc3/at91uc3_irq.c
index c05e7496a..c5bdeafbd 100644
--- a/nuttx/arch/avr/src/at91uc3/at91uc3_irq.c
+++ b/nuttx/arch/avr/src/at91uc3/at91uc3_irq.c
@@ -39,6 +39,7 @@
****************************************************************************/
#include <nuttx/config.h>
+#include "at91uc3_config.h"
#include <stdint.h>
#include <errno.h>
@@ -226,6 +227,12 @@ void up_irqinitialize(void)
irq_attach(irq, avr32_xcptn);
}
+ /* Initialize GPIO interrupt facilities */
+
+#ifdef CONFIG_AVR32_GPIOIRQ
+ gpio_irqinitialize();
+#endif
+
/* And finally, enable interrupts */
#ifndef CONFIG_SUPPRESS_INTERRUPTS
diff --git a/nuttx/arch/avr/src/at91uc3/at91uc3_lowconsole.c b/nuttx/arch/avr/src/at91uc3/at91uc3_lowconsole.c
index 0fcfb5487..4b2ba02b7 100644
--- a/nuttx/arch/avr/src/at91uc3/at91uc3_lowconsole.c
+++ b/nuttx/arch/avr/src/at91uc3/at91uc3_lowconsole.c
@@ -302,6 +302,11 @@ void usart_configure(uintptr_t usart_base, uint32_t baud, unsigned int parity,
#ifndef CONFIG_USE_EARLYSERIALINIT
void up_consoleinit(void)
{
+ /* Enable clocking for the enabled USART modules. Hmmm... It looks like the
+ * default state for CLK_USART0, USART1 CLK_USART1, and USART2 CLK_USART2 is
+ * "enabled" in the PM's PBAMASK register.
+ */
+
/* Setup GPIO pins for each configured USART/UART */
#ifdef CONFIG_AVR32_USART0_RS232
diff --git a/nuttx/arch/avr/src/at91uc3/at91uc3_pm.h b/nuttx/arch/avr/src/at91uc3/at91uc3_pm.h
index 162c3b055..20007dedb 100755
--- a/nuttx/arch/avr/src/at91uc3/at91uc3_pm.h
+++ b/nuttx/arch/avr/src/at91uc3/at91uc3_pm.h
@@ -132,11 +132,39 @@
#define PM_CKSEL_PBBDIV (1 << 31) /* Bit 31: PBB Division */
/* CPU Mask Register Bit-field Definitions */
+
+#define PM_CPUMASK_OCD (1 << 1) /* Bit 1: OCD */
+
/* HSB Mask Register Bit-field Definitions */
+
+#define PM_HSBMASK_FLASHC (1 << 0) /* Bit 0: FLASHC */
+#define PM_HSBMASK_PBA (1 << 1) /* Bit 1: PBA bridge */
+#define PM_HSBMASK_PBB (1 << 2) /* Bit 2: PBB bridge */
+#define PM_HSBMASK_USBB (1 << 3) /* Bit 3: USBB */
+#define PM_HSBMASK_PDCA (1 << 4) /* Bit 4: PDCA */
+
/* PBA Mask Register Bit-field Definitions */
+
+#define PM_PBAMASK_INTC (1 << 0) /* Bit 0: INTC */
+#define PM_PBAMASK_GPIO (1 << 1) /* Bit 1: GPIO */
+#define PM_PBAMASK_PDCA (1 << 2) /* Bit 2: PDCA */
+#define PM_PBAMASK_PMRTCEIC (1 << 3) /* Bit 3: PM/RTC/EIC */
+#define PM_PBAMASK_ADC (1 << 4) /* Bit 4: ADC */
+#define PM_PBAMASK_SPI (1 << 5) /* Bit 5: SPI */
+#define PM_PBAMASK_TWI (1 << 6) /* Bit 6: TWI */
+#define PM_PBAMASK_USART0 (1 << 7) /* Bit 7: USART0 */
+#define PM_PBAMASK_USART1 (1 << 8) /* Bit 8: USART1 */
+#define PM_PBAMASK_USART2 (1 << 9) /* Bit 9: USART2 */
+#define PM_PBAMASK_PWM (1 << 10) /* Bit 10: PWM */
+#define PM_PBAMASK_SSC (1 << 11) /* Bit 11: SSC */
+#define PM_PBAMASK_TC (1 << 12) /* Bit 12: TC */
+#define PM_PBAMASK_ABDAC (1 << 13) /* Bit 13: ABDAC */
+
/* PBB Mask Register Bit-field Definitions */
-/* These registers contain a 32-bit value with no smaller bit-field */
+#define PM_PBBMASK_HMATRIX (1 << 0) /* Bit 0: HMATRIX */
+#define PM_PBBMASK_USBB (1 << 2) /* Bit 2: USBB */
+#define PM_PBBMASK_FLASHC (1 << 3) /* Bit 3: FLASHC */
/* PLL0/1 Control Register Bit-field Definitions */
diff --git a/nuttx/configs/avr32dev1/README.txt b/nuttx/configs/avr32dev1/README.txt
index c28da89e0..01c38cb0e 100755
--- a/nuttx/configs/avr32dev1/README.txt
+++ b/nuttx/configs/avr32dev1/README.txt
@@ -156,6 +156,10 @@ AVR32DEV1 Configuration Options
the delay actually is 100 seconds.
Individual subsystems can be enabled:
+
+ CONFIG_AVR32_GPIOIRQ - GPIO interrupt support
+ CONFIG_AVR32_GPIOIRQSETA - Set of GPIOs on PORTA that support interrupts
+ CONFIG_AVR32_GPIOIRQSETB - Set of GPIOs on PORTB that support interrupts
CONFIG_AVR32_USARTn - Enable support for USARTn
CONFIG_AVR32_USARTn_RS232 - Configure USARTn as an RS232 interface.
diff --git a/nuttx/configs/avr32dev1/include/board.h b/nuttx/configs/avr32dev1/include/board.h
index c166cae05..7c6371e1d 100755
--- a/nuttx/configs/avr32dev1/include/board.h
+++ b/nuttx/configs/avr32dev1/include/board.h
@@ -43,6 +43,9 @@
#include <nuttx/config.h>
+#include <stdint.h>
+#include <nuttx/irq.h>
+
/************************************************************************************
* Definitions
************************************************************************************/
@@ -135,6 +138,10 @@ EXTERN void avr32_boardinitialize(void);
* 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.
*
+ * NOTE: Nothing in the "base" NuttX code calls up_buttoninit(). If you want button
+ * support in an application, your application startup code must call up_buttoninit()
+ * prior to calling any of the other button interfaces.
+ *
************************************************************************************/
#ifdef CONFIG_ARCH_BUTTONS
@@ -161,9 +168,15 @@ EXTERN uint8_t up_buttons(void);
* called when BUTTON1/2 is depressed. The previous interrupt handler value is
* returned (so that it may restored, if so desired).
*
+ * Configuration Notes:
+ * Configuration CONFIG_AVR32_GPIOIRQ must be selected to enable the overall GPIO
+ * IRQ feature and CONFIG_AVR32_GPIOIRQSETA and/or CONFIG_AVR32_GPIOIRQSETB must
+ * be enabled to select GPIOs to support interrupts on. For button support, bits
+ * 2 and 3 must be set in CONFIG_AVR32_GPIOIRQSETB (PB2 and PB3).
+ *
************************************************************************************/
-#ifdef CONFIG_GPIOB_IRQ
+#ifdef CONFIG_AVR32_GPIOIRQ
EXTERN xcpt_t up_irqbutton1(xcpt_t irqhandler);
EXTERN xcpt_t up_irqbutton2(xcpt_t irqhandler);
#endif
diff --git a/nuttx/configs/avr32dev1/ostest/defconfig b/nuttx/configs/avr32dev1/ostest/defconfig
index 0068dae6e..234725b82 100755
--- a/nuttx/configs/avr32dev1/ostest/defconfig
+++ b/nuttx/configs/avr32dev1/ostest/defconfig
@@ -89,7 +89,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
@@ -103,6 +103,10 @@ CONFIG_AVR32_AVRTOOLSL=n
#
# Individual subsystems can be enabled:
#
+# CONFIG_AVR32_GPIOIRQ - GPIO interrupt support
+# CONFIG_AVR32_GPIOIRQSETA - Set of GPIOs on PORTA that support interrupts
+# CONFIG_AVR32_GPIOIRQSETB - Set of GPIOs on PORTB that support interrupts
+#
# CONFIG_AVR32_USARTn - Enable support for USARTn
# CONFIG_AVR32_USARTn_RS232 - Configure USARTn as an RS232 interface.
# CONFIG_AVR32_USARTn_SPI - Configure USARTn as an SPI interface.
@@ -113,6 +117,10 @@ CONFIG_AVR32_AVRTOOLSL=n
# CONFIG_AVR32_USARTn_ISO786 - Configure USARTn as an ISO786 interface.
#
+CONFIG_AVR32_GPIOIRQ=y
+CONFIG_AVR32_GPIOIRQSETA=0
+CONFIG_AVR32_GPIOIRQSETB=0x0000000c
+
CONFIG_AVR32_USART0=n
CONFIG_AVR32_USART0_RS232=n
CONFIG_AVR32_USART0_SPI=n
diff --git a/nuttx/configs/avr32dev1/src/avr32dev1_internal.h b/nuttx/configs/avr32dev1/src/avr32dev1_internal.h
index f46ed5516..1d3343127 100755
--- a/nuttx/configs/avr32dev1/src/avr32dev1_internal.h
+++ b/nuttx/configs/avr32dev1/src/avr32dev1_internal.h
@@ -43,11 +43,22 @@
#include <nuttx/config.h>
#include <nuttx/compiler.h>
+#include "at91uc3_config.h"
/************************************************************************************
* Definitions
************************************************************************************/
+/* Configuration ********************************************************************/
+
+#if (CONFIG_AVR32_GPIOIRQSETB & 4) == 1
+# define CONFIG_AVR32DEV_BUTTON1_IRQ 1
+#endif
+
+#if (CONFIG_AVR32_GPIOIRQSETB & 8) == 1
+# define CONFIG_AVR32DEV_BUTTON2_IRQ 1
+#endif
+
/* AVRDEV1 GPIO Pin Definitions *****************************************************/
/* LEDs
*
@@ -68,8 +79,23 @@
* PIN 25 PB3 KEY2
*/
-#define PINMUX_GPIO_BUTTON1 (GPIO_ENABLE | GPIO_INPUT | GPIO_PORTB | 2)
-#define PINMUX_GPIO_BUTTON2 (GPIO_ENABLE | GPIO_INPUT | GPIO_PORTB | 3)
+#if CONFIG_AVR32DEV_BUTTON1_IRQ
+# define PINMUX_GPIO_BUTTON1 (GPIO_ENABLE | GPIO_INPUT | GPIO_INTR | \
+ GPIO_INTMODE_BOTH | GPIO_GLITCH | GPIO_PORTB | 2)
+# define GPIO_BUTTON1_IRQ AVR32_IRQ_GPIO_PB2
+#else
+# define PINMUX_GPIO_BUTTON1 (GPIO_ENABLE | GPIO_INPUT | GPIO_GLITCH | \
+ GPIO_PORTB | 2)
+#endif
+
+#if CONFIG_AVR32DEV_BUTTON2_IRQ
+# define PINMUX_GPIO_BUTTON2 (GPIO_ENABLE | GPIO_INPUT | GPIO_INTR | \
+ GPIO_INTMODE_BOTH | GPIO_GLITCH | GPIO_PORTB | 3)
+# define GPIO_BUTTON2_IRQ AVR32_IRQ_GPIO_PB3
+#else
+# define PINMUX_GPIO_BUTTON2 (GPIO_ENABLE | GPIO_INPUT | GPIO_GLITCH | \
+ GPIO_PORTB | 3)
+#endif
/************************************************************************************
* Public Types
diff --git a/nuttx/configs/avr32dev1/src/up_buttons.c b/nuttx/configs/avr32dev1/src/up_buttons.c
index 37434d656..b891d8698 100755
--- a/nuttx/configs/avr32dev1/src/up_buttons.c
+++ b/nuttx/configs/avr32dev1/src/up_buttons.c
@@ -38,7 +38,9 @@
****************************************************************************/
#include <nuttx/config.h>
+#include "at91uc3_config.h"
+#include <sys/types.h>
#include <stdint.h>
#include <nuttx/irq.h>
@@ -59,9 +61,6 @@
* Private Data
****************************************************************************/
-static xcpt_t g_irqbutton1;
-static xcpt_t g_irqbutton2;
-
/****************************************************************************
* Private Functions
****************************************************************************/
@@ -89,7 +88,7 @@ uint8_t up_buttons(void)
uint8_t retval;
retval = at91uc3_gpioread(PINMUX_GPIO_BUTTON1) ? 0 : BUTTON1;
- retval |= sat91uc3_gpioread(PINMUX_GPIO_BUTTON2) ? 0 : BUTTON2;
+ retval |= at91uc3_gpioread(PINMUX_GPIO_BUTTON2) ? 0 : BUTTON2;
return retval;
}
@@ -98,30 +97,33 @@ uint8_t up_buttons(void)
* Name: up_irqbutton1
****************************************************************************/
-#ifdef CONFIG_GPIOB_IRQ
+#ifdef CONFIG_AVR32_GPIOIRQ
xcpt_t up_irqbutton1(xcpt_t irqhandler)
{
+#ifdef CONFIG_AVR32DEV_BUTTON1_IRQ
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 */
+ /* Attach the handler */
- oldhandler = g_irqbutton1;
- g_irqbutton1 = irqhandler;
+ gpio_irqattach(GPIO_BUTTON1_IRQ, irqhandler, &oldhandler);
- /* Configure and enable the interrupt */
+ /* Enable/disable the interrupt */
-#warning "Missing Logic"
-
- irqrestore(flags);
+ if (irqhandler)
+ {
+ gpio_irqenable(GPIO_BUTTON1_IRQ);
+ }
+ else
+ {
+ gpio_irqdisable(GPIO_BUTTON1_IRQ);
+ }
/* Return the old button handler (so that it can be restored) */
return oldhandler;
+#else
+ return NULL;
+#endif
}
#endif
@@ -129,30 +131,33 @@ xcpt_t up_irqbutton1(xcpt_t irqhandler)
* Name: up_irqbutton2
****************************************************************************/
-#ifdef CONFIG_GPIOB_IRQ
+#ifdef CONFIG_AVR32_GPIOIRQ
xcpt_t up_irqbutton2(xcpt_t irqhandler)
{
+#ifdef CONFIG_AVR32DEV_BUTTON2_IRQ
xcpt_t oldhandler;
- irqstate_t flags;
- /* Disable interrupts until we are done */
+ /* Attach the handler */
- flags = irqsave();
+ gpio_irqattach(GPIO_BUTTON2_IRQ, irqhandler, &oldhandler);
- /* Get the old button interrupt handler and save the new one */
+ /* Enable/disable the interrupt */
- oldhandler = g_irqbutton2;
- g_irqbutton2 = irqhandler;
-
- /* Configure and enable the interrupt */
-
-#warning "Missing Logic"
-
- irqrestore(flags);
+ if (irqhandler)
+ {
+ gpio_irqenable(GPIO_BUTTON2_IRQ);
+ }
+ else
+ {
+ gpio_irqdisable(GPIO_BUTTON2_IRQ);
+ }
/* Return the old button handler (so that it can be restored) */
return oldhandler;
+#else
+ return NULL;
+#endif
}
#endif