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/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 ++++++++++++++++++++++++++- 5 files changed, 144 insertions(+), 19 deletions(-) (limited to 'nuttx/configs/sam3u-ek') 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 */ -- cgit v1.2.3