summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-03-01 21:41:29 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-03-01 21:41:29 +0000
commitf21ed9cf4e8c8e3a7ae95118d7f61545b83cc0d6 (patch)
tree809c38f39f662ee756144eeec0d41b6e474a1af7 /nuttx
parent7b9858c44c827799d2d4c898fc081b907bce7b49 (diff)
downloadpx4-nuttx-f21ed9cf4e8c8e3a7ae95118d7f61545b83cc0d6.tar.gz
px4-nuttx-f21ed9cf4e8c8e3a7ae95118d7f61545b83cc0d6.tar.bz2
px4-nuttx-f21ed9cf4e8c8e3a7ae95118d7f61545b83cc0d6.zip
Add interrupt vector logic for the LM4F120
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5693 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/arch/arm/Kconfig2
-rw-r--r--nuttx/arch/arm/include/lm/lm3s_irq.h10
-rw-r--r--nuttx/arch/arm/include/lm/lm4f_irq.h244
-rw-r--r--nuttx/arch/arm/src/lm/Kconfig5
-rw-r--r--nuttx/arch/arm/src/lm/chip/lm4f_vectors.h223
-rw-r--r--nuttx/configs/Kconfig13
-rw-r--r--nuttx/configs/README.txt10
-rw-r--r--nuttx/configs/c5471evm/Kconfig6
-rw-r--r--nuttx/configs/eagle100/Kconfig6
-rw-r--r--nuttx/configs/lm3s6432-s2e/Kconfig6
-rw-r--r--nuttx/configs/lm3s6965-ek/Kconfig6
-rw-r--r--nuttx/configs/lm3s8962-ek/Kconfig6
-rw-r--r--nuttx/configs/lm4f120-launchpad/Kconfig8
-rw-r--r--nuttx/configs/lm4f120-launchpad/README.txt2
-rw-r--r--nuttx/configs/lm4f120-launchpad/include/board.h2
-rwxr-xr-xnuttx/configs/lm4f120-launchpad/ostest/defconfig76
-rwxr-xr-xnuttx/configs/lm4f120-launchpad/ostest/setenv.sh34
-rw-r--r--nuttx/configs/lm4f120-launchpad/src/lm4f_autoleds.c48
-rw-r--r--nuttx/configs/lm4f120-launchpad/src/lm4f_nsh.c2
-rw-r--r--nuttx/configs/lm4f120-launchpad/src/lm4f_ssi.c3
-rw-r--r--nuttx/configs/lm4f120-launchpad/src/lmf4120-launchpad.h14
-rw-r--r--nuttx/configs/lpcxpresso-lpc1768/Kconfig6
-rw-r--r--nuttx/configs/mbed/Kconfig6
-rw-r--r--nuttx/configs/mcu123-lpc214x/Kconfig6
-rw-r--r--nuttx/configs/mirtoo/Kconfig6
-rw-r--r--nuttx/configs/mx1ads/Kconfig6
-rw-r--r--nuttx/configs/ntosd-dm320/Kconfig6
-rw-r--r--nuttx/configs/nucleus2g/Kconfig6
-rw-r--r--nuttx/configs/nutiny-nuc120/Kconfig6
-rw-r--r--nuttx/configs/olimex-lpc2378/Kconfig6
-rw-r--r--nuttx/configs/pic32-starterkit/Kconfig6
-rw-r--r--nuttx/configs/pic32mx7mmb/Kconfig6
-rw-r--r--nuttx/configs/pjrc-8051/Kconfig6
-rw-r--r--nuttx/configs/teensy/Kconfig6
-rw-r--r--nuttx/configs/us7032evb1/Kconfig6
-rw-r--r--nuttx/configs/zkit-arm-1769/Kconfig6
36 files changed, 618 insertions, 198 deletions
diff --git a/nuttx/arch/arm/Kconfig b/nuttx/arch/arm/Kconfig
index 869ed74c5..72526654b 100644
--- a/nuttx/arch/arm/Kconfig
+++ b/nuttx/arch/arm/Kconfig
@@ -55,7 +55,7 @@ config ARCH_CHIP_LM
bool "TI Stellaris"
select ARCH_HAVE_MPU
---help---
- TI Stellaris LMS3 architecutres (ARM Cortex-M3)
+ TI Stellaris LMS3 and LM4F architecutres (ARM Cortex-M3/4)
config ARCH_CHIP_LPC17XX
bool "NXP LPC17xx"
diff --git a/nuttx/arch/arm/include/lm/lm3s_irq.h b/nuttx/arch/arm/include/lm/lm3s_irq.h
index e9cfe8bdc..7dc4b7ee3 100644
--- a/nuttx/arch/arm/include/lm/lm3s_irq.h
+++ b/nuttx/arch/arm/include/lm/lm3s_irq.h
@@ -82,8 +82,8 @@
# define LM_IRQ_TIMER1A (37) /* Vector 37: Timer 1 A */
# define LM_IRQ_TIMER1B (38) /* Vector 38: Timer 1 B */
# define LM_IRQ_TIMER2A (39) /* Vector 39: Timer 2 A */
-# define LM_IRQ_TIMER2B (40) /* Vector 40: Timer 3 B */
+# define LM_IRQ_TIMER2B (40) /* Vector 40: Timer 2 B */
# define LM_IRQ_COMPARE0 (41) /* Vector 41: Analog Comparator 0 */
# define LM_IRQ_COMPARE1 (42) /* Vector 42: Analog Comparator 1 */
# define LM_RESERVED_43 (43) /* Vector 43: Reserved */
@@ -148,7 +148,7 @@
# define LM_IRQ_TIMER1B (38) /* Vector 38: Timer 1 B */
# define LM_IRQ_TIMER2A (39) /* Vector 39: Timer 2 A */
-# define LM_IRQ_TIMER2B (40) /* Vector 40: Timer 3 B */
+# define LM_IRQ_TIMER2B (40) /* Vector 40: Timer 2 B */
# define LM_IRQ_COMPARE0 (41) /* Vector 41: Analog Comparator 0 */
# define LM_IRQ_COMPARE1 (42) /* Vector 42: Analog Comparator 1 */
# define LM_RESERVED_43 (43) /* Vector 43: Reserved */
@@ -212,7 +212,7 @@
# define LM_IRQ_TIMER1B (38) /* Vector 38: Timer 1 B */
# define LM_IRQ_TIMER2A (39) /* Vector 39: Timer 2 A */
-# define LM_IRQ_TIMER2B (40) /* Vector 40: Timer 3 B */
+# define LM_IRQ_TIMER2B (40) /* Vector 40: Timer 2 B */
# define LM_IRQ_COMPARE0 (41) /* Vector 41: Analog Comparator 0 */
# define LM_IRQ_COMPARE1 (42) /* Vector 42: Analog Comparator 1 */
# define LM_RESERVED_43 (43) /* Vector 43: Reserved */
@@ -276,7 +276,7 @@
# define LM_IRQ_TIMER1B (38) /* Vector 38: Timer 1 B */
# define LM_IRQ_TIMER2A (39) /* Vector 39: Timer 2 A */
-# define LM_IRQ_TIMER2B (40) /* Vector 40: Timer 3 B */
+# define LM_IRQ_TIMER2B (40) /* Vector 40: Timer 2 B */
# define LM_IRQ_COMPARE0 (41) /* Vector 41: Analog Comparator 0 */
# define LM_IRQ_COMPARE1 (42) /* Vector 42: Analog Comparator 1 */
# define LM_IRQ_COMPARE2 (43) /* Vector 43: Analog Comparator 3 */
@@ -340,8 +340,8 @@
# define LM_IRQ_TIMER1A (37) /* Vector 37: Timer 1 A */
# define LM_IRQ_TIMER1B (38) /* Vector 38: Timer 1 B */
# define LM_IRQ_TIMER2A (39) /* Vector 39: Timer 2 A */
-# define LM_IRQ_TIMER2B (40) /* Vector 40: Timer 3 B */
+# define LM_IRQ_TIMER2B (40) /* Vector 40: Timer 2 B */
# define LM_IRQ_COMPARE0 (41) /* Vector 41: Analog Comparator 0 */
# define LM_RESERVED_42 (42) /* Vector 42: Reserved */
# define LM_RESERVED_43 (43) /* Vector 43: Reserved */
diff --git a/nuttx/arch/arm/include/lm/lm4f_irq.h b/nuttx/arch/arm/include/lm/lm4f_irq.h
new file mode 100644
index 000000000..2d4cb3c53
--- /dev/null
+++ b/nuttx/arch/arm/include/lm/lm4f_irq.h
@@ -0,0 +1,244 @@
+/************************************************************************************
+ * arch/arm/include/lm/lm4f_irq.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_ARM_INCLUDE_LM_LM4F_IRQ_H
+#define __ARCH_ARM_INCLUDE_LM_LM4F_IRQ_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/* IRQ numbers. The IRQ number corresponds vector number and hence map directly to
+ * bits in the NVIC. This does, however, waste several words of memory in the IRQ
+ * to handle mapping tables.
+ */
+
+/* External interrupts (vectors >= 16) */
+
+#define LM_IRQ_INTERRUPTS (16) /* Vector number of the first external interrupt */
+
+#if defined(CONFIG_ARCH_CHIP_LM4F120)
+
+# define LM_IRQ_GPIOA (16) /* Vector 16: GPIO Port A */
+# define LM_IRQ_GPIOB (17) /* Vector 17: GPIO Port B */
+# define LM_IRQ_GPIOC (18) /* Vector 18: GPIO Port C */
+# define LM_IRQ_GPIOD (19) /* Vector 19: GPIO Port D */
+
+# define LM_IRQ_GPIOE (20) /* Vector 20: GPIO Port E */
+# define LM_IRQ_UART0 (21) /* Vector 21: UART 0 */
+# define LM_IRQ_UART1 (22) /* Vector 22: UART 1 */
+# define LM_IRQ_SSI0 (23) /* Vector 23: SSI 0 */
+# define LM_IRQ_I2C0 (24) /* Vector 24: I2C 0 */
+# define LM_RESERVED_25 (25) /* Vector 25: Reserved */
+# define LM_RESERVED_26 (26) /* Vector 26: Reserved */
+# define LM_RESERVED_27 (27) /* Vector 27: Reserved */
+# define LM_RESERVED_28 (28) /* Vector 28: Reserved */
+# define LM_RESERVED_29 (29) /* Vector 29: Reserved */
+
+# define LM_IRQ_ADC0 (30) /* Vector 30: ADC Sequence 0 */
+# define LM_IRQ_ADC1 (31) /* Vector 31: ADC Sequence 1 */
+# define LM_IRQ_ADC2 (32) /* Vector 32: ADC Sequence 2 */
+# define LM_IRQ_ADC3 (33) /* Vector 33: ADC Sequence 3 */
+# define LM_IRQ_WDOG (34) /* Vector 34: Watchdog Timers 0 and 1 */
+# define LM_IRQ_TIMER0A (35) /* Vector 35: 16/32-Bit Timer 0 A */
+# define LM_IRQ_TIMER0B (36) /* Vector 36: 16/32-Bit Timer 0 B */
+# define LM_IRQ_TIMER1A (37) /* Vector 37: 16/32-Bit Timer 1 A */
+# define LM_IRQ_TIMER1B (38) /* Vector 38: 16/32-Bit Timer 1 B */
+# define LM_IRQ_TIMER2A (39) /* Vector 39: 16/32-Bit Timer 2 A */
+
+# define LM_IRQ_TIMER2B (40) /* Vector 40: 16/32-Bit Timer 2 B */
+# define LM_IRQ_COMPARE0 (41) /* Vector 41: Analog Comparator 0 */
+# define LM_IRQ_COMPARE1 (42) /* Vector 42: Analog Comparator 1 */
+# define LM_RESERVED_43 (43) /* Vector 43: Reserved */
+# define LM_IRQ_SYSCON (44) /* Vector 44: System Control */
+# define LM_IRQ_FLASHCON (45) /* Vector 45: FLASH and EEPROM Control */
+# define LM_IRQ_GPIOF (46) /* Vector 46: GPIO Port F */
+# define LM_RESERVED_47 (47) /* Vector 47: Reserved */
+# define LM_RESERVED_48 (48) /* Vector 48: Reserved */
+# define LM_IRQ_UART2 (49) /* Vector 22: UART 2 */
+
+# define LM_IRQ_SSI1 (50) /* Vector 50: SSI 1 */
+# define LM_IRQ_TIMER3A (51) /* Vector 51: 16/32-Bit Timer 3 A */
+# define LM_IRQ_TIMER3B (52) /* Vector 52: 16/32-Bit Timer 3 B */
+# define LM_IRQ_I2C1 (53) /* Vector 53: I2C 1 */
+# define LM_RESERVED_54 (54) /* Vector 54: Reserved */
+# define LM_IRQ_CAN0 (55) /* Vector 55: CAN 0 */
+# define LM_RESERVED_56 (56) /* Vector 56: Reserved */
+# define LM_RESERVED_57 (57) /* Vector 57: Reserved */
+# define LM_RESERVED_58 (58) /* Vector 58: Reserved */
+# define LM_IRQ_HIBERNATE (59) /* Vector 59: Hibernation Module */
+
+# define LM_IRQ_USB (60) /* Vector 60: USB */
+# define LM_RESERVED_61 (61) /* Vector 61: Reserved */
+# define LM_IRQ_UDMASOFT (62) /* Vector 62: uDMA Software */
+# define LM_IRQ_UDMAERROR (63) /* Vector 63: uDMA Error */
+# define LM_IRQ_ADC1_0 (64) /* Vector 64: ADC1 Sequence 0 */
+# define LM_IRQ_ADC1_1 (65) /* Vector 65: ADC1 Sequence 1 */
+# define LM_IRQ_ADC1_2 (66) /* Vector 66: ADC1 Sequence 2 */
+# define LM_IRQ_ADC1_3 (67) /* Vector 67: ADC1 Sequence 3 */
+# define LM_RESERVED_68 (68) /* Vector 68: Reserved */
+# define LM_RESERVED_69 (69) /* Vector 69: Reserved */
+
+# define LM_RESERVED_70 (70) /* Vector 70: Reserved */
+# define LM_RESERVED_71 (71) /* Vector 71: Reserved */
+# define LM_RESERVED_72 (72) /* Vector 72: Reserved */
+# define LM_IRQ_SSI2 (73) /* Vector 73: SSI 2 */
+# define LM_IRQ_SSI3 (74) /* Vector 74: SSI 3 */
+# define LM_IRQ_UART3 (75) /* Vector 75: UART 3 */
+# define LM_IRQ_UART4 (76) /* Vector 76: UART 4 */
+# define LM_IRQ_UART5 (77) /* Vector 77: UART 5 */
+# define LM_IRQ_UART6 (78) /* Vector 78: UART 6 */
+# define LM_IRQ_UART7 (79) /* Vector 79: UART 7 */
+
+# define LM_RESERVED_80 (80) /* Vector 80: Reserved */
+# define LM_RESERVED_81 (81) /* Vector 81: Reserved */
+# define LM_RESERVED_82 (82) /* Vector 82: Reserved */
+# define LM_RESERVED_83 (83) /* Vector 83: Reserved */
+# define LM_IRQ_I2C2 (84) /* Vector 84: I2C 2 */
+# define LM_IRQ_I2C3 (85) /* Vector 85: I2C 3 */
+# define LM_IRQ_TIMER4A (86) /* Vector 86: 16/32-Bit Timer 4 A */
+# define LM_IRQ_TIMER4B (87) /* Vector 87: 16/32-Bit Timer 4 B */
+# define LM_RESERVED_88 (88) /* Vector 88: Reserved */
+# define LM_RESERVED_89 (89) /* Vector 89: Reserved */
+
+# define LM_RESERVED_90 (90) /* Vector 90: Reserved */
+# define LM_RESERVED_91 (91) /* Vector 91: Reserved */
+# define LM_RESERVED_92 (92) /* Vector 92: Reserved */
+# define LM_RESERVED_93 (93) /* Vector 93: Reserved */
+# define LM_RESERVED_94 (94) /* Vector 94: Reserved */
+# define LM_RESERVED_95 (95) /* Vector 95: Reserved */
+# define LM_RESERVED_96 (96) /* Vector 96: Reserved */
+# define LM_RESERVED_97 (97) /* Vector 97: Reserved */
+# define LM_RESERVED_98 (98) /* Vector 98: Reserved */
+# define LM_RESERVED_99 (99) /* Vector 99: Reserved */
+
+# define LM_RESERVED_100 (100) /* Vector 100: Reserved */
+# define LM_RESERVED_101 (101) /* Vector 101: Reserved */
+# define LM_RESERVED_102 (102) /* Vector 102: Reserved */
+# define LM_RESERVED_103 (103) /* Vector 103: Reserved */
+# define LM_RESERVED_104 (104) /* Vector 104: Reserved */
+# define LM_RESERVED_105 (105) /* Vector 105: Reserved */
+# define LM_RESERVED_106 (106) /* Vector 106: Reserved */
+# define LM_RESERVED_107 (107) /* Vector 107: Reserved */
+# define LM_IRQ_TIMER5A (108) /* Vector 108: 16/32-Bit Timer 5 A */
+# define LM_IRQ_TIMER5B (109) /* Vector 109: 16/32-Bit Timer 5 B */
+
+# define LM_IRQ_WTIMER0A (110) /* Vector 110: 32/64-Bit Timer 0 A */
+# define LM_IRQ_WTIMER0B (111) /* Vector 111: 32/64-Bit Timer 0 B */
+# define LM_IRQ_WTIMER1A (112) /* Vector 112: 32/64-Bit Timer 1 A */
+# define LM_IRQ_WTIMER1B (113) /* Vector 113: 32/64-Bit Timer 1 B */
+# define LM_IRQ_WTIMER2A (114) /* Vector 114: 32/64-Bit Timer 2 A */
+# define LM_IRQ_WTIMER2B (115) /* Vector 115: 32/64-Bit Timer 2 B */
+# define LM_IRQ_WTIMER3A (116) /* Vector 116: 32/64-Bit Timer 3 A */
+# define LM_IRQ_WTIMER3B (117) /* Vector 117: 32/64-Bit Timer 3 B */
+# define LM_IRQ_WTIMER4A (118) /* Vector 118: 32/64-Bit Timer 4 A */
+# define LM_IRQ_WTIMER4B (119) /* Vector 119: 32/64-Bit Timer 4 B */
+
+# define LM_IRQ_WTIMER5A (120) /* Vector 120: 32/64-Bit Timer 5 A */
+# define LM_IRQ_WTIMER5B (121) /* Vector 121: 32/64-Bit Timer 5 B */
+# define LM_IRQ_SYSTEM (122) /* Vector 122: System Exception (imprecise) */
+# define LM_RESERVED_123 (123) /* Vector 123: Reserved */
+# define LM_RESERVED_124 (124) /* Vector 124: Reserved */
+# define LM_RESERVED_125 (125) /* Vector 125: Reserved */
+# define LM_RESERVED_126 (126) /* Vector 126: Reserved */
+# define LM_RESERVED_127 (127) /* Vector 127: Reserved */
+# define LM_RESERVED_128 (128) /* Vector 128: Reserved */
+# define LM_RESERVED_129 (129) /* Vector 129: Reserved */
+
+# define LM_RESERVED_130 (130) /* Vector 130: Reserved */
+# define LM_RESERVED_131 (131) /* Vector 131: Reserved */
+# define LM_RESERVED_132 (132) /* Vector 132: Reserved */
+# define LM_RESERVED_133 (133) /* Vector 133: Reserved */
+# define LM_RESERVED_134 (134) /* Vector 134: Reserved */
+# define LM_RESERVED_135 (135) /* Vector 135: Reserved */
+# define LM_RESERVED_136 (136) /* Vector 136: Reserved */
+# define LM_RESERVED_137 (137) /* Vector 137: Reserved */
+# define LM_RESERVED_138 (138) /* Vector 138: Reserved */
+# define LM_RESERVED_139 (139) /* Vector 139: Reserved */
+
+# define LM_RESERVED_140 (140) /* Vector 140: Reserved */
+# define LM_RESERVED_141 (141) /* Vector 141: Reserved */
+# define LM_RESERVED_142 (142) /* Vector 142: Reserved */
+# define LM_RESERVED_143 (143) /* Vector 143: Reserved */
+# define LM_RESERVED_144 (144) /* Vector 144: Reserved */
+# define LM_RESERVED_145 (145) /* Vector 145: Reserved */
+# define LM_RESERVED_146 (146) /* Vector 146: Reserved */
+# define LM_RESERVED_147 (147) /* Vector 147: Reserved */
+# define LM_RESERVED_148 (148) /* Vector 148: Reserved */
+# define LM_RESERVED_149 (149) /* Vector 149: Reserved */
+
+# define LM_RESERVED_150 (150) /* Vector 150: Reserved */
+# define LM_RESERVED_151 (151) /* Vector 151: Reserved */
+# define LM_RESERVED_152 (152) /* Vector 152: Reserved */
+# define LM_RESERVED_153 (153) /* Vector 153: Reserved */
+# define LM_RESERVED_154 (154) /* Vector 154: Reserved */
+
+# define NR_IRQS (123) /* (Really fewer because of reserved vectors) */
+
+#else
+# error "IRQ Numbers not known for this Stellaris chip"
+#endif
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#ifdef __cplusplus
+}
+#endif
+#endif
+
+#endif /* __ARCH_ARM_INCLUDE_LM_LM4F_IRQ_H */
+
diff --git a/nuttx/arch/arm/src/lm/Kconfig b/nuttx/arch/arm/src/lm/Kconfig
index 972f68bc0..b2786c265 100644
--- a/nuttx/arch/arm/src/lm/Kconfig
+++ b/nuttx/arch/arm/src/lm/Kconfig
@@ -36,6 +36,11 @@ config ARCH_CHIP_LM3S8962
select ARCH_CORTEXM3
select ARCH_CHIP_LM3S
+config ARCH_CHIP_LM4F120
+ bool "LM4F120"
+ select ARCH_CORTEXM4
+ select ARCH_CHIP_LM4F
+
endchoice
# Chip families
diff --git a/nuttx/arch/arm/src/lm/chip/lm4f_vectors.h b/nuttx/arch/arm/src/lm/chip/lm4f_vectors.h
new file mode 100644
index 000000000..c8e69377b
--- /dev/null
+++ b/nuttx/arch/arm/src/lm/chip/lm4f_vectors.h
@@ -0,0 +1,223 @@
+/************************************************************************************
+ * arch/arm/src/lm/chip/lm4f_vectors.S
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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.
+ *
+ ************************************************************************************/
+
+/************************************************************************************
+ * Preprocessor Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Vectors
+ ************************************************************************************/
+
+/* This file is included by lm_vectors.S. It provides the macro VECTOR that
+ * supplies ach Stellaris vector in terms of a (lower-case) ISR label and an
+ * (upper-case) IRQ number as defined in arch/arm/include/lm/lm4f_irq.h.
+ * lm_vectors.S will define the VECTOR in different ways in order to generate
+ * the interrupt vectors and handlers in their final form.
+ */
+
+#if defined(CONFIG_ARCH_CHIP_LM4F120)
+
+/* If the common ARMv7-M vector handling is used, then all it needs is the following
+ * definition that provides the number of supported vectors.
+ */
+
+# ifdef CONFIG_ARMV7M_CMNVECTOR
+
+/* Reserve 155 interrupt table entries for I/O interrupts. */
+
+ARMV7M_PERIPHERAL_INTERRUPTS 155
+
+# else
+
+VECTOR(lm_gpioa, LM_IRQ_GPIOA) /* Vector 16: GPIO Port A */
+VECTOR(lm_gpiob, LM_IRQ_GPIOB) /* Vector 17: GPIO Port B */
+VECTOR(lm_gpioc, LM_IRQ_GPIOC) /* Vector 18: GPIO Port C */
+VECTOR(lm_gpiod, LM_IRQ_GPIOD) /* Vector 19: GPIO Port D */
+
+VECTOR(lm_gpioe, LM_IRQ_GPIOE) /* Vector 20: GPIO Port E */
+VECTOR(lm_uart0, LM_IRQ_UART0) /* Vector 21: UART 0 */
+VECTOR(lm_uart1, LM_IRQ_UART1) /* Vector 22: UART 1 */
+VECTOR(lm_ssi0, LM_IRQ_SSI0) /* Vector 23: SSI 0 */
+VECTOR(lm_i2c0, LM_IRQ_I2C0) /* Vector 24: I2C 0 */
+UNUSED(LM_RESERVED_25) /* Vector 25: Reserved */
+UNUSED(LM_RESERVED_26) /* Vector 26: Reserved */
+UNUSED(LM_RESERVED_27) /* Vector 27: Reserved */
+UNUSED(LM_RESERVED_28) /* Vector 28: Reserved */
+UNUSED(LM_RESERVED_29) /* Vector 29: Reserved */
+
+VECTOR(lm_adc0, LM_IRQ_ADC0) /* Vector 30: ADC Sequence 0 */
+VECTOR(lm_adc1, LM_IRQ_ADC1) /* Vector 31: ADC Sequence 1 */
+VECTOR(lm_adc2, LM_IRQ_ADC2) /* Vector 32: ADC Sequence 2 */
+VECTOR(lm_adc3, LM_IRQ_ADC3) /* Vector 33: ADC Sequence 3 */
+VECTOR(lm_wdog, LM_IRQ_WDOG) /* Vector 34: Watchdog Timers 0 and 1 */
+VECTOR(lm_timer0a, LM_IRQ_TIMER0A) /* Vector 35: 16/32-Bit Timer 0 A */
+VECTOR(lm_timer0b, LM_IRQ_TIMER0B) /* Vector 36: 16/32-Bit Timer 0 B */
+VECTOR(lm_timer1a, LM_IRQ_TIMER1A) /* Vector 37: 16/32-Bit Timer 1 A */
+VECTOR(lm_timer1b, LM_IRQ_TIMER1B) /* Vector 38: 16/32-Bit Timer 1 B */
+VECTOR(lm_timer2a, LM_IRQ_TIMER2A) /* Vector 39: 16/32-Bit Timer 2 A */
+
+VECTOR(lm_timer2b, LM_IRQ_TIMER2B) /* Vector 40: 16/32-Bit Timer 2 B */
+VECTOR(lm_compare0, LM_IRQ_COMPARE0) /* Vector 41: Analog Comparator 0 */
+VECTOR(lm_compare1, LM_IRQ_COMPARE1) /* Vector 42: Analog Comparator 1 */
+UNUSED(LM_RESERVED_43) /* Vector 43: Reserved */
+VECTOR(lm_syscon, LM_IRQ_SYSCON) /* Vector 44: System Control */
+VECTOR(lm_flashcon, LM_IRQ_FLASHCON) /* Vector 45: FLASH and EEPROM Control */
+VECTOR(lm_gpiof, LM_IRQ_GPIOF) /* Vector 46: GPIO Port F */
+UNUSED(LM_RESERVED_47) /* Vector 47: Reserved */
+UNUSED(LM_RESERVED_48) /* Vector 48: Reserved */
+VECTOR(lm_uart2, LM_IRQ_UART2) /* Vector 22: UART 2 */
+
+VECTOR(lm_ssi1, LM_IRQ_SSI1) /* Vector 50: SSI 1 */
+VECTOR(lm_timer3a, LM_IRQ_TIMER3A) /* Vector 51: 16/32-Bit Timer 3 A */
+VECTOR(lm_timer3b, LM_IRQ_TIMER3B) /* Vector 52: 16/32-Bit Timer 3 B */
+VECTOR(lm_i2c1, LM_IRQ_I2C1) /* Vector 53: I2C 1 */
+UNUSED(LM_RESERVED_54) /* Vector 54: Reserved */
+VECTOR(lm_can0, LM_IRQ_CAN0) /* Vector 55: CAN 0 */
+UNUSED(LM_RESERVED_56) /* Vector 56: Reserved */
+UNUSED(LM_RESERVED_57) /* Vector 57: Reserved */
+UNUSED(LM_RESERVED_58) /* Vector 58: Reserved */
+VECTOR(lm_hibernate, LM_IRQ_HIBERNATE) /* Vector 59: Hibernation Module */
+
+VECTOR(lm_usb, LM_IRQ_USB) /* Vector 60: USB */
+UNUSED(LM_RESERVED_61) /* Vector 61: Reserved */
+VECTOR(lm_udmasoft, LM_IRQ_UDMASOFT) /* Vector 62: uDMA Software */
+VECTOR(lm_udmaerro, LM_IRQ_UDMAERROR) /* Vector 63: uDMA Error */
+VECTOR(lm_adc1_0, LM_IRQ_ADC1_0) /* Vector 64: ADC1 Sequence 0 */
+VECTOR(lm_adc1_1, LM_IRQ_ADC1_1) /* Vector 65: ADC1 Sequence 1 */
+VECTOR(lm_adc1_2, LM_IRQ_ADC1_2) /* Vector 66: ADC1 Sequence 2 */
+VECTOR(lm_adc1_3, LM_IRQ_ADC1_3) /* Vector 67: ADC1 Sequence 3 */
+UNUSED(LM_RESERVED_68) /* Vector 68: Reserved */
+UNUSED(LM_RESERVED_69) /* Vector 69: Reserved */
+
+UNUSED(LM_RESERVED_70) /* Vector 70: Reserved */
+UNUSED(LM_RESERVED_71) /* Vector 71: Reserved */
+UNUSED(LM_RESERVED_72) /* Vector 72: Reserved */
+VECTOR(lm_ssi2, LM_IRQ_SSI2) /* Vector 73: SSI 2 */
+VECTOR(lm_ssi3, LM_IRQ_SSI3) /* Vector 74: SSI 3 */
+VECTOR(lm_uart3, LM_IRQ_UART3) /* Vector 75: UART 3 */
+VECTOR(lm_uart4, LM_IRQ_UART4) /* Vector 76: UART 4 */
+VECTOR(lm_uart5, LM_IRQ_UART5) /* Vector 77: UART 5 */
+VECTOR(lm_uart6, LM_IRQ_UART6) /* Vector 78: UART 6 */
+VECTOR(lm_uart7, LM_IRQ_UART7) /* Vector 79: UART 7 */
+
+UNUSED(LM_RESERVED_80) /* Vector 80: Reserved */
+UNUSED(LM_RESERVED_81) /* Vector 81: Reserved */
+UNUSED(LM_RESERVED_82) /* Vector 82: Reserved */
+UNUSED(LM_RESERVED_83) /* Vector 83: Reserved */
+VECTOR(lm_i2c2, LM_IRQ_I2C2) /* Vector 84: I2C 2 */
+VECTOR(lm_i2c3, LM_IRQ_I2C3) /* Vector 85: I2C 3 */
+VECTOR(lm_timer4a, LM_IRQ_TIMER4A) /* Vector 86: 16/32-Bit Timer 4 A */
+VECTOR(lm_timer4b, LM_IRQ_TIMER4B) /* Vector 87: 16/32-Bit Timer 4 B */
+UNUSED(LM_RESERVED_88) /* Vector 88: Reserved */
+UNUSED(LM_RESERVED_89) /* Vector 89: Reserved */
+
+UNUSED(LM_RESERVED_90) /* Vector 90: Reserved */
+UNUSED(LM_RESERVED_91) /* Vector 91: Reserved */
+UNUSED(LM_RESERVED_92) /* Vector 92: Reserved */
+UNUSED(LM_RESERVED_93) /* Vector 93: Reserved */
+UNUSED(LM_RESERVED_94) /* Vector 94: Reserved */
+UNUSED(LM_RESERVED_95) /* Vector 95: Reserved */
+UNUSED(LM_RESERVED_96) /* Vector 96: Reserved */
+UNUSED(LM_RESERVED_97) /* Vector 97: Reserved */
+UNUSED(LM_RESERVED_98) /* Vector 98: Reserved */
+UNUSED(LM_RESERVED_99) /* Vector 99: Reserved */
+
+UNUSED(LM_RESERVED_100) /* Vector 100: Reserved */
+UNUSED(LM_RESERVED_101) /* Vector 101: Reserved */
+UNUSED(LM_RESERVED_102) /* Vector 102: Reserved */
+UNUSED(LM_RESERVED_103) /* Vector 103: Reserved */
+UNUSED(LM_RESERVED_104) /* Vector 104: Reserved */
+UNUSED(LM_RESERVED_105) /* Vector 105: Reserved */
+UNUSED(LM_RESERVED_106) /* Vector 106: Reserved */
+UNUSED(LM_RESERVED_107) /* Vector 107: Reserved */
+VECTOR(lm_timer5a, LM_IRQ_TIMER5A) /* Vector 108: 16/32-Bit Timer 5 A */
+VECTOR(lm_timer5b, LM_IRQ_TIMER5B) /* Vector 109: 16/32-Bit Timer 5 B */
+
+VECTOR(lm_wtimer0a, LM_IRQ_WTIMER0A) /* Vector 110: 32/64-Bit Timer 0 A */
+VECTOR(lm_wtimer0b, LM_IRQ_WTIMER0B) /* Vector 111: 32/64-Bit Timer 0 B */
+VECTOR(lm_wtimer1a, LM_IRQ_WTIMER1A) /* Vector 112: 32/64-Bit Timer 1 A */
+VECTOR(lm_wtimer1b, LM_IRQ_WTIMER1B) /* Vector 113: 32/64-Bit Timer 1 B */
+VECTOR(lm_wtimer2a, LM_IRQ_WTIMER2A) /* Vector 114: 32/64-Bit Timer 2 A */
+VECTOR(lm_wtimer2b, LM_IRQ_WTIMER2B) /* Vector 115: 32/64-Bit Timer 2 B */
+VECTOR(lm_wtimer3a, LM_IRQ_WTIMER3A) /* Vector 116: 32/64-Bit Timer 3 A */
+VECTOR(lm_wtimer3b, LM_IRQ_WTIMER3B) /* Vector 117: 32/64-Bit Timer 3 B */
+VECTOR(lm_wtimer4a, LM_IRQ_WTIMER4A) /* Vector 118: 32/64-Bit Timer 4 A */
+VECTOR(lm_WTIMER4B, LM_IRQ_WTIMER4B) /* Vector 119: 32/64-Bit Timer 4 B */
+
+VECTOR(lm_wtimer5a, LM_IRQ_WTIMER5A) /* Vector 120: 32/64-Bit Timer 5 A */
+VECTOR(lm_wtimer5b, LM_IRQ_WTIMER5B) /* Vector 121: 32/64-Bit Timer 5 B */
+VECTOR(lm_system, LM_IRQ_SYSTEM) /* Vector 122: System Exception (imprecise) */
+UNUSED(LM_RESERVED_123) /* Vector 123: Reserved */
+UNUSED(LM_RESERVED_124) /* Vector 124: Reserved */
+UNUSED(LM_RESERVED_125) /* Vector 125: Reserved */
+UNUSED(LM_RESERVED_126) /* Vector 126: Reserved */
+UNUSED(LM_RESERVED_127) /* Vector 127: Reserved */
+UNUSED(LM_RESERVED_128) /* Vector 128: Reserved */
+UNUSED(LM_RESERVED_129) /* Vector 129: Reserved */
+
+UNUSED(LM_RESERVED_130) /* Vector 130: Reserved */
+UNUSED(LM_RESERVED_131) /* Vector 131: Reserved */
+UNUSED(LM_RESERVED_132) /* Vector 132: Reserved */
+UNUSED(LM_RESERVED_133) /* Vector 133: Reserved */
+UNUSED(LM_RESERVED_134) /* Vector 134: Reserved */
+UNUSED(LM_RESERVED_135) /* Vector 135: Reserved */
+UNUSED(LM_RESERVED_136) /* Vector 136: Reserved */
+UNUSED(LM_RESERVED_137) /* Vector 137: Reserved */
+UNUSED(LM_RESERVED_138) /* Vector 138: Reserved */
+UNUSED(LM_RESERVED_139) /* Vector 139: Reserved */
+
+UNUSED(LM_RESERVED_140) /* Vector 140: Reserved */
+UNUSED(LM_RESERVED_141) /* Vector 141: Reserved */
+UNUSED(LM_RESERVED_142) /* Vector 142: Reserved */
+UNUSED(LM_RESERVED_143) /* Vector 143: Reserved */
+UNUSED(LM_RESERVED_144) /* Vector 144: Reserved */
+UNUSED(LM_RESERVED_145) /* Vector 145: Reserved */
+UNUSED(LM_RESERVED_146) /* Vector 146: Reserved */
+UNUSED(LM_RESERVED_147) /* Vector 147: Reserved */
+UNUSED(LM_RESERVED_148) /* Vector 148: Reserved */
+UNUSED(LM_RESERVED_149) /* Vector 149: Reserved */
+
+UNUSED(LM_RESERVED_150) /* Vector 150: Reserved */
+UNUSED(LM_RESERVED_151) /* Vector 151: Reserved */
+UNUSED(LM_RESERVED_152) /* Vector 152: Reserved */
+UNUSED(LM_RESERVED_153) /* Vector 153: Reserved */
+UNUSED(LM_RESERVED_154) /* Vector 154: Reserved */
+
+# endif /* CONFIG_ARMV7M_CMNVECTOR */
+
+#else
+# error "Vectors not known for this Stellaris chip"
+#endif
diff --git a/nuttx/configs/Kconfig b/nuttx/configs/Kconfig
index 7933f48e3..0f0685177 100644
--- a/nuttx/configs/Kconfig
+++ b/nuttx/configs/Kconfig
@@ -200,6 +200,15 @@ config ARCH_BOARD_LM3S8962EK
---help---
Stellaris LMS38962 Evaluation Kit.
+config ARCH_BOARD_LM4F120_LAUNCHPAD
+ bool "Stellaris LM4F120 LaunchPad"
+ depends on ARCH_CHIP_LM4F120
+ select ARCH_HAVE_LEDS
+ select ARCH_HAVE_BUTTONS
+ select ARCH_HAVE_IRQBUTTONS
+ ---help---
+ Stellaris LM4F120 LaunchPad.
+
config ARCH_BOARD_LPCXPRESSO
bool "NXP LPCExpresso LPC1768"
depends on ARCH_CHIP_LPC1768
@@ -700,6 +709,7 @@ config ARCH_BOARD
default "lm3s6432-s2e" if ARCH_BOARD_LM3S6432S2E
default "lm3s6965-ek" if ARCH_BOARD_LM3S6965EK
default "lm3s8962-ek" if ARCH_BOARD_LM3S8962EK
+ default "lm4f120-launchpad" if ARCH_BOARD_LM4F120_LAUNCHPAD
default "lpc4330-xplorer" if ARCH_BOARD_LPC4330_XPLORER
default "lpcxpresso-lpc1768" if ARCH_BOARD_LPCXPRESSO
default "m68322evb" if ARCH_BOARD_M68332EVB
@@ -861,6 +871,9 @@ endif
if ARCH_BOARD_LM3S8962EK
source "configs/lm3s8962-ek/Kconfig"
endif
+if ARCH_BOARD_LM3S8962EK
+source "configs/lm4f120-launchpad/Kconfig"
+endif
if ARCH_BOARD_LPC4330_XPLORER
source "configs/lpc4330-xplorer/Kconfig"
endif
diff --git a/nuttx/configs/README.txt b/nuttx/configs/README.txt
index dd8b6a10b..b0e6b16d1 100644
--- a/nuttx/configs/README.txt
+++ b/nuttx/configs/README.txt
@@ -1781,6 +1781,12 @@ configs/lm3s6965-ek
configs/lm3s8962-ek
Stellaris LMS38962 Evaluation Kit.
+configs/lm4f120-launchpad
+ This is the port of NuttX to the Stellaris LM4F120 LaunchPad. The
+ Stellaris® LM4F120 LaunchPad Evaluation Board is a low-cost evaluation
+ platform for ARM® Cortex™-M4F-based microcontrollers from Texas\
+ Instruments.
+
configs/lpcxpresso-lpc1768
Embedded Artists base board with NXP LPCExpresso LPC1768. This board
is based on the NXP LPC1768. The Code Red toolchain is used by default.
@@ -1846,6 +1852,10 @@ configs/nucleus2g
features an NXP LPC1768 processor. See the 2G website (http://www.2g-eng.com/)
for more information about the Nucleus 2G.
+configs/nutiny-nuc120
+ This is the port of NuttX to the NuvoTon NuTiny-SDK-NUC120 board. This
+ board has the NUC120LE3AN chip with a built-in NuLink debugger.
+
configs/olimex-lpc1766stk
This port uses the Olimex LPC1766-STK board and a GNU GCC toolchain* under
Linux or Cygwin. STATUS: Complete and mature.
diff --git a/nuttx/configs/c5471evm/Kconfig b/nuttx/configs/c5471evm/Kconfig
index 025ba5e0e..cadb1d12a 100644
--- a/nuttx/configs/c5471evm/Kconfig
+++ b/nuttx/configs/c5471evm/Kconfig
@@ -4,10 +4,4 @@
#
if ARCH_BOARD_C5471EVM
-config ARCH_LEDS
- bool "NuttX LED support"
- default n
- ---help---
- "Support control of board LEDs by NuttX to indicate system state"
-
endif
diff --git a/nuttx/configs/eagle100/Kconfig b/nuttx/configs/eagle100/Kconfig
index 40b9f8294..8f4df4305 100644
--- a/nuttx/configs/eagle100/Kconfig
+++ b/nuttx/configs/eagle100/Kconfig
@@ -4,10 +4,4 @@
#
if ARCH_BOARD_EAGLE100
-config ARCH_LEDS
- bool "NuttX LED support"
- default n
- ---help---
- "Support control of board LEDs by NuttX to indicate system state"
-
endif
diff --git a/nuttx/configs/lm3s6432-s2e/Kconfig b/nuttx/configs/lm3s6432-s2e/Kconfig
index 102f4a5f6..f970a89c2 100644
--- a/nuttx/configs/lm3s6432-s2e/Kconfig
+++ b/nuttx/configs/lm3s6432-s2e/Kconfig
@@ -4,10 +4,4 @@
#
if ARCH_BOARD_LM3S6432S2E
-config ARCH_LEDS
- bool "NuttX LED support"
- default n
- ---help---
- "Support control of board LEDs by NuttX to indicate system state"
-
endif
diff --git a/nuttx/configs/lm3s6965-ek/Kconfig b/nuttx/configs/lm3s6965-ek/Kconfig
index 809ae2fe6..d956f4733 100644
--- a/nuttx/configs/lm3s6965-ek/Kconfig
+++ b/nuttx/configs/lm3s6965-ek/Kconfig
@@ -4,10 +4,4 @@
#
if ARCH_BOARD_LM3S6965EK
-config ARCH_LEDS
- bool "NuttX LED support"
- default n
- ---help---
- "Support control of board LEDs by NuttX to indicate system state"
-
endif
diff --git a/nuttx/configs/lm3s8962-ek/Kconfig b/nuttx/configs/lm3s8962-ek/Kconfig
index 87dc03a9d..dd9739f99 100644
--- a/nuttx/configs/lm3s8962-ek/Kconfig
+++ b/nuttx/configs/lm3s8962-ek/Kconfig
@@ -4,10 +4,4 @@
#
if ARCH_BOARD_LM3S8962EK
-config ARCH_LEDS
- bool "NuttX LED support"
- default n
- ---help---
- "Support control of board LEDs by NuttX to indicate system state"
-
endif
diff --git a/nuttx/configs/lm4f120-launchpad/Kconfig b/nuttx/configs/lm4f120-launchpad/Kconfig
index 24afc84f8..0e53e4023 100644
--- a/nuttx/configs/lm4f120-launchpad/Kconfig
+++ b/nuttx/configs/lm4f120-launchpad/Kconfig
@@ -3,11 +3,5 @@
# see misc/tools/kconfig-language.txt.
#
-if ARCH_BOARD_LM4FLAUNCHPAD
-config ARCH_LEDS
- bool "NuttX LED support"
- default n
- ---help---
- "Support control of board LEDs by NuttX to indicate system state"
-
+if ARCH_BOARD_LM4F120_LAUNCHPAD
endif
diff --git a/nuttx/configs/lm4f120-launchpad/README.txt b/nuttx/configs/lm4f120-launchpad/README.txt
index d05e37966..b4d6fda93 100644
--- a/nuttx/configs/lm4f120-launchpad/README.txt
+++ b/nuttx/configs/lm4f120-launchpad/README.txt
@@ -512,7 +512,7 @@ LM4F120 LaunchPad Configuration Options
CONFIG_ARCH_BOARD_name - For use in C code
- CONFIG_ARCH_BOARD_LM4FLAUNCHPAD
+ CONFIG_ARCH_BOARD_LM4F120_LAUNCHPAD
CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation
of delay loops
diff --git a/nuttx/configs/lm4f120-launchpad/include/board.h b/nuttx/configs/lm4f120-launchpad/include/board.h
index 87e6dca8f..f4de4e5b6 100644
--- a/nuttx/configs/lm4f120-launchpad/include/board.h
+++ b/nuttx/configs/lm4f120-launchpad/include/board.h
@@ -142,7 +142,7 @@
#define LED_INIRQ 2 /* NC NC ON (momentary) */
#define LED_SIGNAL 2 /* NC NC ON (momentary) */
#define LED_ASSERTION 3 /* ON NC NC (momentary) */
-#define LED_PANIC 3 /* ON OFF OFF (flashing 2Hz) */
+#define LED_PANIC 4 /* ON OFF OFF (flashing 2Hz) */
/* LED definitions ******************************************************************/
/* The LM32F120 has a two buttons:
diff --git a/nuttx/configs/lm4f120-launchpad/ostest/defconfig b/nuttx/configs/lm4f120-launchpad/ostest/defconfig
index fdc515995..34ae0e602 100755
--- a/nuttx/configs/lm4f120-launchpad/ostest/defconfig
+++ b/nuttx/configs/lm4f120-launchpad/ostest/defconfig
@@ -66,22 +66,22 @@ CONFIG_ARCH="arm"
# CONFIG_ARCH_CHIP_IMX is not set
# CONFIG_ARCH_CHIP_KINETIS is not set
CONFIG_ARCH_CHIP_LM=y
-CONFIG_ARCH_CHIP_LM4F=y
# CONFIG_ARCH_CHIP_LPC17XX is not set
# CONFIG_ARCH_CHIP_LPC214X is not set
# CONFIG_ARCH_CHIP_LPC2378 is not set
# CONFIG_ARCH_CHIP_LPC31XX is not set
# CONFIG_ARCH_CHIP_LPC43XX is not set
+# CONFIG_ARCH_CHIP_NUC1XX is not set
# CONFIG_ARCH_CHIP_SAM3U is not set
# CONFIG_ARCH_CHIP_STM32 is not set
# CONFIG_ARCH_CHIP_STR71X is not set
CONFIG_ARCH_CORTEXM4=y
CONFIG_ARCH_FAMILY="armv7-m"
CONFIG_ARCH_CHIP="lm"
+# CONFIG_ARMV7M_USEBASEPRI is not set
+# CONFIG_ARCH_FPU is not set
CONFIG_ARCH_HAVE_MPU=y
# CONFIG_ARMV7M_MPU is not set
-CONFIG_BOARD_LOOPSPERMSEC=4531
-# CONFIG_ARCH_CALIBRATION is not set
#
# ARMV7M Configuration Options
@@ -98,12 +98,14 @@ CONFIG_ARMV7M_OABI_TOOLCHAIN=y
# CONFIG_ARCH_CHIP_LM3S6918 is not set
# CONFIG_ARCH_CHIP_LM3S9B96 is not set
# CONFIG_ARCH_CHIP_LM3S6432 is not set
-CONFIG_ARCH_CHIP_LM4F120=y
+# CONFIG_ARCH_CHIP_LM3S6965 is not set
# CONFIG_ARCH_CHIP_LM3S8962 is not set
+CONFIG_ARCH_CHIP_LM4F120=y
+CONFIG_ARCH_CHIP_LM4F=y
# CONFIG_LM_REVA2 is not set
#
-# Select Stellaris Peripheral Support
+# Stellaris Peripheral Support
#
CONFIG_LM_UART0=y
# CONFIG_LM_UART1 is not set
@@ -130,23 +132,30 @@ CONFIG_LM_DISABLE_GPIOJ_IRQS=y
#
CONFIG_SSI_POLLWAIT=y
CONFIG_SSI_TXLIMIT=4
-# CONFIG_SDIO_DMA is not set
-# CONFIG_SDIO_WIDTH_D1_ONLY is not set
+
+#
+# External Memory Configuration
+#
#
# Architecture Options
#
# CONFIG_ARCH_NOINTC is not set
+# CONFIG_ARCH_VECNOTIRQ is not set
# CONFIG_ARCH_DMA is not set
CONFIG_ARCH_IRQPRIO=y
# CONFIG_CUSTOM_STACK is not set
# CONFIG_ADDRENV is not set
+CONFIG_ARCH_HAVE_VFORK=y
CONFIG_ARCH_STACKDUMP=y
# CONFIG_ENDIAN_BIG is not set
+# CONFIG_ARCH_HAVE_RAMFUNCS is not set
#
# Board Settings
#
+CONFIG_BOARD_LOOPSPERMSEC=4531
+# CONFIG_ARCH_CALIBRATION is not set
CONFIG_DRAM_START=0x20000000
CONFIG_DRAM_SIZE=65536
CONFIG_ARCH_HAVE_INTERRUPTSTACK=y
@@ -164,7 +173,7 @@ CONFIG_BOOT_RUNFROMFLASH=y
#
# Board Selection
#
-CONFIG_ARCH_BOARD_LM4FLAUNCHPAD=y
+CONFIG_ARCH_BOARD_LM4F120_LAUNCHPAD=y
# CONFIG_ARCH_BOARD_CUSTOM is not set
CONFIG_ARCH_BOARD="lm4f120-launchpad"
@@ -173,6 +182,9 @@ CONFIG_ARCH_BOARD="lm4f120-launchpad"
#
CONFIG_ARCH_HAVE_LEDS=y
CONFIG_ARCH_LEDS=y
+CONFIG_ARCH_HAVE_BUTTONS=y
+# CONFIG_ARCH_BUTTONS is not set
+CONFIG_ARCH_HAVE_IRQBUTTONS=y
#
# Board-Specific Options
@@ -181,10 +193,12 @@ CONFIG_ARCH_LEDS=y
#
# RTOS Features
#
+# CONFIG_BOARD_INITIALIZE is not set
CONFIG_MSEC_PER_TICK=10
CONFIG_RR_INTERVAL=200
# CONFIG_SCHED_INSTRUMENTATION is not set
CONFIG_TASK_NAME_SIZE=0
+# CONFIG_SCHED_HAVE_PARENT is not set
# CONFIG_JULIAN_TIME is not set
CONFIG_START_YEAR=2010
CONFIG_START_MONTH=5
@@ -197,6 +211,7 @@ CONFIG_DEV_CONSOLE=y
CONFIG_SDCLONE_DISABLE=y
# CONFIG_SCHED_WORKQUEUE is not set
# CONFIG_SCHED_WAITPID is not set
+# CONFIG_SCHED_STARTHOOK is not set
# CONFIG_SCHED_ATEXIT is not set
# CONFIG_SCHED_ONEXIT is not set
CONFIG_USER_ENTRYPOINT="ostest_main"
@@ -206,9 +221,15 @@ CONFIG_DISABLE_OS_API=y
# CONFIG_DISABLE_PTHREAD is not set
# CONFIG_DISABLE_SIGNALS is not set
# CONFIG_DISABLE_MQUEUE is not set
-CONFIG_DISABLE_MOUNTPOINT=y
CONFIG_DISABLE_ENVIRON=y
-CONFIG_DISABLE_POLL=y
+
+#
+# Signal Numbers
+#
+CONFIG_SIG_SIGUSR1=1
+CONFIG_SIG_SIGUSR2=2
+CONFIG_SIG_SIGALARM=3
+CONFIG_SIG_SIGCONDTIMEDOUT=16
#
# Sizes of configurable things (0 disables)
@@ -236,6 +257,7 @@ CONFIG_PTHREAD_STACK_DEFAULT=2048
#
# Device Drivers
#
+CONFIG_DISABLE_POLL=y
CONFIG_DEV_NULL=y
# CONFIG_DEV_ZERO is not set
# CONFIG_LOOP is not set
@@ -250,16 +272,7 @@ CONFIG_DEV_NULL=y
# CONFIG_BCH is not set
# CONFIG_INPUT is not set
# CONFIG_LCD is not set
-CONFIG_MMCSD=y
-CONFIG_MMCSD_NSLOTS=1
-# CONFIG_MMCSD_READONLY is not set
-# CONFIG_MMCSD_MULTIBLOCK_DISABLE is not set
-CONFIG_MMCSD_MMCSUPPORT=y
-CONFIG_MMCSD_HAVECARDDETECT=y
-CONFIG_MMCSD_SPI=y
-CONFIG_MMCSD_SPICLOCK=12500000
-# CONFIG_MMCSD_SDIO is not set
-# CONFIG_SDIO_MUXBUS is not set
+# CONFIG_MMCSD is not set
# CONFIG_MTD is not set
# CONFIG_PIPES is not set
# CONFIG_PM is not set
@@ -308,11 +321,13 @@ CONFIG_UART0_2STOP=0
#
# File system configuration
#
+CONFIG_DISABLE_MOUNTPOINT=y
# CONFIG_FS_RAMMAP is not set
#
# System Logging
#
+# CONFIG_SYSLOG_ENABLE is not set
# CONFIG_SYSLOG is not set
#
@@ -333,6 +348,7 @@ CONFIG_MM_REGIONS=1
# CONFIG_BINFMT_DISABLE is not set
# CONFIG_NXFLAT is not set
# CONFIG_ELF is not set
+# CONFIG_BUILTIN is not set
# CONFIG_PIC is not set
# CONFIG_SYMTAB_ORDEREDBYNAME is not set
@@ -353,6 +369,9 @@ CONFIG_NUNGET_CHARS=2
# CONFIG_EOL_IS_LF is not set
# CONFIG_EOL_IS_BOTH_CRLF is not set
CONFIG_EOL_IS_EITHER_CRLF=y
+# CONFIG_LIBC_EXECFUNCS is not set
+CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=1024
+CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=2048
# CONFIG_LIBC_STRERROR is not set
# CONFIG_LIBC_PERROR_STDOUT is not set
CONFIG_ARCH_LOWPUTC=y
@@ -378,14 +397,12 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
#
# Built-In Applications
#
-# CONFIG_BUILTIN is not set
#
# Examples
#
# CONFIG_EXAMPLES_BUTTONS is not set
# CONFIG_EXAMPLES_CAN is not set
-# CONFIG_EXAMPLES_CDCACM is not set
# CONFIG_EXAMPLES_COMPOSITE is not set
# CONFIG_EXAMPLES_DHCPD is not set
# CONFIG_EXAMPLES_ELF is not set
@@ -401,7 +418,6 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
# CONFIG_EXAMPLES_MM is not set
# CONFIG_EXAMPLES_MOUNT is not set
# CONFIG_EXAMPLES_MODBUS is not set
-# CONFIG_EXAMPLES_NETTEST is not set
# CONFIG_EXAMPLES_NSH is not set
# CONFIG_EXAMPLES_NULL is not set
# CONFIG_EXAMPLES_NX is not set
@@ -422,6 +438,7 @@ CONFIG_EXAMPLES_OSTEST_RR_RUNS=10
# CONFIG_EXAMPLES_PASHELLO is not set
# CONFIG_EXAMPLES_PIPE is not set
# CONFIG_EXAMPLES_POLL is not set
+# CONFIG_EXAMPLES_POSIXSPAWN is not set
# CONFIG_EXAMPLES_QENCODER is not set
# CONFIG_EXAMPLES_RGMP is not set
# CONFIG_EXAMPLES_ROMFS is not set
@@ -439,8 +456,9 @@ CONFIG_EXAMPLES_OSTEST_RR_RUNS=10
# CONFIG_EXAMPLES_WATCHDOG is not set
#
-# Interpreters
+# Graphics Support
#
+# CONFIG_TIFF is not set
#
# Interpreters
@@ -470,11 +488,7 @@ CONFIG_EXAMPLES_OSTEST_RR_RUNS=10
# CONFIG_NETUTILS_WEBCLIENT is not set
#
-# ModBus
-#
-
-#
-# FreeModbus
+# FreeModBus
#
# CONFIG_MODBUS is not set
@@ -529,3 +543,7 @@ CONFIG_EXAMPLES_OSTEST_RR_RUNS=10
# Sysinfo
#
# CONFIG_SYSTEM_SYSINFO is not set
+
+#
+# USB Monitor
+#
diff --git a/nuttx/configs/lm4f120-launchpad/ostest/setenv.sh b/nuttx/configs/lm4f120-launchpad/ostest/setenv.sh
index 831ad2add..a121d61d7 100755
--- a/nuttx/configs/lm4f120-launchpad/ostest/setenv.sh
+++ b/nuttx/configs/lm4f120-launchpad/ostest/setenv.sh
@@ -32,15 +32,39 @@
# POSSIBILITY OF SUCH DAMAGE.
#
-if [ "$(basename $0)" = "setenv.sh" ] ; then
+if [ "$_" = "$0" ] ; then
echo "You must source this script, not run it!" 1>&2
exit 1
fi
-if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
-
WD=`pwd`
-export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
-export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
+if [ ! -x "setenv.sh" ]; then
+ echo "This script must be executed from the top-level NuttX build directory"
+ exit 1
+fi
+
+if [ -z "${PATH_ORIG}" ]; then
+ export PATH_ORIG="${PATH}"
+fi
+
+# This is the Cygwin path to the location where I installed the CodeSourcery
+# toolchain under windows. You will also have to edit this if you install
+# the CodeSourcery toolchain in any other location
+#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
+
+# These are the Cygwin paths to the locations where I installed the Atollic
+# toolchain under windows. You will also have to edit this if you install
+# the Atollic toolchain in any other location. /usr/bin is added before
+# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
+# at those locations as well.
+#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
+#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
+
+# This is the Cygwin path to the location where I build the buildroot
+# toolchain.
+export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
+
+# Add the path to the toolchain to the PATH varialble
+export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
echo "PATH : ${PATH}"
diff --git a/nuttx/configs/lm4f120-launchpad/src/lm4f_autoleds.c b/nuttx/configs/lm4f120-launchpad/src/lm4f_autoleds.c
index 313c995da..9b26b9536 100644
--- a/nuttx/configs/lm4f120-launchpad/src/lm4f_autoleds.c
+++ b/nuttx/configs/lm4f120-launchpad/src/lm4f_autoleds.c
@@ -93,7 +93,7 @@
* LED_INIRQ 2 NC NC ON (momentary)
* LED_SIGNAL 2 NC NC ON (momentary)
* LED_ASSERTION 3 ON NC NC (momentary)
- * LED_PANIC 3 ON OFF OFF (flashing 2Hz)
+ * LED_PANIC 4 ON OFF OFF (flashing 2Hz)
*/
/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
@@ -130,6 +130,10 @@
/****************************************************************************
* Name: lm4f_ledinit
+ *
+ * Description:
+ * Called to initialize the on-board LEDs.
+ *
****************************************************************************/
#ifdef CONFIG_ARCH_LEDS
@@ -157,35 +161,31 @@ void up_ledon(int led)
/* All components stay off until the file initialization step */
default:
- case LED_STARTED:
- case LED_HEAPALLOCATE:
- case LED_IRQSENABLED:
- default:
+ case 0:
break;
/* The GREEN component is illuminated at the final initialization step */
- case LED_STACKCREATED:
- lm_gpiowrite(GPIO_LED_GREEN, false);
+ case 1:
+ lm_gpiowrite(GPIO_LED_G, false);
break;
/* These will illuminate the BLUE component with on effect no RED and GREEN */
- case LED_INIRQ:
- case LED_SIGNAL:
- lm_gpiowrite(GPIO_LED_BLUE, false);
+ case 2:
+ lm_gpiowrite(GPIO_LED_B, false);
break;
/* This will turn off RED and GREEN and turn RED on */
- case LED_PANIC:
- lm_gpiowrite(GPIO_LED_GREEN, true);
- lm_gpiowrite(GPIO_LED_BLUE, true);
+ case 4:
+ lm_gpiowrite(GPIO_LED_G, true);
+ lm_gpiowrite(GPIO_LED_B, true);
/* This will illuminate the RED component with no effect on RED and GREEN */
- case LED_ASSERTION:
- lm_gpiowrite(GPIO_LED_RED, false);
+ case 3:
+ lm_gpiowrite(GPIO_LED_R, false);
break;
}
}
@@ -201,25 +201,21 @@ void up_ledoff(int led)
/* These should not happen and are ignored */
default:
- case LED_STARTED:
- case LED_HEAPALLOCATE:
- case LED_IRQSENABLED:
- case LED_STACKCREATED:
- default:
+ case 0:
+ case 1:
break;
/* These will extinguish the BLUE component with no effect on RED and GREEN */
- case LED_INIRQ:
- case LED_SIGNAL:
- lm_gpiowrite(GPIO_LED_BLUE, true);
+ case 2:
+ lm_gpiowrite(GPIO_LED_B, true);
break;
/* These will extinguish the RED component with on effect on RED and GREEN */
- case LED_INIRQ:
- case LED_SIGNAL:
- lm_gpiowrite(GPIO_LED_RED, true);
+ case 3:
+ case 4:
+ lm_gpiowrite(GPIO_LED_R, true);
break;
}
}
diff --git a/nuttx/configs/lm4f120-launchpad/src/lm4f_nsh.c b/nuttx/configs/lm4f120-launchpad/src/lm4f_nsh.c
index 3efcf4c72..ed1547e04 100644
--- a/nuttx/configs/lm4f120-launchpad/src/lm4f_nsh.c
+++ b/nuttx/configs/lm4f120-launchpad/src/lm4f_nsh.c
@@ -55,7 +55,7 @@
/* PORT and SLOT number probably depend on the board configuration */
-#ifdef CONFIG_ARCH_BOARD_LM4FLAUNCHPAD
+#ifdef CONFIG_ARCH_BOARD_LM4F120_LAUNCHPAD
# undef NSH_HAVEUSBDEV
#else
# error "Unrecognized lm3s board"
diff --git a/nuttx/configs/lm4f120-launchpad/src/lm4f_ssi.c b/nuttx/configs/lm4f120-launchpad/src/lm4f_ssi.c
index 92b68d082..29c31409e 100644
--- a/nuttx/configs/lm4f120-launchpad/src/lm4f_ssi.c
+++ b/nuttx/configs/lm4f120-launchpad/src/lm4f_ssi.c
@@ -54,7 +54,7 @@
/* The LM4F LaunchPad microSD CS is on SSI0 */
-#if !defined(CONFIG_SSI0_DISABLE) || !defined(CONFIG_SSI1_DISABLE)
+#if !defined(CONFIG_SSI0_DISABLE) || !defined(CONFIG_SSI1_DISABLE)
/************************************************************************************
* Definitions
@@ -64,7 +64,6 @@
#ifdef CONFIG_DEBUG_SPI
# define ssidbg lldbg
-# endif
#else
# define ssidbg(x...)
#endif
diff --git a/nuttx/configs/lm4f120-launchpad/src/lmf4120-launchpad.h b/nuttx/configs/lm4f120-launchpad/src/lmf4120-launchpad.h
index 5f5812645..95dfc052a 100644
--- a/nuttx/configs/lm4f120-launchpad/src/lmf4120-launchpad.h
+++ b/nuttx/configs/lm4f120-launchpad/src/lmf4120-launchpad.h
@@ -136,7 +136,19 @@
*
************************************************************************************/
-extern void weak_function lm4f_ssiinitialize(void);
+void weak_function lm4f_ssiinitialize(void);
+
+/****************************************************************************
+ * Name: lm4f_ledinit
+ *
+ * Description:
+ * Called to initialize the on-board LEDs.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_ARCH_LEDS
+void lm4f_ledinit(void);
+#endif
#endif /* __ASSEMBLY__ */
#endif /* __CONFIGS_LM4F120_LAUNCHPAD_LM4F120_LAUNCHPAD_H */
diff --git a/nuttx/configs/lpcxpresso-lpc1768/Kconfig b/nuttx/configs/lpcxpresso-lpc1768/Kconfig
index 944df07b7..e0504027c 100644
--- a/nuttx/configs/lpcxpresso-lpc1768/Kconfig
+++ b/nuttx/configs/lpcxpresso-lpc1768/Kconfig
@@ -4,10 +4,4 @@
#
if ARCH_BOARD_LPCXPRESSO
-config ARCH_LEDS
- bool "NuttX LED support"
- default n
- ---help---
- "Support control of board LEDs by NuttX to indicate system state"
-
endif
diff --git a/nuttx/configs/mbed/Kconfig b/nuttx/configs/mbed/Kconfig
index 84d7d461e..5ef86f3b5 100644
--- a/nuttx/configs/mbed/Kconfig
+++ b/nuttx/configs/mbed/Kconfig
@@ -4,10 +4,4 @@
#
if ARCH_BOARD_MBED
-config ARCH_LEDS
- bool "NuttX LED support"
- default n
- ---help---
- "Support control of board LEDs by NuttX to indicate system state"
-
endif
diff --git a/nuttx/configs/mcu123-lpc214x/Kconfig b/nuttx/configs/mcu123-lpc214x/Kconfig
index e429d3d75..f5582e0e8 100644
--- a/nuttx/configs/mcu123-lpc214x/Kconfig
+++ b/nuttx/configs/mcu123-lpc214x/Kconfig
@@ -4,10 +4,4 @@
#
if ARCH_BOARD_MCU123
-config ARCH_LEDS
- bool "NuttX LED support"
- default n
- ---help---
- "Support control of board LEDs by NuttX to indicate system state"
-
endif
diff --git a/nuttx/configs/mirtoo/Kconfig b/nuttx/configs/mirtoo/Kconfig
index 1ff7e4246..736707186 100644
--- a/nuttx/configs/mirtoo/Kconfig
+++ b/nuttx/configs/mirtoo/Kconfig
@@ -4,15 +4,11 @@
#
if ARCH_BOARD_MIRTOO
-config ARCH_LEDS
- bool "NuttX LED support"
- default n
- ---help---
- "Support control of board LEDs by NuttX to indicate system state"
config MIRTOO_RELEASE
int "Mirtoo Release 1 (R1)"
default 2
---help---
Select the Mirtoo release number
+
endif
diff --git a/nuttx/configs/mx1ads/Kconfig b/nuttx/configs/mx1ads/Kconfig
index ba83e1cf7..4a1c14517 100644
--- a/nuttx/configs/mx1ads/Kconfig
+++ b/nuttx/configs/mx1ads/Kconfig
@@ -4,10 +4,4 @@
#
if ARCH_BOARD_MX1ADS
-config ARCH_LEDS
- bool "NuttX LED support"
- default n
- ---help---
- "Support control of board LEDs by NuttX to indicate system state"
-
endif
diff --git a/nuttx/configs/ntosd-dm320/Kconfig b/nuttx/configs/ntosd-dm320/Kconfig
index 67681a845..326f73f6c 100644
--- a/nuttx/configs/ntosd-dm320/Kconfig
+++ b/nuttx/configs/ntosd-dm320/Kconfig
@@ -4,10 +4,4 @@
#
if ARCH_BOARD_NTOSD_DM320
-config ARCH_LEDS
- bool "NuttX LED support"
- default n
- ---help---
- "Support control of board LEDs by NuttX to indicate system state"
-
endif
diff --git a/nuttx/configs/nucleus2g/Kconfig b/nuttx/configs/nucleus2g/Kconfig
index 32a7fae76..457b6bb86 100644
--- a/nuttx/configs/nucleus2g/Kconfig
+++ b/nuttx/configs/nucleus2g/Kconfig
@@ -4,10 +4,4 @@
#
if ARCH_BOARD_NUCLEUS2G
-config ARCH_LEDS
- bool "NuttX LED support"
- default n
- ---help---
- "Support control of board LEDs by NuttX to indicate system state"
-
endif
diff --git a/nuttx/configs/nutiny-nuc120/Kconfig b/nuttx/configs/nutiny-nuc120/Kconfig
index 3c0c7a1e5..416063f7d 100644
--- a/nuttx/configs/nutiny-nuc120/Kconfig
+++ b/nuttx/configs/nutiny-nuc120/Kconfig
@@ -4,10 +4,4 @@
#
if ARCH_BOARD_NUTINY_NUC120
-config ARCH_LEDS
- bool "NuttX LED support"
- default n
- ---help---
- "Support control of the on-board LED by NuttX to indicate system state"
-
endif
diff --git a/nuttx/configs/olimex-lpc2378/Kconfig b/nuttx/configs/olimex-lpc2378/Kconfig
index 962ea29de..f479970f0 100644
--- a/nuttx/configs/olimex-lpc2378/Kconfig
+++ b/nuttx/configs/olimex-lpc2378/Kconfig
@@ -5,10 +5,4 @@
#
if ARCH_BOARD_OLIMEXLPC2378
-config ARCH_LEDS
- bool "NuttX LED support"
- default n
- ---help---
- "Support control of board LEDs by NuttX to indicate system state"
-
endif
diff --git a/nuttx/configs/pic32-starterkit/Kconfig b/nuttx/configs/pic32-starterkit/Kconfig
index d2dbdba15..7689eee13 100644
--- a/nuttx/configs/pic32-starterkit/Kconfig
+++ b/nuttx/configs/pic32-starterkit/Kconfig
@@ -4,10 +4,4 @@
#
if ARCH_BOARD_PIC32_STARTERKIT
-config ARCH_LEDS
- bool "NuttX LED support"
- default n
- ---help---
- "Support control of board LEDs by NuttX to indicate system state"
-
endif
diff --git a/nuttx/configs/pic32mx7mmb/Kconfig b/nuttx/configs/pic32mx7mmb/Kconfig
index 41c5a7896..f83241651 100644
--- a/nuttx/configs/pic32mx7mmb/Kconfig
+++ b/nuttx/configs/pic32mx7mmb/Kconfig
@@ -4,10 +4,4 @@
#
if ARCH_BOARD_PIC32_PIC32MX7MMB
-config ARCH_LEDS
- bool "NuttX LED support"
- default n
- ---help---
- "Support control of board LEDs by NuttX to indicate system state"
-
endif
diff --git a/nuttx/configs/pjrc-8051/Kconfig b/nuttx/configs/pjrc-8051/Kconfig
index afa9f6a9f..921bc732c 100644
--- a/nuttx/configs/pjrc-8051/Kconfig
+++ b/nuttx/configs/pjrc-8051/Kconfig
@@ -4,10 +4,4 @@
#
if ARCH_BOARD_PJRC_87C52
-config ARCH_LEDS
- bool "NuttX LED support"
- default n
- ---help---
- "Support control of board LEDs by NuttX to indicate system state"
-
endif
diff --git a/nuttx/configs/teensy/Kconfig b/nuttx/configs/teensy/Kconfig
index 5b751c285..11cf2e798 100644
--- a/nuttx/configs/teensy/Kconfig
+++ b/nuttx/configs/teensy/Kconfig
@@ -4,10 +4,4 @@
#
if ARCH_BOARD_TEENSY
-config ARCH_LEDS
- bool "NuttX LED support"
- default n
- ---help---
- "Support control of board LEDs by NuttX to indicate system state"
-
endif
diff --git a/nuttx/configs/us7032evb1/Kconfig b/nuttx/configs/us7032evb1/Kconfig
index d054a1624..94e6b725a 100644
--- a/nuttx/configs/us7032evb1/Kconfig
+++ b/nuttx/configs/us7032evb1/Kconfig
@@ -4,10 +4,4 @@
#
if ARCH_BOARD_TWR_K60N512
-config ARCH_LEDS
- bool "NuttX LED support"
- default n
- ---help---
- "Support control of board LEDs by NuttX to indicate system state"
-
endif
diff --git a/nuttx/configs/zkit-arm-1769/Kconfig b/nuttx/configs/zkit-arm-1769/Kconfig
index 42ed37151..ab80e40dd 100644
--- a/nuttx/configs/zkit-arm-1769/Kconfig
+++ b/nuttx/configs/zkit-arm-1769/Kconfig
@@ -4,10 +4,4 @@
#
if ARCH_BOARD_ZKITARM
-config ARCH_LEDS
- bool "NuttX LED support"
- default n
- ---help---
- "Support control of board LEDs by NuttX to indicate system state"
-
endif