summaryrefslogtreecommitdiff
path: root/nuttx/configs/stm3210e-eval
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-11-05 14:07:41 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-11-05 14:07:41 +0000
commit5f6797a5963b61c3b91a0161a9c9f2a373c4a0fe (patch)
tree7cc0a9a2174b975fb0595a69aa3ae766b0b2a543 /nuttx/configs/stm3210e-eval
parentdeab3d6e8ea2a6f4e4cb4f14927e660b5b56156b (diff)
downloadpx4-nuttx-5f6797a5963b61c3b91a0161a9c9f2a373c4a0fe.tar.gz
px4-nuttx-5f6797a5963b61c3b91a0161a9c9f2a373c4a0fe.tar.bz2
px4-nuttx-5f6797a5963b61c3b91a0161a9c9f2a373c4a0fe.zip
Add support for GPIO interrupts & STM3210E-EVAL board buttons
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@2226 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/configs/stm3210e-eval')
-rwxr-xr-xnuttx/configs/stm3210e-eval/RIDE/defconfig2
-rwxr-xr-xnuttx/configs/stm3210e-eval/include/board.h64
-rwxr-xr-xnuttx/configs/stm3210e-eval/nsh/defconfig2
-rwxr-xr-xnuttx/configs/stm3210e-eval/ostest/defconfig2
-rwxr-xr-xnuttx/configs/stm3210e-eval/src/Makefile5
-rwxr-xr-xnuttx/configs/stm3210e-eval/src/stm3210e-internal.h21
-rw-r--r--nuttx/configs/stm3210e-eval/src/up_buttons.c112
-rwxr-xr-xnuttx/configs/stm3210e-eval/usbserial/defconfig2
8 files changed, 205 insertions, 5 deletions
diff --git a/nuttx/configs/stm3210e-eval/RIDE/defconfig b/nuttx/configs/stm3210e-eval/RIDE/defconfig
index 6bb7331ad..3f7bfec5a 100755
--- a/nuttx/configs/stm3210e-eval/RIDE/defconfig
+++ b/nuttx/configs/stm3210e-eval/RIDE/defconfig
@@ -60,6 +60,7 @@
# CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions
# CONFIG_ARCH_BOOTLOADER - Set if you are using a bootloader.
# CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture.
+# CONFIG_ARCH_BUTTONS - Enable support for buttons. Unique to board architecture.
# CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that
# cause a 100 second delay during boot-up. This 100 second delay
# serves no purpose other than it allows you to calibrate
@@ -83,6 +84,7 @@ CONFIG_ARCH_INTERRUPTSTACK=n
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
+CONFIG_ARCH_BUTTONS=n
CONFIG_ARCH_CALIBRATION=n
#
diff --git a/nuttx/configs/stm3210e-eval/include/board.h b/nuttx/configs/stm3210e-eval/include/board.h
index 9968957c2..c753d0650 100755
--- a/nuttx/configs/stm3210e-eval/include/board.h
+++ b/nuttx/configs/stm3210e-eval/include/board.h
@@ -102,12 +102,51 @@
#define LED_ASSERTION 6 /* LED1 + LED2 + LED3 */
#define LED_PANIC 7 /* N/C + N/C + N/C + LED4 */
+/* The STM3210E-EVAL supports several buttons
+ *
+ * Reset -- Connected to NRST
+ * Wakeup -- Connected to PA.0
+ * Tamper -- Connected to PC.13
+ * Key -- Connected to PG.8
+ *
+ * And a Joystick
+ *
+ * Joystick center -- Connected to PG.7
+ * Joystick down -- Connected to PD.3
+ * Joystick left -- Connected to PG.14
+ * Joystick right -- Connected to PG.13
+ * Joystick up -- Connected to PG.15
+ */
+
+#define BUTTON_WAKEUP (1 << 0)
+#define BUTTON_TAMPER (1 << 1)
+#define BUTTON_KEY (1 << 2)
+
+#define JOYSTICK_SEL (1 << 3)
+#define JOYSTICK_DOWN (1 << 4)
+#define JOYSTICK_LEFT (1 << 5)
+#define JOYSTICK_RIGHT (1 << 6)
+#define JOYSTICK_UP (1 << 7)
+
+#define NUM_BUTTONS 8
+
/************************************************************************************
- * Public Function Prototypes
+ * Public Data
************************************************************************************/
#ifndef __ASSEMBLY__
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/************************************************************************************
+ * Public Function Prototypes
+ ************************************************************************************/
/************************************************************************************
* Name: stm32_boardinitialize
*
@@ -118,7 +157,28 @@
*
************************************************************************************/
-extern void stm32_boardinitialize(void);
+EXTERN void stm32_boardinitialize(void);
+
+/************************************************************************************
+ * Button support.
+ *
+ * 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.
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_ARCH_BUTTONS
+EXTERN void up_buttoninit(void);
+EXTERN ubyte up_buttons(void);
+#endif
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
#endif /* __ASSEMBLY__ */
#endif /* __ARCH_BOARD_BOARD_H */
diff --git a/nuttx/configs/stm3210e-eval/nsh/defconfig b/nuttx/configs/stm3210e-eval/nsh/defconfig
index 842f5951a..a3d22defd 100755
--- a/nuttx/configs/stm3210e-eval/nsh/defconfig
+++ b/nuttx/configs/stm3210e-eval/nsh/defconfig
@@ -60,6 +60,7 @@
# CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions
# CONFIG_ARCH_BOOTLOADER - Set if you are using a bootloader.
# CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture.
+# CONFIG_ARCH_BUTTONS - Enable support for buttons. Unique to board architecture.
# CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that
# cause a 100 second delay during boot-up. This 100 second delay
# serves no purpose other than it allows you to calibrate
@@ -83,6 +84,7 @@ CONFIG_ARCH_INTERRUPTSTACK=n
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
+CONFIG_ARCH_BUTTONS=n
CONFIG_ARCH_CALIBRATION=n
#
diff --git a/nuttx/configs/stm3210e-eval/ostest/defconfig b/nuttx/configs/stm3210e-eval/ostest/defconfig
index 06b8df95d..1d18778fe 100755
--- a/nuttx/configs/stm3210e-eval/ostest/defconfig
+++ b/nuttx/configs/stm3210e-eval/ostest/defconfig
@@ -60,6 +60,7 @@
# CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions
# CONFIG_ARCH_BOOTLOADER - Set if you are using a bootloader.
# CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture.
+# CONFIG_ARCH_BUTTONS - Enable support for buttons. Unique to board architecture.
# CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that
# cause a 100 second delay during boot-up. This 100 second delay
# serves no purpose other than it allows you to calibrate
@@ -83,6 +84,7 @@ CONFIG_ARCH_INTERRUPTSTACK=n
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
+CONFIG_ARCH_BUTTONS=n
CONFIG_ARCH_CALIBRATION=n
#
diff --git a/nuttx/configs/stm3210e-eval/src/Makefile b/nuttx/configs/stm3210e-eval/src/Makefile
index 3e3576ee9..b3e82e7af 100755
--- a/nuttx/configs/stm3210e-eval/src/Makefile
+++ b/nuttx/configs/stm3210e-eval/src/Makefile
@@ -39,8 +39,9 @@ CFLAGS += -I$(TOPDIR)/sched
ASRCS =
AOBJS = $(ASRCS:.S=$(OBJEXT))
-CSRCS = up_boot.c up_leds.c up_spi.c up_usbdev.c up_extcontext.c \
- up_selectnor.c up_deselectnor.c up_selectsram.c up_deselectsram.c
+CSRCS = up_boot.c up_leds.c up_buttons.c up_spi.c up_usbdev.c \
+ up_extcontext.c up_selectnor.c up_deselectnor.c \
+ up_selectsram.c up_deselectsram.c
ifeq ($(CONFIG_EXAMPLES_NSH_ARCHINIT),y)
CSRCS += up_nsh.c
endif
diff --git a/nuttx/configs/stm3210e-eval/src/stm3210e-internal.h b/nuttx/configs/stm3210e-eval/src/stm3210e-internal.h
index 897f2a5ca..64101af73 100755
--- a/nuttx/configs/stm3210e-eval/src/stm3210e-internal.h
+++ b/nuttx/configs/stm3210e-eval/src/stm3210e-internal.h
@@ -72,7 +72,26 @@
#define GPIO_LED3 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\
GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN8)
#define GPIO_LED4 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\
- GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN9)
+ GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN9)
+
+/* BUTTONS -- NOTE that some have EXTI interrupts configured */
+
+#define GPIO_BTN_WAKEUP (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|\
+ GPIO_PORTA|GPIO_PIN0)
+#define GPIO_BTN_TAMPER (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|\
+ GPIO_PORTA|GPIO_PIN0)
+#define GPIO_BTN_KEY (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|\
+ GPIO_EXTI|GPIO_PORTG|GPIO_PIN8)
+#define GPIO_JOY_KEY (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|\
+ GPIO_EXTI|GPIO_PORTG|GPIO_PIN7)
+#define GPIO_JOY_DOWN (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|\
+ GPIO_EXTI|GPIO_PORTD|GPIO_PIN3)
+#define GPIO_JOY_LEFT (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|\
+ GPIO_EXTI|GPIO_PORTG|GPIO_PIN14)
+#define GPIO_JOY_RIGHT (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|\
+ GPIO_EXTI|GPIO_PORTG|GPIO_PIN13)
+#define GPIO_JOY_UP (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|\
+ GPIO_EXTI|GPIO_PORTG|GPIO_PIN15)
/* SPI FLASH chip select: PA.4 */
diff --git a/nuttx/configs/stm3210e-eval/src/up_buttons.c b/nuttx/configs/stm3210e-eval/src/up_buttons.c
new file mode 100644
index 000000000..67b8537c7
--- /dev/null
+++ b/nuttx/configs/stm3210e-eval/src/up_buttons.c
@@ -0,0 +1,112 @@
+/****************************************************************************
+ * configs/stm3210e-eval/src/up_leds.c
+ *
+ * Copyright (C) 2009 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 <sys/types.h>
+
+#include <arch/board/board.h>
+#include "stm3210e-internal.h"
+
+#ifdef CONFIG_ARCH_BUTTONS
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static const uint16 g_buttons[NUM_BUTTONS] =
+{
+ GPIO_BTN_WAKEUP, GPIO_BTN_TAMPER, GPIO_BTN_KEY, GPIO_JOY_KEY,
+ GPIO_JOY_DOWN, GPIO_JOY_LEFT, GPIO_JOY_RIGHT, GPIO_JOY_UP
+};
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_buttoninit
+ ****************************************************************************/
+
+void up_buttoninit(void)
+{
+ int i;
+
+ /* Configure the GPIO pins as inputs. NOTE that EXTI interrupts are
+ * configured for some pins but NOT used in this file
+ */
+
+ for (i = 0; i < NUM_BUTTONS; i++)
+ {
+ stm32_configgpio(g_buttons[i]);
+ }
+}
+
+/****************************************************************************
+ * Name: up_buttons
+ ****************************************************************************/
+
+ubyte up_buttons(void)
+{
+ ubyte ret = 0;
+ int i;
+
+ /* Check that state of each key */
+
+ for (i = 0; i < NUM_BUTTONS; i++)
+ {
+ /* A LOW value means that the key is pressed */
+
+ if (!stm32_gpioread(g_buttons[i]))
+ {
+ ret |= (1 << i);
+ }
+ }
+
+ return ret;
+}
+
+#endif /* CONFIG_ARCH_BUTTONS */
diff --git a/nuttx/configs/stm3210e-eval/usbserial/defconfig b/nuttx/configs/stm3210e-eval/usbserial/defconfig
index 1ee43d1cb..0917bc2f1 100755
--- a/nuttx/configs/stm3210e-eval/usbserial/defconfig
+++ b/nuttx/configs/stm3210e-eval/usbserial/defconfig
@@ -60,6 +60,7 @@
# CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions
# CONFIG_ARCH_BOOTLOADER - Set if you are using a bootloader.
# CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture.
+# CONFIG_ARCH_BUTTONS - Enable support for buttons. Unique to board architecture.
# CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that
# cause a 100 second delay during boot-up. This 100 second delay
# serves no purpose other than it allows you to calibrate
@@ -83,6 +84,7 @@ CONFIG_ARCH_INTERRUPTSTACK=n
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
+CONFIG_ARCH_BUTTONS=n
CONFIG_ARCH_CALIBRATION=n
#