summaryrefslogtreecommitdiff
path: root/nuttx/configs/olimex-lpc1766stk
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-12-31 16:53:05 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-12-31 16:53:05 +0000
commit051fc115cb2dedf13a2b00b4fa46d06b783d47bb (patch)
tree86e483ad27a158056974b1c794afda1a5db9bea1 /nuttx/configs/olimex-lpc1766stk
parentfe3199408b03f3b9df2d0daca9e2fefe29135746 (diff)
downloadpx4-nuttx-051fc115cb2dedf13a2b00b4fa46d06b783d47bb.tar.gz
px4-nuttx-051fc115cb2dedf13a2b00b4fa46d06b783d47bb.tar.bz2
px4-nuttx-051fc115cb2dedf13a2b00b4fa46d06b783d47bb.zip
Update README, LPC1766-STK button improvements, new Make targets, new Getting Started document
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4244 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/configs/olimex-lpc1766stk')
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/include/board.h9
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/src/lpc1766stk_internal.h54
-rw-r--r--nuttx/configs/olimex-lpc1766stk/src/up_buttons.c41
3 files changed, 71 insertions, 33 deletions
diff --git a/nuttx/configs/olimex-lpc1766stk/include/board.h b/nuttx/configs/olimex-lpc1766stk/include/board.h
index 2d99fe40a..5a22c0970 100755
--- a/nuttx/configs/olimex-lpc1766stk/include/board.h
+++ b/nuttx/configs/olimex-lpc1766stk/include/board.h
@@ -413,6 +413,9 @@ EXTERN void up_buttoninit(void);
* Name: up_buttons
*
* Description:
+ * up_buttoninit() must be called to initialize button resources. After that,
+ * up_buttons() may be called to collect the current state of all buttons.
+ *
* 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 BOARD_BUTTON_*_BIT and BOARD_JOYSTICK_*_BIT
@@ -427,7 +430,6 @@ EXTERN uint8_t up_buttons(void);
*
* Description:
* up_buttoninit() must be called to initialize button resources. After that,
- * up_buttons() may be called to collect the current state of all buttons or
* up_irqbutton() may be called to register button interrupt handlers.
*
* up_irqbutton() may be called to register an interrupt handler that will be called
@@ -437,6 +439,11 @@ EXTERN uint8_t up_buttons(void);
* The previous interrupt handler address is returned (so that it may restored, if
* so desired).
*
+ * Note that up_irqbutton() also enables button interrupts. Button interrupts
+ * will remain enabled after the interrupt handler is attached. Interrupts may
+ * be disabled (and detached) by calling up_irqbutton with irqhandler equal to
+ * NULL.
+ *
************************************************************************************/
#if defined(CONFIG_ARCH_IRQBUTTONS) && defined(CONFIG_GPIO_IRQ)
diff --git a/nuttx/configs/olimex-lpc1766stk/src/lpc1766stk_internal.h b/nuttx/configs/olimex-lpc1766stk/src/lpc1766stk_internal.h
index 4fa082369..d1c0ebe80 100755
--- a/nuttx/configs/olimex-lpc1766stk/src/lpc1766stk_internal.h
+++ b/nuttx/configs/olimex-lpc1766stk/src/lpc1766stk_internal.h
@@ -129,22 +129,26 @@
* P0[4]/I2SRX_CLK/RD2/CAP2[0] 81 LED2/ACC IRQ
*/
-#define LPC1766STK_LED1 (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT1 | GPIO_PIN25)
-#define LPC1766STK_LED2 (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT0 | GPIO_PIN4)
+#define LPC1766STK_LED1 (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT1 | GPIO_PIN25)
+#define LPC1766STK_LED2 (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT0 | GPIO_PIN4)
/* Buttons GPIO PIN SIGNAL NAME
* -------------------------------- ---- --------------
- * P2[12]/#EINT2/I2STX_WS 51 WAKE-UP
* P0[23]/AD0[0]/I2SRX_CLK/CAP3[0] 9 BUT1
* P2[13]/#EINT3/I2STX_SDA 50 BUT2
+ * P2[12]/#EINT2/I2STX_WS 51 WAKE-UP
*
- * Pull-ups are not required because the pins are already pulled-up by through
- * resistors on the board.
+ * NOTES:
+ * 1. Pull-ups are not required because the pins are already pulled-up by
+ * through resistors on the board.
+ * 2. All buttons are capable of supporting interrupts if up_irqbutton() is
+ * called to attach an interrupt handler. Interrupts are configured to
+ * occur on both edges.
*/
-#define LPC1766STK_BUT1 (GPIO_INPUT | GPIO_FLOAT | GPIO_PORT0 | GPIO_PIN23)
-#define LPC1766STK_BUT2 (GPIO_INPUT | GPIO_FLOAT | GPIO_PORT2 | GPIO_PIN13)
-#define LPC1766STK_WAKEUP (GPIO_INPUT | GPIO_FLOAT | GPIO_PORT2 | GPIO_PIN12)
+#define LPC1766STK_BUT1 (GPIO_INTBOTH | GPIO_FLOAT | GPIO_PORT0 | GPIO_PIN23)
+#define LPC1766STK_BUT2 (GPIO_INTBOTH | GPIO_FLOAT | GPIO_PORT2 | GPIO_PIN13)
+#define LPC1766STK_WAKEUP (GPIO_INTBOTH | GPIO_FLOAT | GPIO_PORT2 | GPIO_PIN12)
/* Button IRQ numbers */
@@ -160,15 +164,19 @@
* P2[7]/RD2/RTS1 66 LEFT
* P2[8]/TD2/TXD2 65 RIGHT
*
- * Pull-ups are not required because the pins are already pulled-up by through
- * resistors on the board.
+ * NOTES:
+ * 1. Pull-ups are not required because the pins are already pulled-up by
+ * through resistors on the board.
+ * 2. All buttons are capable of supporting interrupts if up_irqbutton() is
+ * called to attach an interrupt handler. Interrupts are configured to
+ * occur on both edges.
*/
-#define LPC1766STK_CENTER (GPIO_INPUT | GPIO_FLOAT | GPIO_PORT0 | GPIO_PIN5)
-#define LPC1766STK_UP (GPIO_INPUT | GPIO_FLOAT | GPIO_PORT2 | GPIO_PIN0)
-#define LPC1766STK_DOWN (GPIO_INPUT | GPIO_FLOAT | GPIO_PORT2 | GPIO_PIN1)
-#define LPC1766STK_LEFT (GPIO_INPUT | GPIO_FLOAT | GPIO_PORT2 | GPIO_PIN7)
-#define LPC1766STK_RIGHT (GPIO_INPUT | GPIO_FLOAT | GPIO_PORT2 | GPIO_PIN8)
+#define LPC1766STK_CENTER (GPIO_INTBOTH | GPIO_FLOAT | GPIO_PORT0 | GPIO_PIN5)
+#define LPC1766STK_UP (GPIO_INTBOTH | GPIO_FLOAT | GPIO_PORT2 | GPIO_PIN0)
+#define LPC1766STK_DOWN (GPIO_INTBOTH | GPIO_FLOAT | GPIO_PORT2 | GPIO_PIN1)
+#define LPC1766STK_LEFT (GPIO_INTBOTH | GPIO_FLOAT | GPIO_PORT2 | GPIO_PIN7)
+#define LPC1766STK_RIGHT (GPIO_INTBOTH | GPIO_FLOAT | GPIO_PORT2 | GPIO_PIN8)
/* Joystick IRQ numbers */
@@ -188,10 +196,10 @@
* P3[26]/STCLK/MAT0[1]/PWM1[3] 26 LCD_BL (PWM1)
*/
-#define LPC1766STK_LCD_CS (GPIO_OUTPUT | GPIO_VALUE_ONE | GPIO_PORT1 | GPIO_PIN21)
-#define LPC1766STK_LCD_RST (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT3 | GPIO_PIN25)
-#define LPC1766STK_LCD_BL GPIO_PWM1p3_3
-#define GPIO_PWM1p3 GPIO_PWM1p3_3
+#define LPC1766STK_LCD_CS (GPIO_OUTPUT | GPIO_VALUE_ONE | GPIO_PORT1 | GPIO_PIN21)
+#define LPC1766STK_LCD_RST (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT3 | GPIO_PIN25)
+#define LPC1766STK_LCD_BL GPIO_PWM1p3_3
+#define GPIO_PWM1p3 GPIO_PWM1p3_3
/* SD/MMC GPIO PIN SIGNAL NAME
* -------------------------------- ---- --------------
@@ -202,8 +210,8 @@
* P0[21]/RI1/RD1 57 MMC PWR (active low)
*/
-#define LPC1766STK_MMC_CS (GPIO_OUTPUT | GPIO_VALUE_ONE | GPIO_PORT0 | GPIO_PIN6)
-#define LPC1766STK_MMC_PWR (GPIO_OUTPUT | GPIO_VALUE_ONE | GPIO_PORT0 | GPIO_PIN21)
+#define LPC1766STK_MMC_CS (GPIO_OUTPUT | GPIO_VALUE_ONE | GPIO_PORT0 | GPIO_PIN6)
+#define LPC1766STK_MMC_PWR (GPIO_OUTPUT | GPIO_VALUE_ONE | GPIO_PORT0 | GPIO_PIN21)
/* AD GPIO PIN SIGNAL NAME
* -------------------------------- ---- --------------
@@ -211,8 +219,8 @@
* P0[25]/AD0[2]/I2SRX_SDA/TXD3 7 MIC IN
*/
-#define LPC1766STK_TEMP GPIO_AD0p1
-#define LPC1766STK_MIC_IN GPIO_AD0p2
+#define LPC1766STK_TEMP GPIO_AD0p1
+#define LPC1766STK_MIC_IN GPIO_AD0p2
/* UEXT GPIO PIN SIGNAL NAME
* -------------------------------- ---- --------------
diff --git a/nuttx/configs/olimex-lpc1766stk/src/up_buttons.c b/nuttx/configs/olimex-lpc1766stk/src/up_buttons.c
index 65fe89dfc..611ff5640 100644
--- a/nuttx/configs/olimex-lpc1766stk/src/up_buttons.c
+++ b/nuttx/configs/olimex-lpc1766stk/src/up_buttons.c
@@ -119,6 +119,10 @@ void up_buttoninit(void)
* Name: up_buttons
*
* Description:
+ * up_buttoninit() must be called to initialize button resources. After
+ * that, up_buttons() may be called to collect the current state of all
+ * buttons.
+ *
* up_buttons() may be called at any time to harvest the state of every
* button. The state of the buttons is returned as a bitset with one
* bit corresponding to each button: If the bit is set, then the button
@@ -151,14 +155,12 @@ uint8_t up_buttons(void)
return ret;
}
-/************************************************************************************
+/****************************************************************************
* Button support.
*
* Description:
* up_buttoninit() must be called to initialize button resources. After
- * that, up_buttons() may be called to collect the current state of all
- * buttons or up_irqbutton() may be called to register button interrupt
- * handlers.
+ * that, up_irqbutton() may be called to register button interrupt handlers.
*
* up_irqbutton() may be called to register an interrupt handler that will
* be called when a button is depressed or released. The ID value is a
@@ -167,13 +169,19 @@ uint8_t up_buttons(void)
* of enumeration values. The previous interrupt handler address is returned
* (so that it may restored, if so desired).
*
- ************************************************************************************/
+ * Note that up_irqbutton() also enables button interrupts. Button
+ * interrupts will remain enabled after the interrupt handler is attached.
+ * Interrupts may be disabled (and detached) by calling up_irqbutton with
+ * irqhandler equal to NULL.
+ *
+ ****************************************************************************/
#if defined(CONFIG_ARCH_IRQBUTTONS) && defined(CONFIG_GPIO_IRQ)
xcpt_t up_irqbutton(int id, xcpt_t irqhandler)
{
xcpt_t oldhandler = NULL;
irqstate_t flags;
+ int irq;
/* Verify that the button ID is within range */
@@ -188,10 +196,25 @@ xcpt_t up_irqbutton(int id, xcpt_t irqhandler)
flags = irqsave();
- /* Configure the interrupt */
-
- (void)irq_attach(g_buttonirq[id], irqhandler);
- up_enable_irq(g_buttonirq[id]);
+ /* Configure the interrupt. Either attach and enable the new
+ * interrupt or disable and detach the old interrupt handler.
+ */
+
+ irq = g_buttonirq[id];
+ if (irqhandler)
+ {
+ /* Attach then enable the new interrupt handler */
+
+ (void)irq_attach(irq, irqhandler);
+ up_enable_irq(irq);
+ }
+ else
+ {
+ /* Disable then then detach the the old interrupt handler */
+
+ up_disable_irq(irq);
+ (void)irq_detach(irq);
+ }
irqrestore(flags);
}
return oldhandler;