summaryrefslogtreecommitdiff
path: root/nuttx/configs
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-01-05 16:58:18 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-01-05 16:58:18 +0000
commit7dcb0729864fa8f28f5e9a217a2b79141aeae3a2 (patch)
treec67455478d70f198818b1d52ca222c2f315a70ca /nuttx/configs
parentd7fadacd141270fc041f9cae09eb40fbd8ee7bce (diff)
downloadpx4-nuttx-7dcb0729864fa8f28f5e9a217a2b79141aeae3a2.tar.gz
px4-nuttx-7dcb0729864fa8f28f5e9a217a2b79141aeae3a2.tar.bz2
px4-nuttx-7dcb0729864fa8f28f5e9a217a2b79141aeae3a2.zip
Add APIs to support user access to the STM3240G-EVAL LEDs
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4263 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/configs')
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/include/board.h8
-rwxr-xr-xnuttx/configs/stm3240g-eval/include/board.h39
-rw-r--r--nuttx/configs/stm3240g-eval/src/Makefile12
-rw-r--r--nuttx/configs/stm3240g-eval/src/up_autoleds.c (renamed from nuttx/configs/stm3240g-eval/src/up_leds.c)7
4 files changed, 57 insertions, 9 deletions
diff --git a/nuttx/configs/olimex-lpc1766stk/include/board.h b/nuttx/configs/olimex-lpc1766stk/include/board.h
index 3ad2191f3..94fd74fee 100755
--- a/nuttx/configs/olimex-lpc1766stk/include/board.h
+++ b/nuttx/configs/olimex-lpc1766stk/include/board.h
@@ -383,14 +383,14 @@ extern "C" {
EXTERN void lpc17_boardinitialize(void);
/************************************************************************************
- * Name: lpc17_ledinit and lpc17_setled
+ * Name: lpc17_ledinit, lpc17_setled, and lpc17_setleds
*
* Description:
* If CONFIG_ARCH_LEDS is defined, then NuttX will control the on-board LEDs. If
* CONFIG_ARCH_LEDS is not defined, then the following interfacesare available to
* control the LEDs from user applications.
*
- ****************************************************************************/
+ ************************************************************************************/
#ifndef CONFIG_ARCH_LEDS
EXTERN void lpc17_ledinit(void);
@@ -406,7 +406,7 @@ EXTERN void lpc17_setleds(uint8_t ledset);
* up_buttons() may be called to collect the current state of all buttons or
* up_irqbutton() may be called to register button interrupt handlers.
*
- ****************************************************************************/
+ ************************************************************************************/
#ifdef CONFIG_ARCH_BUTTONS
EXTERN void up_buttoninit(void);
@@ -423,7 +423,7 @@ EXTERN void up_buttoninit(void);
* associated with a button. See the BOARD_BUTTON_*_BIT and BOARD_JOYSTICK_*_BIT
* definitions above for the meaning of each bit.
*
- ****************************************************************************/
+ ************************************************************************************/
EXTERN uint8_t up_buttons(void);
diff --git a/nuttx/configs/stm3240g-eval/include/board.h b/nuttx/configs/stm3240g-eval/include/board.h
index 6c3b32497..80ac9a809 100755
--- a/nuttx/configs/stm3240g-eval/include/board.h
+++ b/nuttx/configs/stm3240g-eval/include/board.h
@@ -212,7 +212,28 @@
#endif
/* LED definitions ******************************************************************/
-/* The STM3240G-EVAL board has 4 LEDs that we will encode as: */
+/* If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any
+ * way. The following definitions are used to access individual LEDs.
+ */
+
+/* LED index values for use with stm32_setled() */
+
+#define BOARD_LED1 0
+#define BOARD_LED2 1
+#define BOARD_LED3 2
+#define BOARD_LED4 3
+#define BOARD_NLEDS 4
+
+/* LED bits for use with stm32_setleds() */
+
+#define BOARD_LED1_BIT (1 << BOARD_LED1)
+#define BOARD_LED2_BIT (1 << BOARD_LED2)
+#define BOARD_LED3_BIT (1 << BOARD_LED3)
+#define BOARD_LED4_BIT (1 << BOARD_LED4)
+
+/* If CONFIG_ARCH_LEDs is defined, then NuttX will control the 4 LEDs on board the
+ * STM3240G-EVAL. The following definitions describe how NuttX controls the LEDs:
+ */
#define LED_STARTED 0 /* LED1 */
#define LED_HEAPALLOCATE 1 /* LED2 */
@@ -357,6 +378,22 @@ extern "C" {
EXTERN void stm32_boardinitialize(void);
/************************************************************************************
+ * Name: stm32_ledinit, stm32_setled, and stm32_setleds
+ *
+ * Description:
+ * If CONFIG_ARCH_LEDS is defined, then NuttX will control the on-board LEDs. If
+ * CONFIG_ARCH_LEDS is not defined, then the following interfacesare available to
+ * control the LEDs from user applications.
+ *
+ ************************************************************************************/
+
+#ifndef CONFIG_ARCH_LEDS
+EXTERN void stm32_ledinit(void);
+EXTERN void stm32_setled(int led, bool ledon);
+EXTERN void stm32_setleds(uint8_t ledset);
+#endif
+
+/************************************************************************************
* Button support.
*
* Description:
diff --git a/nuttx/configs/stm3240g-eval/src/Makefile b/nuttx/configs/stm3240g-eval/src/Makefile
index 6cda7250d..8ddca49e1 100644
--- a/nuttx/configs/stm3240g-eval/src/Makefile
+++ b/nuttx/configs/stm3240g-eval/src/Makefile
@@ -40,7 +40,17 @@ CFLAGS += -I$(TOPDIR)/sched
ASRCS =
AOBJS = $(ASRCS:.S=$(OBJEXT))
-CSRCS = up_boot.c up_leds.c up_buttons.c up_spi.c
+CSRCS = up_boot.c up_spi.c
+
+ifeq ($(CONFIG_ARCH_LEDS),y)
+CSRCS += up_autoleds.c
+else
+CSRCS += up_userleds.c
+endif
+
+ifeq ($(CONFIG_ARCH_BUTTONS),y)
+CSRCS += up_buttons.c
+endif
ifeq ($(CONFIG_ADC),y)
CSRCS += up_adc.c
diff --git a/nuttx/configs/stm3240g-eval/src/up_leds.c b/nuttx/configs/stm3240g-eval/src/up_autoleds.c
index f7635f54c..6c2cba455 100644
--- a/nuttx/configs/stm3240g-eval/src/up_leds.c
+++ b/nuttx/configs/stm3240g-eval/src/up_autoleds.c
@@ -1,6 +1,6 @@
/****************************************************************************
- * configs/stm3240g_eval/src/up_leds.c
- * arch/arm/src/board/up_leds.c
+ * configs/stm3240g_eval/src/up_autoleds.c
+ * arch/arm/src/board/up_autoleds.c
*
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@@ -52,6 +52,8 @@
#include "stm32_internal.h"
#include "stm3240g-internal.h"
+#ifdef CONFIG_ARCH_LEDS
+
/****************************************************************************
* Definitions
****************************************************************************/
@@ -227,7 +229,6 @@ static void led_setonoff(unsigned int bits)
* Name: up_ledinit
****************************************************************************/
-#ifdef CONFIG_ARCH_LEDS
void up_ledinit(void)
{
/* Configure LED1-4 GPIOs for output */