summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-05-08 21:12:33 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-05-08 21:12:33 +0000
commit77c4a4d3e9f5a8f9c8d6c921e05dfae965512117 (patch)
tree1fbdded94bf80f8b3710c7590573fff28c250a86
parent637a7d82473a76f00af93d16c38624b4960e8575 (diff)
downloadnuttx-77c4a4d3e9f5a8f9c8d6c921e05dfae965512117.tar.gz
nuttx-77c4a4d3e9f5a8f9c8d6c921e05dfae965512117.tar.bz2
nuttx-77c4a4d3e9f5a8f9c8d6c921e05dfae965512117.zip
lm3s6918 update
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@1764 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--nuttx/arch/arm/include/lm3s/irq.h89
-rw-r--r--nuttx/arch/arm/src/lm3s/Make.defs18
-rw-r--r--nuttx/arch/arm/src/lm3s/lm3s_ethernet.c609
-rw-r--r--nuttx/arch/arm/src/lm3s/lm3s_gpio.h69
-rw-r--r--nuttx/arch/arm/src/lm3s/lm3s_irq.c235
-rw-r--r--nuttx/arch/arm/src/lm3s/lm3s_start.c169
-rw-r--r--nuttx/arch/arm/src/lm3s/lm3s_vectors.S272
-rw-r--r--nuttx/configs/eagle100/README.txt6
-rw-r--r--nuttx/configs/eagle100/ostest/defconfig38
-rw-r--r--nuttx/configs/eagle100/src/up_leds.c4
-rw-r--r--nuttx/examples/ostest/cond.c1
11 files changed, 1311 insertions, 199 deletions
diff --git a/nuttx/arch/arm/include/lm3s/irq.h b/nuttx/arch/arm/include/lm3s/irq.h
index 1187f3538..d4dc87355 100644
--- a/nuttx/arch/arm/include/lm3s/irq.h
+++ b/nuttx/arch/arm/include/lm3s/irq.h
@@ -56,52 +56,69 @@
* exceptions)
*/
+/* Processor Exceptions (vectors 0-15) */
+
+#define LMSB_IRQ_RESERVED (0) /* Reserved vector (only used with CONFIG_DEBUG) */
+ /* Vector 0: Reset stack pointer value */
+ /* Vector 1: Reset (not handler as an IRQ) */
+#define LMSB_IRQ_NMI (1) /* Vector 2: Non-Maskable Interrupt (NMI) */
+#define LMSB_IRQ_HARDFAULT (2) /* Vector 3: Hard fault */
+#define LMSB_IRQ_MPU (3) /* Vector 4: Memory management (MPU) */
+#define LMSB_IRQ_BUSFAULT (4) /* Vector 5: Bus fault */
+#define LMSB_IRQ_USAGEFAULT (5) /* Vector 6: Usage fault */
+#define LMSB_IRQ_SVCALL (6) /* Vector 11: SVC call */
+#define LMSB_IRQ_DBGMONITOR (7) /* Vector 12: Debug Monitor */
+ /* Vector 13: Reserved */
+#define LMSB_IRQ_PENDSV (8) /* Vector 14: Penable system service request */
+#define LMSB_IRQ_SYSTICK (9) /* Vector 15: System tick */
+
+/* External interrupts (vectors > 16) */
+
#ifdef CONFIG_ARCH_CHIP_LM3S6918
- /* Vector 0-15: Processor exceptions */
-# define LM3S_IRQ_GPIOA (0) /* Vector 16: GPIO Port A */
-# define LM3S_IRQ_GPIOB (1) /* Vector 17: GPIO Port B */
-# define LM3S_IRQ_GPIOC (2) /* Vector 18: GPIO Port C */
-# define LM3S_IRQ_GPIOD (3) /* Vector 19: GPIO Port D */
-# define LM3S_IRQ_GPIOE (4) /* Vector 20: GPIO Port E */
-# define LM3S_IRQ_UART0 (5) /* Vector 21: UART 0 */
-# define LM3S_IRQ_UART1 (6) /* Vector 22: UART 1 */
-# define LM3S_IRQ_SSI0 (7) /* Vector 23: SSI 0 */
-# define LM3S_IRQ_I2C0 (8) /* Vector 24: I2C 0 */
+
+# define LM3S_IRQ_GPIOA (10) /* Vector 16: GPIO Port A */
+# define LM3S_IRQ_GPIOB (11) /* Vector 17: GPIO Port B */
+# define LM3S_IRQ_GPIOC (12) /* Vector 18: GPIO Port C */
+# define LM3S_IRQ_GPIOD (13) /* Vector 19: GPIO Port D */
+# define LM3S_IRQ_GPIOE (14) /* Vector 20: GPIO Port E */
+# define LM3S_IRQ_UART0 (15) /* Vector 21: UART 0 */
+# define LM3S_IRQ_UART1 (16) /* Vector 22: UART 1 */
+# define LM3S_IRQ_SSI0 (17) /* Vector 23: SSI 0 */
+# define LM3S_IRQ_I2C0 (18) /* Vector 24: I2C 0 */
/* Vector 25-29: Reserved */
-# define LM3S_IRQ_ADC0 (14) /* Vector 30: ADC Sequence 0 */
-# define LM3S_IRQ_ADC1 (15) /* Vector 31: ADC Sequence 1 */
-# define LM3S_IRQ_ADC2 (16) /* Vector 32: ADC Sequence 2 */
-# define LM3S_IRQ_ADC3 (17) /* Vector 33: ADC Sequence 3 */
-# define LM3S_IRQ_WDOG (18) /* Vector 34: Watchdog Timer */
-# define LM3S_IRQ_TIMER0A (19) /* Vector 35: Timer 0 A */
-# define LM3S_IRQ_TIMER0B (20) /* Vector 36: Timer 0 B */
-# define LM3S_IRQ_TIMER1A (21) /* Vector 37: Timer 1 A */
-# define LM3S_IRQ_TIMER1B (22) /* Vector 38: Timer 1 B */
-# define LM3S_IRQ_TIMER2A (23) /* Vector 39: Timer 2 A */
-# define LM3S_IRQ_TIMER2B (24) /* Vector 40: Timer 3 B */
-# define LM3S_IRQ_COMPARE0 (25) /* Vector 41: Analog Comparator 0 */
-# define LM3S_IRQ_COMPARE1 (26) /* Vector 42: Analog Comparator 1 */
+# define LM3S_IRQ_ADC0 (19) /* Vector 30: ADC Sequence 0 */
+# define LM3S_IRQ_ADC1 (20) /* Vector 31: ADC Sequence 1 */
+# define LM3S_IRQ_ADC2 (21) /* Vector 32: ADC Sequence 2 */
+# define LM3S_IRQ_ADC3 (22) /* Vector 33: ADC Sequence 3 */
+# define LM3S_IRQ_WDOG (23) /* Vector 34: Watchdog Timer */
+# define LM3S_IRQ_TIMER0A (24) /* Vector 35: Timer 0 A */
+# define LM3S_IRQ_TIMER0B (25) /* Vector 36: Timer 0 B */
+# define LM3S_IRQ_TIMER1A (26) /* Vector 37: Timer 1 A */
+# define LM3S_IRQ_TIMER1B (27) /* Vector 38: Timer 1 B */
+# define LM3S_IRQ_TIMER2A (28) /* Vector 39: Timer 2 A */
+# define LM3S_IRQ_TIMER2B (29) /* Vector 40: Timer 3 B */
+# define LM3S_IRQ_COMPARE0 (30) /* Vector 41: Analog Comparator 0 */
+# define LM3S_IRQ_COMPARE1 (31) /* Vector 42: Analog Comparator 1 */
/* Vector 43: Reserved */
-# define LM3S_IRQ_SYSCON (28) /* Vector 44: System Control */
-# define LM3S_IRQ_FLASHCON (29) /* Vector 45: FLASH Control */
-# define LM3S_IRQ_GPIOF (30) /* Vector 46: GPIO Port F */
-# define LM3S_IRQ_GPIOG (31) /* Vector 47: GPIO Port G */
-# define LM3S_IRQ_GPIOH (32) /* Vector 48: GPIO Port H */
+# define LM3S_IRQ_SYSCON (32) /* Vector 44: System Control */
+# define LM3S_IRQ_FLASHCON (33) /* Vector 45: FLASH Control */
+# define LM3S_IRQ_GPIOF (34) /* Vector 46: GPIO Port F */
+# define LM3S_IRQ_GPIOG (35) /* Vector 47: GPIO Port G */
+# define LM3S_IRQ_GPIOH (36) /* Vector 48: GPIO Port H */
/* Vector 49: Reserved */
-# define LM3S_IRQ_SSI1 (34) /* Vector 50: SSI 1 */
-# define LM3S_IRQ_TIMER3A (35) /* Vector 51: Timer 3 A */
-# define LM3S_IRQ_TIMER3B (36) /* Vector 52: Timer 3 B */
-# define LM3S_IRQ_I2C1 (37) /* Vector 53: I2C 1 */
+# define LM3S_IRQ_SSI1 (37) /* Vector 50: SSI 1 */
+# define LM3S_IRQ_TIMER3A (38) /* Vector 51: Timer 3 A */
+# define LM3S_IRQ_TIMER3B (39) /* Vector 52: Timer 3 B */
+# define LM3S_IRQ_I2C1 (40) /* Vector 53: I2C 1 */
/* Vectors 54-57: Reserved */
-# define LM3S_IRQ_ETHCON (42) /* Vector 58: Ethernet Controller */
-# define LM3S_IRQ_HIBERNATE (43) /* Vector 59: Hibernation Module */
+# define LM3S_IRQ_ETHCON (41) /* Vector 58: Ethernet Controller */
+# define LM3S_IRQ_HIBERNATE (42) /* Vector 59: Hibernation Module */
/* Vectors 60-70: Reserved */
#else
# error "IRQ Numbers not specified for this LM3S chip"
#endif
-#define LM3S_IRQ_SYSTIMER too-be-determined
-#define NR_IRQS (44)
+#define NR_IRQS (43)
/************************************************************************************
* Public Types
diff --git a/nuttx/arch/arm/src/lm3s/Make.defs b/nuttx/arch/arm/src/lm3s/Make.defs
index 3115927a7..1d2fbdbdc 100644
--- a/nuttx/arch/arm/src/lm3s/Make.defs
+++ b/nuttx/arch/arm/src/lm3s/Make.defs
@@ -33,17 +33,21 @@
#
############################################################################
-HEAD_ASRC =
+HEAD_ASRC = lm3s_vectors.S
CMN_ASRCS =
-CMN_CSRCS = up_assert.c up_blocktask.c up_copystate.c up_createstack.c \
- up_dataabort.c up_mdelay.c up_udelay.c up_exit.c up_idle.c \
- up_initialize.c up_initialstate.c up_interruptcontext.c \
+CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copystate.c \
+ up_createstack.c up_dataabort.c up_mdelay.c up_udelay.c up_exit.c \
+ up_idle.c up_initialize.c up_initialstate.c up_interruptcontext.c \
+ up_modifyreg8.c up_modifyreg16.c up_modifyreg32.c \
up_prefetchabort.c up_releasepending.c up_releasestack.c \
up_reprioritizertr.c up_schedulesigaction.c \
up_sigdeliver.c up_syscall.c up_unblocktask.c \
- up_undefinedinsn.c up_usestack.c \
- up_modifyreg8.c up_modifyreg16.c up_modifyreg32.c
+ up_undefinedinsn.c up_usestack.c
CHIP_ASRCS =
-CHIP_CSRCS =
+CHIP_CSRCS = lm3s_start.c
+
+ifdef CONFIG_NET
+CHIP_CSRCS += lm3s_ethernet.c
+endif
diff --git a/nuttx/arch/arm/src/lm3s/lm3s_ethernet.c b/nuttx/arch/arm/src/lm3s/lm3s_ethernet.c
new file mode 100644
index 000000000..eccf6b83e
--- /dev/null
+++ b/nuttx/arch/arm/src/lm3s/lm3s_ethernet.c
@@ -0,0 +1,609 @@
+/****************************************************************************
+ * arch/arm/src/lm3s/lm3s_ethernet.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>
+#if defined(CONFIG_NET) && defined(CONFIG_LM3S_ETHERNET)
+
+#include <time.h>
+#include <string.h>
+#include <debug.h>
+#include <wdog.h>
+#include <errno.h>
+
+#include <nuttx/irq.h>
+#include <nuttx/arch.h>
+
+#include <net/uip/uip.h>
+#include <net/uip/uip-arp.h>
+#include <net/uip/uip-arch.h>
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* TX poll deley = 1 seconds. CLK_TCK is the number of clock ticks per second */
+
+#define LM3S_WDDELAY (1*CLK_TCK)
+#define LM3S_POLLHSEC (1*2)
+
+/* TX timeout = 1 minute */
+
+#define LM3S_TXTIMEOUT (60*CLK_TCK)
+
+/* This is a helper pointer for accessing the contents of the Ethernet header */
+
+#define BUF ((struct uip_eth_hdr *)skel->ld_dev.d_buf)
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/* The lm3s_driver_s encapsulates all state information for a single hardware
+ * interface
+ */
+
+struct lm3s_driver_s
+{
+ boolean ld_bifup; /* TRUE:ifup FALSE:ifdown */
+ WDOG_ID ld_txpoll; /* TX poll timer */
+ WDOG_ID ld_txtimeout; /* TX timeout timer */
+
+ /* This holds the information visible to uIP/NuttX */
+
+ struct uip_driver_s ld_dev; /* Interface understood by uIP */
+};
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static struct lm3s_driver_s g_lm3sdev;
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/* Common TX logic */
+
+static int lm3s_transmit(struct lm3s_driver_s *skel);
+static int lm3s_uiptxpoll(struct uip_driver_s *dev);
+
+/* Interrupt handling */
+
+static void lm3s_receive(struct lm3s_driver_s *skel);
+static void lm3s_txdone(struct lm3s_driver_s *skel);
+static int lm3s_interrupt(int irq, FAR void *context);
+
+/* Watchdog timer expirations */
+
+static void lm3s_polltimer(int argc, uint32 arg, ...);
+static void lm3s_txtimeout(int argc, uint32 arg, ...);
+
+/* NuttX callback functions */
+
+static int lm3s_ifup(struct uip_driver_s *dev);
+static int lm3s_ifdown(struct uip_driver_s *dev);
+static int lm3s_txavail(struct uip_driver_s *dev);
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: lm3s_transmit
+ *
+ * Description:
+ * Start hardware transmission. Called either from the txdone interrupt
+ * handling or from watchdog based polling.
+ *
+ * Parameters:
+ * skel - Reference to the driver state structure
+ *
+ * Returned Value:
+ * OK on success; a negated errno on failure
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+static int lm3s_transmit(struct lm3s_driver_s *skel)
+{
+ /* Verify that the hardware is ready to send another packet */
+#warning "Missing logic"
+ /* Increment statistics */
+
+ /* Disable Ethernet interrupts */
+
+ /* Send the packet: address=skel->ld_dev.d_buf, length=skel->ld_dev.d_len */
+
+ /* Restore Ethernet interrupts */
+
+ /* Setup the TX timeout watchdog (perhaps restarting the timer) */
+
+ (void)wd_start(skel->ld_txtimeout, LM3S_TXTIMEOUT, lm3s_txtimeout, 1, (uint32)skel);
+ return OK;
+}
+
+/****************************************************************************
+ * Function: lm3s_uiptxpoll
+ *
+ * Description:
+ * The transmitter is available, check if uIP has any outgoing packets ready
+ * to send. This is a callback from uip_poll(). uip_poll() may be called:
+ *
+ * 1. When the preceding TX packet send is complete,
+ * 2. When the preceding TX packet send timesout and the interface is reset
+ * 3. During normal TX polling
+ *
+ * Parameters:
+ * dev - Reference to the NuttX driver state structure
+ *
+ * Returned Value:
+ * OK on success; a negated errno on failure
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+static int lm3s_uiptxpoll(struct uip_driver_s *dev)
+{
+ struct lm3s_driver_s *skel = (struct lm3s_driver_s *)dev->d_private;
+
+ /* If the polling resulted in data that should be sent out on the network,
+ * the field d_len is set to a value > 0.
+ */
+
+ if (skel->ld_dev.d_len > 0)
+ {
+ uip_arp_out(&skel->ld_dev);
+ lm3s_transmit(skel);
+
+ /* Check if there is room in the device to hold another packet. If not,
+ * return a non-zero value to terminate the poll.
+ */
+#warning "Missing logic"
+ }
+
+ /* If zero is returned, the polling will continue until all connections have
+ * been examined.
+ */
+
+ return 0;
+}
+
+/****************************************************************************
+ * Function: lm3s_receive
+ *
+ * Description:
+ * An interrupt was received indicating the availability of a new RX packet
+ *
+ * Parameters:
+ * skel - Reference to the driver state structure
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+static void lm3s_receive(struct lm3s_driver_s *skel)
+{
+ do
+ {
+ /* Check for errors and update statistics */
+#warning "Missing logic"
+
+ /* Check if the packet is a valid size for the uIP buffer configuration */
+
+ /* Copy the data data from the hardware to skel->ld_dev.d_buf. Set
+ * amount of data in skel->ld_dev.d_len
+ */
+
+ /* We only accept IP packets of the configured type and ARP packets */
+
+#ifdef CONFIG_NET_IPv6
+ if (BUF->type == HTONS(UIP_ETHTYPE_IP6))
+#else
+ if (BUF->type == HTONS(UIP_ETHTYPE_IP))
+#endif
+ {
+ uip_arp_ipin();
+ uip_input(&skel->ld_dev);
+
+ /* If the above function invocation resulted in data that should be
+ * sent out on the network, the field d_len will set to a value > 0.
+ */
+
+ if (skel->ld_dev.d_len > 0)
+ {
+ uip_arp_out(&skel->ld_dev);
+ lm3s_transmit(skel);
+ }
+ }
+ else if (BUF->type == htons(UIP_ETHTYPE_ARP))
+ {
+ uip_arp_arpin(&skel->ld_dev);
+
+ /* If the above function invocation resulted in data that should be
+ * sent out on the network, the field d_len will set to a value > 0.
+ */
+
+ if (skel->ld_dev.d_len > 0)
+ {
+ lm3s_transmit(skel);
+ }
+ }
+ }
+ }
+ while (); /* While there are more packets to be processed */
+}
+
+/****************************************************************************
+ * Function: lm3s_txdone
+ *
+ * Description:
+ * An interrupt was received indicating that the last TX packet(s) is done
+ *
+ * Parameters:
+ * skel - Reference to the driver state structure
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+static void lm3s_txdone(struct lm3s_driver_s *skel)
+{
+ /* Check for errors and update statistics */
+#warning "Missing logic"
+
+ /* If no further xmits are pending, then cancel the TX timeout */
+
+ wd_cancel(skel->ld_txtimeout);
+
+ /* Then poll uIP for new XMIT data */
+
+ (void)uip_poll(&skel->ld_dev, lm3s_uiptxpoll);
+}
+
+/****************************************************************************
+ * Function: lm3s_interrupt
+ *
+ * Description:
+ * Hardware interrupt handler
+ *
+ * Parameters:
+ * irq - Number of the IRQ that generated the interrupt
+ * context - Interrupt register state save info (architecture-specific)
+ *
+ * Returned Value:
+ * OK on success
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+static int lm3s_interrupt(int irq, FAR void *context)
+{
+ register struct lm3s_driver_s *skel = &g_lm3sdev;
+
+ /* Disable Ethernet interrupts */
+#warning "Missing logic"
+
+ /* Get and clear interrupt status bits */
+
+ /* Handle interrupts according to status bit settings */
+
+ /* Check if we received an incoming packet, if so, call lm3s_receive() */
+
+ lm3s_receive(skel);
+
+ /* Check is a packet transmission just completed. If so, call lm3s_txdone */
+
+ lm3s_txdone(skel);
+
+ /* Enable Ethernet interrupts (perhaps excluding the TX done interrupt if
+ * there are no pending transmissions.
+ */
+
+ return OK;
+}
+
+/****************************************************************************
+ * Function: lm3s_txtimeout
+ *
+ * Description:
+ * Our TX watchdog timed out. Called from the timer interrupt handler.
+ * The last TX never completed. Reset the hardware and start again.
+ *
+ * Parameters:
+ * argc - The number of available arguments
+ * arg - The first argument
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+static void lm3s_txtimeout(int argc, uint32 arg, ...)
+{
+ struct lm3s_driver_s *skel = (struct lm3s_driver_s *)arg;
+
+ /* Increment statistics and dump debug info */
+#warning "Missing logic"
+
+ /* Then reset the hardware */
+
+ /* Then poll uIP for new XMIT data */
+
+ (void)uip_poll(&skel->ld_dev, lm3s_uiptxpoll);
+}
+
+/****************************************************************************
+ * Function: lm3s_polltimer
+ *
+ * Description:
+ * Periodic timer handler. Called from the timer interrupt handler.
+ *
+ * Parameters:
+ * argc - The number of available arguments
+ * arg - The first argument
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+static void lm3s_polltimer(int argc, uint32 arg, ...)
+{
+ struct lm3s_driver_s *skel = (struct lm3s_driver_s *)arg;
+
+ /* Check if there is room in the send another Tx packet. */
+#warning "Missing logic"
+
+ /* If so, update TCP timing states and poll uIP for new XMIT data */
+
+ (void)uip_timer(&skel->ld_dev, lm3s_uiptxpoll, LM3S_POLLHSEC);
+
+ /* Setup the watchdog poll timer again */
+
+ (void)wd_start(skel->ld_txpoll, LM3S_WDDELAY, lm3s_polltimer, 1, arg);
+}
+
+/****************************************************************************
+ * Function: lm3s_ifup
+ *
+ * Description:
+ * NuttX Callback: Bring up the Ethernet interface when an IP address is
+ * provided
+ *
+ * Parameters:
+ * dev - Reference to the NuttX driver state structure
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+static int lm3s_ifup(struct uip_driver_s *dev)
+{
+ struct lm3s_driver_s *skel = (struct lm3s_driver_s *)dev->d_private;
+
+ ndbg("Bringing up: %d.%d.%d.%d\n",
+ dev->d_ipaddr & 0xff, (dev->d_ipaddr >> 8) & 0xff,
+ (dev->d_ipaddr >> 16) & 0xff, dev->d_ipaddr >> 24 );
+
+ /* Initilize Ethernet interface */
+#warning "Missing logic"
+
+ /* Set and activate a timer process */
+
+ (void)wd_start(skel->ld_txpoll, LM3S_WDDELAY, lm3s_polltimer, 1, (uint32)skel);
+
+ /* Enable the Ethernet interrupt */
+
+ skel->ld_bifup = TRUE;
+ up_enable_irq(CONFIG_LM3S_IRQ);
+ return OK;
+}
+
+/****************************************************************************
+ * Function: lm3s_ifdown
+ *
+ * Description:
+ * NuttX Callback: Stop the interface.
+ *
+ * Parameters:
+ * dev - Reference to the NuttX driver state structure
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+static int lm3s_ifdown(struct uip_driver_s *dev)
+{
+ struct lm3s_driver_s *skel = (struct lm3s_driver_s *)dev->d_private;
+ irqstate_t flags;
+
+ /* Disable the Ethernet interrupt */
+
+ flags = irqsave();
+ up_disable_irq(CONFIG_LM3S_IRQ);
+
+ /* Cancel the TX poll timer and TX timeout timers */
+
+ wd_cancel(skel->ld_txpoll);
+ wd_cancel(skel->ld_txtimeout);
+
+ /* Reset the device */
+
+ skel->ld_bifup = FALSE;
+ irqrestore(flags);
+ return OK;
+}
+
+/****************************************************************************
+ * Function: lm3s_txavail
+ *
+ * Description:
+ * Driver callback invoked when new TX data is available. This is a
+ * stimulus perform an out-of-cycle poll and, thereby, reduce the TX
+ * latency.
+ *
+ * Parameters:
+ * dev - Reference to the NuttX driver state structure
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Called in normal user mode
+ *
+ ****************************************************************************/
+
+static int lm3s_txavail(struct uip_driver_s *dev)
+{
+ struct lm3s_driver_s *skel = (struct lm3s_driver_s *)dev->d_private;
+ irqstate_t flags;
+
+ flags = irqsave();
+
+ /* Ignore the notification if the interface is not yet up */
+
+ if (skel->ld_bifup)
+ {
+ /* Check if there is room in the hardware to hold another outgoing packet. */
+#warning "Missing logic"
+
+ /* If so, then poll uIP for new XMIT data */
+
+ (void)uip_poll(&skel->ld_dev, lm3s_uiptxpoll);
+ }
+
+ irqrestore(flags);
+ return OK;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: lm3s_initialize
+ *
+ * Description:
+ * Initialize the Ethernet driver
+ *
+ * Parameters:
+ * None
+ *
+ * Returned Value:
+ * OK on success; Negated errno on failure.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+/* Initialize the Ethernet controller and driver */
+
+int lm3s_initialize(void)
+{
+ /* Check if the Ethernet module is present */
+
+ DEBUGASSERT((getreg32(LM3S_SYSCON_DC4) & (SYSCON_DC4_EMAC0|SYSCON_DC4_EPHY0)) == (SYSCON_DC4_EMAC0|SYSCON_DC4_EPHY0));
+
+ /* Enable Port F for Ethernet LEDs: LED0=Bit 3; LED1=Bit 2 */
+
+#ifdef CONFIG_LM3S_ETHLEDS
+ /* Make sure that the GPIOF peripheral is enabled */
+
+ modifyreg32(LM3S_SYSCON_RCGC2_OFFSET, 0, SYSCON_RCGC2_GPIOF);
+
+ /* Configure the pins for the peripheral function */
+
+ lm3s_configgpio(GPIO_FUNC_PERIPHERAL | GPIO_STRENGTH_2MA | GPIO_PADTYPE_STD | GPIO_PORTF | 2);
+ lm3s_configgpio(GPIO_FUNC_PERIPHERAL | GPIO_STRENGTH_2MA | GPIO_PADTYPE_STD | GPIO_PORTF | 3);
+#endif
+
+#warning "Missing logic"
+
+ /* Attach the IRQ to the driver */
+
+ if (irq_attach(CONFIG_LM3S_IRQ, lm3s_interrupt))
+ {
+ /* We could not attach the ISR to the ISR */
+
+ return -EAGAIN;
+ }
+
+ /* Initialize the driver structure */
+
+ memset(g_lm3sdev, 0, sizeof(struct lm3s_driver_s));
+ g_lm3sdev.ld_dev.d_ifup = lm3s_ifup; /* I/F down callback */
+ g_lm3sdev.ld_dev.d_ifdown = lm3s_ifdown; /* I/F up (new IP address) callback */
+ g_lm3sdev.ld_dev.d_txavail = lm3s_txavail; /* New TX data callback */
+ g_lm3sdev.ld_dev.d_private = (void*)g_lm3sdev; /* Used to recover private state from dev */
+
+ /* Create a watchdog for timing polling for and timing of transmisstions */
+
+ g_lm3sdev.ld_txpoll = wd_create(); /* Create periodic poll timer */
+ g_lm3sdev.ld_txtimeout = wd_create(); /* Create TX timeout timer */
+
+ /* Read the MAC address from the hardware into g_lm3sdev.ld_dev.d_mac.ether_addr_octet */
+
+ /* Register the device with the OS so that socket IOCTLs can be performed */
+
+ (void)netdev_register(&g_lm3sdev.ld_dev);
+ return OK;
+}
+
+#endif /* CONFIG_NET && CONFIG_LM3S_ETHERNET */
+
diff --git a/nuttx/arch/arm/src/lm3s/lm3s_gpio.h b/nuttx/arch/arm/src/lm3s/lm3s_gpio.h
index 4c1ac407e..b4db728f8 100644
--- a/nuttx/arch/arm/src/lm3s/lm3s_gpio.h
+++ b/nuttx/arch/arm/src/lm3s/lm3s_gpio.h
@@ -354,26 +354,55 @@
/* Bit-encoded input to lm3s_configgpio() *******************************************/
-#define GPIO_DIR_MASK (1 << 31) /* Bit 31: GPIO direction */
-#define GPIO_DIR_OUTPUT (1 << 31)
-#define GPIO_DIR_INPUT (0 << 31)
-
-#define GPIO_VALUE_MASK (1 << 6) /* Bit 6: If output, inital value of output */
-#define GPIO_VALUE_ONE (1 << 6)
-#define GPIO_VALUE_ZERO (0 << 6)
-
-#define GPIO_PORT_SHIFT 3 /* Bit 3-5: Port number */
-#define GPIO_PORT_MASK (0x07 << GPIO_PORT_SHIFT)
-#define GPIO_PORTA (0 << GPIO_PORT_SHIFT)
-#define GPIO_PORTB (1 << GPIO_PORT_SHIFT)
-#define GPIO_PORTC (2 << GPIO_PORT_SHIFT)
-#define GPIO_PORTD (3 << GPIO_PORT_SHIFT)
-#define GPIO_PORTE (4 << GPIO_PORT_SHIFT)
-#define GPIO_PORTF (5 << GPIO_PORT_SHIFT)
-#define GPIO_PORTG (6 << GPIO_PORT_SHIFT)
-#define GPIO_PORTH (7 << GPIO_PORT_SHIFT)
-
-#define GPIO_NUMBER_SHIFT 0 /* Bits 0-2: GPIO number: 0-7 */
+#define GPIO_FUNC_SHIFT 30 /* Bit 31-30: GPIO function */
+#define GPIO_FUNC_MASK (3 << GPIO_FUNC_SHIFT)
+#define GPIO_FUNC_INPUT (0 << GPIO_FUNC_SHIFT) /* Normal GPIO input */
+#define GPIO_FUNC_OUTPUT (1 << GPIO_FUNC_SHIFT) /* Normal GPIO output */
+#define GPIO_FUNC_PERIPHERAL (2 << GPIO_FUNC_SHIFT) /* Peripheral function */
+#define GPIO_FUNC_INTERRUPT (3 << GPIO_FUNC_SHIFT) /* Interrupt function */
+
+#define GPIO_INT_SHIFT 27 /* Bits 29-27: Interrupt type */
+#define GPIO_INT_MASK (7 << GPIO_INT_SHIFT)
+#define GPIO_INT_FALLINGEDGE (0 << GPIO_INT_SHIFT) /* Interrupt on falling edge */
+#define GPIO_INT_RISINGEDGE (1 << GPIO_INT_SHIFT) /* Interrupt on rising edge */
+#define GPIO_INT_BOTHEDGES (2 << GPIO_INT_SHIFT) /* Interrupt on both edges */
+#define GPIO_INT_LOWLEVEL (3 << GPIO_INT_SHIFT) /* Interrupt on low level */
+#define GPIO_INT_HIGHLEVEL (4 << GPIO_INT_SHIFT) /* Interrupt on high level */
+
+#define GPIO_STRENGTH_SHIFT 25 /* Bits 26-25: Pad drive strength */
+#define GPIO_STRENGTH_MASK (3 << GPIO_STRENGTH_SHIFT)
+#define GPIO_STRENGTH_2MA (0 << GPIO_STRENGTH_SHIFT) /* 2mA pad drive strength */
+#define GPIO_STRENGTH_4MA (1 << GPIO_STRENGTH_SHIFT) /* 4mA pad drive strength */
+#define GPIO_STRENGTH_8MA (2 << GPIO_STRENGTH_SHIFT) /* 8mA pad drive strength */
+#define GPIO_STRENGTH_8MASC (3 << GPIO_STRENGTH_SHIFT) /* 8mA Pad drive with slew rate control */
+
+#define GPIO_PADTYPE_SHIFT 22 /* Bits 22-24: Pad type */
+#define GPIO_PADTYPE_MASK (0 << GPIO_PADTYPE_SHIFT)
+#define GPIO_PADTYPE_STD (1 << GPIO_PADTYPE_SHIFT) /* Push-pull */
+#define GPIO_PADTYPE_STDWPU (2 << GPIO_PADTYPE_SHIFT) /* Push-pull with weak pull-up */
+#define GPIO_PADTYPE_STDWPD (3 << GPIO_PADTYPE_SHIFT) /* Push-pull with weak pull-down */
+#define GPIO_PADTYPE_OD (4 << GPIO_PADTYPE_SHIFT) /* Open-drain */
+#define GPIO_PADTYPE_ODWPU (5 << GPIO_PADTYPE_SHIFT) /* Open-drain with weak pull-up */
+#define GPIO_PADTYPE_ODWPD (6 << GPIO_PADTYPE_SHIFT) /* Open-drain with weak pull-down */
+#define GPIO_PADTYPE_ANALOG (7 << GPIO_PADTYPE_SHIFT) /* Analog comparator */
+
+#define GPIO_VALUE_SHIFT 6 /* Bit 6: If output, inital value of output */
+#define GPIO_VALUE_MASK (1 << GPIO_VALUE_SHIFT)
+#define GPIO_VALUE_ZERO (0 << GPIO_VALUE_SHIFT) /* Initial value is zero */
+#define GPIO_VALUE_ONE (1 << GPIO_VALUE_SHIFT) /* Initial value is one */
+
+#define GPIO_PORT_SHIFT 3 /* Bit 3-5: Port number */
+#define GPIO_PORT_MASK (7 << GPIO_PORT_SHIFT)
+#define GPIO_PORTA (0 << GPIO_PORT_SHIFT) /* GPIOA */
+#define GPIO_PORTB (1 << GPIO_PORT_SHIFT) /* GPIOB */
+#define GPIO_PORTC (2 << GPIO_PORT_SHIFT) /* GPIOC */
+#define GPIO_PORTD (3 << GPIO_PORT_SHIFT) /* GPIOD */
+#define GPIO_PORTE (4 << GPIO_PORT_SHIFT) /* GPIOE */
+#define GPIO_PORTF (5 << GPIO_PORT_SHIFT) /* GPIOF */
+#define GPIO_PORTG (6 << GPIO_PORT_SHIFT) /* GPIOG */
+#define GPIO_PORTH (7 << GPIO_PORT_SHIFT) /* GPIOH */
+
+#define GPIO_NUMBER_SHIFT 0 /* Bits 0-2: GPIO number: 0-7 */
#define GPIO_NUMBER_MASK (0x07 << GPIO_NUMBER_SHIFT)
/************************************************************************************
diff --git a/nuttx/arch/arm/src/lm3s/lm3s_irq.c b/nuttx/arch/arm/src/lm3s/lm3s_irq.c
new file mode 100644
index 000000000..31da0754d
--- /dev/null
+++ b/nuttx/arch/arm/src/lm3s/lm3s_irq.c
@@ -0,0 +1,235 @@
+/****************************************************************************
+ * arch/arm/src/lm3s/lm3s_irq.c
+ * arch/arm/src/chip/lm3s_irq.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 <nuttx/irq.h>
+
+#include "up_arch.h"
+#include "os_internal.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+uint32 *current_regs;
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Funtions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_irqinitialize
+ ****************************************************************************/
+
+void up_irqinitialize(void)
+{
+ /* Clear, disable and configure all interrupts. */
+
+# warning "Missing logic"
+
+ /* currents_regs is non-NULL only while processing an interrupt */
+
+ current_regs = NULL;
+
+ /* Attach all processor exceptions (except reset and sys tick) */
+
+#ifdef CONFIG_DEBUG
+ irq_attach(LMSB_IRQ_NMI, lm3s_nmi);
+ irq_attach(LMSB_IRQ_HARDFAULT, lm3s_hardfault);
+ irq_attach(LMSB_IRQ_MPU, lm3s_mpu);
+ irq_attach(LMSB_IRQ_BUSFAULT, lm3s_busfault);
+ irq_attach(LMSB_IRQ_USAGEFAULT, lm3s_usagefault);
+ irq_attach(LMSB_IRQ_SVCALL, lm3s_svcall);
+ irq_attach(LMSB_IRQ_DBGMONITOR, lm3s_dbgmonitor);
+ irq_attach(LMSB_IRQ_PENDSV, lm3s_pendsv);
+ irq_attach(LMSB_IRQ_RESERVED, lm3s_reserved);
+#endif
+
+#ifndef CONFIG_SUPPRESS_INTERRUPTS
+
+ /* Initialize FIQs */
+
+#ifdef CONFIG_ARCH_FIQ
+ up_fiqinitialize();
+#endif
+
+ /* And finally, enable interrupts */
+
+ irqrestore(0);
+#endif
+}
+
+/****************************************************************************
+ * Name: up_disable_irq
+ *
+ * Description:
+ * Disable the IRQ specified by 'irq'
+ *
+ ****************************************************************************/
+
+void up_disable_irq(int irq)
+{
+# warning "Missing logic"
+}
+
+/****************************************************************************
+ * Name: up_enable_irq
+ *
+ * Description:
+ * Enable the IRQ specified by 'irq'
+ *
+ ****************************************************************************/
+
+void up_enable_irq(int irq)
+{
+# warning "Missing logic"
+}
+
+/****************************************************************************
+ * Name: up_maskack_irq
+ *
+ * Description:
+ * Mask the IRQ and acknowledge it
+ *
+ ****************************************************************************/
+
+void up_maskack_irq(int irq)
+{
+# warning "Missing logic"
+}
+
+
+/****************************************************************************
+ * Name: lm3s_nmi, lm3s_hardfault, lm3s_mpu, lm3s_busfault, lm3s_usagefault,
+ * lm3s_svcall, lm3s_dbgmonitor, lm3s_pendsv, lm3s_reserved
+ *
+ * Description:
+ * Handlers for various execptions. None are handler and all are fatal
+ * error conditions.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_DEBUG
+int lm3s_nmi(int irq, FAR void *context)
+{
+ (void)irqsave();
+ dbg("PANIC!!! NMI received\n");
+ PANIC(OSERR_UNEXPECTEDISR);
+ return 0;
+}
+
+int lm3s_hardfault(int irq, FAR void *context)
+{
+ (void)irqsave();
+ dbg("PANIC!!! Hard fault received\n");
+ PANIC(OSERR_UNEXPECTEDISR);
+ return 0;
+}
+
+int lm3s_mpu(int irq, FAR void *context)
+{
+ (void)irqsave();
+ dbg("PANIC!!! MPU interrupt received\n");
+ PANIC(OSERR_UNEXPECTEDISR);
+ return 0;
+}
+
+int lm3s_busfault(int irq, FAR void *context)
+{
+ (void)irqsave();
+ dbg("PANIC!!! Bus fault recived\n");
+ PANIC(OSERR_UNEXPECTEDISR);
+ return 0;
+}
+
+int lm3s_usagefault(int irq, FAR void *context)
+{
+ (void)irqsave();
+ dbg("PANIC!!! Usage fault received\n");
+ PANIC(OSERR_UNEXPECTEDISR);
+ return 0;
+}
+
+int lm3s_svcall(int irq, FAR void *context)
+{
+ (void)irqsave();
+ dbg("PANIC!!! SVCALL received\n");
+ PANIC(OSERR_UNEXPECTEDISR);
+ return 0;
+}
+
+int lm3s_dbgmonitor(int irq, FAR void *context)
+{
+ (void)irqsave();
+ dbg("PANIC!!! Debug Monitor receieved\n");
+ PANIC(OSERR_UNEXPECTEDISR);
+ return 0;
+}
+
+int lm3s_pendsv(int irq, FAR void *context)
+{
+ (void)irqsave();
+ dbg("PANIC!!! PendSV received\n");
+ PANIC(OSERR_UNEXPECTEDISR);
+ return 0;
+}
+
+int lm3s_reserved(int irq, FAR void *context)
+{
+ (void)irqsave();
+ dbg("PANIC!!! Reserved interrupt\n");
+ PANIC(OSERR_UNEXPECTEDISR);
+ return 0;
+}
+#endif \ No newline at end of file
diff --git a/nuttx/arch/arm/src/lm3s/lm3s_start.c b/nuttx/arch/arm/src/lm3s/lm3s_start.c
new file mode 100644
index 000000000..8894117dc
--- /dev/null
+++ b/nuttx/arch/arm/src/lm3s/lm3s_start.c
@@ -0,0 +1,169 @@
+/****************************************************************************
+ * arch/arm/src/lm3s/lm3s_start.c
+ * arch/arm/src/chip/lm3s_start.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 <assert.h>
+#include <debug.h>
+
+#include <nuttx/init.h>
+
+#include "up_arch.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Private Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/* These values are setup by the linker script */
+
+extern const uint32 _eronly; /* End of read only (.text + .rodata) */
+extern uint32 _sdata; /* Start of .data */
+extern uint32 _edata; /* End+1 of .data */
+extern uint32 _sbss; /* Start of .bss */
+extern uint32 _ebss; /* End+1 of .bss */
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: showprogress
+ *
+ * Description:
+ * Print a character on the UART to show boot status.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_DEBUG
+# define showprogress(c) up_lowputc(c)
+#else
+# define showprogress(c)
+#endif
+
+/****************************************************************************
+ * Name: up_lowsetup
+ *
+ * Description:
+ * Set up initial clocking
+ *
+ ****************************************************************************/
+
+static inline void up_lowsetup(void)
+{
+ up_clockconfig();
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: _start
+ *
+ * Description:
+ * This is the reset entry point.
+ *
+ ****************************************************************************/
+
+void _start(void)
+{
+ const uint32 *src;
+ uint32 *dest;
+
+ /* Configure the uart so that we can get debug output as soon as possible */
+
+ up_lowsetup();
+ showprogress('A');
+
+ /* Clear .bss. We'll do this inline (vs. calling memset) just to be
+ * certain that there are no issues with the state of global variables.
+ */
+
+ for (dest = &_sbss; dest < &_ebss; )
+ {
+ *dest++ = 0;
+ }
+ showprogress('B');
+
+ /* Move the intialized data section from his temporary holding spot in
+ * FLASH into the correct place in SRAM. The correct place in SRAM is
+ * give by _sdata and _edata. The temporary location is in FLASH at the
+ * end of all of the other read-only data (.text, .rodata) at _eronly.
+ */
+
+ for (src = &_eronly, dest = &_sdata; dest < &_edata; )
+ {
+ *dest++ = *src++;
+ }
+ showprogress('C');
+
+ /* Perform early serial initialization */
+
+#ifdef CONFIG_USE_EARLYSERIALINIT
+ up_earlyserialinit();
+#endif
+ showprogress('D');
+
+ /* Initialize onboard LEDs */
+
+#ifdef CONFIG_ARCH_LEDS
+ up_ledinit();
+#endif
+ showprogress('E');
+
+ /* Then start NuttX */
+
+ showprogress('\n');
+ os_start();
+
+ /* Shoulnd't get here */
+
+ for(;;);
+}
diff --git a/nuttx/arch/arm/src/lm3s/lm3s_vectors.S b/nuttx/arch/arm/src/lm3s/lm3s_vectors.S
index 3871e2b68..d7be13da5 100644
--- a/nuttx/arch/arm/src/lm3s/lm3s_vectors.S
+++ b/nuttx/arch/arm/src/lm3s/lm3s_vectors.S
@@ -43,19 +43,26 @@
* Preprocessor Definitions
************************************************************************************/
-#ifndef CONFIG_DEBUG
-# define lm3s_uncaught 0
-#endif
+/* Memory Map:
+ *
+ * 0x0000:0000 - Beginning of FLASH. Address of vectors (if not using bootloader)
+ * 0x0002:0000 - Address of vectors if using bootloader
+ * 0x0003:ffff - End of flash
+ * 0x2000:0000 - Start of SRAM and start of .data (_sdata)
+ * - End of .data (_edata) abd start of .bss (_sbss)
+ * - End of .bss (_ebss) and bottom of idle stack
+ * - _ebss + CONFIG_IDLETHREAD_STACKSIZE = end of idle stack, start of heap
+ * 0x2000:ffff - End of SRAM and end of heap
+ */
+
+#define IDLE_STACK (_ebss+CONFIG_IDLETHREAD_STACKSIZE-4)
+#define HEAP_BASE (_ebss+CONFIG_IDLETHREAD_STACKSIZE-4)
/************************************************************************************
* Global Symbols
************************************************************************************/
- .globl _vectors
- .globl lm3s_pendsvhandler
- .globl lm3s_systickhandler
- .globl lm3s_faulthandler
- .globl lm3s_portsvchandler
+ .globl dispach_irq
/************************************************************************************
* Macros
@@ -76,125 +83,158 @@
_vectors:
/* Processor Exceptions */
- .word __stack_end__ /* Vector 0: Reset stack pointer */
- .word _start /* Vector 1: Reset vector */
- .word lm3s_nmihandler /* Vector 2: Non-Maskable Interrupt (NMI) */
- .word lm3s_faulthandler /* Vector 3: Hard fault */
- .word lm3s_uncaught /* Vector 4: Memory management (MPU) */
- .word lm3s_uncaught /* Vector 5: Bus fault */
- .word lm3s_uncaught /* Vector 6: Usage fault */
- .word lm3s_uncaught /* Vector 7: Reserved */
- .word lm3s_uncaught /* Vector 8: Reserved */
- .word lm3s_uncaught /* Vector 9: Reserved */
- .word lm3s_uncaught /* Vector 10: Reserved */
- .word lm3s_svchandler /* Vector 11: SVC call */
- .word lm3s_uncaught /* Vector 12: Debug monitor */
- .word lm3s_uncaught /* Vector 13: Reserved */
- .word lm3s_pendsvhandler /* Vector 14: Pendable system service request */
- .word lm3s_systickhandler /* Vector 15: System tick */
+ .word IDLE_STACK /* Vector 0: Reset stack pointer */
+ .word _start /* Vector 1: Reset vector */
+ .word lm3s_nmi /* Vector 2: Non-Maskable Interrupt (NMI) */
+ .word lm3s_hardfault /* Vector 3: Hard fault */
+ .word lm3s_mpu /* Vector 4: Memory management (MPU) */
+ .word lm3s_busfault /* Vector 5: Bus fault */
+ .word lm3s_usagefault /* Vector 6: Usage fault */
+ .word lm3s_reserved /* Vector 7: Reserved */
+ .word lm3s_reserved /* Vector 8: Reserved */
+ .word lm3s_reserved /* Vector 9: Reserved */
+ .word lm3s_reserved /* Vector 10: Reserved */
+ .word lm3s_svcall /* Vector 11: SVC call */
+ .word lm3s_dbgmonitor /* Vector 12: Debug monitor */
+ .word lm3s_reserved /* Vector 13: Reserved */
+ .word lm3s_pendsv /* Vector 14: Pendable system service request */
+ .word lm3s_systick /* Vector 15: System tick */
/* External Interrupts */
#ifdef CONFIG_ARCH_CHIP_LM3S6918
- .word lm3s_gpioahandler /* Vector 16: GPIO Port A */
- .word lm3s_gpiobhandler /* Vector 17: GPIO Port B */
- .word lm3s_gpiodhandler /* Vector 18: GPIO Port C */
- .word lm3s_gpioehandler /* Vector 19: GPIO Port D */
- .word lm3s_gpioehandler /* Vector 20: GPIO Port E */
- .word lm3s_uart0handler /* Vector 21: UART 0 */
- .word lm3s_uart1handler /* Vector 22: UART 1 */
- .word lm3s_ssi0handler /* Vector 23: SSI 0 */
- .word lm3s_i2c0handler /* Vector 24: I2C 0 */
- .word lm3s_uncaught /* Vector 25: Reserved */
- .word lm3s_uncaught /* Vector 26: Reserved */
- .word lm3s_uncaught /* Vector 27: Reserved */
- .word lm3s_uncaught /* Vector 28: Reserved */
- .word lm3s_uncaught /* Vector 29: Reserved */
- .word lm3s_adc0handler /* Vector 30: ADC Sequence 0 */
- .word lm3s_adc1handler /* Vector 31: ADC Sequence 1 */
- .word lm3s_adc2handler /* Vector 32: ADC Sequence 2 */
- .word lm3s_adc3handler /* Vector 33: ADC Sequence 3 */
- .word lm3s_wdoghandler /* Vector 34: Watchdog Timer */
- .word lm3s_tmr0ahandler /* Vector 35: Timer 0 A */
- .word lm3s_tmr0bhandler /* Vector 36: Timer 0 B */
- .word lm3s_tmr1ahandler /* Vector 37: Timer 1 A */
- .word lm3s_tmr1bhandler /* Vector 38: Timer 1 B */
- .word lm3s_tmr2ahandler /* Vector 39: Timer 2 A */
- .word lm3s_tmr2bhandler /* Vector 40: Timer 3 B */
- .word lm3s_cmp0handler /* Vector 41: Analog Comparator 0 */
- .word lm3s_dmp1handler /* Vector 42: Analog Comparator 1 */
- .word lm3s_uncaught /* Vector 43: Reserved */
- .word lm3s_sysconhandler /* Vector 44: System Control */
- .word lm3s_flashconhandler /* Vector 45: FLASH Control */
- .word lm3s_gpiofhandler /* Vector 46: GPIO Port F */
- .word lm3s_gpioghandler /* Vector 47: GPIO Port G */
- .word lm3s_gpiohhandler /* Vector 48: GPIO Port H */
- .word lm3s_uncaught /* Vector 49: Reserved */
- .word lm3s_ssi1handler /* Vector 50: SSI 1 */
- .word lm3s_tmr3ahandler /* Vector 51: Timer 3 A */
- .word lm3s_tmr3bhandler /* Vector 52: Timer 3 B */
- .word lm3s_i2c1handler /* Vector 53: I2C 1 */
- .word lm3s_uncaught /* Vector 54: Reserved */
- .word lm3s_uncaught /* Vector 55: Reserved */
- .word lm3s_uncaught /* Vector 56: Reserved */
- .word lm3s_uncaught /* Vector 57: Reserved */
- .word lm3s_ethhandler /* Vector 58: Ethernet Controller */
- .word lm3s_hibhandler /* Vector 59: Hibernation Module */
- .word lm3s_uncaught /* Vector 60: Reserved */
- .word lm3s_uncaught /* Vector 61: Reserved */
- .word lm3s_uncaught /* Vector 62: Reserved */
- .word lm3s_uncaught /* Vector 63: Reserved */
- .word lm3s_uncaught /* Vector 64: Reserved */
- .word lm3s_uncaught /* Vector 65: Reserved */
- .word lm3s_uncaught /* Vector 66: Reserved */
- .word lm3s_uncaught /* Vector 67: Reserved */
- .word lm3s_uncaught /* Vector 68: Reserved */
- .word lm3s_uncaught /* Vector 69: Reserved */
- .word lm3s_uncaught /* Vector 70: Reserved */
+ .word lm3s_gpioa /* Vector 16: GPIO Port A */
+ .word lm3s_gpiob /* Vector 17: GPIO Port B */
+ .word lm3s_gpiod /* Vector 18: GPIO Port C */
+ .word lm3s_gpioe /* Vector 19: GPIO Port D */
+ .word lm3s_gpioe /* Vector 20: GPIO Port E */
+ .word lm3s_uart0 /* Vector 21: UART 0 */
+ .word lm3s_uart1 /* Vector 22: UART 1 */
+ .word lm3s_ssi0 /* Vector 23: SSI 0 */
+ .word lm3s_i2c0 /* Vector 24: I2C 0 */
+ .word lm3s_reserved /* Vector 25: Reserved */
+ .word lm3s_reserved /* Vector 26: Reserved */
+ .word lm3s_reserved /* Vector 27: Reserved */
+ .word lm3s_reserved /* Vector 28: Reserved */
+ .word lm3s_reserved /* Vector 29: Reserved */
+ .word lm3s_adc0 /* Vector 30: ADC Sequence 0 */
+ .word lm3s_adc1 /* Vector 31: ADC Sequence 1 */
+ .word lm3s_adc2 /* Vector 32: ADC Sequence 2 */
+ .word lm3s_adc3 /* Vector 33: ADC Sequence 3 */
+ .word lm3s_wdog /* Vector 34: Watchdog Timer */
+ .word lm3s_tmr0a /* Vector 35: Timer 0 A */
+ .word lm3s_tmr0b /* Vector 36: Timer 0 B */
+ .word lm3s_tmr1a /* Vector 37: Timer 1 A */
+ .word lm3s_tmr1b /* Vector 38: Timer 1 B */
+ .word lm3s_tmr2a /* Vector 39: Timer 2 A */
+ .word lm3s_tmr2b /* Vector 40: Timer 3 B */
+ .word lm3s_cmp0 /* Vector 41: Analog Comparator 0 */
+ .word lm3s_dmp1 /* Vector 42: Analog Comparator 1 */
+ .word lm3s_reserved /* Vector 43: Reserved */
+ .word lm3s_syscon /* Vector 44: System Control */
+ .word lm3s_flashcon /* Vector 45: FLASH Control */
+ .word lm3s_gpiof /* Vector 46: GPIO Port F */
+ .word lm3s_gpiog /* Vector 47: GPIO Port G */
+ .word lm3s_gpioh /* Vector 48: GPIO Port H */
+ .word lm3s_reserved /* Vector 49: Reserved */
+ .word lm3s_ssi1 /* Vector 50: SSI 1 */
+ .word lm3s_tmr3a /* Vector 51: Timer 3 A */
+ .word lm3s_tmr3b /* Vector 52: Timer 3 B */
+ .word lm3s_i2c1 /* Vector 53: I2C 1 */
+ .word lm3s_reserved /* Vector 54: Reserved */
+ .word lm3s_reserved /* Vector 55: Reserved */
+ .word lm3s_reserved /* Vector 56: Reserved */
+ .word lm3s_reserved /* Vector 57: Reserved */
+ .word lm3s_eth /* Vector 58: Ethernet Controller */
+ .word lm3s_hib /* Vector 59: Hibernation Module */
+ .word lm3s_reserved /* Vector 60: Reserved */
+ .word lm3s_reserved /* Vector 61: Reserved */
+ .word lm3s_reserved /* Vector 62: Reserved */
+ .word lm3s_reserved /* Vector 63: Reserved */
+ .word lm3s_reserved /* Vector 64: Reserved */
+ .word lm3s_reserved /* Vector 65: Reserved */
+ .word lm3s_reserved /* Vector 66: Reserved */
+ .word lm3s_reserved /* Vector 67: Reserved */
+ .word lm3s_reserved /* Vector 68: Reserved */
+ .word lm3s_reserved /* Vector 69: Reserved */
+ .word lm3s_reserved /* Vector 70: Reserved */
#else
# error "Vectors not specified for this LM3S chip"
#endif
+
+/************************************************************************************
+ * .text
+ ************************************************************************************/
+
.text
.thumb_func
+ HANDLER lm3s_reserved, LMSB_IRQ_RESERVED /* Unexpected/reserved vector */
+ HANDLER lm3s_nmi, LMSB_IRQ_NMI /* Vector 2: Non-Maskable Interrupt (NMI) */
+ HANDLER lm3s_hardfault, LMSB_IRQ_HARDFAULT /* Vector 3: Hard fault */
+ HANDLER lm3s_mpu, LMSB_IRQ_MPU /* Vector 4: Memory management (MPU) */
+ HANDLER lm3s_busfault, LMSB_IRQ_BUSFAULT /* Vector 5: Bus fault */
+ HANDLER lm3s_usagefault, LMSB_IRQ_USAGEFAULT /* Vector 6: Usage fault */
+ HANDLER lm3s_svcall, LMSB_IRQ_SVCALL /* Vector 11: SVC call */
+ HANDLER lm3s_dbgmonitor, LMSB_IRQ_DBGMONITOR /* Vector 12: Debug Monitor */
+ HANDLER lm3s_pendsv, LMSB_IRQ_PENDSV /* Vector 14: Penable system service request */
+ HANDLER lm3s_systick, LMSB_IRQ_SYSTICK /* Vector 15: System tick */
+
#ifdef CONFIG_ARCH_CHIP_LM3S6918
- HANDLER lm3s_gpioahandler, LM3S_IRQ_GPIOA /* Vector 16: GPIO Port A */
- HANDLER lm3s_gpiobhandler, LM3S_IRQ_GPIOB /* Vector 17: GPIO Port B */
- HANDLER lm3s_gpiodhandler, LM3S_IRQ_GPIOC /* Vector 18: GPIO Port C */
- HANDLER lm3s_gpioehandler, LM3S_IRQ_GPIOD /* Vector 19: GPIO Port D */
- HANDLER lm3s_gpioehandler, LM3S_IRQ_GPIOE /* Vector 20: GPIO Port E */
- HANDLER lm3s_uart0handler, LM3S_IRQ_UART0 /* Vector 21: UART 0 */
- HANDLER lm3s_uart1handler, LM3S_IRQ_UART1 /* Vector 22: UART 1 */
- HANDLER lm3s_ssi0handler, LM3S_IRQ_SSI0 /* Vector 23: SSI 0 */
- HANDLER lm3s_i2c0handler, LM3S_IRQ_I2C0 /* Vector 24: I2C 0 */
- HANDLER lm3s_adc0handler, LM3S_IRQ_ADC0 /* Vector 30: ADC Sequence 0 */
- HANDLER lm3s_adc1handler, LM3S_IRQ_ADC1 /* Vector 31: ADC Sequence 1 */
- HANDLER lm3s_adc2handler, LM3S_IRQ_ADC2 /* Vector 32: ADC Sequence 2 */
- HANDLER lm3s_adc3handler, LM3S_IRQ_ADC3 /* Vector 33: ADC Sequence 3 */
- HANDLER lm3s_wdoghandler, LM3S_IRQ_WDOG /* Vector 34: Watchdog Timer */
- HANDLER lm3s_tmr0ahandler, LM3S_IRQ_TIMER0A /* Vector 35: Timer 0 A */
- HANDLER lm3s_tmr0bhandler, LM3S_IRQ_TIMER0B /* Vector 36: Timer 0 B */
- HANDLER lm3s_tmr1ahandler, LM3S_IRQ_TIMER1A /* Vector 37: Timer 1 A */
- HANDLER lm3s_tmr1bhandler, LM3S_IRQ_TIMER1B /* Vector 38: Timer 1 B */
- HANDLER lm3s_tmr2ahandler, LM3S_IRQ_TIMER2A /* Vector 39: Timer 2 A */
- HANDLER lm3s_tmr2bhandler, LM3S_IRQ_TIMER2B /* Vector 40: Timer 3 B */
- HANDLER lm3s_cmp0handler, LM3S_IRQ_COMPARE0 /* Vector 41: Analog Comparator 0 */
- HANDLER lm3s_dmp1handler, LM3S_IRQ_COMPARE1 /* Vector 42: Analog Comparator 1 */
- HANDLER lm3s_sysconhandler, LM3S_IRQ_SYSCON /* Vector 44: System Control */
- HANDLER lm3s_flashconhandler, LM3S_IRQ_FLASHCON /* Vector 45: FLASH Control */
- HANDLER lm3s_gpiofhandler, LM3S_IRQ_GPIOF /* Vector 46: GPIO Port F */
- HANDLER lm3s_gpioghandler, LM3S_IRQ_GPIOG /* Vector 47: GPIO Port G */
- HANDLER lm3s_gpiohhandler, LM3S_IRQ_GPIOH /* Vector 48: GPIO Port H */
- HANDLER lm3s_ssi1handler, LM3S_IRQ_SSI1 /* Vector 50: SSI 1 */
- HANDLER lm3s_tmr3ahandler, LM3S_IRQ_TIMER3A /* Vector 51: Timer 3 A */
- HANDLER lm3s_tmr3bhandler, LM3S_IRQ_TIMER3B /* Vector 52: Timer 3 B */
- HANDLER lm3s_i2c1handler, LM3S_IRQ_I2C1 /* Vector 53: I2C 1 */
- HANDLER lm3s_ethhandler , LM3S_IRQ_ETHCON /* Vector 58: Ethernet Controller */
- HANDLER lm3s_hibhandler , LM3S_IRQ_HIBERNATE /* Vector 59: Hibernation Module */
+ HANDLER lm3s_gpioa, LM3S_IRQ_GPIOA /* Vector 16: GPIO Port A */
+ HANDLER lm3s_gpiob, LM3S_IRQ_GPIOB /* Vector 17: GPIO Port B */
+ HANDLER lm3s_gpiod, LM3S_IRQ_GPIOC /* Vector 18: GPIO Port C */
+ HANDLER lm3s_gpioe, LM3S_IRQ_GPIOD /* Vector 19: GPIO Port D */
+ HANDLER lm3s_gpioe, LM3S_IRQ_GPIOE /* Vector 20: GPIO Port E */
+ HANDLER lm3s_uart0, LM3S_IRQ_UART0 /* Vector 21: UART 0 */
+ HANDLER lm3s_uart1, LM3S_IRQ_UART1 /* Vector 22: UART 1 */
+ HANDLER lm3s_ssi0, LM3S_IRQ_SSI0 /* Vector 23: SSI 0 */
+ HANDLER lm3s_i2c0, LM3S_IRQ_I2C0 /* Vector 24: I2C 0 */
+ HANDLER lm3s_adc0, LM3S_IRQ_ADC0 /* Vector 30: ADC Sequence 0 */
+ HANDLER lm3s_adc1, LM3S_IRQ_ADC1 /* Vector 31: ADC Sequence 1 */
+ HANDLER lm3s_adc2, LM3S_IRQ_ADC2 /* Vector 32: ADC Sequence 2 */
+ HANDLER lm3s_adc3, LM3S_IRQ_ADC3 /* Vector 33: ADC Sequence 3 */
+ HANDLER lm3s_wdog, LM3S_IRQ_WDOG /* Vector 34: Watchdog Timer */
+ HANDLER lm3s_tmr0a, LM3S_IRQ_TIMER0A /* Vector 35: Timer 0 A */
+ HANDLER lm3s_tmr0b, LM3S_IRQ_TIMER0B /* Vector 36: Timer 0 B */
+ HANDLER lm3s_tmr1a, LM3S_IRQ_TIMER1A /* Vector 37: Timer 1 A */
+ HANDLER lm3s_tmr1b, LM3S_IRQ_TIMER1B /* Vector 38: Timer 1 B */
+ HANDLER lm3s_tmr2a, LM3S_IRQ_TIMER2A /* Vector 39: Timer 2 A */
+ HANDLER lm3s_tmr2b, LM3S_IRQ_TIMER2B /* Vector 40: Timer 3 B */
+ HANDLER lm3s_cmp0, LM3S_IRQ_COMPARE0 /* Vector 41: Analog Comparator 0 */
+ HANDLER lm3s_dmp1, LM3S_IRQ_COMPARE1 /* Vector 42: Analog Comparator 1 */
+ HANDLER lm3s_syscon, LM3S_IRQ_SYSCON /* Vector 44: System Control */
+ HANDLER lm3s_flashcon, LM3S_IRQ_FLASHCON /* Vector 45: FLASH Control */
+ HANDLER lm3s_gpiof, LM3S_IRQ_GPIOF /* Vector 46: GPIO Port F */
+ HANDLER lm3s_gpiog, LM3S_IRQ_GPIOG /* Vector 47: GPIO Port G */
+ HANDLER lm3s_gpioh, LM3S_IRQ_GPIOH /* Vector 48: GPIO Port H */
+ HANDLER lm3s_ssi1, LM3S_IRQ_SSI1 /* Vector 50: SSI 1 */
+ HANDLER lm3s_tmr3a, LM3S_IRQ_TIMER3A /* Vector 51: Timer 3 A */
+ HANDLER lm3s_tmr3b, LM3S_IRQ_TIMER3B /* Vector 52: Timer 3 B */
+ HANDLER lm3s_i2c1, LM3S_IRQ_I2C1 /* Vector 53: I2C 1 */
+ HANDLER lm3s_eth, LM3S_IRQ_ETHCON /* Vector 58: Ethernet Controller */
+ HANDLER lm3s_hib, LM3S_IRQ_HIBERNATE /* Vector 59: Hibernation Module */
#else
# error "Vectors not specified for this LM3S chip"
#endif
-#ifdef CONFIG_DEBUG
- HANDLER lm3s_uncaught, NR_IRQS /* Unexpected vector (default is to reset) */
-#endif
- .end
+/************************************************************************************
+ * .rodata
+ ************************************************************************************/
+
+ .section .rodata, "a"
+
+/* Variables: _sbss is the start of the BSS region (see ld.script) _ebss is the end
+ * of the BSS regsion (see ld.script). The idle task stack starts at the end of BSS
+ * and is of size CONFIG_IDLETHREAD_STACKSIZE. The IDLE thread is the thread that
+ * the system boots on and, eventually, becomes the idle, do nothing task that runs
+ * only when there is nothing else to run. The heap continues from there until the
+ * end of memory. See g_heapbase below.
+ */
+
+ .globl g_heapbase
+ .type g_heapbase, object
+g_heapbase:
+ .long _ebss+CONFIG_IDLETHREAD_STACKSIZE
+ .size g_heapbase, .-g_heapbase
+
+ .end
diff --git a/nuttx/configs/eagle100/README.txt b/nuttx/configs/eagle100/README.txt
index eefd0e18a..b73714aea 100644
--- a/nuttx/configs/eagle100/README.txt
+++ b/nuttx/configs/eagle100/README.txt
@@ -79,7 +79,11 @@ Eagle100-specific Configuration Options
CONFIG_DRAM_START - The start address of installed DRAM
- CONFIG_DRAM_SIZE=0x00000000
+ CONFIG_DRAM_START=0x20000000
+
+ CONFIG_DRAM_END - Last address+1 of installed RAM
+
+ CONFIG_DRAM_END=(CONFIG_DRAM_START+CONFIG_DRAM_SIZE)
CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that
have LEDs
diff --git a/nuttx/configs/eagle100/ostest/defconfig b/nuttx/configs/eagle100/ostest/defconfig
index d88d1e924..d686306bc 100644
--- a/nuttx/configs/eagle100/ostest/defconfig
+++ b/nuttx/configs/eagle100/ostest/defconfig
@@ -49,6 +49,7 @@
# CONFIG_BOARD_LOOPSPERMSEC - for delay loops
# CONFIG_DRAM_SIZE - Describes the installed DRAM.
# CONFIG_DRAM_START - The start address of DRAM (physical)
+# CONFIG_DRAM_END - Last address+1 of installed RAM
# CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt
# stack. If defined, this symbol is the size of the interrupt
# stack in bytes. If not defined, the user task stacks will be
@@ -66,6 +67,7 @@ CONFIG_ARCH_BOARD_EAGLE100=y
CONFIG_BOARD_LOOPSPERMSEC=16945
CONFIG_DRAM_SIZE=0x00010000
CONFIG_DRAM_START=0x00000000
+CONFIG_DRAM_END=(CONFIG_DRAM_START+CONFIG_DRAM_SIZE)
CONFIG_DRAM_NUTTXENTRY=0x00002000
CONFIG_ARCH_INTERRUPTSTACK=n
CONFIG_ARCH_STACKDUMP=y
@@ -78,7 +80,7 @@ CONFIG_ARCH_LEDS=y
# CONFIG_UARTn_DISABLE - select to disable all support for
# the UART
# CONFIG_UARTn_SERIAL_CONSOLE - selects the UARTn for the
-# console and ttys0 (default is the UART1).
+# console and ttys0 (default is the UART0).
# CONFIG_UARTn_RXBUFSIZE - Characters are buffered as received.
# This specific the size of the receive buffer
# CONFIG_UARTn_TXBUFSIZE - Characters are buffered before
@@ -88,30 +90,22 @@ CONFIG_ARCH_LEDS=y
# CONFIG_UARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity
# CONFIG_UARTn_2STOP - Two stop bits
#
-CONFIG_UART1_DISABLE=n
-CONFIG_UART2_DISABLE=y
-CONFIG_UART3_DISABLE=y
-CONFIG_UART1_SERIAL_CONSOLE=y
-CONFIG_UART2_SERIAL_CONSOLE=n
-CONFIG_UART3_SERIAL_CONSOLE=n
+CONFIG_UART0_DISABLE=n
+CONFIG_UART1_DISABLE=y
+CONFIG_UART0_SERIAL_CONSOLE=y
+CONFIG_UART1_SERIAL_CONSOLE=n
+CONFIG_UART0_TXBUFSIZE=256
CONFIG_UART1_TXBUFSIZE=256
-CONFIG_UART2_TXBUFSIZE=256
-CONFIG_UART3_TXBUFSIZE=256
+CONFIG_UART0_RXBUFSIZE=256
CONFIG_UART1_RXBUFSIZE=256
-CONFIG_UART2_RXBUFSIZE=256
-CONFIG_UART3_RXBUFSIZE=256
+CONFIG_UART0_BAUD=115200
CONFIG_UART1_BAUD=115200
-CONFIG_UART2_BAUD=115200
-CONFIG_UART3_BAUD=115200
+CONFIG_UART0_BITS=8
CONFIG_UART1_BITS=8
-CONFIG_UART2_BITS=8
-CONFIG_UART3_BITS=8
+CONFIG_UART0_PARITY=0
CONFIG_UART1_PARITY=0
-CONFIG_UART2_PARITY=0
-CONFIG_UART3_PARITY=0
+CONFIG_UART0_2STOP=0
CONFIG_UART1_2STOP=0
-CONFIG_UART2_2STOP=0
-CONFIG_UART3_2STOP=0
#
# LM3S6918 specific SPI device driver settings
@@ -122,6 +116,12 @@ CONFIG_SPI1_DISABLE=n
CONFIG_SPI2_DISABLE=y
#
+# LM3S6918 specific serial device driver settings
+#
+CONFIG_LM3S_ETHERNET=n
+CONFIG_LM3S_ETHLEDS=n
+
+#
# General build options
#
# CONFIG_RRLOAD_BINARY - make the rrload binary format used with
diff --git a/nuttx/configs/eagle100/src/up_leds.c b/nuttx/configs/eagle100/src/up_leds.c
index 2b8dcfb6b..bf23b1eaa 100644
--- a/nuttx/configs/eagle100/src/up_leds.c
+++ b/nuttx/configs/eagle100/src/up_leds.c
@@ -70,6 +70,10 @@
#ifdef CONFIG_ARCH_LEDS
void up_ledinit(void)
{
+ /* Make sure that the GPIOE peripheral is enabled */
+
+ modifyreg32(LM3S_SYSCON_RCGC2_OFFSET, 0, SYSCON_RCGC2_GPIOE);
+
/* Configure Port E, Bit 1 as an output, initial value=OFF */
lm3s_configgpio(GPIO_DIR_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORTE | 1);
diff --git a/nuttx/examples/ostest/cond.c b/nuttx/examples/ostest/cond.c
index d5f96dfc5..11191b7d5 100644
--- a/nuttx/examples/ostest/cond.c
+++ b/nuttx/examples/ostest/cond.c
@@ -123,6 +123,7 @@ static void *thread_waiter(void *parameter)
waiter_nloops++;
}
+ return NULL;
}
static void *thread_signaler(void *parameter)