summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/arch/arm/src/common/up_schedulesigaction.c39
-rw-r--r--nuttx/arch/arm/src/common/up_sigdeliver.c8
-rw-r--r--nuttx/arch/arm/src/lpc214x/Make.defs7
-rw-r--r--nuttx/arch/arm/src/lpc214x/Startup.s80
-rw-r--r--nuttx/arch/arm/src/lpc214x/chip.h12
-rw-r--r--nuttx/arch/arm/src/lpc214x/lpc214x_decodeirq.c2
-rw-r--r--nuttx/arch/arm/src/lpc214x/lpc214x_head.S36
-rw-r--r--nuttx/arch/arm/src/lpc214x/lpc214x_lowputc.S9
-rwxr-xr-xnuttx/arch/arm/src/lpc214x/lpc214x_uart.h2
-rw-r--r--nuttx/configs/mcu123-lpc214x/defconfig8
-rw-r--r--nuttx/configs/mcu123-lpc214x/include/board.h11
11 files changed, 85 insertions, 129 deletions
diff --git a/nuttx/arch/arm/src/common/up_schedulesigaction.c b/nuttx/arch/arm/src/common/up_schedulesigaction.c
index 1dbecc8e7..a6b2315af 100644
--- a/nuttx/arch/arm/src/common/up_schedulesigaction.c
+++ b/nuttx/arch/arm/src/common/up_schedulesigaction.c
@@ -1,7 +1,7 @@
-/************************************************************
+/****************************************************************************
* common/up_schedulesigaction.c
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -14,7 +14,7 @@
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
- * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * 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.
*
@@ -31,38 +31,43 @@
* 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 <sched.h>
#include <debug.h>
+
#include <nuttx/arch.h>
+
#include "os_internal.h"
#include "up_internal.h"
#include "up_arch.h"
-/************************************************************
+#ifndef CONFIG_DISABLE_SIGNALS
+
+/****************************************************************************
* Private Definitions
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Private Data
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Private Funtions
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Public Funtions
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Name: up_schedule_sigaction
*
* Description:
@@ -93,7 +98,7 @@
* currently executing task -- just call the signal
* handler now.
*
- ************************************************************/
+ ****************************************************************************/
void up_schedule_sigaction(_TCB *tcb, sig_deliver_t sigdeliver)
{
@@ -188,3 +193,5 @@ void up_schedule_sigaction(_TCB *tcb, sig_deliver_t sigdeliver)
irqrestore(flags);
}
}
+
+#endif /* !CONFIG_DISABLE_SIGNALS */
diff --git a/nuttx/arch/arm/src/common/up_sigdeliver.c b/nuttx/arch/arm/src/common/up_sigdeliver.c
index 4b2f1c27b..04202b1a4 100644
--- a/nuttx/arch/arm/src/common/up_sigdeliver.c
+++ b/nuttx/arch/arm/src/common/up_sigdeliver.c
@@ -38,15 +38,20 @@
****************************************************************************/
#include <nuttx/config.h>
+
#include <sys/types.h>
#include <sched.h>
#include <debug.h>
+
#include <nuttx/irq.h>
#include <nuttx/arch.h>
+
#include "os_internal.h"
#include "up_internal.h"
#include "up_arch.h"
+#ifndef CONFIG_DISABLE_SIGNALS
+
/****************************************************************************
* Definitions
****************************************************************************/
@@ -135,3 +140,6 @@ void up_sigdeliver(void)
up_fullcontextrestore(regs);
#endif
}
+
+#endif /* !CONFIG_DISABLE_SIGNALS */
+
diff --git a/nuttx/arch/arm/src/lpc214x/Make.defs b/nuttx/arch/arm/src/lpc214x/Make.defs
index 40b0c4430..6b10e4bad 100644
--- a/nuttx/arch/arm/src/lpc214x/Make.defs
+++ b/nuttx/arch/arm/src/lpc214x/Make.defs
@@ -40,10 +40,13 @@ 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_prefetchabort.c up_releasepending.c \
- up_releasestack.c up_reprioritizertr.c up_schedulesigaction.c \
- up_sigdeliver.c up_syscall.c up_unblocktask.c \
+ up_releasestack.c up_reprioritizertr.c up_syscall.c up_unblocktask.c \
up_undefinedinsn.c up_usestack.c
+ifneq ($(CONFIG_DISABLE_SIGNALS),y)
+CMN_CSRCS += up_schedulesigaction.c up_sigdeliver.c
+endif
+
CHIP_ASRCS = lpc214x_lowputc.S
CHIP_CSRCS = lpc214x_decodeirq.c lpc214x_irq.c lpc214x_timerisr.c \
lpc214x_serial.c
diff --git a/nuttx/arch/arm/src/lpc214x/Startup.s b/nuttx/arch/arm/src/lpc214x/Startup.s
deleted file mode 100644
index ecf692747..000000000
--- a/nuttx/arch/arm/src/lpc214x/Startup.s
+++ /dev/null
@@ -1,80 +0,0 @@
-/*
- * The STARTUP.S code is executed after CPU Reset. This file may be
- * translated with the following SET symbols. In uVision these SET
- * symbols are entered under Options - ASM - Set.
- *
- * REMAP: when set the startup code initializes the register MEMMAP
- * which overwrites the settings of the CPU configuration pins. The
- * startup and interrupt vectors are remapped from:
- * 0x00000000 default setting (not remapped)
- * 0x80000000 when EXTMEM_MODE is used
- * 0x40000000 when RAM_MODE is used
- *
- * EXTMEM_MODE: when set the device is configured for code execution
- * from external memory starting at address 0x80000000. The startup
- * vectors are located to 0x80000000.
- *
- * RAM_MODE: when set the device is configured for code execution
- * from on-chip RAM starting at address 0x40000000. The startup
- * vectors are located to 0x40000000.
- */
-
-Reset_Handler:
-
-
-
-/* Memory Mapping */
-
-
-/* Setup Stack for each mode */
- ldr r0, =Top_Stack
-
-/* Enter Undefined Instruction Mode and set its Stack Pointer */
- msr CPSR_c, #UND_MODE | PSR_I_BIT | PSR_F_BIT
- mov SP, r0
- sub r0, r0, #UND_Stack_Size
-
-/* Enter Abort Mode and set its Stack Pointer */
- msr CPSR_c, #ABT_MODE | PSR_I_BIT | PSR_F_BIT
- mov SP, r0
- sub r0, r0, #ABT_Stack_Size
-
-/* Enter FIQ Mode and set its Stack Pointer */
- msr CPSR_c, #FIQ_MODE | PSR_I_BIT | PSR_F_BIT
- mov SP, r0
- sub r0, r0, #FIQ_Stack_Size
-
-/* Enter IRQ Mode and set its Stack Pointer */
- msr CPSR_c, #IRQ_MODE | PSR_I_BIT | PSR_F_BIT
- mov SP, r0
- sub r0, r0, #IRQ_Stack_Size
-
-/* Enter Supervisor Mode and set its Stack Pointer */
- msr CPSR_c, #SVC_MODE | PSR_I_BIT | PSR_F_BIT
- mov SP, r0
- sub r0, r0, #SVC_Stack_Size
-
-/* Enter User Mode and set its Stack Pointer */
- msr CPSR_c, #USR_MODE
- mov SP, r0
-
-/* Enter the C code */
- ldr r0,=?C?INIT
- tst r0,#1 ; Bit-0 set: INIT is Thumb
- ldreq LR,=exit?A ; ARM Mode
- ldrne LR,=exit?T ; Thumb Mode
- bx r0
- ENDP
-
-PUBLIC exit?A
-exit?A PROC CODE32
- B exit?A
- ENDP
-
-PUBLIC exit?T
-exit?T PROC CODE16
-exit: B exit?T
- ENDP
-
-
- END
diff --git a/nuttx/arch/arm/src/lpc214x/chip.h b/nuttx/arch/arm/src/lpc214x/chip.h
index d237b39cc..2d78d8b8c 100644
--- a/nuttx/arch/arm/src/lpc214x/chip.h
+++ b/nuttx/arch/arm/src/lpc214x/chip.h
@@ -256,8 +256,20 @@
#define LPC214X_PLL_CFG_MSEL (0x1f << 0) /* PLL Multiplier */
#define LPC214X_PLL_CFG_PSEL (0x03 << 5) /* PLL Divider */
+
+/* PLL Status Register Bit Settings */
+
+#define LPC214X_PLL_STAT_MSEL (0x1f << 0) /* PLL Multiplier Readback */
+#define LPC214X_PLL_STAT_PSEL (0x03 << 5) /* PLL Divider Readback */
+#define LPC214X_PLL_STAT_PLLE (1 << 8) /* PLL Enable Readback */
+#define LPC214X_PLL_STAT_PLLC (1 << 9) /* PLL Connect Readback */
#define LPC214X_PLL_STAT_PLOCK (1 << 10) /* PLL Lock Status */
+/* PLL Feed Register values */
+
+#define LPC214X_PLL_FEED1 0xaa
+#define LPC214X_PLL_FEED2 0x55
+
/* Power Control register offsets */
#define LPC214X_PCON_OFFSET 0x00 /* Control Register */
diff --git a/nuttx/arch/arm/src/lpc214x/lpc214x_decodeirq.c b/nuttx/arch/arm/src/lpc214x/lpc214x_decodeirq.c
index 6ee78e68c..12ae2354f 100644
--- a/nuttx/arch/arm/src/lpc214x/lpc214x_decodeirq.c
+++ b/nuttx/arch/arm/src/lpc214x/lpc214x_decodeirq.c
@@ -67,7 +67,9 @@
/* This type arry maps 4 bits into the bit number of the lowest bit that it set */
+#ifndef CONFIG_SUPPRESS_INTERRUPTS
static uint8 g_nibblemap[16] = { 0, 0, 1, 0, 2, 0, 1, 0, 3, 0, 1, 0, 2, 0, 1, 0 };
+#endif
/********************************************************************************
* Private Functions
diff --git a/nuttx/arch/arm/src/lpc214x/lpc214x_head.S b/nuttx/arch/arm/src/lpc214x/lpc214x_head.S
index b3c2a9ee6..117ca6a1f 100644
--- a/nuttx/arch/arm/src/lpc214x/lpc214x_head.S
+++ b/nuttx/arch/arm/src/lpc214x/lpc214x_head.S
@@ -38,6 +38,8 @@
*****************************************************************************/
#include <nuttx/config.h>
+
+#include "chip.h"
#include "up_internal.h"
#include "up_arch.h"
@@ -92,6 +94,12 @@
# define CONFIG_PLLCFG_VALUE 0x00000024
#endif
+/* PLL Control register */
+
+#ifndef CONFIG_PLLCON_VALUE /* Can be selected from config file */
+# define CONFIG_PLLCON_VALUE LPC214X_PLL_CON_PLLE
+#endif
+
/* Memory Accelerator Module (MAM) initialization values
*
* MAM Control Register
@@ -265,32 +273,32 @@
/* Configure the PLL */
.macro configpll, base, val1, val2, val3
-#ifdef LPC214X_PLL_SETUP
+#ifdef CONFIG_PLL_SETUP
ldr \base, =LPC214X_PLL_BASE
- mov \val1, #0xaa
- mov \val2, #0x55
+ mov \val1, #LPC214X_PLL_FEED1
+ mov \val2, #LPC214X_PLL_FEED2
/* Configure and Enable PLL */
mov \val3, #CONFIG_PLLCFG_VALUE
- str \val3, [\base, #LPC214X_PLLCFG_OFFSET]
- mov \val3, #LPC214X_PLLCON_PLLE
- str \val3, [\base, #LPC214X_PLLCON_OFFSET]
- str \val1, [\base, #LPC214X_PLLFEED_OFFSET]
- str \val2, [\base, #LPC214X_PLLFEED_OFFSET]
+ str \val3, [\base, #LPC214X_PLL_CFG_OFFSET]
+ mov \val3, #CONFIG_PLLCON_VALUE
+ str \val3, [\base, #LPC214X_PLL_CON_OFFSET]
+ str \val1, [\base, #LPC214X_PLL_FEED_OFFSET]
+ str \val2, [\base, #LPC214X_PLL_FEED_OFFSET]
/* Wait until PLL Locked */
1:
- ldr \val3, [\base, #LPC214X_PLLSTAT_OFFSET]
- ands \val3, \val3, #LPC214X_PLLSTAT_PLOCK
+ ldr \val3, [\base, #LPC214X_PLL_STAT_OFFSET]
+ ands \val3, \val3, #LPC214X_PLL_STAT_PLOCK
beq 1b
/* Switch to PLL Clock */
- mov \val3, #(LPC214X_PLLCON_PLLE | LPC214X_PLLCON_PLLC)
- str \val3, [\base, #LPC214X_PLLCON__OFFSET]
- str \val1, [\base, #LPC214X_PLLFEED_OFFSET]
- str \val2, [\base, #LPC214X_PLLFEED_OFFSET]
+ mov \val3, #(LPC214X_PLL_CON_PLLE | LPC214X_PLL_CON_PLLC)
+ str \val3, [\base, #LPC214X_PLL_CON_OFFSET]
+ str \val1, [\base, #LPC214X_PLL_FEED_OFFSET]
+ str \val2, [\base, #LPC214X_PLL_FEED_OFFSET]
#endif
.endm
diff --git a/nuttx/arch/arm/src/lpc214x/lpc214x_lowputc.S b/nuttx/arch/arm/src/lpc214x/lpc214x_lowputc.S
index 23258fce9..5e00d15cf 100644
--- a/nuttx/arch/arm/src/lpc214x/lpc214x_lowputc.S
+++ b/nuttx/arch/arm/src/lpc214x/lpc214x_lowputc.S
@@ -99,6 +99,8 @@
#endif
#define LPC214X_LCR_VALUE (LPC214X_LCR_CHAR | LPC214X_LCR_PAR | LPC214X_LCR_STOP)
+#define LPC214X_FCR_VALUE (LPC214X_FCR_FIFO_TRIG8 | LPC214X_FCR_TX_FIFO_RESET |\
+ LPC214X_FCR_RX_FIFO_RESET | LPC214X_FCR_FIFO_ENABLE)
/**************************************************************************
* Private Types
@@ -174,7 +176,7 @@ up_lowsetup:
/* Configure parity, data bits, stop bits and set DLAB=1 */
- ldr r0, =LPC214X_UART0_BASE
+ ldr r0, =LPC214X_UART_BASE
mov r1, #(LPC214X_LCR_VALUE | LPC214X_LCR_DLAB_ENABLE)
strb r1, [r0, #LPC214X_UART_LCR_OFFSET]
@@ -191,6 +193,11 @@ up_lowsetup:
mov r1, #LPC214X_LCR_VALUE
strb r1, [r0, #LPC214X_UART_LCR_OFFSET]
+ /* Configure the FIFOs */
+
+ mov r1, #LPC214X_FCR_VALUE
+ strb r1, [r0, #LPC214X_UART_FCR_OFFSET]
+
/* And return */
mov pc, lr
diff --git a/nuttx/arch/arm/src/lpc214x/lpc214x_uart.h b/nuttx/arch/arm/src/lpc214x/lpc214x_uart.h
index e87c7cb28..9e5b6883d 100755
--- a/nuttx/arch/arm/src/lpc214x/lpc214x_uart.h
+++ b/nuttx/arch/arm/src/lpc214x/lpc214x_uart.h
@@ -78,7 +78,7 @@
/* FIFO Control Register (FCR) bit definitions */
-#define LPC214X_FCR_FIFO_ENABLE (1 << 0) /* FIFO wnable */
+#define LPC214X_FCR_FIFO_ENABLE (1 << 0) /* FIFO enable */
#define LPC214X_FCR_RX_FIFO_RESET (1 << 1) /* Reset receive FIFO */
#define LPC214X_FCR_TX_FIFO_RESET (1 << 2) /* Reset transmit FIFO */
#define LPC214X_FCR_FIFO_TRIG1 (0 << 6) /* Trigger @1 character in FIFO */
diff --git a/nuttx/configs/mcu123-lpc214x/defconfig b/nuttx/configs/mcu123-lpc214x/defconfig
index a1f0b9086..a5fdf00da 100644
--- a/nuttx/configs/mcu123-lpc214x/defconfig
+++ b/nuttx/configs/mcu123-lpc214x/defconfig
@@ -57,7 +57,7 @@ CONFIG_ARCH_CHIP=lpc214x
CONFIG_ARCH_LPC2148=y
CONFIG_ARCH_BOARD=mcu123-lpc214x
CONFIG_ARCH_BOARD_MCU123=y
-CONFIG_BOARD_LOOPSPERMSEC=1250
+CONFIG_BOARD_LOOPSPERMSEC=2778
CONFIG_ARCH_LEDS=y
CONFIG_DRAM_SIZE=0x02000000
CONFIG_DRAM_START=0x40000000
@@ -163,9 +163,9 @@ CONFIG_ARCH_LOWPUTC=y
CONFIG_RR_INTERVAL=200
CONFIG_SCHED_INSTRUMENTATION=n
CONFIG_TASK_NAME_SIZE=0
-CONFIG_START_YEAR=2007
-CONFIG_START_MONTH=2
-CONFIG_START_DAY=13
+CONFIG_START_YEAR=2008
+CONFIG_START_MONTH=9
+CONFIG_START_DAY=17
CONFIG_JULIAN_TIME=n
CONFIG_DEV_CONSOLE=y
diff --git a/nuttx/configs/mcu123-lpc214x/include/board.h b/nuttx/configs/mcu123-lpc214x/include/board.h
index e9821b733..080b06abe 100644
--- a/nuttx/configs/mcu123-lpc214x/include/board.h
+++ b/nuttx/configs/mcu123-lpc214x/include/board.h
@@ -57,17 +57,6 @@
#define LPC214X_PCLKFREQ (LPC214X_FOSC/4) /* PCLK must be FOSC/4 */
-#define LPC214X_PSEL0 5
-#define LPC214X_PSEL1 6
-
-#define LPC214X_PLLE 0
-#define LPC214X_PLLC 1
-
-#define LPC214X_PLOCK 10
-
-#define LPC214X_PLL_FEED1 0xaa
-#define LPC214X_PLL_FEED2 0x55
-
/* LED definitions **********************************************************/
#define LED_STARTED 0