diff --git a/platform/mbed_retarget.cpp b/platform/mbed_retarget.cpp
index 909049dd8e..33e02cbd6d 100644
--- a/platform/mbed_retarget.cpp
+++ b/platform/mbed_retarget.cpp
@@ -766,9 +766,6 @@ extern "C" uint32_t __HeapLimit;
#undef errno
extern "C" int errno;
-// For ARM7 only
-register unsigned char * stack_ptr __asm ("sp");
-
// Dynamic memory allocation related syscall.
#if defined(TARGET_NUMAKER_PFM_NUC472) || defined(TARGET_NUMAKER_PFM_M453)
// Overwrite _sbrk() to support two region model (heap and stack are two distinct regions).
@@ -785,9 +782,7 @@ extern "C" caddr_t _sbrk(int incr) {
unsigned char* prev_heap = heap;
unsigned char* new_heap = heap + incr;
-#if defined(TARGET_ARM7)
- if (new_heap >= stack_ptr) {
-#elif defined(TARGET_CORTEX_A)
+#if defined(TARGET_CORTEX_A)
if (new_heap >= (unsigned char*)&__HeapLimit) { /* __HeapLimit is end of heap section */
#else
if (new_heap >= (unsigned char*)__get_MSP()) {
diff --git a/rtos/rtx/TARGET_ARM7/ARM7/TOOLCHAIN_GCC/HAL_CM0.S b/rtos/rtx/TARGET_ARM7/ARM7/TOOLCHAIN_GCC/HAL_CM0.S
deleted file mode 100644
index 029de0f372..0000000000
--- a/rtos/rtx/TARGET_ARM7/ARM7/TOOLCHAIN_GCC/HAL_CM0.S
+++ /dev/null
@@ -1,329 +0,0 @@
-/*----------------------------------------------------------------------------
- * RL-ARM - RTX
- *----------------------------------------------------------------------------
- * Name: HAL_CM0.S
- * Purpose: Hardware Abstraction Layer for ARM7TDMI
- * Rev.: V1.0
- *----------------------------------------------------------------------------
- *
- * Copyright (c) 1999-2009 KEIL, 2009-2015 ARM Germany GmbH
- * All rights reserved.
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- * - Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * - 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.
- * - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
- *---------------------------------------------------------------------------*/
-
- .file "HAL_CM0.S"
- .syntax unified
-
- .equ TCB_TSTACK, 40
-
-
-/*----------------------------------------------------------------------------
- * Functions
- *---------------------------------------------------------------------------*/
-
- .arm
-
- .section ".text"
- .align 2
-
-/*-------------------------- Save Context --------------------------------*/
-/* MUST be called the first */
-.macro SaveContext
-
- /* Push R0 as we are going to use the register. */ \
- STMDB SP!, {R0}
-
- /* Set R0 to SP(user) */
- STMDB SP,{SP}^
- NOP
- SUB SP, SP, #4
- LDMIA SP!,{R0}
-
- /* Push the LR return address onto the user stack. */
- STMDB R0!, {LR}
-
- /* Now we have saved LR we can use it instead of R0. */
- MOV LR, R0
-
- /* Pop R0 so we can save it onto the system mode stack. */
- LDMIA SP!, {R0}
-
- /* Push all the system mode registers onto the task stack. */
- STMDB LR,{R0-R12,LR}^ /* LR can not be changed because user's LR is used*/
- NOP /* pass 1 cycle before changing LR */
- SUB LR, LR, #14*4 /* change LR now -15 dwords (R0-R14)*/
-
- /* Push the SPSR onto the task stack. */
- MRS R0, SPSR
- STMDB LR!, {R0}
-
- /* Store the new top of stack for the task. */
- LDR R0,=os_tsk
- LDR R0, [R0] /* R0 = (tcb) os_tsk.run */
- STR LR, [R0, TCB_TSTACK] /* tcb.tsk_stack = SP(user) */
-.endm
-
-/*-------------------------- Restore Context --------------------------------*/
- .type RestoreContext, %function
- .global RestoreContext
-RestoreContext:
- .fnstart
- .cantunwind
- /* Set the LR to the task stack. */
- LDR R0,=os_tsk
- LDR R1, [R0, 4] /* R1 = (tcb) os_tsk.new */
- STR R1, [R0] /* os_tsk.run = os_tsk_newk */
- LDR LR, [R1, TCB_TSTACK] /* LR = tcb.tsk_stack */
-
- /* Get the SPSR from the stack. */
- LDMFD LR!, {R0} /* SPSR */
- MSR SPSR, R0
-
- /* Restore all system mode registers for the task. */
- LDMFD LR, {R0-R12,LR}^
- NOP
-
- ADD LR, LR, 15*4 /* increase stack pointer */
- /* Set SP(user) to LR */
- STMDB SP!,{LR}
- LDMIA SP,{SP}^
- NOP
- ADD SP, SP, #4
-
- /* Restore the return address. */
- LDR LR, [LR,#-4] /* last dword is task's PC register */
-
- /* And return - correcting the offset in the LR to obtain the */
- /* correct address. */
- SUBS PC, LR, #4
-
-/*-------------------------- End --------------------------------*/
- .fnend
- .size RestoreContext, .-RestoreContext
-
-
-
-/*--------------------------- rt_set_PSP ------------------------------------*/
-
-# void rt_set_PSP (U32 stack);
-
- .type rt_set_PSP, %function
- .global rt_set_PSP
-rt_set_PSP:
- .fnstart
- .cantunwind
-
- MOV SP,R0
- BX LR
-
- .fnend
- .size rt_set_PSP, .-rt_set_PSP
-
-
-/*--------------------------- rt_get_PSP ------------------------------------*/
-
-# U32 rt_get_PSP (void);
-
- .type rt_get_PSP, %function
- .global rt_get_PSP
-rt_get_PSP:
- .fnstart
- .cantunwind
-
- MOV R0,SP
- BX LR
-
- .fnend
- .size rt_get_PSP, .-rt_get_PSP
-
-
-
-/*--------------------------- _alloc_box ------------------------------------*/
-
-# void *_alloc_box (void *box_mem);
- /* Function wrapper for Unprivileged/Privileged mode. */
-
- .type _alloc_box, %function
- .global _alloc_box
-_alloc_box:
- .fnstart
- .cantunwind
-
- LDR R3,=rt_alloc_box
- MOV R12, R3
- MRS R3, CPSR
- AND R3, 0x1F
- CMP R3, 0x12 /* IRQ mode*/
- BNE PrivilegedA
- CMP R3, 0x1F /* System mode*/
- BNE PrivilegedA
- SVC 0
- BX LR
-PrivilegedA:
- BX R12
-
- .fnend
- .size _alloc_box, .-_alloc_box
-
-
-/*--------------------------- _free_box -------------------------------------*/
-
-# int _free_box (void *box_mem, void *box);
- /* Function wrapper for Unprivileged/Privileged mode. */
-
- .type _free_box, %function
- .global _free_box
-_free_box:
- .fnstart
- .cantunwind
-
- LDR R3,=rt_free_box
- MOV R12, R3
- MRS R3, CPSR
- AND R3, 0x1F
- CMP R3, 0x12 /* IRQ mode*/
- BNE PrivilegedA
- CMP R3, 0x1F /* System mode*/
- BNE PrivilegedA
- SVC 0
- BX LR
-PrivilegedF:
- BX R12
-
- .fnend
- .size _free_box, .-_free_box
-
-
-/*-------------------------- SVC_Handler ------------------------------------*/
-
-# void SVC_Handler (void);
-
- .type SVC_Handler, %function
- .global SVC_Handler
-SVC_Handler:
- .fnstart
- .cantunwind
- /* Within an IRQ ISR the link register has an offset from the true return
- address, but an SWI ISR does not. Add the offset manually so the same
- ISR return code can be used in both cases. */
-
- STMFD SP!, {R0,LR} /* Store registers. */
- ADD LR, LR, #4 /* Align LR with IRQ handler */
- SaveContext
- MOV R11, LR /* Save Task Stack Pointer */
- LDMFD SP!, {R0,LR} /* Restore registers and return. */
- STMFD SP!, {R11} /* Save Task Stack Pointer */
-
- LDR R5, [LR,#-4] /* Calculate address of SWI instruction and load it into r5. */
- BIC R5, R5,#0xff000000 /* Mask off top 8 bits of instruction to give SWI number. */
-
- CMP R5, #0
- BNE SVC_User /* User SVC Number > 0 */
- MOV LR, PC /* set LR to return address */
- BX R12 /* Call SVC Function */
-
- LDMFD SP!, {R11} /* Load Task Stack Pointer */
- STMIB R11!, {R0-R3} /* Store return values to Task stack */
-
-SVC_Exit:
- B RestoreContext /* return to the task */
-
- /*------------------- User SVC ------------------------------*/
-
-SVC_User:
- LDR R6,=SVC_Count
- LDR R6,[R6]
- CMP R5,R6
- LDMFDHI SP!, {R11}
- BHI SVC_Done /* Overflow */
-
- LDR R4,=SVC_Table - 4
- LSLS R5,R5,#2
- LDR R4,[R4,R5] /* Load SVC Function Address */
- /* R0-R3,R12 are unchanged */
- MOV LR, PC /* set LR to return address */
- BX R4 /* Call SVC Function */
-
- LDMFD SP!, {R11} /* Load Task Stack Pointer */
- BEQ SVC_Exit /* no need in return values */
-
- STMIB R11!, {R0-R3} /* Store return values to Task stack */
-SVC_Done:
- B RestoreContext /* return to the task */
-
- .fnend
- .size SVC_Handler, .-SVC_Handler
-
-
-/*-------------------------- IRQ_Handler ---------------------------------*/
-
-# void IRQ_Handler (void);
-
- .type IRQ_Handler, %function
- .global IRQ_Handler
-IRQ_Handler:
- .fnstart
- .cantunwind
-
- SaveContext
-
- MOV R0, #0xFFFFFF00
- LDR R0, [R0] /* Load address of raised IRQ handler*/
-
- MOV LR, PC
- BX R0
-
- MOV R0, #0xFFFFFF00
- STR R0, [R0] /* Clear interrupt */
-
- B RestoreContext
-
- .fnend
- .size IRQ_Handler, .-IRQ_Handler
-
-/*-------------------------- SysTick_Handler --------------------------------*/
-
-# void SysTick_Handler (void);
-
- .type SysTick_Handler, %function
- .global SysTick_Handler
-SysTick_Handler:
- .fnstart
- .cantunwind
-
- PUSH {LR}
- BL rt_systick
- POP {LR}
- BX LR /* return to IRQ handler */
-
-/*-------------------------- End --------------------------------*/
- .fnend
- .size SysTick_Handler, .-SysTick_Handler
-
-
-/*----------------------------------------------------------------------------
- * end of file
- *---------------------------------------------------------------------------*/
-
-.end
\ No newline at end of file
diff --git a/rtos/rtx/TARGET_ARM7/ARM7/TOOLCHAIN_GCC/SVC_Table.S b/rtos/rtx/TARGET_ARM7/ARM7/TOOLCHAIN_GCC/SVC_Table.S
deleted file mode 100644
index 1942f4c81f..0000000000
--- a/rtos/rtx/TARGET_ARM7/ARM7/TOOLCHAIN_GCC/SVC_Table.S
+++ /dev/null
@@ -1,56 +0,0 @@
-;/*----------------------------------------------------------------------------
-; * RL-ARM - RTX
-; *----------------------------------------------------------------------------
-; * Name: SVC_TABLE.S
-; * Purpose: Pre-defined SVC Table for Cortex-M
-; * Rev.: V4.60
-; *----------------------------------------------------------------------------
-; *
-; * Copyright (c) 1999-2009 KEIL, 2009-2015 ARM Germany GmbH
-; * All rights reserved.
-; * Redistribution and use in source and binary forms, with or without
-; * modification, are permitted provided that the following conditions are met:
-; * - Redistributions of source code must retain the above copyright
-; * notice, this list of conditions and the following disclaimer.
-; * - 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.
-; * - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
-; *---------------------------------------------------------------------------*/
-
-
- .file "SVC_Table.S"
-
-
- .section ".svc_table"
-
- .global SVC_Table
-SVC_Table:
-/* Insert user SVC functions here. SVC 0 used by RTL Kernel. */
-# .long __SVC_1 /* user SVC function */
-SVC_End:
-
- .global SVC_Count
-SVC_Count:
- .long (SVC_End-SVC_Table)/4
-
-
- .end
-
-/*----------------------------------------------------------------------------
- * end of file
- *---------------------------------------------------------------------------*/
diff --git a/rtos/rtx/TARGET_ARM7/HAL_CM.c b/rtos/rtx/TARGET_ARM7/HAL_CM.c
deleted file mode 100644
index 071fd73d83..0000000000
--- a/rtos/rtx/TARGET_ARM7/HAL_CM.c
+++ /dev/null
@@ -1,161 +0,0 @@
-/*----------------------------------------------------------------------------
- * RL-ARM - RTX
- *----------------------------------------------------------------------------
- * Name: HAL_CM.C
- * Purpose: Hardware Abstraction Layer for ARM7TDMI
- * Rev.: V1.0
- *----------------------------------------------------------------------------
- *
- * Copyright (c) 1999-2009 KEIL, 2009-2015 ARM Germany GmbH
- * All rights reserved.
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- * - Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * - 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.
- * - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
- *---------------------------------------------------------------------------*/
-
-#include "rt_TypeDef.h"
-#include "RTX_Conf.h"
-#include "rt_HAL_CM.h"
-
-
-/*----------------------------------------------------------------------------
- * Global Variables
- *---------------------------------------------------------------------------*/
-
-#ifdef DBG_MSG
-BIT dbg_msg;
-#endif
-
-/*----------------------------------------------------------------------------
- * Functions
- *---------------------------------------------------------------------------*/
-
-
-/*--------------------------- rt_init_stack ---------------------------------*/
-
-void rt_init_stack (P_TCB p_TCB, FUNCP task_body) {
- /* Prepare TCB and saved context for a first time start of a task. */
- U32 *stk,i,size;
-
- /* Prepare a complete interrupt frame for first task start */
- size = p_TCB->priv_stack >> 2;
-
- /* Write to the top of stack. */
- stk = &p_TCB->stack[size];
-
- /* Auto correct to 8-byte ARM stack alignment. */
- if ((U32)stk & 0x04) {
- stk--;
- }
-
- stk -= 16;
-
- /* Default xPSR and initial PC */
- stk[15] = (U32)task_body + 4; /* add 4 byte offset because SUB PC, LR - 4 */
- stk[0] = INITIAL_xPSR;
-
- /* Clear R0-R13/LR registers. */
- for (i = 1; i < 14; i++) {
- stk[i] = 0;
- }
-
- /* Assign a void pointer to R0. */
- stk[TCB_STACK_R0_OFFSET_DWORDS] = (U32)p_TCB->msg;
-
- /* Initial Task stack pointer. */
- p_TCB->tsk_stack = (U32)stk;
-
- /* Task entry point. */
- p_TCB->ptask = task_body;
-
- /* Set a magic word for checking of stack overflow.
- For the main thread (ID: 0x01) the stack is in a memory area shared with the
- heap, therefore the last word of the stack is a moving target.
- We want to do stack/heap collision detection instead.
- */
- if (p_TCB->task_id != 0x01)
- p_TCB->stack[0] = MAGIC_WORD;
-}
-
-
-/*--------------------------- rt_ret_val ----------------------------------*/
-
-static __inline U32 *rt_ret_regs (P_TCB p_TCB) {
- /* Get pointer to task return value registers (R0..R3) in Stack */
-
- /* Stack Frame: CPSR,R0-R13,PC */
- return (U32 *)(p_TCB->tsk_stack + TCB_STACK_R0_OFFSET_BYTES);
-}
-
-void rt_ret_val (P_TCB p_TCB, U32 v0) {
- U32 *ret;
-
- ret = rt_ret_regs(p_TCB);
- ret[0] = v0;
-}
-
-void rt_ret_val2(P_TCB p_TCB, U32 v0, U32 v1) {
- U32 *ret;
-
- ret = rt_ret_regs(p_TCB);
- ret[0] = v0;
- ret[1] = v1;
-}
-
-
-/*--------------------------- dbg_init --------------------------------------*/
-
-#ifdef DBG_MSG
-void dbg_init (void) {
- if ((DEMCR & DEMCR_TRCENA) &&
- (ITM_CONTROL & ITM_ITMENA) &&
- (ITM_ENABLE & (1UL << 31))) {
- dbg_msg = __TRUE;
- }
-}
-#endif
-
-/*--------------------------- dbg_task_notify -------------------------------*/
-
-#ifdef DBG_MSG
-void dbg_task_notify (P_TCB p_tcb, BOOL create) {
- while (ITM_PORT31_U32 == 0);
- ITM_PORT31_U32 = (U32)p_tcb->ptask;
- while (ITM_PORT31_U32 == 0);
- ITM_PORT31_U16 = (create << 8) | p_tcb->task_id;
-}
-#endif
-
-/*--------------------------- dbg_task_switch -------------------------------*/
-
-#ifdef DBG_MSG
-void dbg_task_switch (U32 task_id) {
- while (ITM_PORT31_U32 == 0);
- ITM_PORT31_U8 = task_id;
-}
-#endif
-
-
-/*----------------------------------------------------------------------------
- * end of file
- *---------------------------------------------------------------------------*/
-
diff --git a/rtos/rtx/TARGET_ARM7/RTX_CM_lib.h b/rtos/rtx/TARGET_ARM7/RTX_CM_lib.h
deleted file mode 100755
index 3cde4b76d9..0000000000
--- a/rtos/rtx/TARGET_ARM7/RTX_CM_lib.h
+++ /dev/null
@@ -1,401 +0,0 @@
-/*----------------------------------------------------------------------------
- * RL-ARM - RTX
- *----------------------------------------------------------------------------
- * Name: RTX_CM_LIB.H
- * Purpose: RTX Kernel System Configuration
- * Rev.: V4.60
- *----------------------------------------------------------------------------
- *
- * Copyright (c) 1999-2009 KEIL, 2009-2015 ARM Germany GmbH
- * All rights reserved.
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- * - Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * - 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.
- * - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
- *---------------------------------------------------------------------------*/
-#include "mbed_error.h"
-
-#if defined (__CC_ARM)
-#pragma O3
-#define __USED __attribute__((used))
-#elif defined (__GNUC__)
-#pragma GCC optimize ("O3")
-#define __USED __attribute__((used))
-#elif defined (__ICCARM__)
-#define __USED __root
-#endif
-
-
-/*----------------------------------------------------------------------------
- * Definitions
- *---------------------------------------------------------------------------*/
-
-#define _declare_box(pool,size,cnt) uint32_t pool[(((size)+3)/4)*(cnt) + 3]
-#define _declare_box8(pool,size,cnt) uint64_t pool[(((size)+7)/8)*(cnt) + 2]
-
-#define OS_TCB_SIZE 48
-#define OS_TMR_SIZE 8
-
-#if defined (__CC_ARM) && !defined (__MICROLIB)
-
-typedef void *OS_ID;
-typedef uint32_t OS_TID;
-typedef uint32_t OS_MUT[3];
-typedef uint32_t OS_RESULT;
-
-#define runtask_id() rt_tsk_self()
-#define mutex_init(m) rt_mut_init(m)
-#define mutex_wait(m) os_mut_wait(m,0xFFFF)
-#define mutex_rel(m) os_mut_release(m)
-
-extern OS_TID rt_tsk_self (void);
-extern void rt_mut_init (OS_ID mutex);
-extern OS_RESULT rt_mut_release (OS_ID mutex);
-extern OS_RESULT rt_mut_wait (OS_ID mutex, uint16_t timeout);
-
-#define os_mut_wait(mutex,timeout) _os_mut_wait((uint32_t)rt_mut_wait,mutex,timeout)
-#define os_mut_release(mutex) _os_mut_release((uint32_t)rt_mut_release,mutex)
-
-OS_RESULT _os_mut_release (uint32_t p, OS_ID mutex) __svc_indirect(0);
-OS_RESULT _os_mut_wait (uint32_t p, OS_ID mutex, uint16_t timeout) __svc_indirect(0);
-
-#endif
-
-
-/*----------------------------------------------------------------------------
- * Global Variables
- *---------------------------------------------------------------------------*/
-
-#if (OS_TIMERS != 0)
-#define OS_TASK_CNT (OS_TASKCNT + 1)
-#else
-#define OS_TASK_CNT OS_TASKCNT
-#endif
-
-uint16_t const os_maxtaskrun = OS_TASK_CNT;
-uint32_t const os_rrobin = (OS_ROBIN << 16) | OS_ROBINTOUT;
-uint32_t const os_trv = OS_TRV;
-uint8_t const os_flags = OS_RUNPRIV;
-
-/* Export following defines to uVision debugger. */
-__USED uint32_t const os_clockrate = OS_TICK;
-__USED uint32_t const os_timernum = 0;
-
-/* Stack for the os_idle_demon */
-unsigned int idle_task_stack[OS_IDLESTKSIZE];
-unsigned short const idle_task_stack_size = OS_IDLESTKSIZE;
-
-#ifndef OS_FIFOSZ
- #define OS_FIFOSZ 16
-#endif
-
-/* Fifo Queue buffer for ISR requests.*/
-uint32_t os_fifo[OS_FIFOSZ*2+1];
-uint8_t const os_fifo_size = OS_FIFOSZ;
-
-/* An array of Active task pointers. */
-void *os_active_TCB[OS_TASK_CNT];
-
-/* User Timers Resources */
-#if (OS_TIMERS != 0)
-extern void osTimerThread (void const *argument);
-osThreadDef(osTimerThread, (osPriority)(OS_TIMERPRIO-3), 4*OS_TIMERSTKSZ);
-osThreadId osThreadId_osTimerThread;
-osMessageQDef(osTimerMessageQ, OS_TIMERCBQS, void *);
-osMessageQId osMessageQId_osTimerMessageQ;
-#else
-osThreadDef_t os_thread_def_osTimerThread = { NULL };
-osThreadId osThreadId_osTimerThread;
-osMessageQDef(osTimerMessageQ, 0, void *);
-osMessageQId osMessageQId_osTimerMessageQ;
-#endif
-
-
-/*----------------------------------------------------------------------------
- * RTX Optimizations (empty functions)
- *---------------------------------------------------------------------------*/
-
-#if OS_ROBIN == 0
- void rt_init_robin (void) {;}
- void rt_chk_robin (void) {;}
-#endif
-
-#if OS_STKCHECK == 0
- void rt_stk_check (void) {;}
-#endif
-
-
-/*----------------------------------------------------------------------------
- * Standard Library multithreading interface
- *---------------------------------------------------------------------------*/
-
-#if defined (__CC_ARM) && !defined (__MICROLIB)
- static OS_MUT std_libmutex[OS_MUTEXCNT];
- static uint32_t nr_mutex;
-
- /*--------------------------- _mutex_initialize -----------------------------*/
-
-int _mutex_initialize (OS_ID *mutex) {
- /* Allocate and initialize a system mutex. */
-
- if (nr_mutex >= OS_MUTEXCNT) {
- /* If you are here, you need to increase the number OS_MUTEXCNT. */
- error("Not enough stdlib mutexes\n");
- }
- *mutex = &std_libmutex[nr_mutex++];
- mutex_init (*mutex);
- return (1);
-}
-
-
-/*--------------------------- _mutex_acquire --------------------------------*/
-
-__attribute__((used)) void _mutex_acquire (OS_ID *mutex) {
- /* Acquire a system mutex, lock stdlib resources. */
- if (runtask_id ()) {
- /* RTX running, acquire a mutex. */
- mutex_wait (*mutex);
- }
-}
-
-
-/*--------------------------- _mutex_release --------------------------------*/
-
-__attribute__((used)) void _mutex_release (OS_ID *mutex) {
- /* Release a system mutex, unlock stdlib resources. */
- if (runtask_id ()) {
- /* RTX running, release a mutex. */
- mutex_rel (*mutex);
- }
-}
-
-#endif
-
-
-/*----------------------------------------------------------------------------
- * RTX Startup
- *---------------------------------------------------------------------------*/
-
-/* Main Thread definition */
-extern void pre_main (void);
-osThreadDef_t os_thread_def_main = {(os_pthread)pre_main, osPriorityNormal, 0, NULL};
-
-#ifndef INITIAL_SP
- #error "no target defined"
-#endif
-
-#ifdef __CC_ARM
-extern unsigned char Image$$RW_IRAM1$$ZI$$Limit[];
-#define HEAP_START (Image$$RW_IRAM1$$ZI$$Limit)
-#elif defined(__GNUC__)
-extern unsigned char __end__[];
-#define HEAP_START (__end__)
-#elif defined(__ICCARM__)
-#pragma section="HEAP"
-#define HEAP_START (void *)__section_begin("HEAP")
-#endif
-
-void set_main_stack(void) {
- // That is the bottom of the main stack block: no collision detection
- os_thread_def_main.stack_pointer = HEAP_START;
-
- // Leave OS_SCHEDULERSTKSIZE words for the scheduler and interrupts
- os_thread_def_main.stacksize = (INITIAL_SP - (unsigned int)HEAP_START) - (OS_SCHEDULERSTKSIZE * 4);
-}
-
-#if defined (__CC_ARM)
-#ifdef __MICROLIB
-
-int main(void);
-void _main_init (void) __attribute__((section(".ARM.Collect$$$$000000FF")));
-void $Super$$__cpp_initialize__aeabi_(void);
-
-void _main_init (void) {
- osKernelInitialize();
- set_main_stack();
- osThreadCreate(&os_thread_def_main, NULL);
- osKernelStart();
- for (;;);
-}
-
-void $Sub$$__cpp_initialize__aeabi_(void)
-{
- // this should invoke C++ initializers prior _main_init, we keep this empty and
- // invoke them after _main_init (=starts RTX kernel)
-}
-
-void pre_main()
-{
- $Super$$__cpp_initialize__aeabi_();
- main();
-}
-
-#else
-
-void * armcc_heap_base;
-void * armcc_heap_top;
-
-__asm void pre_main (void)
-{
- IMPORT __rt_lib_init
- IMPORT main
- IMPORT armcc_heap_base
- IMPORT armcc_heap_top
-
- LDR R0,=armcc_heap_base
- LDR R1,=armcc_heap_top
- LDR R0,[R0]
- LDR R1,[R1]
- /* Save link register (keep 8 byte alignment with dummy R4) */
- PUSH {R4, LR}
- BL __rt_lib_init
- BL main
- /* Return to the thread destroy function.
- */
- POP {R4, PC}
- ALIGN
-}
-
-/* The single memory model is checking for stack collision at run time, verifing
- that the heap pointer is underneath the stack pointer.
-
- With the RTOS there is not only one stack above the heap, there are multiple
- stacks and some of them are underneath the heap pointer.
-*/
-#pragma import(__use_two_region_memory)
-
-__asm void __rt_entry (void) {
-
- IMPORT __user_setup_stackheap
- IMPORT armcc_heap_base
- IMPORT armcc_heap_top
- IMPORT os_thread_def_main
- IMPORT osKernelInitialize
- IMPORT set_main_stack
- IMPORT osKernelStart
- IMPORT osThreadCreate
-
- /* __user_setup_stackheap returns:
- * - Heap base in r0 (if the program uses the heap).
- * - Stack base in sp.
- * - Heap limit in r2 (if the program uses the heap and uses two-region memory).
- *
- * More info can be found in:
- * ARM Compiler ARM C and C++ Libraries and Floating-Point Support User Guide
- */
- BL __user_setup_stackheap
- LDR R3,=armcc_heap_base
- LDR R4,=armcc_heap_top
- STR R0,[R3]
- STR R2,[R4]
- BL osKernelInitialize
- BL set_main_stack
- LDR R0,=os_thread_def_main
- MOVS R1,#0
- BL osThreadCreate
- BL osKernelStart
- /* osKernelStart should not return */
- B .
-
- ALIGN
-}
-
-#endif
-
-#elif defined (__GNUC__)
-
-extern int atexit(void (*func)(void));
-extern void __libc_fini_array(void);
-extern void __libc_init_array (void);
-extern int main(int argc, char **argv);
-
-void pre_main(void) {
- atexit(__libc_fini_array);
- __libc_init_array();
- main(0, NULL);
-}
-
-__attribute__((naked)) void software_init_hook_rtos (void) {
- __asm (
- ".syntax unified\n"
- ".thumb\n"
- "bl osKernelInitialize\n"
- "bl set_main_stack\n"
- "ldr r0,=os_thread_def_main\n"
- "movs r1,#0\n"
- "bl osThreadCreate\n"
- "bl osKernelStart\n"
- /* osKernelStart should not return */
- "B .\n"
- );
-}
-
-#elif defined (__ICCARM__)
-
-extern void* __vector_table;
-extern int __low_level_init(void);
-extern void __iar_data_init3(void);
-extern __weak void __iar_init_core( void );
-extern __weak void __iar_init_vfp( void );
-extern void __iar_dynamic_initialization(void);
-extern void mbed_sdk_init(void);
-extern void exit(int arg);
-
-static uint8_t low_level_init_needed;
-
-void pre_main(void) {
- if (low_level_init_needed) {
- __iar_dynamic_initialization();
- }
- main();
-}
-
-#pragma required=__vector_table
-void __iar_program_start( void )
-{
- __iar_init_core();
- __iar_init_vfp();
-
- uint8_t low_level_init_needed_local;
-
- low_level_init_needed_local = __low_level_init();
- if (low_level_init_needed_local) {
- __iar_data_init3();
- mbed_sdk_init();
- }
- /* Store in a global variable after RAM has been initialized */
- low_level_init_needed = low_level_init_needed_local;
- osKernelInitialize();
- set_main_stack();
- osThreadCreate(&os_thread_def_main, NULL);
- osKernelStart();
- /* osKernelStart should not return */
- while (1);
-}
-
-#endif
-
-
-/*----------------------------------------------------------------------------
- * end of file
- *---------------------------------------------------------------------------*/
-
-
diff --git a/rtos/rtx/TARGET_ARM7/RTX_Conf.h b/rtos/rtx/TARGET_ARM7/RTX_Conf.h
deleted file mode 100644
index babf9c1a53..0000000000
--- a/rtos/rtx/TARGET_ARM7/RTX_Conf.h
+++ /dev/null
@@ -1,72 +0,0 @@
-/*----------------------------------------------------------------------------
- * RL-ARM - RTX
- *----------------------------------------------------------------------------
- * Name: RTX_CONFIG.H
- * Purpose: Exported functions of RTX_Config.c
- * Rev.: V4.60
- *----------------------------------------------------------------------------
- *
- * Copyright (c) 1999-2009 KEIL, 2009-2015 ARM Germany GmbH
- * All rights reserved.
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- * - Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * - 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.
- * - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
- *---------------------------------------------------------------------------*/
-
-
-/* Error Codes */
-#define OS_ERR_STK_OVF 1
-#define OS_ERR_FIFO_OVF 2
-#define OS_ERR_MBX_OVF 3
-
-/* Definitions */
-#define BOX_ALIGN_8 0x80000000
-#define _declare_box(pool,size,cnt) U32 pool[(((size)+3)/4)*(cnt) + 3]
-#define _declare_box8(pool,size,cnt) U64 pool[(((size)+7)/8)*(cnt) + 2]
-#define _init_box8(pool,size,bsize) _init_box (pool,size,(bsize) | BOX_ALIGN_8)
-
-/* Variables */
-extern U32 idle_task_stack[];
-extern U32 os_fifo[];
-extern void *os_active_TCB[];
-
-/* Constants */
-extern U16 const os_maxtaskrun;
-extern U32 const os_trv;
-extern U8 const os_flags;
-extern U32 const os_rrobin;
-extern U32 const os_clockrate;
-extern U32 const os_timernum;
-extern U16 const idle_task_stack_size;
-
-extern U8 const os_fifo_size;
-
-/* Functions */
-extern void os_idle_demon (void);
-extern int os_tick_init (void);
-extern void os_tick_irqack (void);
-extern void os_tmr_call (U16 info);
-extern void os_error (U32 err_code);
-
-/*----------------------------------------------------------------------------
- * end of file
- *---------------------------------------------------------------------------*/
diff --git a/rtos/rtx/TARGET_ARM7/RTX_Conf_CM.c b/rtos/rtx/TARGET_ARM7/RTX_Conf_CM.c
deleted file mode 100755
index 0e481f3d8e..0000000000
--- a/rtos/rtx/TARGET_ARM7/RTX_Conf_CM.c
+++ /dev/null
@@ -1,228 +0,0 @@
-/*----------------------------------------------------------------------------
- * RL-ARM - RTX
- *----------------------------------------------------------------------------
- * Name: RTX_Conf_CM.C
- * Purpose: Configuration of CMSIS RTX Kernel for ARM7TDMI
- * Rev.: V1.0
- *----------------------------------------------------------------------------
- *
- * Copyright (c) 1999-2009 KEIL, 2009-2015 ARM Germany GmbH
- * All rights reserved.
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- * - Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * - 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.
- * - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
- *---------------------------------------------------------------------------*/
-
-#include "cmsis_os.h"
-
-
-/*----------------------------------------------------------------------------
- * RTX User configuration part BEGIN
- *---------------------------------------------------------------------------*/
-
-// Include per-target RTX config file
-#include "mbed_rtx.h"
-
-//-------- <<< Use Configuration Wizard in Context Menu >>> -----------------
-//
-// Thread Configuration
-// =======================
-//
-// Number of concurrent running threads <0-250>
-// Defines max. number of threads that will run at the same time.
-// counting "main", but not counting "osTimerThread"
-// Default: 6
-#ifndef OS_TASKCNT
- #error "no target defined"
-#endif
-
-// Scheduler (+ interrupts) stack size [bytes] <64-4096:8><#/4>
-#ifndef OS_SCHEDULERSTKSIZE
- #error "no target defined"
-#endif
-
-// Idle stack size [bytes] <64-4096:8><#/4>
-// Defines default stack size for the Idle thread.
-#ifndef OS_IDLESTKSIZE
- #define OS_IDLESTKSIZE 136
-#endif
-
-// Timer Thread stack size [bytes] <64-4096:8><#/4>
-// Defines stack size for Timer thread.
-// Default: 200
-#ifndef OS_TIMERSTKSZ
- #define OS_TIMERSTKSZ WORDS_STACK_SIZE
-#endif
-
-// Check for stack overflow
-// Includes the stack checking code for stack overflow.
-// Note that additional code reduces the Kernel performance.
-#ifndef OS_STKCHECK
- #define OS_STKCHECK 1
-#endif
-
-// Processor mode for thread execution
-// <0=> Unprivileged mode
-// <1=> Privileged mode
-// Default: Privileged mode
-#ifndef OS_RUNPRIV
- #define OS_RUNPRIV 1
-#endif
-
-//
-// SysTick Timer Configuration
-// ==============================
-//
-// Timer clock value [Hz] <1-1000000000>
-// Defines the timer clock value.
-// Default: 6000000 (6MHz)
-#ifndef OS_CLOCK
- #error "no target defined"
-#endif
-
-// Timer tick value [us] <1-1000000>
-// Defines the timer tick value.
-// Default: 1000 (1ms)
-#ifndef OS_TICK
- #define OS_TICK 1000
-#endif
-
-//
-
-// System Configuration
-// =======================
-//
-// Round-Robin Thread switching
-// ===============================
-//
-// Enables Round-Robin Thread switching.
-#ifndef OS_ROBIN
- #define OS_ROBIN 1
-#endif
-
-// Round-Robin Timeout [ticks] <1-1000>
-// Defines how long a thread will execute before a thread switch.
-// Default: 5
-#ifndef OS_ROBINTOUT
- #define OS_ROBINTOUT 5
-#endif
-
-//
-
-// User Timers
-// ==============
-// Enables user Timers
-#ifndef OS_TIMERS
- #define OS_TIMERS 1
-#endif
-
-// Timer Thread Priority
-// <1=> Low
-// <2=> Below Normal
-// <3=> Normal
-// <4=> Above Normal
-// <5=> High
-// <6=> Realtime (highest)
-// Defines priority for Timer Thread
-// Default: High
-#ifndef OS_TIMERPRIO
- #define OS_TIMERPRIO 5
-#endif
-
-// Timer Callback Queue size <1-32>
-// Number of concurrent active timer callback functions.
-// Default: 4
-#ifndef OS_TIMERCBQSZ
- #define OS_TIMERCBQS 4
-#endif
-
-//
-
-// ISR FIFO Queue size<4=> 4 entries <8=> 8 entries
-// <12=> 12 entries <16=> 16 entries
-// <24=> 24 entries <32=> 32 entries
-// <48=> 48 entries <64=> 64 entries
-// <96=> 96 entries
-// ISR functions store requests to this buffer,
-// when they are called from the interrupt handler.
-// Default: 16 entries
-#ifndef OS_FIFOSZ
- #define OS_FIFOSZ 16
-#endif
-
-//
-
-//------------- <<< end of configuration section >>> -----------------------
-
-// Standard library system mutexes
-// ===============================
-// Define max. number system mutexes that are used to protect
-// the arm standard runtime library. For microlib they are not used.
-#ifndef OS_MUTEXCNT
- #define OS_MUTEXCNT 12
-#endif
-
-/*----------------------------------------------------------------------------
- * RTX User configuration part END
- *---------------------------------------------------------------------------*/
-
-#define OS_TRV ((uint32_t)(((double)OS_CLOCK*(double)OS_TICK)/1E6)-1)
-
-
-/*----------------------------------------------------------------------------
- * OS Idle daemon
- *---------------------------------------------------------------------------*/
-extern void rtos_idle_loop(void);
-
-void os_idle_demon (void) {
- /* The idle demon is a system thread, running when no other thread is */
- /* ready to run. */
- rtos_idle_loop();
-}
-
-/*----------------------------------------------------------------------------
- * RTX Errors
- *---------------------------------------------------------------------------*/
-extern void mbed_die(void);
-
-void os_error (uint32_t err_code) {
- /* This function is called when a runtime error is detected. Parameter */
- /* 'err_code' holds the runtime error code (defined in RTX_Conf.h). */
- mbed_die();
-}
-
-void sysThreadError(osStatus status) {
- if (status != osOK) {
- mbed_die();
- }
-}
-
-/*----------------------------------------------------------------------------
- * RTX Configuration Functions
- *---------------------------------------------------------------------------*/
-
-#include "RTX_CM_lib.h"
-
-/*----------------------------------------------------------------------------
- * end of file
- *---------------------------------------------------------------------------*/
-
diff --git a/rtos/rtx/TARGET_ARM7/cmsis_os.h b/rtos/rtx/TARGET_ARM7/cmsis_os.h
deleted file mode 100644
index 9bfa1535cb..0000000000
--- a/rtos/rtx/TARGET_ARM7/cmsis_os.h
+++ /dev/null
@@ -1,774 +0,0 @@
-/* ----------------------------------------------------------------------
- * Copyright (C) 2015 ARM Limited. All rights reserved.
- *
- * $Date: 5. June 2012
- * $Revision: V1.01
- *
- * Project: CMSIS-RTOS API
- * Title: cmsis_os.h RTX header file
- *
- * Version 0.02
- * Initial Proposal Phase
- * Version 0.03
- * osKernelStart added, optional feature: main started as thread
- * osSemaphores have standard behavior
- * osTimerCreate does not start the timer, added osTimerStart
- * osThreadPass is renamed to osThreadYield
- * Version 1.01
- * Support for C++ interface
- * - const attribute removed from the osXxxxDef_t typedef's
- * - const attribute added to the osXxxxDef macros
- * Added: osTimerDelete, osMutexDelete, osSemaphoreDelete
- * Added: osKernelInitialize
- * -------------------------------------------------------------------- */
-
-/**
-\page cmsis_os_h Header File Template: cmsis_os.h
-
-The file \b cmsis_os.h is a template header file for a CMSIS-RTOS compliant Real-Time Operating System (RTOS).
-Each RTOS that is compliant with CMSIS-RTOS shall provide a specific \b cmsis_os.h header file that represents
-its implementation.
-
-The file cmsis_os.h contains:
- - CMSIS-RTOS API function definitions
- - struct definitions for parameters and return types
- - status and priority values used by CMSIS-RTOS API functions
- - macros for defining threads and other kernel objects
-
-
-Name conventions and header file modifications
-
-All definitions are prefixed with \b os to give an unique name space for CMSIS-RTOS functions.
-Definitions that are prefixed \b os_ are not used in the application code but local to this header file.
-All definitions and functions that belong to a module are grouped and have a common prefix, i.e. \b osThread.
-
-Definitions that are marked with CAN BE CHANGED can be adapted towards the needs of the actual CMSIS-RTOS implementation.
-These definitions can be specific to the underlying RTOS kernel.
-
-Definitions that are marked with MUST REMAIN UNCHANGED cannot be altered. Otherwise the CMSIS-RTOS implementation is no longer
-compliant to the standard. Note that some functions are optional and need not to be provided by every CMSIS-RTOS implementation.
-
-
-Function calls from interrupt service routines
-
-The following CMSIS-RTOS functions can be called from threads and interrupt service routines (ISR):
- - \ref osSignalSet
- - \ref osSemaphoreRelease
- - \ref osPoolAlloc, \ref osPoolCAlloc, \ref osPoolFree
- - \ref osMessagePut, \ref osMessageGet
- - \ref osMailAlloc, \ref osMailCAlloc, \ref osMailGet, \ref osMailPut, \ref osMailFree
-
-Functions that cannot be called from an ISR are verifying the interrupt status and return in case that they are called
-from an ISR context the status code \b osErrorISR. In some implementations this condition might be caught using the HARD FAULT vector.
-
-Some CMSIS-RTOS implementations support CMSIS-RTOS function calls from multiple ISR at the same time.
-If this is impossible, the CMSIS-RTOS rejects calls by nested ISR functions with the status code \b osErrorISRRecursive.
-
-
-Define and reference object definitions
-
-With \#define osObjectsExternal objects are defined as external symbols. This allows to create a consistent header file
-that is used throughout a project as shown below:
-
-Header File
-\code
-#include // CMSIS RTOS header file
-
-// Thread definition
-extern void thread_sample (void const *argument); // function prototype
-osThreadDef (thread_sample, osPriorityBelowNormal, 1, 100);
-
-// Pool definition
-osPoolDef(MyPool, 10, long);
-\endcode
-
-
-This header file defines all objects when included in a C/C++ source file. When \#define osObjectsExternal is
-present before the header file, the objects are defined as external symbols. A single consistent header file can therefore be
-used throughout the whole project.
-
-Example
-\code
-#include "osObjects.h" // Definition of the CMSIS-RTOS objects
-\endcode
-
-\code
-#define osObjectExternal // Objects will be defined as external symbols
-#include "osObjects.h" // Reference to the CMSIS-RTOS objects
-\endcode
-
-*/
-
-#ifndef _CMSIS_OS_H
-#define _CMSIS_OS_H
-
-/// \note MUST REMAIN UNCHANGED: \b osCMSIS identifies the CMSIS-RTOS API version.
-#define osCMSIS 0x10001 ///< API version (main [31:16] .sub [15:0])
-
-/// \note CAN BE CHANGED: \b osCMSIS_KERNEL identifies the underlying RTOS kernel and version number.
-#define osCMSIS_RTX ((4<<16)|61) ///< RTOS identification and version (main [31:16] .sub [15:0])
-
-/// \note MUST REMAIN UNCHANGED: \b osKernelSystemId shall be consistent in every CMSIS-RTOS.
-#define osKernelSystemId "RTX V4.61" ///< RTOS identification string
-
-
-#define CMSIS_OS_RTX
-
-// The stack space occupied is mainly dependent on the underling C standard library
-#if defined(TOOLCHAIN_GCC) || defined(TOOLCHAIN_ARM_STD) || defined(TOOLCHAIN_IAR)
-# define WORDS_STACK_SIZE 512
-#elif defined(TOOLCHAIN_ARM_MICRO)
-# define WORDS_STACK_SIZE 128
-#endif
-
-#define DEFAULT_STACK_SIZE (WORDS_STACK_SIZE*4)
-
-
-/// \note MUST REMAIN UNCHANGED: \b osFeature_xxx shall be consistent in every CMSIS-RTOS.
-#define osFeature_MainThread 1 ///< main thread 1=main can be thread, 0=not available
-#define osFeature_Pool 1 ///< Memory Pools: 1=available, 0=not available
-#define osFeature_MailQ 1 ///< Mail Queues: 1=available, 0=not available
-#define osFeature_MessageQ 1 ///< Message Queues: 1=available, 0=not available
-#define osFeature_Signals 16 ///< maximum number of Signal Flags available per thread
-#define osFeature_Semaphore 65535 ///< maximum count for \ref osSemaphoreCreate function
-#define osFeature_Wait 0 ///< osWait function: 1=available, 0=not available
-
-#if defined (__CC_ARM)
-#define os_InRegs __value_in_regs // Compiler specific: force struct in registers
-#elif defined (__ICCARM__)
-#define os_InRegs __value_in_regs // Compiler specific: force struct in registers
-#else
-#define os_InRegs
-#endif
-
-#include
-#include
-
-#ifdef __cplusplus
-extern "C"
-{
-#endif
-
-#include "os_tcb.h"
-
-// ==== Enumeration, structures, defines ====
-
-/// Priority used for thread control.
-/// \note MUST REMAIN UNCHANGED: \b osPriority shall be consistent in every CMSIS-RTOS.
-typedef enum {
- osPriorityIdle = -3, ///< priority: idle (lowest)
- osPriorityLow = -2, ///< priority: low
- osPriorityBelowNormal = -1, ///< priority: below normal
- osPriorityNormal = 0, ///< priority: normal (default)
- osPriorityAboveNormal = +1, ///< priority: above normal
- osPriorityHigh = +2, ///< priority: high
- osPriorityRealtime = +3, ///< priority: realtime (highest)
- osPriorityError = 0x84 ///< system cannot determine priority or thread has illegal priority
-} osPriority;
-
-/// Timeout value.
-/// \note MUST REMAIN UNCHANGED: \b osWaitForever shall be consistent in every CMSIS-RTOS.
-#define osWaitForever 0xFFFFFFFF ///< wait forever timeout value
-
-/// Status code values returned by CMSIS-RTOS functions.
-/// \note MUST REMAIN UNCHANGED: \b osStatus shall be consistent in every CMSIS-RTOS.
-typedef enum {
- osOK = 0, ///< function completed; no error or event occurred.
- osEventSignal = 0x08, ///< function completed; signal event occurred.
- osEventMessage = 0x10, ///< function completed; message event occurred.
- osEventMail = 0x20, ///< function completed; mail event occurred.
- osEventTimeout = 0x40, ///< function completed; timeout occurred.
- osErrorParameter = 0x80, ///< parameter error: a mandatory parameter was missing or specified an incorrect object.
- osErrorResource = 0x81, ///< resource not available: a specified resource was not available.
- osErrorTimeoutResource = 0xC1, ///< resource not available within given time: a specified resource was not available within the timeout period.
- osErrorISR = 0x82, ///< not allowed in ISR context: the function cannot be called from interrupt service routines.
- osErrorISRRecursive = 0x83, ///< function called multiple times from ISR with same object.
- osErrorPriority = 0x84, ///< system cannot determine priority or thread has illegal priority.
- osErrorNoMemory = 0x85, ///< system is out of memory: it was impossible to allocate or reserve memory for the operation.
- osErrorValue = 0x86, ///< value of a parameter is out of range.
- osErrorOS = 0xFF, ///< unspecified RTOS error: run-time error but no other error message fits.
- os_status_reserved = 0x7FFFFFFF ///< prevent from enum down-size compiler optimization.
-} osStatus;
-
-
-/// Timer type value for the timer definition.
-/// \note MUST REMAIN UNCHANGED: \b os_timer_type shall be consistent in every CMSIS-RTOS.
-typedef enum {
- osTimerOnce = 0, ///< one-shot timer
- osTimerPeriodic = 1 ///< repeating timer
-} os_timer_type;
-
-/// Entry point of a thread.
-/// \note MUST REMAIN UNCHANGED: \b os_pthread shall be consistent in every CMSIS-RTOS.
-typedef void (*os_pthread) (void const *argument);
-
-/// Entry point of a timer call back function.
-/// \note MUST REMAIN UNCHANGED: \b os_ptimer shall be consistent in every CMSIS-RTOS.
-typedef void (*os_ptimer) (void const *argument);
-
-// >>> the following data type definitions may shall adapted towards a specific RTOS
-
-/// Thread ID identifies the thread (pointer to a thread control block).
-/// \note CAN BE CHANGED: \b os_thread_cb is implementation specific in every CMSIS-RTOS.
-typedef struct os_thread_cb *osThreadId;
-
-/// Timer ID identifies the timer (pointer to a timer control block).
-/// \note CAN BE CHANGED: \b os_timer_cb is implementation specific in every CMSIS-RTOS.
-typedef struct os_timer_cb *osTimerId;
-
-/// Mutex ID identifies the mutex (pointer to a mutex control block).
-/// \note CAN BE CHANGED: \b os_mutex_cb is implementation specific in every CMSIS-RTOS.
-typedef struct os_mutex_cb *osMutexId;
-
-/// Semaphore ID identifies the semaphore (pointer to a semaphore control block).
-/// \note CAN BE CHANGED: \b os_semaphore_cb is implementation specific in every CMSIS-RTOS.
-typedef struct os_semaphore_cb *osSemaphoreId;
-
-/// Pool ID identifies the memory pool (pointer to a memory pool control block).
-/// \note CAN BE CHANGED: \b os_pool_cb is implementation specific in every CMSIS-RTOS.
-typedef struct os_pool_cb *osPoolId;
-
-/// Message ID identifies the message queue (pointer to a message queue control block).
-/// \note CAN BE CHANGED: \b os_messageQ_cb is implementation specific in every CMSIS-RTOS.
-typedef struct os_messageQ_cb *osMessageQId;
-
-/// Mail ID identifies the mail queue (pointer to a mail queue control block).
-/// \note CAN BE CHANGED: \b os_mailQ_cb is implementation specific in every CMSIS-RTOS.
-typedef struct os_mailQ_cb *osMailQId;
-
-
-/// Thread Definition structure contains startup information of a thread.
-/// \note CAN BE CHANGED: \b os_thread_def is implementation specific in every CMSIS-RTOS.
-typedef struct os_thread_def {
- os_pthread pthread; ///< start address of thread function
- osPriority tpriority; ///< initial thread priority
- uint32_t stacksize; ///< stack size requirements in bytes
- uint32_t *stack_pointer; ///< pointer to the stack memory block
- struct OS_TCB tcb;
-} osThreadDef_t;
-
-/// Timer Definition structure contains timer parameters.
-/// \note CAN BE CHANGED: \b os_timer_def is implementation specific in every CMSIS-RTOS.
-typedef struct os_timer_def {
- os_ptimer ptimer; ///< start address of a timer function
- void *timer; ///< pointer to internal data
-} osTimerDef_t;
-
-/// Mutex Definition structure contains setup information for a mutex.
-/// \note CAN BE CHANGED: \b os_mutex_def is implementation specific in every CMSIS-RTOS.
-typedef struct os_mutex_def {
- void *mutex; ///< pointer to internal data
-} osMutexDef_t;
-
-/// Semaphore Definition structure contains setup information for a semaphore.
-/// \note CAN BE CHANGED: \b os_semaphore_def is implementation specific in every CMSIS-RTOS.
-typedef struct os_semaphore_def {
- void *semaphore; ///< pointer to internal data
-} osSemaphoreDef_t;
-
-/// Definition structure for memory block allocation.
-/// \note CAN BE CHANGED: \b os_pool_def is implementation specific in every CMSIS-RTOS.
-typedef struct os_pool_def {
- uint32_t pool_sz; ///< number of items (elements) in the pool
- uint32_t item_sz; ///< size of an item
- void *pool; ///< pointer to memory for pool
-} osPoolDef_t;
-
-/// Definition structure for message queue.
-/// \note CAN BE CHANGED: \b os_messageQ_def is implementation specific in every CMSIS-RTOS.
-typedef struct os_messageQ_def {
- uint32_t queue_sz; ///< number of elements in the queue
- void *pool; ///< memory array for messages
-} osMessageQDef_t;
-
-/// Definition structure for mail queue.
-/// \note CAN BE CHANGED: \b os_mailQ_def is implementation specific in every CMSIS-RTOS.
-typedef struct os_mailQ_def {
- uint32_t queue_sz; ///< number of elements in the queue
- uint32_t item_sz; ///< size of an item
- void *pool; ///< memory array for mail
-} osMailQDef_t;
-
-/// Event structure contains detailed information about an event.
-/// \note MUST REMAIN UNCHANGED: \b os_event shall be consistent in every CMSIS-RTOS.
-/// However the struct may be extended at the end.
-typedef struct {
- osStatus status; ///< status code: event or error information
- union {
- uint32_t v; ///< message as 32-bit value
- void *p; ///< message or mail as void pointer
- int32_t signals; ///< signal flags
- } value; ///< event value
- union {
- osMailQId mail_id; ///< mail id obtained by \ref osMailCreate
- osMessageQId message_id; ///< message id obtained by \ref osMessageCreate
- } def; ///< event definition
-} osEvent;
-
-
-// ==== Kernel Control Functions ====
-
-/// Initialize the RTOS Kernel for creating objects.
-/// \return status code that indicates the execution status of the function.
-/// \note MUST REMAIN UNCHANGED: \b osKernelInitialize shall be consistent in every CMSIS-RTOS.
-osStatus osKernelInitialize (void);
-
-/// Start the RTOS Kernel.
-/// \return status code that indicates the execution status of the function.
-/// \note MUST REMAIN UNCHANGED: \b osKernelStart shall be consistent in every CMSIS-RTOS.
-osStatus osKernelStart (void);
-
-/// Check if the RTOS kernel is already started.
-/// \note MUST REMAIN UNCHANGED: \b osKernelRunning shall be consistent in every CMSIS-RTOS.
-/// \return 0 RTOS is not started, 1 RTOS is started.
-int32_t osKernelRunning(void);
-
-
-// ==== Thread Management ====
-
-/// Create a Thread Definition with function, priority, and stack requirements.
-/// \param name name of the thread function.
-/// \param priority initial priority of the thread function.
-/// \param stacksz stack size (in bytes) requirements for the thread function.
-/// \note CAN BE CHANGED: The parameters to \b osThreadDef shall be consistent but the
-/// macro body is implementation specific in every CMSIS-RTOS.
-#if defined (osObjectsExternal) // object is external
-#define osThreadDef(name, priority, stacksz) \
-extern osThreadDef_t os_thread_def_##name
-#else // define the object
-#define osThreadDef(name, priority, stacksz) \
-uint32_t os_thread_def_stack_##name [stacksz / sizeof(uint32_t)]; \
-osThreadDef_t os_thread_def_##name = \
-{ (name), (priority), (stacksz), (os_thread_def_stack_##name)}
-#endif
-
-/// Access a Thread definition.
-/// \param name name of the thread definition object.
-/// \note CAN BE CHANGED: The parameter to \b osThread shall be consistent but the
-/// macro body is implementation specific in every CMSIS-RTOS.
-#define osThread(name) \
-&os_thread_def_##name
-
-/// Create a thread and add it to Active Threads and set it to state READY.
-/// \param[in] thread_def thread definition referenced with \ref osThread.
-/// \param[in] argument pointer that is passed to the thread function as start argument.
-/// \return thread ID for reference by other functions or NULL in case of error.
-/// \note MUST REMAIN UNCHANGED: \b osThreadCreate shall be consistent in every CMSIS-RTOS.
-osThreadId osThreadCreate (osThreadDef_t *thread_def, void *argument);
-
-/// Return the thread ID of the current running thread.
-/// \return thread ID for reference by other functions or NULL in case of error.
-/// \note MUST REMAIN UNCHANGED: \b osThreadGetId shall be consistent in every CMSIS-RTOS.
-osThreadId osThreadGetId (void);
-
-/// Terminate execution of a thread and remove it from Active Threads.
-/// \param[in] thread_id thread ID obtained by \ref osThreadCreate or \ref osThreadGetId.
-/// \return status code that indicates the execution status of the function.
-/// \note MUST REMAIN UNCHANGED: \b osThreadTerminate shall be consistent in every CMSIS-RTOS.
-osStatus osThreadTerminate (osThreadId thread_id);
-
-/// Pass control to next thread that is in state \b READY.
-/// \return status code that indicates the execution status of the function.
-/// \note MUST REMAIN UNCHANGED: \b osThreadYield shall be consistent in every CMSIS-RTOS.
-osStatus osThreadYield (void);
-
-/// Change priority of an active thread.
-/// \param[in] thread_id thread ID obtained by \ref osThreadCreate or \ref osThreadGetId.
-/// \param[in] priority new priority value for the thread function.
-/// \return status code that indicates the execution status of the function.
-/// \note MUST REMAIN UNCHANGED: \b osThreadSetPriority shall be consistent in every CMSIS-RTOS.
-osStatus osThreadSetPriority (osThreadId thread_id, osPriority priority);
-
-/// Get current priority of an active thread.
-/// \param[in] thread_id thread ID obtained by \ref osThreadCreate or \ref osThreadGetId.
-/// \return current priority value of the thread function.
-/// \note MUST REMAIN UNCHANGED: \b osThreadGetPriority shall be consistent in every CMSIS-RTOS.
-osPriority osThreadGetPriority (osThreadId thread_id);
-
-
-// ==== Generic Wait Functions ====
-
-/// Wait for Timeout (Time Delay).
-/// \param[in] millisec time delay value
-/// \return status code that indicates the execution status of the function.
-osStatus osDelay (uint32_t millisec);
-
-#if (defined (osFeature_Wait) && (osFeature_Wait != 0)) // Generic Wait available
-
-/// Wait for Signal, Message, Mail, or Timeout.
-/// \param[in] millisec timeout value or 0 in case of no time-out
-/// \return event that contains signal, message, or mail information or error code.
-/// \note MUST REMAIN UNCHANGED: \b osWait shall be consistent in every CMSIS-RTOS.
-os_InRegs osEvent osWait (uint32_t millisec);
-
-#endif // Generic Wait available
-
-
-// ==== Timer Management Functions ====
-/// Define a Timer object.
-/// \param name name of the timer object.
-/// \param function name of the timer call back function.
-/// \note CAN BE CHANGED: The parameter to \b osTimerDef shall be consistent but the
-/// macro body is implementation specific in every CMSIS-RTOS.
-#if defined (osObjectsExternal) // object is external
-#define osTimerDef(name, function) \
-extern osTimerDef_t os_timer_def_##name
-#else // define the object
-#define osTimerDef(name, function) \
-uint32_t os_timer_cb_##name[5]; \
-osTimerDef_t os_timer_def_##name = \
-{ (function), (os_timer_cb_##name) }
-#endif
-
-/// Access a Timer definition.
-/// \param name name of the timer object.
-/// \note CAN BE CHANGED: The parameter to \b osTimer shall be consistent but the
-/// macro body is implementation specific in every CMSIS-RTOS.
-#define osTimer(name) \
-&os_timer_def_##name
-
-/// Create a timer.
-/// \param[in] timer_def timer object referenced with \ref osTimer.
-/// \param[in] type osTimerOnce for one-shot or osTimerPeriodic for periodic behavior.
-/// \param[in] argument argument to the timer call back function.
-/// \return timer ID for reference by other functions or NULL in case of error.
-/// \note MUST REMAIN UNCHANGED: \b osTimerCreate shall be consistent in every CMSIS-RTOS.
-osTimerId osTimerCreate (osTimerDef_t *timer_def, os_timer_type type, void *argument);
-
-/// Start or restart a timer.
-/// \param[in] timer_id timer ID obtained by \ref osTimerCreate.
-/// \param[in] millisec time delay value of the timer.
-/// \return status code that indicates the execution status of the function.
-/// \note MUST REMAIN UNCHANGED: \b osTimerStart shall be consistent in every CMSIS-RTOS.
-osStatus osTimerStart (osTimerId timer_id, uint32_t millisec);
-
-/// Stop the timer.
-/// \param[in] timer_id timer ID obtained by \ref osTimerCreate.
-/// \return status code that indicates the execution status of the function.
-/// \note MUST REMAIN UNCHANGED: \b osTimerStop shall be consistent in every CMSIS-RTOS.
-osStatus osTimerStop (osTimerId timer_id);
-
-/// Delete a timer that was created by \ref osTimerCreate.
-/// \param[in] timer_id timer ID obtained by \ref osTimerCreate.
-/// \return status code that indicates the execution status of the function.
-/// \note MUST REMAIN UNCHANGED: \b osTimerDelete shall be consistent in every CMSIS-RTOS.
-osStatus osTimerDelete (osTimerId timer_id);
-
-
-// ==== Signal Management ====
-
-/// Set the specified Signal Flags of an active thread.
-/// \param[in] thread_id thread ID obtained by \ref osThreadCreate or \ref osThreadGetId.
-/// \param[in] signals specifies the signal flags of the thread that should be set.
-/// \return previous signal flags of the specified thread or 0x80000000 in case of incorrect parameters.
-/// \note MUST REMAIN UNCHANGED: \b osSignalSet shall be consistent in every CMSIS-RTOS.
-int32_t osSignalSet (osThreadId thread_id, int32_t signals);
-
-/// Clear the specified Signal Flags of an active thread.
-/// \param[in] thread_id thread ID obtained by \ref osThreadCreate or \ref osThreadGetId.
-/// \param[in] signals specifies the signal flags of the thread that shall be cleared.
-/// \return previous signal flags of the specified thread or 0x80000000 in case of incorrect parameters.
-/// \note MUST REMAIN UNCHANGED: \b osSignalClear shall be consistent in every CMSIS-RTOS.
-int32_t osSignalClear (osThreadId thread_id, int32_t signals);
-
-/// Get Signal Flags status of an active thread.
-/// \param[in] thread_id thread ID obtained by \ref osThreadCreate or \ref osThreadGetId.
-/// \return previous signal flags of the specified thread or 0x80000000 in case of incorrect parameters.
-/// \note MUST REMAIN UNCHANGED: \b osSignalGet shall be consistent in every CMSIS-RTOS.
-int32_t osSignalGet (osThreadId thread_id);
-
-/// Wait for one or more Signal Flags to become signaled for the current \b RUNNING thread.
-/// \param[in] signals wait until all specified signal flags set or 0 for any single signal flag.
-/// \param[in] millisec timeout value or 0 in case of no time-out.
-/// \return event flag information or error code.
-/// \note MUST REMAIN UNCHANGED: \b osSignalWait shall be consistent in every CMSIS-RTOS.
-os_InRegs osEvent osSignalWait (int32_t signals, uint32_t millisec);
-
-
-// ==== Mutex Management ====
-
-/// Define a Mutex.
-/// \param name name of the mutex object.
-/// \note CAN BE CHANGED: The parameter to \b osMutexDef shall be consistent but the
-/// macro body is implementation specific in every CMSIS-RTOS.
-#if defined (osObjectsExternal) // object is external
-#define osMutexDef(name) \
-extern osMutexDef_t os_mutex_def_##name
-#else // define the object
-#define osMutexDef(name) \
-uint32_t os_mutex_cb_##name[3]; \
-osMutexDef_t os_mutex_def_##name = { (os_mutex_cb_##name) }
-#endif
-
-/// Access a Mutex definition.
-/// \param name name of the mutex object.
-/// \note CAN BE CHANGED: The parameter to \b osMutex shall be consistent but the
-/// macro body is implementation specific in every CMSIS-RTOS.
-#define osMutex(name) \
-&os_mutex_def_##name
-
-/// Create and Initialize a Mutex object.
-/// \param[in] mutex_def mutex definition referenced with \ref osMutex.
-/// \return mutex ID for reference by other functions or NULL in case of error.
-/// \note MUST REMAIN UNCHANGED: \b osMutexCreate shall be consistent in every CMSIS-RTOS.
-osMutexId osMutexCreate (osMutexDef_t *mutex_def);
-
-/// Wait until a Mutex becomes available.
-/// \param[in] mutex_id mutex ID obtained by \ref osMutexCreate.
-/// \param[in] millisec timeout value or 0 in case of no time-out.
-/// \return status code that indicates the execution status of the function.
-/// \note MUST REMAIN UNCHANGED: \b osMutexWait shall be consistent in every CMSIS-RTOS.
-osStatus osMutexWait (osMutexId mutex_id, uint32_t millisec);
-
-/// Release a Mutex that was obtained by \ref osMutexWait.
-/// \param[in] mutex_id mutex ID obtained by \ref osMutexCreate.
-/// \return status code that indicates the execution status of the function.
-/// \note MUST REMAIN UNCHANGED: \b osMutexRelease shall be consistent in every CMSIS-RTOS.
-osStatus osMutexRelease (osMutexId mutex_id);
-
-/// Delete a Mutex that was created by \ref osMutexCreate.
-/// \param[in] mutex_id mutex ID obtained by \ref osMutexCreate.
-/// \return status code that indicates the execution status of the function.
-/// \note MUST REMAIN UNCHANGED: \b osMutexDelete shall be consistent in every CMSIS-RTOS.
-osStatus osMutexDelete (osMutexId mutex_id);
-
-
-// ==== Semaphore Management Functions ====
-
-#if (defined (osFeature_Semaphore) && (osFeature_Semaphore != 0)) // Semaphore available
-
-/// Define a Semaphore object.
-/// \param name name of the semaphore object.
-/// \note CAN BE CHANGED: The parameter to \b osSemaphoreDef shall be consistent but the
-/// macro body is implementation specific in every CMSIS-RTOS.
-#if defined (osObjectsExternal) // object is external
-#define osSemaphoreDef(name) \
-extern osSemaphoreDef_t os_semaphore_def_##name
-#else // define the object
-#define osSemaphoreDef(name) \
-uint32_t os_semaphore_cb_##name[2]; \
-osSemaphoreDef_t os_semaphore_def_##name = { (os_semaphore_cb_##name) }
-#endif
-
-/// Access a Semaphore definition.
-/// \param name name of the semaphore object.
-/// \note CAN BE CHANGED: The parameter to \b osSemaphore shall be consistent but the
-/// macro body is implementation specific in every CMSIS-RTOS.
-#define osSemaphore(name) \
-&os_semaphore_def_##name
-
-/// Create and Initialize a Semaphore object used for managing resources.
-/// \param[in] semaphore_def semaphore definition referenced with \ref osSemaphore.
-/// \param[in] count number of available resources.
-/// \return semaphore ID for reference by other functions or NULL in case of error.
-/// \note MUST REMAIN UNCHANGED: \b osSemaphoreCreate shall be consistent in every CMSIS-RTOS.
-osSemaphoreId osSemaphoreCreate (osSemaphoreDef_t *semaphore_def, int32_t count);
-
-/// Wait until a Semaphore token becomes available.
-/// \param[in] semaphore_id semaphore object referenced with \ref osSemaphoreCreate.
-/// \param[in] millisec timeout value or 0 in case of no time-out.
-/// \return number of available tokens, or -1 in case of incorrect parameters.
-/// \note MUST REMAIN UNCHANGED: \b osSemaphoreWait shall be consistent in every CMSIS-RTOS.
-int32_t osSemaphoreWait (osSemaphoreId semaphore_id, uint32_t millisec);
-
-/// Release a Semaphore token.
-/// \param[in] semaphore_id semaphore object referenced with \ref osSemaphoreCreate.
-/// \return status code that indicates the execution status of the function.
-/// \note MUST REMAIN UNCHANGED: \b osSemaphoreRelease shall be consistent in every CMSIS-RTOS.
-osStatus osSemaphoreRelease (osSemaphoreId semaphore_id);
-
-/// Delete a Semaphore that was created by \ref osSemaphoreCreate.
-/// \param[in] semaphore_id semaphore object referenced with \ref osSemaphoreCreate.
-/// \return status code that indicates the execution status of the function.
-/// \note MUST REMAIN UNCHANGED: \b osSemaphoreDelete shall be consistent in every CMSIS-RTOS.
-osStatus osSemaphoreDelete (osSemaphoreId semaphore_id);
-
-#endif // Semaphore available
-
-
-// ==== Memory Pool Management Functions ====
-
-#if (defined (osFeature_Pool) && (osFeature_Pool != 0)) // Memory Pool Management available
-
-/// \brief Define a Memory Pool.
-/// \param name name of the memory pool.
-/// \param no maximum number of blocks (objects) in the memory pool.
-/// \param type data type of a single block (object).
-/// \note CAN BE CHANGED: The parameter to \b osPoolDef shall be consistent but the
-/// macro body is implementation specific in every CMSIS-RTOS.
-#if defined (osObjectsExternal) // object is external
-#define osPoolDef(name, no, type) \
-extern osPoolDef_t os_pool_def_##name
-#else // define the object
-#define osPoolDef(name, no, type) \
-uint32_t os_pool_m_##name[3+((sizeof(type)+3)/4)*(no)]; \
-osPoolDef_t os_pool_def_##name = \
-{ (no), sizeof(type), (os_pool_m_##name) }
-#endif
-
-/// \brief Access a Memory Pool definition.
-/// \param name name of the memory pool
-/// \note CAN BE CHANGED: The parameter to \b osPool shall be consistent but the
-/// macro body is implementation specific in every CMSIS-RTOS.
-#define osPool(name) \
-&os_pool_def_##name
-
-/// Create and Initialize a memory pool.
-/// \param[in] pool_def memory pool definition referenced with \ref osPool.
-/// \return memory pool ID for reference by other functions or NULL in case of error.
-/// \note MUST REMAIN UNCHANGED: \b osPoolCreate shall be consistent in every CMSIS-RTOS.
-osPoolId osPoolCreate (osPoolDef_t *pool_def);
-
-/// Allocate a memory block from a memory pool.
-/// \param[in] pool_id memory pool ID obtain referenced with \ref osPoolCreate.
-/// \return address of the allocated memory block or NULL in case of no memory available.
-/// \note MUST REMAIN UNCHANGED: \b osPoolAlloc shall be consistent in every CMSIS-RTOS.
-void *osPoolAlloc (osPoolId pool_id);
-
-/// Allocate a memory block from a memory pool and set memory block to zero.
-/// \param[in] pool_id memory pool ID obtain referenced with \ref osPoolCreate.
-/// \return address of the allocated memory block or NULL in case of no memory available.
-/// \note MUST REMAIN UNCHANGED: \b osPoolCAlloc shall be consistent in every CMSIS-RTOS.
-void *osPoolCAlloc (osPoolId pool_id);
-
-/// Return an allocated memory block back to a specific memory pool.
-/// \param[in] pool_id memory pool ID obtain referenced with \ref osPoolCreate.
-/// \param[in] block address of the allocated memory block that is returned to the memory pool.
-/// \return status code that indicates the execution status of the function.
-/// \note MUST REMAIN UNCHANGED: \b osPoolFree shall be consistent in every CMSIS-RTOS.
-osStatus osPoolFree (osPoolId pool_id, void *block);
-
-#endif // Memory Pool Management available
-
-
-// ==== Message Queue Management Functions ====
-
-#if (defined (osFeature_MessageQ) && (osFeature_MessageQ != 0)) // Message Queues available
-
-/// \brief Create a Message Queue Definition.
-/// \param name name of the queue.
-/// \param queue_sz maximum number of messages in the queue.
-/// \param type data type of a single message element (for debugger).
-/// \note CAN BE CHANGED: The parameter to \b osMessageQDef shall be consistent but the
-/// macro body is implementation specific in every CMSIS-RTOS.
-#if defined (osObjectsExternal) // object is external
-#define osMessageQDef(name, queue_sz, type) \
-extern osMessageQDef_t os_messageQ_def_##name
-#else // define the object
-#define osMessageQDef(name, queue_sz, type) \
-uint32_t os_messageQ_q_##name[4+(queue_sz)]; \
-osMessageQDef_t os_messageQ_def_##name = \
-{ (queue_sz), (os_messageQ_q_##name) }
-#endif
-
-/// \brief Access a Message Queue Definition.
-/// \param name name of the queue
-/// \note CAN BE CHANGED: The parameter to \b osMessageQ shall be consistent but the
-/// macro body is implementation specific in every CMSIS-RTOS.
-#define osMessageQ(name) \
-&os_messageQ_def_##name
-
-/// Create and Initialize a Message Queue.
-/// \param[in] queue_def queue definition referenced with \ref osMessageQ.
-/// \param[in] thread_id thread ID (obtained by \ref osThreadCreate or \ref osThreadGetId) or NULL.
-/// \return message queue ID for reference by other functions or NULL in case of error.
-/// \note MUST REMAIN UNCHANGED: \b osMessageCreate shall be consistent in every CMSIS-RTOS.
-osMessageQId osMessageCreate (osMessageQDef_t *queue_def, osThreadId thread_id);
-
-/// Put a Message to a Queue.
-/// \param[in] queue_id message queue ID obtained with \ref osMessageCreate.
-/// \param[in] info message information.
-/// \param[in] millisec timeout value or 0 in case of no time-out.
-/// \return status code that indicates the execution status of the function.
-/// \note MUST REMAIN UNCHANGED: \b osMessagePut shall be consistent in every CMSIS-RTOS.
-osStatus osMessagePut (osMessageQId queue_id, uint32_t info, uint32_t millisec);
-
-/// Get a Message or Wait for a Message from a Queue.
-/// \param[in] queue_id message queue ID obtained with \ref osMessageCreate.
-/// \param[in] millisec timeout value or 0 in case of no time-out.
-/// \return event information that includes status code.
-/// \note MUST REMAIN UNCHANGED: \b osMessageGet shall be consistent in every CMSIS-RTOS.
-os_InRegs osEvent osMessageGet (osMessageQId queue_id, uint32_t millisec);
-
-#endif // Message Queues available
-
-
-// ==== Mail Queue Management Functions ====
-
-#if (defined (osFeature_MailQ) && (osFeature_MailQ != 0)) // Mail Queues available
-
-/// \brief Create a Mail Queue Definition.
-/// \param name name of the queue
-/// \param queue_sz maximum number of messages in queue
-/// \param type data type of a single message element
-/// \note CAN BE CHANGED: The parameter to \b osMailQDef shall be consistent but the
-/// macro body is implementation specific in every CMSIS-RTOS.
-#if defined (osObjectsExternal) // object is external
-#define osMailQDef(name, queue_sz, type) \
-extern osMailQDef_t os_mailQ_def_##name
-#else // define the object
-#define osMailQDef(name, queue_sz, type) \
-uint32_t os_mailQ_q_##name[4+(queue_sz)]; \
-uint32_t os_mailQ_m_##name[3+((sizeof(type)+3)/4)*(queue_sz)]; \
-void * os_mailQ_p_##name[2] = { (os_mailQ_q_##name), os_mailQ_m_##name }; \
-osMailQDef_t os_mailQ_def_##name = \
-{ (queue_sz), sizeof(type), (os_mailQ_p_##name) }
-#endif
-
-/// \brief Access a Mail Queue Definition.
-/// \param name name of the queue
-/// \note CAN BE CHANGED: The parameter to \b osMailQ shall be consistent but the
-/// macro body is implementation specific in every CMSIS-RTOS.
-#define osMailQ(name) \
-&os_mailQ_def_##name
-
-/// Create and Initialize mail queue.
-/// \param[in] queue_def reference to the mail queue definition obtain with \ref osMailQ
-/// \param[in] thread_id thread ID (obtained by \ref osThreadCreate or \ref osThreadGetId) or NULL.
-/// \return mail queue ID for reference by other functions or NULL in case of error.
-/// \note MUST REMAIN UNCHANGED: \b osMailCreate shall be consistent in every CMSIS-RTOS.
-osMailQId osMailCreate (osMailQDef_t *queue_def, osThreadId thread_id);
-
-/// Allocate a memory block from a mail.
-/// \param[in] queue_id mail queue ID obtained with \ref osMailCreate.
-/// \param[in] millisec timeout value or 0 in case of no time-out
-/// \return pointer to memory block that can be filled with mail or NULL in case of error.
-/// \note MUST REMAIN UNCHANGED: \b osMailAlloc shall be consistent in every CMSIS-RTOS.
-void *osMailAlloc (osMailQId queue_id, uint32_t millisec);
-
-/// Allocate a memory block from a mail and set memory block to zero.
-/// \param[in] queue_id mail queue ID obtained with \ref osMailCreate.
-/// \param[in] millisec timeout value or 0 in case of no time-out
-/// \return pointer to memory block that can be filled with mail or NULL in case of error.
-/// \note MUST REMAIN UNCHANGED: \b osMailCAlloc shall be consistent in every CMSIS-RTOS.
-void *osMailCAlloc (osMailQId queue_id, uint32_t millisec);
-
-/// Put a mail to a queue.
-/// \param[in] queue_id mail queue ID obtained with \ref osMailCreate.
-/// \param[in] mail memory block previously allocated with \ref osMailAlloc or \ref osMailCAlloc.
-/// \return status code that indicates the execution status of the function.
-/// \note MUST REMAIN UNCHANGED: \b osMailPut shall be consistent in every CMSIS-RTOS.
-osStatus osMailPut (osMailQId queue_id, void *mail);
-
-/// Get a mail from a queue.
-/// \param[in] queue_id mail queue ID obtained with \ref osMailCreate.
-/// \param[in] millisec timeout value or 0 in case of no time-out
-/// \return event that contains mail information or error code.
-/// \note MUST REMAIN UNCHANGED: \b osMailGet shall be consistent in every CMSIS-RTOS.
-os_InRegs osEvent osMailGet (osMailQId queue_id, uint32_t millisec);
-
-/// Free a memory block from a mail.
-/// \param[in] queue_id mail queue ID obtained with \ref osMailCreate.
-/// \param[in] mail pointer to the memory block that was obtained with \ref osMailGet.
-/// \return status code that indicates the execution status of the function.
-/// \note MUST REMAIN UNCHANGED: \b osMailFree shall be consistent in every CMSIS-RTOS.
-osStatus osMailFree (osMailQId queue_id, void *mail);
-
-#endif // Mail Queues available
-
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif // _CMSIS_OS_H
diff --git a/rtos/rtx/TARGET_ARM7/os_tcb.h b/rtos/rtx/TARGET_ARM7/os_tcb.h
deleted file mode 100644
index 7a8c5c379e..0000000000
--- a/rtos/rtx/TARGET_ARM7/os_tcb.h
+++ /dev/null
@@ -1,55 +0,0 @@
-#ifndef OS_TCB_H
-#define OS_TCB_H
-
-/* Types */
-typedef char S8;
-typedef unsigned char U8;
-typedef short S16;
-typedef unsigned short U16;
-typedef int S32;
-typedef unsigned int U32;
-typedef long long S64;
-typedef unsigned long long U64;
-typedef unsigned char BIT;
-typedef unsigned int BOOL;
-typedef void (*FUNCP)(void);
-#define TCB_STACK_LR_OFFSET_BYTES (14*4) // prelast DWORD
-#define TCB_STACK_LR_OFFSET_DWORDS (14) // prelast DWORD
-#define TCB_STACK_R0_OFFSET_BYTES (1*4) // second DWORD
-#define TCB_STACK_R0_OFFSET_DWORDS (1) // second DWORD
-
-typedef struct OS_TCB {
- /* General part: identical for all implementations. */
- U8 cb_type; /* Control Block Type */
- U8 state; /* Task state */
- U8 prio; /* Execution priority */
- U8 task_id; /* Task ID value for optimized TCB access */
- struct OS_TCB *p_lnk; /* Link pointer for ready/sem. wait list */
- struct OS_TCB *p_rlnk; /* Link pointer for sem./mbx lst backwards */
- struct OS_TCB *p_dlnk; /* Link pointer for delay list */
- struct OS_TCB *p_blnk; /* Link pointer for delay list backwards */
- U16 delta_time; /* Time until time out */
- U16 interval_time; /* Time interval for periodic waits */
- U16 events; /* Event flags */
- U16 waits; /* Wait flags */
- void **msg; /* Direct message passing when task waits */
-
- /* Hardware dependant part: specific for CM processor */
- U8 stack_frame; /* Stack frame: 0=Basic, 1=Extended */
- U8 reserved1;
- U16 reserved2;
- U32 priv_stack; /* Private stack size in bytes */
- U32 tsk_stack; /* Current task Stack pointer (R13) */
- U32 *stack; /* Pointer to Task Stack memory block */
-
- /* Library dependant part */
-#if defined (__CC_ARM) && !defined (__MICROLIB)
- /* A memory space for arm standard library. */
- U32 std_libspace[96/4];
-#endif
-
- /* Task entry point used for uVision debugger */
- FUNCP ptask; /* Task entry address */
-} *P_TCB;
-
-#endif
diff --git a/rtos/rtx/TARGET_ARM7/rt_CMSIS.c b/rtos/rtx/TARGET_ARM7/rt_CMSIS.c
deleted file mode 100644
index b2992c8050..0000000000
--- a/rtos/rtx/TARGET_ARM7/rt_CMSIS.c
+++ /dev/null
@@ -1,1853 +0,0 @@
-/*----------------------------------------------------------------------------
- * RL-ARM - RTX
- *----------------------------------------------------------------------------
- * Name: rt_CMSIS.c
- * Purpose: CMSIS RTOS API
- * Rev.: V4.60
- *----------------------------------------------------------------------------
- *
- * Copyright (c) 1999-2009 KEIL, 2009-2015 ARM Germany GmbH
- * All rights reserved.
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- * - Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * - 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.
- * - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
- *---------------------------------------------------------------------------*/
-
-#define __CMSIS_GENERIC
-
-#include "core_arm7.h"
-
-#include "rt_TypeDef.h"
-#include "RTX_Conf.h"
-#include "rt_System.h"
-#include "rt_Task.h"
-#include "rt_Event.h"
-#include "rt_List.h"
-#include "rt_Time.h"
-#include "rt_Mutex.h"
-#include "rt_Semaphore.h"
-#include "rt_Mailbox.h"
-#include "rt_MemBox.h"
-#include "rt_HAL_CM.h"
-
-#define os_thread_cb OS_TCB
-
-#include "cmsis_os.h"
-
-#if (osFeature_Signals != 16)
-#error Invalid "osFeature_Signals" value!
-#endif
-#if (osFeature_Semaphore > 65535)
-#error Invalid "osFeature_Semaphore" value!
-#endif
-#if (osFeature_Wait != 0)
-#error osWait not supported!
-#endif
-
-
-// ==== Enumeration, structures, defines ====
-
-// Service Calls defines
-
-#if defined (__CC_ARM) /* ARM Compiler */
-
-#define __NO_RETURN __declspec(noreturn)
-
-#define osEvent_type osEvent
-#define osEvent_ret_status ret
-#define osEvent_ret_value ret
-#define osEvent_ret_msg ret
-#define osEvent_ret_mail ret
-
-#define osCallback_type osCallback
-#define osCallback_ret ret
-
-#define SVC_0_1(f,t,...) \
-__svc_indirect(0) t _##f (t(*)()); \
- t f (void); \
-__attribute__((always_inline)) \
-static __inline t __##f (void) { \
- return _##f(f); \
-}
-
-#define SVC_1_1(f,t,t1,...) \
-__svc_indirect(0) t _##f (t(*)(t1),t1); \
- t f (t1 a1); \
-__attribute__((always_inline)) \
-static __inline t __##f (t1 a1) { \
- return _##f(f,a1); \
-}
-
-#define SVC_2_1(f,t,t1,t2,...) \
-__svc_indirect(0) t _##f (t(*)(t1,t2),t1,t2); \
- t f (t1 a1, t2 a2); \
-__attribute__((always_inline)) \
-static __inline t __##f (t1 a1, t2 a2) { \
- return _##f(f,a1,a2); \
-}
-
-#define SVC_3_1(f,t,t1,t2,t3,...) \
-__svc_indirect(0) t _##f (t(*)(t1,t2,t3),t1,t2,t3); \
- t f (t1 a1, t2 a2, t3 a3); \
-__attribute__((always_inline)) \
-static __inline t __##f (t1 a1, t2 a2, t3 a3) { \
- return _##f(f,a1,a2,a3); \
-}
-
-#define SVC_4_1(f,t,t1,t2,t3,t4,...) \
-__svc_indirect(0) t _##f (t(*)(t1,t2,t3,t4),t1,t2,t3,t4); \
- t f (t1 a1, t2 a2, t3 a3, t4 a4); \
-__attribute__((always_inline)) \
-static __inline t __##f (t1 a1, t2 a2, t3 a3, t4 a4) { \
- return _##f(f,a1,a2,a3,a4); \
-}
-
-#define SVC_1_2 SVC_1_1
-#define SVC_1_3 SVC_1_1
-#define SVC_2_3 SVC_2_1
-
-#elif defined (__GNUC__) /* GNU Compiler */
-
-#define __NO_RETURN __attribute__((noreturn))
-
-typedef uint32_t __attribute__((vector_size(8))) ret64;
-typedef uint32_t __attribute__((vector_size(16))) ret128;
-
-#define RET_pointer __r0
-#define RET_int32_t __r0
-#define RET_osStatus __r0
-#define RET_osPriority __r0
-#define RET_osEvent {(osStatus)__r0, {(uint32_t)__r1}, {(void *)__r2}}
-#define RET_osCallback {(void *)__r0, (void *)__r1}
-
-#define osEvent_type ret128
-#define osEvent_ret_status (ret128){ret.status}
-#define osEvent_ret_value (ret128){ret.status, ret.value.v}
-#define osEvent_ret_msg (ret128){ret.status, ret.value.v, (uint32_t)ret.def.message_id}
-#define osEvent_ret_mail (ret128){ret.status, ret.value.v, (uint32_t)ret.def.mail_id}
-
-#define osCallback_type ret64
-#define osCallback_ret (ret64) {(uint32_t)ret.fp, (uint32_t)ret.arg}
-
-#define SVC_ArgN(n) \
- register int __r##n __asm("r"#n);
-
-#define SVC_ArgR(n,t,a) \
- register t __r##n __asm("r"#n) = a;
-
-#define SVC_Arg0() \
- SVC_ArgN(0) \
- SVC_ArgN(1) \
- SVC_ArgN(2) \
- SVC_ArgN(3)
-
-#define SVC_Arg1(t1) \
- SVC_ArgR(0,t1,a1) \
- SVC_ArgN(1) \
- SVC_ArgN(2) \
- SVC_ArgN(3)
-
-#define SVC_Arg2(t1,t2) \
- SVC_ArgR(0,t1,a1) \
- SVC_ArgR(1,t2,a2) \
- SVC_ArgN(2) \
- SVC_ArgN(3)
-
-#define SVC_Arg3(t1,t2,t3) \
- SVC_ArgR(0,t1,a1) \
- SVC_ArgR(1,t2,a2) \
- SVC_ArgR(2,t3,a3) \
- SVC_ArgN(3)
-
-#define SVC_Arg4(t1,t2,t3,t4) \
- SVC_ArgR(0,t1,a1) \
- SVC_ArgR(1,t2,a2) \
- SVC_ArgR(2,t3,a3) \
- SVC_ArgR(3,t4,a4)
-
-#if (defined (__CORTEX_M0)) || defined (__CORTEX_M0PLUS)
-#define SVC_Call(f) \
- __asm volatile \
- ( \
- "ldr r7,="#f"\n\t" \
- "mov r12,r7\n\t" \
- "svc 0" \
- : "=r" (__r0), "=r" (__r1), "=r" (__r2), "=r" (__r3) \
- : "r" (__r0), "r" (__r1), "r" (__r2), "r" (__r3) \
- : "r7", "r12", "lr", "cc" \
- );
-#else
-#define SVC_Call(f) \
- __asm volatile \
- ( \
- "ldr r12,="#f"\n\t" \
- "svc 0" \
- : "=r" (__r0), "=r" (__r1), "=r" (__r2), "=r" (__r3) \
- : "r" (__r0), "r" (__r1), "r" (__r2), "r" (__r3) \
- : "r12", "lr", "cc" \
- );
-#endif
-
-#define SVC_0_1(f,t,rv) \
-__attribute__((always_inline)) \
-static inline t __##f (void) { \
- SVC_Arg0(); \
- SVC_Call(f); \
- return (t) rv; \
-}
-
-#define SVC_1_1(f,t,t1,rv) \
-__attribute__((always_inline)) \
-static inline t __##f (t1 a1) { \
- SVC_Arg1(t1); \
- SVC_Call(f); \
- return (t) rv; \
-}
-
-#define SVC_2_1(f,t,t1,t2,rv) \
-__attribute__((always_inline)) \
-static inline t __##f (t1 a1, t2 a2) { \
- SVC_Arg2(t1,t2); \
- SVC_Call(f); \
- return (t) rv; \
-}
-
-#define SVC_3_1(f,t,t1,t2,t3,rv) \
-__attribute__((always_inline)) \
-static inline t __##f (t1 a1, t2 a2, t3 a3) { \
- SVC_Arg3(t1,t2,t3); \
- SVC_Call(f); \
- return (t) rv; \
-}
-
-#define SVC_4_1(f,t,t1,t2,t3,t4,rv) \
-__attribute__((always_inline)) \
-static inline t __##f (t1 a1, t2 a2, t3 a3, t4 a4) { \
- SVC_Arg4(t1,t2,t3,t4); \
- SVC_Call(f); \
- return (t) rv; \
-}
-
-#define SVC_1_2 SVC_1_1
-#define SVC_1_3 SVC_1_1
-#define SVC_2_3 SVC_2_1
-
-#elif defined (__ICCARM__) /* IAR Compiler */
-
-#define __NO_RETURN __noreturn
-
-#define osEvent_type osEvent
-#define osEvent_ret_status ret
-#define osEvent_ret_value ret
-#define osEvent_ret_msg ret
-#define osEvent_ret_mail ret
-
-#define osCallback_type osCallback
-#define osCallback_ret ret
-
-#define RET_osEvent osEvent
-#define RET_osCallback osCallback
-
-#define SVC_Setup(f) \
- __asm( \
- "mov r12,%0\n" \
- :: "r"(&f): "r12" \
- );
-
-
-#define SVC_0_1(f,t,...) \
-t f (void); \
-_Pragma("swi_number=0") __swi t _##f (void); \
-static inline t __##f (void) { \
- SVC_Setup(f); \
- return _##f(); \
-}
-
-#define SVC_1_1(f,t,t1,...) \
-t f (t1 a1); \
-_Pragma("swi_number=0") __swi t _##f (t1 a1); \
-static inline t __##f (t1 a1) { \
- SVC_Setup(f); \
- return _##f(a1); \
-}
-
-#define SVC_2_1(f,t,t1,t2,...) \
-t f (t1 a1, t2 a2); \
-_Pragma("swi_number=0") __swi t _##f (t1 a1, t2 a2); \
-static inline t __##f (t1 a1, t2 a2) { \
- SVC_Setup(f); \
- return _##f(a1,a2); \
-}
-
-#define SVC_3_1(f,t,t1,t2,t3,...) \
-t f (t1 a1, t2 a2, t3 a3); \
-_Pragma("swi_number=0") __swi t _##f (t1 a1, t2 a2, t3 a3); \
-static inline t __##f (t1 a1, t2 a2, t3 a3) { \
- SVC_Setup(f); \
- return _##f(a1,a2,a3); \
-}
-
-#define SVC_4_1(f,t,t1,t2,t3,t4,...) \
-t f (t1 a1, t2 a2, t3 a3, t4 a4); \
-_Pragma("swi_number=0") __swi t _##f (t1 a1, t2 a2, t3 a3, t4 a4); \
-static inline t __##f (t1 a1, t2 a2, t3 a3, t4 a4) { \
- SVC_Setup(f); \
- return _##f(a1,a2,a3,a4); \
-}
-
-#define SVC_1_2 SVC_1_1
-#define SVC_1_3 SVC_1_1
-#define SVC_2_3 SVC_2_1
-
-#endif
-
-
-// Callback structure
-typedef struct {
- void *fp; // Function pointer
- void *arg; // Function argument
-} osCallback;
-
-
-// OS Section definitions
-#ifdef OS_SECTIONS_LINK_INFO
-extern const uint32_t os_section_id$$Base;
-extern const uint32_t os_section_id$$Limit;
-#endif
-
-// OS Timers external resources
-extern osThreadDef_t os_thread_def_osTimerThread;
-extern osThreadId osThreadId_osTimerThread;
-extern osMessageQDef_t os_messageQ_def_osTimerMessageQ;
-extern osMessageQId osMessageQId_osTimerMessageQ;
-
-
-// ==== Helper Functions ====
-
-/// Convert timeout in millisec to system ticks
-static uint32_t rt_ms2tick (uint32_t millisec) {
- uint32_t tick;
-
- if (millisec == osWaitForever) return 0xFFFF; // Indefinite timeout
- if (millisec > 4000000) return 0xFFFE; // Max ticks supported
-
- tick = ((1000 * millisec) + os_clockrate - 1) / os_clockrate;
- if (tick > 0xFFFE) return 0xFFFE;
-
- return tick;
-}
-
-/// Convert Thread ID to TCB pointer
-static P_TCB rt_tid2ptcb (osThreadId thread_id) {
- P_TCB ptcb;
-
- if (thread_id == NULL) return NULL;
-
- if ((uint32_t)thread_id & 3) return NULL;
-
-#ifdef OS_SECTIONS_LINK_INFO
- if ((os_section_id$$Base != 0) && (os_section_id$$Limit != 0)) {
- if (thread_id < (osThreadId)os_section_id$$Base) return NULL;
- if (thread_id >= (osThreadId)os_section_id$$Limit) return NULL;
- }
-#endif
-
- ptcb = thread_id;
-
- if (ptcb->cb_type != TCB) return NULL;
-
- return ptcb;
-}
-
-/// Convert ID pointer to Object pointer
-static void *rt_id2obj (void *id) {
-
- if ((uint32_t)id & 3) return NULL;
-
-#ifdef OS_SECTIONS_LINK_INFO
- if ((os_section_id$$Base != 0) && (os_section_id$$Limit != 0)) {
- if (id < (void *)os_section_id$$Base) return NULL;
- if (id >= (void *)os_section_id$$Limit) return NULL;
- }
-#endif
-
- return id;
-}
-
-
-// ==== Kernel Control ====
-
-uint8_t os_initialized; // Kernel Initialized flag
-uint8_t os_running; // Kernel Running flag
-
-// Kernel Control Service Calls declarations
-SVC_0_1(svcKernelInitialize, osStatus, RET_osStatus)
-SVC_0_1(svcKernelStart, osStatus, RET_osStatus)
-SVC_0_1(svcKernelRunning, int32_t, RET_int32_t)
-
-extern void sysThreadError (osStatus status);
-osThreadId svcThreadCreate (osThreadDef_t *thread_def, void *argument);
-osMessageQId svcMessageCreate (osMessageQDef_t *queue_def, osThreadId thread_id);
-
-// Kernel Control Service Calls
-
-/// Initialize the RTOS Kernel for creating objects
-osStatus svcKernelInitialize (void) {
- if (os_initialized) return osOK;
-
- rt_sys_init(); // RTX System Initialization
- os_tsk.run->prio = 255; // Highest priority
-
- sysThreadError(osOK);
-
- os_initialized = 1;
-
- return osOK;
-}
-
-/// Start the RTOS Kernel
-osStatus svcKernelStart (void) {
-
- if (os_running) return osOK;
-
- // Create OS Timers resources (Message Queue & Thread)
- osMessageQId_osTimerMessageQ = svcMessageCreate (&os_messageQ_def_osTimerMessageQ, NULL);
- osThreadId_osTimerThread = svcThreadCreate(&os_thread_def_osTimerThread, NULL);
-
- rt_tsk_prio(0, 0); // Lowest priority
-// __set_SP(os_tsk.run->tsk_stack + 8*4); // New context
- os_tsk.run = NULL; // Force context switch
-
- rt_sys_start();
-
- os_running = 1;
-
- return osOK;
-}
-
-/// Check if the RTOS kernel is already started
-int32_t svcKernelRunning(void) {
- return os_running;
-}
-
-// Kernel Control Public API
-
-/// Initialize the RTOS Kernel for creating objects
-osStatus osKernelInitialize (void) {
- if (__get_CONTROL() == MODE_IRQ) return osErrorISR; // Not allowed in ISR
- if (__get_CONTROL() == MODE_SUPERVISOR) { // Privileged mode
- return svcKernelInitialize();
- } else {
- return __svcKernelInitialize();
- }
-}
-
-/// Start the RTOS Kernel
-osStatus osKernelStart (void) {
-
- if (__get_CONTROL() == MODE_IRQ) return osErrorISR; // Not allowed in ISR
- switch (__get_CONTROL()) {
- case MODE_SUPERVISOR: // Privileged mode
- break;
- case MODE_USER:
- case MODE_SYSTEM: // Unprivileged mode
- return osErrorOS;
- default: // Other invalid modes
- return osErrorOS;
- break;
- }
- return svcKernelStart();
-}
-
-/// Check if the RTOS kernel is already started
-int32_t osKernelRunning(void) {
- if ((__get_CONTROL() == MODE_IRQ) || (__get_CONTROL() == MODE_SUPERVISOR)) {
- // in ISR or Privileged
- return os_running;
- } else {
- return __svcKernelRunning();
- }
-}
-
-
-// ==== Thread Management ====
-
-__NO_RETURN void osThreadExit (void);
-
-// Thread Service Calls declarations
-SVC_2_1(svcThreadCreate, osThreadId, osThreadDef_t *, void *, RET_pointer)
-SVC_0_1(svcThreadGetId, osThreadId, RET_pointer)
-SVC_1_1(svcThreadTerminate, osStatus, osThreadId, RET_osStatus)
-SVC_0_1(svcThreadYield, osStatus, RET_osStatus)
-SVC_2_1(svcThreadSetPriority, osStatus, osThreadId, osPriority, RET_osStatus)
-SVC_1_1(svcThreadGetPriority, osPriority, osThreadId, RET_osPriority)
-
-// Thread Service Calls
-extern OS_TID rt_get_TID (void);
-extern void rt_init_context (P_TCB p_TCB, U8 priority, FUNCP task_body);
-
-/// Create a thread and add it to Active Threads and set it to state READY
-osThreadId svcThreadCreate (osThreadDef_t *thread_def, void *argument) {
- P_TCB ptcb;
-
- if ((thread_def == NULL) ||
- (thread_def->pthread == NULL) ||
- (thread_def->tpriority < osPriorityIdle) ||
- (thread_def->tpriority > osPriorityRealtime) ||
- (thread_def->stacksize == 0) ||
- (thread_def->stack_pointer == NULL) ) {
- sysThreadError(osErrorParameter);
- return NULL;
- }
-
- U8 priority = thread_def->tpriority - osPriorityIdle + 1;
- P_TCB task_context = &thread_def->tcb;
-
- /* Utilize the user provided stack. */
- task_context->stack = (U32*)thread_def->stack_pointer;
- task_context->priv_stack = thread_def->stacksize;
- /* Find a free entry in 'os_active_TCB' table. */
- OS_TID tsk = rt_get_TID ();
- os_active_TCB[tsk-1] = task_context;
- task_context->task_id = tsk;
- /* Pass parameter 'argv' to 'rt_init_context' */
- task_context->msg = argument;
- /* For 'size == 0' system allocates the user stack from the memory pool. */
- rt_init_context (task_context, priority, (FUNCP)thread_def->pthread);
-
- /* Dispatch this task to the scheduler for execution. */
- DBG_TASK_NOTIFY(task_context, __TRUE);
- rt_dispatch (task_context);
-
- ptcb = (P_TCB)os_active_TCB[tsk - 1]; // TCB pointer
-
- *((uint32_t *)ptcb->tsk_stack + TCB_STACK_LR_OFFSET_DWORDS) = (uint32_t)osThreadExit; /* LR = osThreadExit */
-
- return ptcb;
-}
-
-/// Return the thread ID of the current running thread
-osThreadId svcThreadGetId (void) {
- OS_TID tsk;
-
- tsk = rt_tsk_self();
- if (tsk == 0) return NULL;
- return (P_TCB)os_active_TCB[tsk - 1];
-}
-
-/// Terminate execution of a thread and remove it from ActiveThreads
-osStatus svcThreadTerminate (osThreadId thread_id) {
- OS_RESULT res;
- P_TCB ptcb;
-
- ptcb = rt_tid2ptcb(thread_id); // Get TCB pointer
- if (ptcb == NULL) return osErrorParameter;
-
- res = rt_tsk_delete(ptcb->task_id); // Delete task
-
- if (res == OS_R_NOK) return osErrorResource; // Delete task failed
-
- return osOK;
-}
-
-/// Pass control to next thread that is in state READY
-osStatus svcThreadYield (void) {
- rt_tsk_pass(); // Pass control to next task
- return osOK;
-}
-
-/// Change priority of an active thread
-osStatus svcThreadSetPriority (osThreadId thread_id, osPriority priority) {
- OS_RESULT res;
- P_TCB ptcb;
-
- ptcb = rt_tid2ptcb(thread_id); // Get TCB pointer
- if (ptcb == NULL) return osErrorParameter;
-
- if ((priority < osPriorityIdle) || (priority > osPriorityRealtime)) {
- return osErrorValue;
- }
-
- res = rt_tsk_prio( // Change task priority
- ptcb->task_id, // Task ID
- priority - osPriorityIdle + 1 // New task priority
- );
-
- if (res == OS_R_NOK) return osErrorResource; // Change task priority failed
-
- return osOK;
-}
-
-/// Get current priority of an active thread
-osPriority svcThreadGetPriority (osThreadId thread_id) {
- P_TCB ptcb;
-
- ptcb = rt_tid2ptcb(thread_id); // Get TCB pointer
- if (ptcb == NULL) return osPriorityError;
-
- return (osPriority)(ptcb->prio - 1 + osPriorityIdle);
-}
-
-
-// Thread Public API
-
-/// Create a thread and add it to Active Threads and set it to state READY
-osThreadId osThreadCreate (osThreadDef_t *thread_def, void *argument) {
- if (__get_CONTROL() == MODE_IRQ) return NULL; // Not allowed in ISR
- if ((__get_CONTROL() == MODE_SUPERVISOR) && (os_running == 0)) {
- // Privileged and not running
- return svcThreadCreate(thread_def, argument);
- } else {
- return __svcThreadCreate(thread_def, argument);
- }
-}
-
-/// Return the thread ID of the current running thread
-osThreadId osThreadGetId (void) {
- if (__get_CONTROL() == MODE_IRQ) return NULL; // Not allowed in ISR
- return __svcThreadGetId();
-}
-
-/// Terminate execution of a thread and remove it from ActiveThreads
-osStatus osThreadTerminate (osThreadId thread_id) {
- if (__get_CONTROL() == MODE_IRQ) return osErrorISR; // Not allowed in ISR
- return __svcThreadTerminate(thread_id);
-}
-
-/// Pass control to next thread that is in state READY
-osStatus osThreadYield (void) {
- if (__get_CONTROL() == MODE_IRQ) return osErrorISR; // Not allowed in ISR
- return __svcThreadYield();
-}
-
-/// Change priority of an active thread
-osStatus osThreadSetPriority (osThreadId thread_id, osPriority priority) {
- if (__get_CONTROL() == MODE_IRQ) return osErrorISR; // Not allowed in ISR
- return __svcThreadSetPriority(thread_id, priority);
-}
-
-/// Get current priority of an active thread
-osPriority osThreadGetPriority (osThreadId thread_id) {
- if (__get_CONTROL() == MODE_IRQ) return osPriorityError;// Not allowed in ISR
- return __svcThreadGetPriority(thread_id);
-}
-
-/// INTERNAL - Not Public
-/// Auto Terminate Thread on exit (used implicitly when thread exists)
-__NO_RETURN void osThreadExit (void) {
- __svcThreadTerminate(__svcThreadGetId());
- for (;;); // Should never come here
-}
-
-
-// ==== Generic Wait Functions ====
-
-// Generic Wait Service Calls declarations
-SVC_1_1(svcDelay, osStatus, uint32_t, RET_osStatus)
-#if osFeature_Wait != 0
-SVC_1_3(svcWait, os_InRegs osEvent, uint32_t, RET_osEvent)
-#endif
-
-// Generic Wait Service Calls
-
-/// Wait for Timeout (Time Delay)
-osStatus svcDelay (uint32_t millisec) {
- if (millisec == 0) return osOK;
- rt_dly_wait(rt_ms2tick(millisec));
- return osEventTimeout;
-}
-
-/// Wait for Signal, Message, Mail, or Timeout
-#if osFeature_Wait != 0
-os_InRegs osEvent_type svcWait (uint32_t millisec) {
- osEvent ret;
-
- if (millisec == 0) {
- ret.status = osOK;
- return osEvent_ret_status;
- }
-
- /* To Do: osEventSignal, osEventMessage, osEventMail */
- rt_dly_wait(rt_ms2tick(millisec));
- ret.status = osEventTimeout;
-
- return osEvent_ret_status;
-}
-#endif
-
-
-// Generic Wait API
-
-/// Wait for Timeout (Time Delay)
-osStatus osDelay (uint32_t millisec) {
- if (__get_CONTROL() == MODE_IRQ) return osErrorISR; // Not allowed in ISR
- return __svcDelay(millisec);
-}
-
-/// Wait for Signal, Message, Mail, or Timeout
-os_InRegs osEvent osWait (uint32_t millisec) {
- osEvent ret;
-
-#if osFeature_Wait == 0
- ret.status = osErrorOS;
- return ret;
-#else
- if (__get_CONTROL() == MODE_IRQ) { // Not allowed in ISR
- ret.status = osErrorISR;
- return ret;
- }
- return __svcWait(millisec);
-#endif
-}
-
-
-// ==== Timer Management ====
-
-// Timer definitions
-#define osTimerInvalid 0
-#define osTimerStopped 1
-#define osTimerRunning 2
-
-// Timer structures
-
-typedef struct os_timer_cb_ { // Timer Control Block
- struct os_timer_cb_ *next; // Pointer to next active Timer
- uint8_t state; // Timer State
- uint8_t type; // Timer Type (Periodic/One-shot)
- uint16_t reserved; // Reserved
- uint16_t tcnt; // Timer Delay Count
- uint16_t icnt; // Timer Initial Count
- void *arg; // Timer Function Argument
- osTimerDef_t *timer; // Pointer to Timer definition
-} os_timer_cb;
-
-// Timer variables
-os_timer_cb *os_timer_head; // Pointer to first active Timer
-
-
-// Timer Helper Functions
-
-// Insert Timer into the list sorted by time
-static void rt_timer_insert (os_timer_cb *pt, uint32_t tcnt) {
- os_timer_cb *p, *prev;
-
- prev = NULL;
- p = os_timer_head;
- while (p != NULL) {
- if (tcnt < p->tcnt) break;
- tcnt -= p->tcnt;
- prev = p;
- p = p->next;
- }
- pt->next = p;
- pt->tcnt = (uint16_t)tcnt;
- if (p != NULL) {
- p->tcnt -= pt->tcnt;
- }
- if (prev != NULL) {
- prev->next = pt;
- } else {
- os_timer_head = pt;
- }
-}
-
-// Remove Timer from the list
-static int rt_timer_remove (os_timer_cb *pt) {
- os_timer_cb *p, *prev;
-
- prev = NULL;
- p = os_timer_head;
- while (p != NULL) {
- if (p == pt) break;
- prev = p;
- p = p->next;
- }
- if (p == NULL) return -1;
- if (prev != NULL) {
- prev->next = pt->next;
- } else {
- os_timer_head = pt->next;
- }
- if (pt->next != NULL) {
- pt->next->tcnt += pt->tcnt;
- }
-
- return 0;
-}
-
-
-// Timer Service Calls declarations
-SVC_3_1(svcTimerCreate, osTimerId, osTimerDef_t *, os_timer_type, void *, RET_pointer)
-SVC_2_1(svcTimerStart, osStatus, osTimerId, uint32_t, RET_osStatus)
-SVC_1_1(svcTimerStop, osStatus, osTimerId, RET_osStatus)
-SVC_1_1(svcTimerDelete, osStatus, osTimerId, RET_osStatus)
-SVC_1_2(svcTimerCall, os_InRegs osCallback, osTimerId, RET_osCallback)
-
-// Timer Management Service Calls
-
-/// Create timer
-osTimerId svcTimerCreate (osTimerDef_t *timer_def, os_timer_type type, void *argument) {
- os_timer_cb *pt;
-
- if ((timer_def == NULL) || (timer_def->ptimer == NULL)) {
- sysThreadError(osErrorParameter);
- return NULL;
- }
-
- pt = timer_def->timer;
- if (pt == NULL) {
- sysThreadError(osErrorParameter);
- return NULL;
- }
-
- if ((type != osTimerOnce) && (type != osTimerPeriodic)) {
- sysThreadError(osErrorValue);
- return NULL;
- }
-
- if (osThreadId_osTimerThread == NULL) {
- sysThreadError(osErrorResource);
- return NULL;
- }
-
- if (pt->state != osTimerInvalid){
- sysThreadError(osErrorResource);
- return NULL;
- }
-
- pt->state = osTimerStopped;
- pt->type = (uint8_t)type;
- pt->arg = argument;
- pt->timer = timer_def;
-
- return (osTimerId)pt;
-}
-
-/// Start or restart timer
-osStatus svcTimerStart (osTimerId timer_id, uint32_t millisec) {
- os_timer_cb *pt;
- uint32_t tcnt;
-
- pt = rt_id2obj(timer_id);
- if (pt == NULL) return osErrorParameter;
-
- tcnt = rt_ms2tick(millisec);
- if (tcnt == 0) return osErrorValue;
-
- switch (pt->state) {
- case osTimerRunning:
- if (rt_timer_remove(pt) != 0) {
- return osErrorResource;
- }
- break;
- case osTimerStopped:
- pt->state = osTimerRunning;
- pt->icnt = (uint16_t)tcnt;
- break;
- default:
- return osErrorResource;
- }
-
- rt_timer_insert(pt, tcnt);
-
- return osOK;
-}
-
-/// Stop timer
-osStatus svcTimerStop (osTimerId timer_id) {
- os_timer_cb *pt;
-
- pt = rt_id2obj(timer_id);
- if (pt == NULL) return osErrorParameter;
-
- if (pt->state != osTimerRunning) return osErrorResource;
-
- pt->state = osTimerStopped;
-
- if (rt_timer_remove(pt) != 0) {
- return osErrorResource;
- }
-
- return osOK;
-}
-
-/// Delete timer
-osStatus svcTimerDelete (osTimerId timer_id) {
- os_timer_cb *pt;
-
- pt = rt_id2obj(timer_id);
- if (pt == NULL) return osErrorParameter;
-
- switch (pt->state) {
- case osTimerRunning:
- rt_timer_remove(pt);
- break;
- case osTimerStopped:
- break;
- default:
- return osErrorResource;
- }
-
- pt->state = osTimerInvalid;
-
- return osOK;
-}
-
-/// Get timer callback parameters
-os_InRegs osCallback_type svcTimerCall (osTimerId timer_id) {
- os_timer_cb *pt;
- osCallback ret;
-
- pt = rt_id2obj(timer_id);
- if (pt == NULL) {
- ret.fp = NULL;
- ret.arg = NULL;
- return osCallback_ret;
- }
-
- ret.fp = (void *)pt->timer->ptimer;
- ret.arg = pt->arg;
-
- return osCallback_ret;
-}
-
-static __INLINE osStatus isrMessagePut (osMessageQId queue_id, uint32_t info, uint32_t millisec);
-
-/// Timer Tick (called each SysTick)
-void sysTimerTick (void) {
- os_timer_cb *pt, *p;
-
- p = os_timer_head;
- if (p == NULL) return;
-
- p->tcnt--;
- while ((p != NULL) && (p->tcnt == 0)) {
- pt = p;
- p = p->next;
- os_timer_head = p;
- isrMessagePut(osMessageQId_osTimerMessageQ, (uint32_t)pt, 0);
- if (pt->type == osTimerPeriodic) {
- rt_timer_insert(pt, pt->icnt);
- } else {
- pt->state = osTimerStopped;
- }
- }
-}
-
-
-// Timer Management Public API
-
-/// Create timer
-osTimerId osTimerCreate (osTimerDef_t *timer_def, os_timer_type type, void *argument) {
- if (__get_CONTROL() == MODE_IRQ) return NULL; // Not allowed in ISR
- if ((__get_CONTROL() == MODE_SUPERVISOR) && (os_running == 0)) {
- // Privileged and not running
- return svcTimerCreate(timer_def, type, argument);
- } else {
- return __svcTimerCreate(timer_def, type, argument);
- }
-}
-
-/// Start or restart timer
-osStatus osTimerStart (osTimerId timer_id, uint32_t millisec) {
- if (__get_CONTROL() == MODE_IRQ) return osErrorISR; // Not allowed in ISR
- return __svcTimerStart(timer_id, millisec);
-}
-
-/// Stop timer
-osStatus osTimerStop (osTimerId timer_id) {
- if (__get_CONTROL() == MODE_IRQ) return osErrorISR; // Not allowed in ISR
- return __svcTimerStop(timer_id);
-}
-
-/// Delete timer
-osStatus osTimerDelete (osTimerId timer_id) {
- if (__get_CONTROL() == MODE_IRQ) return osErrorISR; // Not allowed in ISR
- return __svcTimerDelete(timer_id);
-}
-
-/// INTERNAL - Not Public
-/// Get timer callback parameters (used by OS Timer Thread)
-os_InRegs osCallback osTimerCall (osTimerId timer_id) {
- return __svcTimerCall(timer_id);
-}
-
-
-// Timer Thread
-__NO_RETURN void osTimerThread (void const *argument) {
- osCallback cb;
- osEvent evt;
-
- for (;;) {
- evt = osMessageGet(osMessageQId_osTimerMessageQ, osWaitForever);
- if (evt.status == osEventMessage) {
- cb = osTimerCall(evt.value.p);
- if (cb.fp != NULL) {
- (*(os_ptimer)cb.fp)(cb.arg);
- }
- }
- }
-}
-
-
-// ==== Signal Management ====
-
-// Signal Service Calls declarations
-SVC_2_1(svcSignalSet, int32_t, osThreadId, int32_t, RET_int32_t)
-SVC_2_1(svcSignalClear, int32_t, osThreadId, int32_t, RET_int32_t)
-SVC_1_1(svcSignalGet, int32_t, osThreadId, RET_int32_t)
-SVC_2_3(svcSignalWait, os_InRegs osEvent, int32_t, uint32_t, RET_osEvent)
-
-// Signal Service Calls
-
-/// Set the specified Signal Flags of an active thread
-int32_t svcSignalSet (osThreadId thread_id, int32_t signals) {
- P_TCB ptcb;
- int32_t sig;
-
- ptcb = rt_tid2ptcb(thread_id); // Get TCB pointer
- if (ptcb == NULL) return 0x80000000;
-
- if (signals & (0xFFFFFFFF << osFeature_Signals)) return 0x80000000;
-
- sig = ptcb->events; // Previous signal flags
-
- rt_evt_set(signals, ptcb->task_id); // Set event flags
-
- return sig;
-}
-
-/// Clear the specified Signal Flags of an active thread
-int32_t svcSignalClear (osThreadId thread_id, int32_t signals) {
- P_TCB ptcb;
- int32_t sig;
-
- ptcb = rt_tid2ptcb(thread_id); // Get TCB pointer
- if (ptcb == NULL) return 0x80000000;
-
- if (signals & (0xFFFFFFFF << osFeature_Signals)) return 0x80000000;
-
- sig = ptcb->events; // Previous signal flags
-
- rt_evt_clr(signals, ptcb->task_id); // Clear event flags
-
- return sig;
-}
-
-/// Get Signal Flags status of an active thread
-int32_t svcSignalGet (osThreadId thread_id) {
- P_TCB ptcb;
-
- ptcb = rt_tid2ptcb(thread_id); // Get TCB pointer
- if (ptcb == NULL) return 0x80000000;
-
- return ptcb->events; // Return event flags
-}
-
-/// Wait for one or more Signal Flags to become signaled for the current RUNNING thread
-os_InRegs osEvent_type svcSignalWait (int32_t signals, uint32_t millisec) {
- OS_RESULT res;
- osEvent ret;
-
- if (signals & (0xFFFFFFFF << osFeature_Signals)) {
- ret.status = osErrorValue;
- return osEvent_ret_status;
- }
-
- if (signals != 0) { // Wait for all specified signals
- res = rt_evt_wait(signals, rt_ms2tick(millisec), __TRUE);
- } else { // Wait for any signal
- res = rt_evt_wait(0xFFFF, rt_ms2tick(millisec), __FALSE);
- }
-
- if (res == OS_R_EVT) {
- ret.status = osEventSignal;
- ret.value.signals = signals ? signals : os_tsk.run->waits;
- } else {
- ret.status = millisec ? osEventTimeout : osOK;
- ret.value.signals = 0;
- }
-
- return osEvent_ret_value;
-}
-
-
-// Signal ISR Calls
-
-/// Set the specified Signal Flags of an active thread
-static __INLINE int32_t isrSignalSet (osThreadId thread_id, int32_t signals) {
- P_TCB ptcb;
- int32_t sig;
-
- ptcb = rt_tid2ptcb(thread_id); // Get TCB pointer
- if (ptcb == NULL) return 0x80000000;
-
- if (signals & (0xFFFFFFFF << osFeature_Signals)) return 0x80000000;
-
- sig = ptcb->events; // Previous signal flags
-
- isr_evt_set(signals, ptcb->task_id); // Set event flags
-
- return sig;
-}
-
-
-// Signal Public API
-
-/// Set the specified Signal Flags of an active thread
-int32_t osSignalSet (osThreadId thread_id, int32_t signals) {
- if (__get_CONTROL() == MODE_IRQ) { // in ISR
- return isrSignalSet(thread_id, signals);
- } else { // in Thread
- return __svcSignalSet(thread_id, signals);
- }
-}
-
-/// Clear the specified Signal Flags of an active thread
-int32_t osSignalClear (osThreadId thread_id, int32_t signals) {
- if (__get_CONTROL() == MODE_IRQ) return osErrorISR; // Not allowed in ISR
- return __svcSignalClear(thread_id, signals);
-}
-
-/// Get Signal Flags status of an active thread
-int32_t osSignalGet (osThreadId thread_id) {
- if (__get_CONTROL() == MODE_IRQ) return osErrorISR; // Not allowed in ISR
- return __svcSignalGet(thread_id);
-}
-
-/// Wait for one or more Signal Flags to become signaled for the current RUNNING thread
-os_InRegs osEvent osSignalWait (int32_t signals, uint32_t millisec) {
- osEvent ret;
-
- if (__get_CONTROL() == MODE_IRQ) { // Not allowed in ISR
- ret.status = osErrorISR;
- return ret;
- }
- return __svcSignalWait(signals, millisec);
-}
-
-
-// ==== Mutex Management ====
-
-// Mutex Service Calls declarations
-SVC_1_1(svcMutexCreate, osMutexId, osMutexDef_t *, RET_pointer)
-SVC_2_1(svcMutexWait, osStatus, osMutexId, uint32_t, RET_osStatus)
-SVC_1_1(svcMutexRelease, osStatus, osMutexId, RET_osStatus)
-SVC_1_1(svcMutexDelete, osStatus, osMutexId, RET_osStatus)
-
-// Mutex Service Calls
-
-/// Create and Initialize a Mutex object
-osMutexId svcMutexCreate (osMutexDef_t *mutex_def) {
- OS_ID mut;
-
- if (mutex_def == NULL) {
- sysThreadError(osErrorParameter);
- return NULL;
- }
-
- mut = mutex_def->mutex;
- if (mut == NULL) {
- sysThreadError(osErrorParameter);
- return NULL;
- }
-
- if (((P_MUCB)mut)->cb_type != 0) {
- sysThreadError(osErrorParameter);
- return NULL;
- }
-
- rt_mut_init(mut); // Initialize Mutex
-
- return mut;
-}
-
-/// Wait until a Mutex becomes available
-osStatus svcMutexWait (osMutexId mutex_id, uint32_t millisec) {
- OS_ID mut;
- OS_RESULT res;
-
- mut = rt_id2obj(mutex_id);
- if (mut == NULL) return osErrorParameter;
-
- if (((P_MUCB)mut)->cb_type != MUCB) return osErrorParameter;
-
- res = rt_mut_wait(mut, rt_ms2tick(millisec)); // Wait for Mutex
-
- if (res == OS_R_TMO) {
- return (millisec ? osErrorTimeoutResource : osErrorResource);
- }
-
- return osOK;
-}
-
-/// Release a Mutex that was obtained with osMutexWait
-osStatus svcMutexRelease (osMutexId mutex_id) {
- OS_ID mut;
- OS_RESULT res;
-
- mut = rt_id2obj(mutex_id);
- if (mut == NULL) return osErrorParameter;
-
- if (((P_MUCB)mut)->cb_type != MUCB) return osErrorParameter;
-
- res = rt_mut_release(mut); // Release Mutex
-
- if (res == OS_R_NOK) return osErrorResource; // Thread not owner or Zero Counter
-
- return osOK;
-}
-
-/// Delete a Mutex that was created by osMutexCreate
-osStatus svcMutexDelete (osMutexId mutex_id) {
- OS_ID mut;
-
- mut = rt_id2obj(mutex_id);
- if (mut == NULL) return osErrorParameter;
-
- if (((P_MUCB)mut)->cb_type != MUCB) return osErrorParameter;
-
- rt_mut_delete(mut); // Release Mutex
-
- return osOK;
-}
-
-
-// Mutex Public API
-
-/// Create and Initialize a Mutex object
-osMutexId osMutexCreate (osMutexDef_t *mutex_def) {
- if (__get_CONTROL() == MODE_IRQ) return NULL; // Not allowed in ISR
- if ((__get_CONTROL() == MODE_SUPERVISOR) && (os_running == 0)) {
- // Privileged and not running
- return svcMutexCreate(mutex_def);
- } else {
- return __svcMutexCreate(mutex_def);
- }
-}
-
-/// Wait until a Mutex becomes available
-osStatus osMutexWait (osMutexId mutex_id, uint32_t millisec) {
- if (__get_CONTROL() == MODE_IRQ) return osErrorISR; // Not allowed in ISR
- return __svcMutexWait(mutex_id, millisec);
-}
-
-/// Release a Mutex that was obtained with osMutexWait
-osStatus osMutexRelease (osMutexId mutex_id) {
- if (__get_CONTROL() == MODE_IRQ) return osErrorISR; // Not allowed in ISR
- return __svcMutexRelease(mutex_id);
-}
-
-/// Delete a Mutex that was created by osMutexCreate
-osStatus osMutexDelete (osMutexId mutex_id) {
- if (__get_CONTROL() == MODE_IRQ) return osErrorISR; // Not allowed in ISR
- return __svcMutexDelete(mutex_id);
-}
-
-
-// ==== Semaphore Management ====
-
-// Semaphore Service Calls declarations
-SVC_2_1(svcSemaphoreCreate, osSemaphoreId, const osSemaphoreDef_t *, int32_t, RET_pointer)
-SVC_2_1(svcSemaphoreWait, int32_t, osSemaphoreId, uint32_t, RET_int32_t)
-SVC_1_1(svcSemaphoreRelease, osStatus, osSemaphoreId, RET_osStatus)
-SVC_1_1(svcSemaphoreDelete, osStatus, osSemaphoreId, RET_osStatus)
-
-// Semaphore Service Calls
-
-/// Create and Initialize a Semaphore object
-osSemaphoreId svcSemaphoreCreate (const osSemaphoreDef_t *semaphore_def, int32_t count) {
- OS_ID sem;
-
- if (semaphore_def == NULL) {
- sysThreadError(osErrorParameter);
- return NULL;
- }
-
- sem = semaphore_def->semaphore;
- if (sem == NULL) {
- sysThreadError(osErrorParameter);
- return NULL;
- }
-
- if (((P_SCB)sem)->cb_type != 0) {
- sysThreadError(osErrorParameter);
- return NULL;
- }
-
- if (count > osFeature_Semaphore) {
- sysThreadError(osErrorValue);
- return NULL;
- }
-
- rt_sem_init(sem, count); // Initialize Semaphore
-
- return sem;
-}
-
-/// Wait until a Semaphore becomes available
-int32_t svcSemaphoreWait (osSemaphoreId semaphore_id, uint32_t millisec) {
- OS_ID sem;
- OS_RESULT res;
-
- sem = rt_id2obj(semaphore_id);
- if (sem == NULL) return -1;
-
- if (((P_SCB)sem)->cb_type != SCB) return -1;
-
- res = rt_sem_wait(sem, rt_ms2tick(millisec)); // Wait for Semaphore
-
- if (res == OS_R_TMO) return 0; // Timeout
-
- return (((P_SCB)sem)->tokens + 1);
-}
-
-/// Release a Semaphore
-osStatus svcSemaphoreRelease (osSemaphoreId semaphore_id) {
- OS_ID sem;
-
- sem = rt_id2obj(semaphore_id);
- if (sem == NULL) return osErrorParameter;
-
- if (((P_SCB)sem)->cb_type != SCB) return osErrorParameter;
-
- if (((P_SCB)sem)->tokens == osFeature_Semaphore) return osErrorResource;
-
- rt_sem_send(sem); // Release Semaphore
-
- return osOK;
-}
-
-/// Delete a Semaphore that was created by osSemaphoreCreate
-osStatus svcSemaphoreDelete (osSemaphoreId semaphore_id) {
- OS_ID sem;
-
- sem = rt_id2obj(semaphore_id);
- if (sem == NULL) return osErrorParameter;
-
- if (((P_SCB)sem)->cb_type != SCB) return osErrorParameter;
-
- rt_sem_delete(sem); // Delete Semaphore
-
- return osOK;
-}
-
-
-// Semaphore ISR Calls
-
-/// Release a Semaphore
-static __INLINE osStatus isrSemaphoreRelease (osSemaphoreId semaphore_id) {
- OS_ID sem;
-
- sem = rt_id2obj(semaphore_id);
- if (sem == NULL) return osErrorParameter;
-
- if (((P_SCB)sem)->cb_type != SCB) return osErrorParameter;
-
- if (((P_SCB)sem)->tokens == osFeature_Semaphore) return osErrorResource;
-
- isr_sem_send(sem); // Release Semaphore
-
- return osOK;
-}
-
-
-// Semaphore Public API
-
-/// Create and Initialize a Semaphore object
-osSemaphoreId osSemaphoreCreate (osSemaphoreDef_t *semaphore_def, int32_t count) {
- if (__get_CONTROL() == MODE_IRQ) return NULL; // Not allowed in ISR
- if ((__get_CONTROL() == MODE_SUPERVISOR) && (os_running == 0)) {
- // Privileged and not running
- return svcSemaphoreCreate(semaphore_def, count);
- } else {
- return __svcSemaphoreCreate(semaphore_def, count);
- }
-}
-
-/// Wait until a Semaphore becomes available
-int32_t osSemaphoreWait (osSemaphoreId semaphore_id, uint32_t millisec) {
- if (__get_CONTROL() == MODE_IRQ) return -1; // Not allowed in ISR
- return __svcSemaphoreWait(semaphore_id, millisec);
-}
-
-/// Release a Semaphore
-osStatus osSemaphoreRelease (osSemaphoreId semaphore_id) {
- if (__get_CONTROL() == MODE_IRQ) { // in ISR
- return isrSemaphoreRelease(semaphore_id);
- } else { // in Thread
- return __svcSemaphoreRelease(semaphore_id);
- }
-}
-
-/// Delete a Semaphore that was created by osSemaphoreCreate
-osStatus osSemaphoreDelete (osSemaphoreId semaphore_id) {
- if (__get_CONTROL() == MODE_IRQ) return osErrorISR; // Not allowed in ISR
- return __svcSemaphoreDelete(semaphore_id);
-}
-
-
-// ==== Memory Management Functions ====
-
-// Memory Management Helper Functions
-
-// Clear Memory Box (Zero init)
-static void rt_clr_box (void *box_mem, void *box) {
- uint32_t *p, n;
-
- if (box) {
- p = box;
- for (n = ((P_BM)box_mem)->blk_size; n; n -= 4) {
- *p++ = 0;
- }
- }
-}
-
-// Memory Management Service Calls declarations
-SVC_1_1(svcPoolCreate, osPoolId, const osPoolDef_t *, RET_pointer)
-SVC_2_1(sysPoolAlloc, void *, osPoolId, uint32_t, RET_pointer)
-SVC_2_1(sysPoolFree, osStatus, osPoolId, void *, RET_osStatus)
-
-// Memory Management Service & ISR Calls
-
-/// Create and Initialize memory pool
-osPoolId svcPoolCreate (const osPoolDef_t *pool_def) {
- uint32_t blk_sz;
-
- if ((pool_def == NULL) ||
- (pool_def->pool_sz == 0) ||
- (pool_def->item_sz == 0) ||
- (pool_def->pool == NULL)) {
- sysThreadError(osErrorParameter);
- return NULL;
- }
-
- blk_sz = (pool_def->item_sz + 3) & ~3;
-
- _init_box(pool_def->pool, sizeof(struct OS_BM) + pool_def->pool_sz * blk_sz, blk_sz);
-
- return pool_def->pool;
-}
-
-/// Allocate a memory block from a memory pool
-void *sysPoolAlloc (osPoolId pool_id, uint32_t clr) {
- void *ptr;
-
- if (pool_id == NULL) return NULL;
-
- ptr = rt_alloc_box(pool_id);
- if (clr) {
- rt_clr_box(pool_id, ptr);
- }
-
- return ptr;
-}
-
-/// Return an allocated memory block back to a specific memory pool
-osStatus sysPoolFree (osPoolId pool_id, void *block) {
- int32_t res;
-
- if (pool_id == NULL) return osErrorParameter;
-
- res = rt_free_box(pool_id, block);
- if (res != 0) return osErrorValue;
-
- return osOK;
-}
-
-
-// Memory Management Public API
-
-/// Create and Initialize memory pool
-osPoolId osPoolCreate (osPoolDef_t *pool_def) {
- if (__get_CONTROL() == MODE_IRQ) return NULL; // Not allowed in ISR
- if ((__get_CONTROL() == MODE_SUPERVISOR) && (os_running == 0)) {
- // Privileged and not running
- return svcPoolCreate(pool_def);
- } else {
- return __svcPoolCreate(pool_def);
- }
-}
-
-/// Allocate a memory block from a memory pool
-void *osPoolAlloc (osPoolId pool_id) {
- if ((__get_CONTROL() == MODE_IRQ) || (__get_CONTROL() == MODE_SUPERVISOR)) { // in ISR or Privileged
- return sysPoolAlloc(pool_id, 0);
- } else { // in Thread
- return __sysPoolAlloc(pool_id, 0);
- }
-}
-
-/// Allocate a memory block from a memory pool and set memory block to zero
-void *osPoolCAlloc (osPoolId pool_id) {
- if ((__get_CONTROL() == MODE_IRQ) || (__get_CONTROL() == MODE_SUPERVISOR)) { // in ISR or Privileged
- return sysPoolAlloc(pool_id, 1);
- } else { // in Thread
- return __sysPoolAlloc(pool_id, 1);
- }
-}
-
-/// Return an allocated memory block back to a specific memory pool
-osStatus osPoolFree (osPoolId pool_id, void *block) {
- if ((__get_CONTROL() == MODE_IRQ) || (__get_CONTROL() == MODE_SUPERVISOR)) { // in ISR or Privileged
- return sysPoolFree(pool_id, block);
- } else { // in Thread
- return __sysPoolFree(pool_id, block);
- }
-}
-
-
-// ==== Message Queue Management Functions ====
-
-// Message Queue Management Service Calls declarations
-SVC_2_1(svcMessageCreate, osMessageQId, osMessageQDef_t *, osThreadId, RET_pointer)
-SVC_3_1(svcMessagePut, osStatus, osMessageQId, uint32_t, uint32_t, RET_osStatus)
-SVC_2_3(svcMessageGet, os_InRegs osEvent, osMessageQId, uint32_t, RET_osEvent)
-
-// Message Queue Service Calls
-
-/// Create and Initialize Message Queue
-osMessageQId svcMessageCreate (osMessageQDef_t *queue_def, osThreadId thread_id) {
-
- if ((queue_def == NULL) ||
- (queue_def->queue_sz == 0) ||
- (queue_def->pool == NULL)) {
- sysThreadError(osErrorParameter);
- return NULL;
- }
-
- if (((P_MCB)queue_def->pool)->cb_type != 0) {
- sysThreadError(osErrorParameter);
- return NULL;
- }
-
- rt_mbx_init(queue_def->pool, 4*(queue_def->queue_sz + 4));
-
- return queue_def->pool;
-}
-
-/// Put a Message to a Queue
-osStatus svcMessagePut (osMessageQId queue_id, uint32_t info, uint32_t millisec) {
- OS_RESULT res;
-
- if (queue_id == NULL) return osErrorParameter;
-
- if (((P_MCB)queue_id)->cb_type != MCB) return osErrorParameter;
-
- res = rt_mbx_send(queue_id, (void *)info, rt_ms2tick(millisec));
-
- if (res == OS_R_TMO) {
- return (millisec ? osErrorTimeoutResource : osErrorResource);
- }
-
- return osOK;
-}
-
-/// Get a Message or Wait for a Message from a Queue
-os_InRegs osEvent_type svcMessageGet (osMessageQId queue_id, uint32_t millisec) {
- OS_RESULT res;
- osEvent ret;
-
- if (queue_id == NULL) {
- ret.status = osErrorParameter;
- return osEvent_ret_status;
- }
-
- if (((P_MCB)queue_id)->cb_type != MCB) {
- ret.status = osErrorParameter;
- return osEvent_ret_status;
- }
-
- res = rt_mbx_wait(queue_id, &ret.value.p, rt_ms2tick(millisec));
-
- if (res == OS_R_TMO) {
- ret.status = millisec ? osEventTimeout : osOK;
- return osEvent_ret_value;
- }
-
- ret.status = osEventMessage;
-
- return osEvent_ret_value;
-}
-
-
-// Message Queue ISR Calls
-
-/// Put a Message to a Queue
-static __INLINE osStatus isrMessagePut (osMessageQId queue_id, uint32_t info, uint32_t millisec) {
-
- if ((queue_id == NULL) || (millisec != 0)) {
- return osErrorParameter;
- }
-
- if (((P_MCB)queue_id)->cb_type != MCB) return osErrorParameter;
-
- if (rt_mbx_check(queue_id) == 0) { // Check if Queue is full
- return osErrorResource;
- }
-
- isr_mbx_send(queue_id, (void *)info);
-
- return osOK;
-}
-
-/// Get a Message or Wait for a Message from a Queue
-static __INLINE os_InRegs osEvent isrMessageGet (osMessageQId queue_id, uint32_t millisec) {
- OS_RESULT res;
- osEvent ret;
-
- if ((queue_id == NULL) || (millisec != 0)) {
- ret.status = osErrorParameter;
- return ret;
- }
-
- if (((P_MCB)queue_id)->cb_type != MCB) {
- ret.status = osErrorParameter;
- return ret;
- }
-
- res = isr_mbx_receive(queue_id, &ret.value.p);
-
- if (res != OS_R_MBX) {
- ret.status = osOK;
- return ret;
- }
-
- ret.status = osEventMessage;
-
- return ret;
-}
-
-
-// Message Queue Management Public API
-
-/// Create and Initialize Message Queue
-osMessageQId osMessageCreate (osMessageQDef_t *queue_def, osThreadId thread_id) {
- if (__get_CONTROL() == MODE_IRQ) return NULL; // Not allowed in ISR
- if ((__get_CONTROL() == MODE_SUPERVISOR) && (os_running == 0)) {
- // Privileged and not running
- return svcMessageCreate(queue_def, thread_id);
- } else {
- return __svcMessageCreate(queue_def, thread_id);
- }
-}
-
-/// Put a Message to a Queue
-osStatus osMessagePut (osMessageQId queue_id, uint32_t info, uint32_t millisec) {
- if (__get_CONTROL() == MODE_IRQ) { // in ISR
- return isrMessagePut(queue_id, info, millisec);
- } else { // in Thread
- return __svcMessagePut(queue_id, info, millisec);
- }
-}
-
-/// Get a Message or Wait for a Message from a Queue
-os_InRegs osEvent osMessageGet (osMessageQId queue_id, uint32_t millisec) {
- if (__get_CONTROL() == MODE_IRQ) { // in ISR
- return isrMessageGet(queue_id, millisec);
- } else { // in Thread
- return __svcMessageGet(queue_id, millisec);
- }
-}
-
-
-// ==== Mail Queue Management Functions ====
-
-// Mail Queue Management Service Calls declarations
-SVC_2_1(svcMailCreate, osMailQId, osMailQDef_t *, osThreadId, RET_pointer)
-SVC_4_1(sysMailAlloc, void *, osMailQId, uint32_t, uint32_t, uint32_t, RET_pointer)
-SVC_3_1(sysMailFree, osStatus, osMailQId, void *, uint32_t, RET_osStatus)
-
-// Mail Queue Management Service & ISR Calls
-
-/// Create and Initialize mail queue
-osMailQId svcMailCreate (osMailQDef_t *queue_def, osThreadId thread_id) {
- uint32_t blk_sz;
- P_MCB pmcb;
- void *pool;
-
- if ((queue_def == NULL) ||
- (queue_def->queue_sz == 0) ||
- (queue_def->item_sz == 0) ||
- (queue_def->pool == NULL)) {
- sysThreadError(osErrorParameter);
- return NULL;
- }
-
- pmcb = *(((void **)queue_def->pool) + 0);
- pool = *(((void **)queue_def->pool) + 1);
-
- if ((pool == NULL) || (pmcb == NULL) || (pmcb->cb_type != 0)) {
- sysThreadError(osErrorParameter);
- return NULL;
- }
-
- blk_sz = (queue_def->item_sz + 3) & ~3;
-
- _init_box(pool, sizeof(struct OS_BM) + queue_def->queue_sz * blk_sz, blk_sz);
-
- rt_mbx_init(pmcb, 4*(queue_def->queue_sz + 4));
-
-
- return queue_def->pool;
-}
-
-/// Allocate a memory block from a mail
-void *sysMailAlloc (osMailQId queue_id, uint32_t millisec, uint32_t isr, uint32_t clr) {
- P_MCB pmcb;
- void *pool;
- void *mem;
-
- if (queue_id == NULL) return NULL;
-
- pmcb = *(((void **)queue_id) + 0);
- pool = *(((void **)queue_id) + 1);
-
- if ((pool == NULL) || (pmcb == NULL)) return NULL;
-
- if (isr && (millisec != 0)) return NULL;
-
- mem = rt_alloc_box(pool);
- if (clr) {
- rt_clr_box(pool, mem);
- }
-
- if ((mem == NULL) && (millisec != 0)) {
- // Put Task to sleep when Memory not available
- if (pmcb->p_lnk != NULL) {
- rt_put_prio((P_XCB)pmcb, os_tsk.run);
- } else {
- pmcb->p_lnk = os_tsk.run;
- os_tsk.run->p_lnk = NULL;
- os_tsk.run->p_rlnk = (P_TCB)pmcb;
- // Task is waiting to allocate a message
- pmcb->state = 3;
- }
- rt_block(rt_ms2tick(millisec), WAIT_MBX);
- }
-
- return mem;
-}
-
-/// Free a memory block from a mail
-osStatus sysMailFree (osMailQId queue_id, void *mail, uint32_t isr) {
- P_MCB pmcb;
- P_TCB ptcb;
- void *pool;
- void *mem;
- int32_t res;
-
- if (queue_id == NULL) return osErrorParameter;
-
- pmcb = *(((void **)queue_id) + 0);
- pool = *(((void **)queue_id) + 1);
-
- if ((pmcb == NULL) || (pool == NULL)) return osErrorParameter;
-
- res = rt_free_box(pool, mail);
-
- if (res != 0) return osErrorValue;
-
- if (pmcb->state == 3) {
- // Task is waiting to allocate a message
- if (isr) {
- rt_psq_enq (pmcb, (U32)pool);
- rt_psh_req ();
- } else {
- mem = rt_alloc_box(pool);
- if (mem != NULL) {
- ptcb = rt_get_first((P_XCB)pmcb);
- if (pmcb->p_lnk == NULL) {
- pmcb->state = 0;
- }
- rt_ret_val(ptcb, (U32)mem);
- rt_rmv_dly(ptcb);
- rt_dispatch(ptcb);
- }
- }
- }
-
- return osOK;
-}
-
-
-// Mail Queue Management Public API
-
-/// Create and Initialize mail queue
-osMailQId osMailCreate (osMailQDef_t *queue_def, osThreadId thread_id) {
- if (__get_CONTROL() == MODE_IRQ) return NULL; // Not allowed in ISR
- if ((__get_CONTROL() == MODE_SUPERVISOR) && (os_running == 0)) {
- // Privileged and not running
- return svcMailCreate(queue_def, thread_id);
- } else {
- return __svcMailCreate(queue_def, thread_id);
- }
-}
-
-/// Allocate a memory block from a mail
-void *osMailAlloc (osMailQId queue_id, uint32_t millisec) {
- if (__get_CONTROL() == MODE_IRQ) { // in ISR
- return sysMailAlloc(queue_id, millisec, 1, 0);
- } else { // in Thread
- return __sysMailAlloc(queue_id, millisec, 0, 0);
- }
-}
-
-/// Allocate a memory block from a mail and set memory block to zero
-void *osMailCAlloc (osMailQId queue_id, uint32_t millisec) {
- if (__get_CONTROL() == MODE_IRQ) { // in ISR
- return sysMailAlloc(queue_id, millisec, 1, 1);
- } else { // in Thread
- return __sysMailAlloc(queue_id, millisec, 0, 1);
- }
-}
-
-/// Free a memory block from a mail
-osStatus osMailFree (osMailQId queue_id, void *mail) {
- if (__get_CONTROL() == MODE_IRQ) { // in ISR
- return sysMailFree(queue_id, mail, 1);
- } else { // in Thread
- return __sysMailFree(queue_id, mail, 0);
- }
-}
-
-/// Put a mail to a queue
-osStatus osMailPut (osMailQId queue_id, void *mail) {
- if (queue_id == NULL) return osErrorParameter;
- if (mail == NULL) return osErrorValue;
- return osMessagePut(*((void **)queue_id), (uint32_t)mail, 0);
-}
-
-/// Get a mail from a queue
-os_InRegs osEvent osMailGet (osMailQId queue_id, uint32_t millisec) {
- osEvent ret;
-
- if (queue_id == NULL) {
- ret.status = osErrorParameter;
- return ret;
- }
-
- ret = osMessageGet(*((void **)queue_id), millisec);
- if (ret.status == osEventMessage) ret.status = osEventMail;
-
- return ret;
-}
diff --git a/rtos/rtx/TARGET_ARM7/rt_Event.c b/rtos/rtx/TARGET_ARM7/rt_Event.c
deleted file mode 100644
index 871e4b0f8a..0000000000
--- a/rtos/rtx/TARGET_ARM7/rt_Event.c
+++ /dev/null
@@ -1,190 +0,0 @@
-/*----------------------------------------------------------------------------
- * RL-ARM - RTX
- *----------------------------------------------------------------------------
- * Name: RT_EVENT.C
- * Purpose: Implements waits and wake-ups for event flags
- * Rev.: V4.60
- *----------------------------------------------------------------------------
- *
- * Copyright (c) 1999-2009 KEIL, 2009-2015 ARM Germany GmbH
- * All rights reserved.
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- * - Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * - 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.
- * - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
- *---------------------------------------------------------------------------*/
-
-#include "rt_TypeDef.h"
-#include "RTX_Conf.h"
-#include "rt_System.h"
-#include "rt_Event.h"
-#include "rt_List.h"
-#include "rt_Task.h"
-#include "rt_HAL_CM.h"
-
-
-/*----------------------------------------------------------------------------
- * Functions
- *---------------------------------------------------------------------------*/
-
-
-/*--------------------------- rt_evt_wait -----------------------------------*/
-
-OS_RESULT rt_evt_wait (U16 wait_flags, U16 timeout, BOOL and_wait) {
- /* Wait for one or more event flags with optional time-out. */
- /* "wait_flags" identifies the flags to wait for. */
- /* "timeout" is the time-out limit in system ticks (0xffff if no time-out) */
- /* "and_wait" specifies the AND-ing of "wait_flags" as condition to be met */
- /* to complete the wait. (OR-ing if set to 0). */
- U32 block_state;
-
- if (and_wait) {
- /* Check for AND-connected events */
- if ((os_tsk.run->events & wait_flags) == wait_flags) {
- os_tsk.run->events &= ~wait_flags;
- return (OS_R_EVT);
- }
- block_state = WAIT_AND;
- }
- else {
- /* Check for OR-connected events */
- if (os_tsk.run->events & wait_flags) {
- os_tsk.run->waits = os_tsk.run->events & wait_flags;
- os_tsk.run->events &= ~wait_flags;
- return (OS_R_EVT);
- }
- block_state = WAIT_OR;
- }
- /* Task has to wait */
- os_tsk.run->waits = wait_flags;
- rt_block (timeout, (U8)block_state);
- return (OS_R_TMO);
-}
-
-
-/*--------------------------- rt_evt_set ------------------------------------*/
-
-void rt_evt_set (U16 event_flags, OS_TID task_id) {
- /* Set one or more event flags of a selectable task. */
- P_TCB p_tcb;
-
- p_tcb = os_active_TCB[task_id-1];
- if (p_tcb == NULL) {
- return;
- }
- p_tcb->events |= event_flags;
- event_flags = p_tcb->waits;
- /* If the task is not waiting for an event, it should not be put */
- /* to ready state. */
- if (p_tcb->state == WAIT_AND) {
- /* Check for AND-connected events */
- if ((p_tcb->events & event_flags) == event_flags) {
- goto wkup;
- }
- }
- if (p_tcb->state == WAIT_OR) {
- /* Check for OR-connected events */
- if (p_tcb->events & event_flags) {
- p_tcb->waits &= p_tcb->events;
-wkup: p_tcb->events &= ~event_flags;
- rt_rmv_dly (p_tcb);
- p_tcb->state = READY;
-#ifdef __CMSIS_RTOS
- rt_ret_val2(p_tcb, 0x08/*osEventSignal*/, p_tcb->waits);
-#else
- rt_ret_val (p_tcb, OS_R_EVT);
-#endif
- rt_dispatch (p_tcb);
- }
- }
-}
-
-
-/*--------------------------- rt_evt_clr ------------------------------------*/
-
-void rt_evt_clr (U16 clear_flags, OS_TID task_id) {
- /* Clear one or more event flags (identified by "clear_flags") of a */
- /* selectable task (identified by "task"). */
- P_TCB task = os_active_TCB[task_id-1];
-
- if (task == NULL) {
- return;
- }
- task->events &= ~clear_flags;
-}
-
-
-/*--------------------------- isr_evt_set -----------------------------------*/
-
-void isr_evt_set (U16 event_flags, OS_TID task_id) {
- /* Same function as "os_evt_set", but to be called by ISRs. */
- P_TCB p_tcb = os_active_TCB[task_id-1];
-
- if (p_tcb == NULL) {
- return;
- }
- rt_psq_enq (p_tcb, event_flags);
- rt_psh_req ();
-}
-
-
-/*--------------------------- rt_evt_get ------------------------------------*/
-
-U16 rt_evt_get (void) {
- /* Get events of a running task after waiting for OR connected events. */
- return (os_tsk.run->waits);
-}
-
-
-/*--------------------------- rt_evt_psh ------------------------------------*/
-
-void rt_evt_psh (P_TCB p_CB, U16 set_flags) {
- /* Check if task has to be waken up */
- U16 event_flags;
-
- p_CB->events |= set_flags;
- event_flags = p_CB->waits;
- if (p_CB->state == WAIT_AND) {
- /* Check for AND-connected events */
- if ((p_CB->events & event_flags) == event_flags) {
- goto rdy;
- }
- }
- if (p_CB->state == WAIT_OR) {
- /* Check for OR-connected events */
- if (p_CB->events & event_flags) {
- p_CB->waits &= p_CB->events;
-rdy: p_CB->events &= ~event_flags;
- rt_rmv_dly (p_CB);
- p_CB->state = READY;
-#ifdef __CMSIS_RTOS
- rt_ret_val2(p_CB, 0x08/*osEventSignal*/, p_CB->waits);
-#else
- rt_ret_val (p_CB, OS_R_EVT);
-#endif
- rt_put_prio (&os_rdy, p_CB);
- }
- }
-}
-
-/*----------------------------------------------------------------------------
- * end of file
- *---------------------------------------------------------------------------*/
diff --git a/rtos/rtx/TARGET_ARM7/rt_Event.h b/rtos/rtx/TARGET_ARM7/rt_Event.h
deleted file mode 100644
index 9118c4faac..0000000000
--- a/rtos/rtx/TARGET_ARM7/rt_Event.h
+++ /dev/null
@@ -1,46 +0,0 @@
-/*----------------------------------------------------------------------------
- * RL-ARM - RTX
- *----------------------------------------------------------------------------
- * Name: RT_EVENT.H
- * Purpose: Implements waits and wake-ups for event flags
- * Rev.: V4.60
- *----------------------------------------------------------------------------
- *
- * Copyright (c) 1999-2009 KEIL, 2009-2015 ARM Germany GmbH
- * All rights reserved.
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- * - Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * - 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.
- * - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
- *---------------------------------------------------------------------------*/
-
-/* Functions */
-extern OS_RESULT rt_evt_wait (U16 wait_flags, U16 timeout, BOOL and_wait);
-extern void rt_evt_set (U16 event_flags, OS_TID task_id);
-extern void rt_evt_clr (U16 clear_flags, OS_TID task_id);
-extern void isr_evt_set (U16 event_flags, OS_TID task_id);
-extern U16 rt_evt_get (void);
-extern void rt_evt_psh (P_TCB p_CB, U16 set_flags);
-
-/*----------------------------------------------------------------------------
- * end of file
- *---------------------------------------------------------------------------*/
-
diff --git a/rtos/rtx/TARGET_ARM7/rt_HAL_CM.h b/rtos/rtx/TARGET_ARM7/rt_HAL_CM.h
deleted file mode 100644
index b6a1907eb5..0000000000
--- a/rtos/rtx/TARGET_ARM7/rt_HAL_CM.h
+++ /dev/null
@@ -1,216 +0,0 @@
-/*----------------------------------------------------------------------------
- * RL-ARM - RTX
- *----------------------------------------------------------------------------
- * Name: RT_HAL_CM.H
- * Purpose: Hardware Abstraction Layer for Cortex-M definitions
- * Rev.: V4.60
- *----------------------------------------------------------------------------
- *
- * Copyright (c) 1999-2009 KEIL, 2009-2015 ARM Germany GmbH
- * All rights reserved.
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- * - Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * - 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.
- * - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
- *---------------------------------------------------------------------------*/
-
-#include "cmsis.h"
-/* Definitions */
-#define INITIAL_xPSR 0x10000000
-#define DEMCR_TRCENA 0x01000000
-#define ITM_ITMENA 0x00000001
-#define MAGIC_WORD 0xE25A2EA5
-
-#define SYS_TICK_IRQn TIMER0_IRQn
-
-extern void rt_set_PSP (U32 stack);
-extern U32 rt_get_PSP (void);
-extern void os_set_env (void);
-extern void SysTick_Handler (void);
-extern void *_alloc_box (void *box_mem);
-extern int _free_box (void *box_mem, void *box);
-
-extern void rt_init_stack (P_TCB p_TCB, FUNCP task_body);
-extern void rt_ret_val (P_TCB p_TCB, U32 v0);
-extern void rt_ret_val2 (P_TCB p_TCB, U32 v0, U32 v1);
-
-extern void dbg_init (void);
-extern void dbg_task_notify (P_TCB p_tcb, BOOL create);
-extern void dbg_task_switch (U32 task_id);
-
-
-#if defined (__CC_ARM) /* ARM Compiler */
-
-#if ((__TARGET_ARCH_7_M || __TARGET_ARCH_7E_M) && !NO_EXCLUSIVE_ACCESS)
- #define __USE_EXCLUSIVE_ACCESS
-#else
- #undef __USE_EXCLUSIVE_ACCESS
-#endif
-
-#elif defined (__GNUC__) /* GNU Compiler */
-
-#undef __USE_EXCLUSIVE_ACCESS
-
-#if defined (__CORTEX_M0) || defined (__CORTEX_M0PLUS)
-#define __TARGET_ARCH_6S_M 1
-#else
-#define __TARGET_ARCH_6S_M 0
-#endif
-
-#if defined (__VFP_FP__) && !defined(__SOFTFP__)
-#define __TARGET_FPU_VFP 1
-#else
-#define __TARGET_FPU_VFP 0
-#endif
-
-#define __inline inline
-#define __weak __attribute__((weak))
-
-
-#elif defined (__ICCARM__) /* IAR Compiler */
-
-#undef __USE_EXCLUSIVE_ACCESS
-
-#if (__CORE__ == __ARM6M__)
-#define __TARGET_ARCH_6S_M 1
-#else
-#define __TARGET_ARCH_6S_M 0
-#endif
-
-#if defined __ARMVFP__
-#define __TARGET_FPU_VFP 1
-#else
-#define __TARGET_FPU_VFP 0
-#endif
-
-#define __inline inline
-
-#endif
-
-
-/* NVIC registers */
-
-#define OS_PEND_IRQ() NVIC_PendIRQ(SYS_TICK_IRQn)
-#define OS_PENDING NVIC_PendingIRQ(SYS_TICK_IRQn)
-#define OS_UNPEND(fl) NVIC_UnpendIRQ(SYS_TICK_IRQn)
-#define OS_PEND(fl,p) NVIC_PendIRQ(SYS_TICK_IRQn)
-#define OS_LOCK() NVIC_DisableIRQ(SYS_TICK_IRQn)
-#define OS_UNLOCK() NVIC_EnableIRQ(SYS_TICK_IRQn)
-
-#define OS_X_PENDING NVIC_PendingIRQ(SYS_TICK_IRQn)
-#define OS_X_UNPEND(fl) NVIC_UnpendIRQ(SYS_TICK_IRQn)
-#define OS_X_PEND(fl,p) NVIC_PendIRQ(SYS_TICK_IRQn)
-
-#define OS_X_INIT(n) NVIC_EnableIRQ(n)
-#define OS_X_LOCK(n) NVIC_DisableIRQ(n)
-#define OS_X_UNLOCK(n) NVIC_EnableIRQ(n)
-
-/* Variables */
-extern BIT dbg_msg;
-
-/* Functions */
-#ifdef __USE_EXCLUSIVE_ACCESS
- #define rt_inc(p) while(__strex((__ldrex(p)+1),p))
- #define rt_dec(p) while(__strex((__ldrex(p)-1),p))
-#else
- #define rt_inc(p) __disable_irq();(*p)++;__enable_irq();
- #define rt_dec(p) __disable_irq();(*p)--;__enable_irq();
-#endif
-
-__inline static U32 rt_inc_qi (U32 size, U8 *count, U8 *first) {
- U32 cnt,c2;
-#ifdef __USE_EXCLUSIVE_ACCESS
- do {
- if ((cnt = __ldrex(count)) == size) {
- __clrex();
- return (cnt); }
- } while (__strex(cnt+1, count));
- do {
- c2 = (cnt = __ldrex(first)) + 1;
- if (c2 == size) c2 = 0;
- } while (__strex(c2, first));
-#else
- __disable_irq();
- if ((cnt = *count) < size) {
- *count = cnt+1;
- c2 = (cnt = *first) + 1;
- if (c2 == size) c2 = 0;
- *first = c2;
- }
- __enable_irq ();
-#endif
- return (cnt);
-}
-
-__inline static void rt_systick_init (void) {
-#if SYS_TICK_IRQn == TIMER0_IRQn
- #define SYS_TICK_TIMER LPC_TIM0
- LPC_SC->PCONP |= (1 << PCTIM0);
- LPC_SC->PCLKSEL0 = (LPC_SC->PCLKSEL0 & (~(1<<3))) | (1<<2); //PCLK == CPUCLK
-#elif SYS_TICK_IRQn == TIMER1_IRQn
- #define SYS_TICK_TIMER LPC_TIM1
- LPC_SC->PCONP |= (1 << PCTIM1);
- LPC_SC->PCLKSEL0 = (LPC_SC->PCLKSEL0 & (~(1<<5))) | (1<<4); //PCLK == CPUCLK
-#elif SYS_TICK_IRQn == TIMER2_IRQn
- #define SYS_TICK_TIMER LPC_TIM2
- LPC_SC->PCONP |= (1 << PCTIM2);
- LPC_SC->PCLKSEL1 = (LPC_SC->PCLKSEL1 & (~(1<<13))) | (1<<12); //PCLK == CPUCLK
-#else
- #define SYS_TICK_TIMER LPC_TIM3
- LPC_SC->PCONP |= (1 << PCTIM3);
- LPC_SC->PCLKSEL1 = (LPC_SC->PCLKSEL1 & (~(1<<15))) | (1<<14); //PCLK == CPUCLK
-#endif
-
- // setup Timer to count forever
- //interrupt_reg
- SYS_TICK_TIMER->TCR = 2; // reset & disable timer 0
- SYS_TICK_TIMER->TC = os_trv;
- SYS_TICK_TIMER->PR = 0; // set the prescale divider
- //Reset of TC and Interrupt when MR3 MR2 matches TC
- SYS_TICK_TIMER->MCR = (1 << 9) |(1 << 10); //TMCR_MR3_R_Msk | TMCR_MR3_I_Msk
- SYS_TICK_TIMER->MR3 = os_trv; // match registers
- SYS_TICK_TIMER->CCR = 0; // disable compare registers
- SYS_TICK_TIMER->EMR = 0; // disable external match register
- // initialize the interrupt vector
- NVIC_SetVector(SYS_TICK_IRQn, (uint32_t)&SysTick_Handler);
- SYS_TICK_TIMER->TCR = 1; // enable timer 0
-}
-
-__inline static void rt_svc_init (void) {
-// TODO: add svcInit
-
-}
-
-#ifdef DBG_MSG
-#define DBG_INIT() dbg_init()
-#define DBG_TASK_NOTIFY(p_tcb,create) if (dbg_msg) dbg_task_notify(p_tcb,create)
-#define DBG_TASK_SWITCH(task_id) if (dbg_msg && (os_tsk.new_tsk != os_tsk.run)) \
- dbg_task_switch(task_id)
-#else
-#define DBG_INIT()
-#define DBG_TASK_NOTIFY(p_tcb,create)
-#define DBG_TASK_SWITCH(task_id)
-#endif
-
-/*----------------------------------------------------------------------------
- * end of file
- *---------------------------------------------------------------------------*/
-
diff --git a/rtos/rtx/TARGET_ARM7/rt_List.c b/rtos/rtx/TARGET_ARM7/rt_List.c
deleted file mode 100644
index 06b5a8928a..0000000000
--- a/rtos/rtx/TARGET_ARM7/rt_List.c
+++ /dev/null
@@ -1,320 +0,0 @@
-/*----------------------------------------------------------------------------
- * RL-ARM - RTX
- *----------------------------------------------------------------------------
- * Name: RT_LIST.C
- * Purpose: Functions for the management of different lists
- * Rev.: V4.60
- *----------------------------------------------------------------------------
- *
- * Copyright (c) 1999-2009 KEIL, 2009-2015 ARM Germany GmbH
- * All rights reserved.
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- * - Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * - 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.
- * - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
- *---------------------------------------------------------------------------*/
-
-#include "rt_TypeDef.h"
-#include "RTX_Conf.h"
-#include "rt_System.h"
-#include "rt_List.h"
-#include "rt_Task.h"
-#include "rt_Time.h"
-#include "rt_HAL_CM.h"
-
-/*----------------------------------------------------------------------------
- * Global Variables
- *---------------------------------------------------------------------------*/
-
-/* List head of chained ready tasks */
-struct OS_XCB os_rdy;
-/* List head of chained delay tasks */
-struct OS_XCB os_dly;
-
-
-/*----------------------------------------------------------------------------
- * Functions
- *---------------------------------------------------------------------------*/
-
-
-/*--------------------------- rt_put_prio -----------------------------------*/
-
-void rt_put_prio (P_XCB p_CB, P_TCB p_task) {
- /* Put task identified with "p_task" into list ordered by priority. */
- /* "p_CB" points to head of list; list has always an element at end with */
- /* a priority less than "p_task->prio". */
- P_TCB p_CB2;
- U32 prio;
- BOOL sem_mbx = __FALSE;
-
- if (p_CB->cb_type == SCB || p_CB->cb_type == MCB || p_CB->cb_type == MUCB) {
- sem_mbx = __TRUE;
- }
- prio = p_task->prio;
- p_CB2 = p_CB->p_lnk;
- /* Search for an entry in the list */
- while (p_CB2 != NULL && prio <= p_CB2->prio) {
- p_CB = (P_XCB)p_CB2;
- p_CB2 = p_CB2->p_lnk;
- }
- /* Entry found, insert the task into the list */
- p_task->p_lnk = p_CB2;
- p_CB->p_lnk = p_task;
- if (sem_mbx) {
- if (p_CB2 != NULL) {
- p_CB2->p_rlnk = p_task;
- }
- p_task->p_rlnk = (P_TCB)p_CB;
- }
- else {
- p_task->p_rlnk = NULL;
- }
-}
-
-
-/*--------------------------- rt_get_first ----------------------------------*/
-
-P_TCB rt_get_first (P_XCB p_CB) {
- /* Get task at head of list: it is the task with highest priority. */
- /* "p_CB" points to head of list. */
- P_TCB p_first;
-
- p_first = p_CB->p_lnk;
- p_CB->p_lnk = p_first->p_lnk;
- if (p_CB->cb_type == SCB || p_CB->cb_type == MCB || p_CB->cb_type == MUCB) {
- if (p_first->p_lnk != NULL) {
- p_first->p_lnk->p_rlnk = (P_TCB)p_CB;
- p_first->p_lnk = NULL;
- }
- p_first->p_rlnk = NULL;
- }
- else {
- p_first->p_lnk = NULL;
- }
- return (p_first);
-}
-
-
-/*--------------------------- rt_put_rdy_first ------------------------------*/
-
-void rt_put_rdy_first (P_TCB p_task) {
- /* Put task identified with "p_task" at the head of the ready list. The */
- /* task must have at least a priority equal to highest priority in list. */
- p_task->p_lnk = os_rdy.p_lnk;
- p_task->p_rlnk = NULL;
- os_rdy.p_lnk = p_task;
-}
-
-
-/*--------------------------- rt_get_same_rdy_prio --------------------------*/
-
-P_TCB rt_get_same_rdy_prio (void) {
- /* Remove a task of same priority from ready list if any exists. Other- */
- /* wise return NULL. */
- P_TCB p_first;
-
- p_first = os_rdy.p_lnk;
- if (p_first->prio == os_tsk.run->prio) {
- os_rdy.p_lnk = os_rdy.p_lnk->p_lnk;
- return (p_first);
- }
- return (NULL);
-}
-
-
-/*--------------------------- rt_resort_prio --------------------------------*/
-
-void rt_resort_prio (P_TCB p_task) {
- /* Re-sort ordered lists after the priority of 'p_task' has changed. */
- P_TCB p_CB;
-
- if (p_task->p_rlnk == NULL) {
- if (p_task->state == READY) {
- /* Task is chained into READY list. */
- p_CB = (P_TCB)&os_rdy;
- goto res;
- }
- }
- else {
- p_CB = p_task->p_rlnk;
- while (p_CB->cb_type == TCB) {
- /* Find a header of this task chain list. */
- p_CB = p_CB->p_rlnk;
- }
-res:rt_rmv_list (p_task);
- rt_put_prio ((P_XCB)p_CB, p_task);
- }
-}
-
-
-/*--------------------------- rt_put_dly ------------------------------------*/
-
-void rt_put_dly (P_TCB p_task, U16 delay) {
- /* Put a task identified with "p_task" into chained delay wait list using */
- /* a delay value of "delay". */
- P_TCB p;
- U32 delta,idelay = delay;
-
- p = (P_TCB)&os_dly;
- if (p->p_dlnk == NULL) {
- /* Delay list empty */
- delta = 0;
- goto last;
- }
- delta = os_dly.delta_time;
- while (delta < idelay) {
- if (p->p_dlnk == NULL) {
- /* End of list found */
-last: p_task->p_dlnk = NULL;
- p->p_dlnk = p_task;
- p_task->p_blnk = p;
- p->delta_time = (U16)(idelay - delta);
- p_task->delta_time = 0;
- return;
- }
- p = p->p_dlnk;
- delta += p->delta_time;
- }
- /* Right place found */
- p_task->p_dlnk = p->p_dlnk;
- p->p_dlnk = p_task;
- p_task->p_blnk = p;
- if (p_task->p_dlnk != NULL) {
- p_task->p_dlnk->p_blnk = p_task;
- }
- p_task->delta_time = (U16)(delta - idelay);
- p->delta_time -= p_task->delta_time;
-}
-
-
-/*--------------------------- rt_dec_dly ------------------------------------*/
-
-void rt_dec_dly (void) {
- /* Decrement delta time of list head: remove tasks having a value of zero.*/
- P_TCB p_rdy;
-
- if (os_dly.p_dlnk == NULL) {
- return;
- }
- os_dly.delta_time--;
- while ((os_dly.delta_time == 0) && (os_dly.p_dlnk != NULL)) {
- p_rdy = os_dly.p_dlnk;
- if (p_rdy->p_rlnk != NULL) {
- /* Task is really enqueued, remove task from semaphore/mailbox */
- /* timeout waiting list. */
- p_rdy->p_rlnk->p_lnk = p_rdy->p_lnk;
- if (p_rdy->p_lnk != NULL) {
- p_rdy->p_lnk->p_rlnk = p_rdy->p_rlnk;
- p_rdy->p_lnk = NULL;
- }
- p_rdy->p_rlnk = NULL;
- }
- rt_put_prio (&os_rdy, p_rdy);
- os_dly.delta_time = p_rdy->delta_time;
- if (p_rdy->state == WAIT_ITV) {
- /* Calculate the next time for interval wait. */
- p_rdy->delta_time = p_rdy->interval_time + (U16)os_time;
- }
- p_rdy->state = READY;
- os_dly.p_dlnk = p_rdy->p_dlnk;
- if (p_rdy->p_dlnk != NULL) {
- p_rdy->p_dlnk->p_blnk = (P_TCB)&os_dly;
- p_rdy->p_dlnk = NULL;
- }
- p_rdy->p_blnk = NULL;
- }
-}
-
-
-/*--------------------------- rt_rmv_list -----------------------------------*/
-
-void rt_rmv_list (P_TCB p_task) {
- /* Remove task identified with "p_task" from ready, semaphore or mailbox */
- /* waiting list if enqueued. */
- P_TCB p_b;
-
- if (p_task->p_rlnk != NULL) {
- /* A task is enqueued in semaphore / mailbox waiting list. */
- p_task->p_rlnk->p_lnk = p_task->p_lnk;
- if (p_task->p_lnk != NULL) {
- p_task->p_lnk->p_rlnk = p_task->p_rlnk;
- }
- return;
- }
-
- p_b = (P_TCB)&os_rdy;
- while (p_b != NULL) {
- /* Search the ready list for task "p_task" */
- if (p_b->p_lnk == p_task) {
- p_b->p_lnk = p_task->p_lnk;
- return;
- }
- p_b = p_b->p_lnk;
- }
-}
-
-
-/*--------------------------- rt_rmv_dly ------------------------------------*/
-
-void rt_rmv_dly (P_TCB p_task) {
- /* Remove task identified with "p_task" from delay list if enqueued. */
- P_TCB p_b;
-
- p_b = p_task->p_blnk;
- if (p_b != NULL) {
- /* Task is really enqueued */
- p_b->p_dlnk = p_task->p_dlnk;
- if (p_task->p_dlnk != NULL) {
- /* 'p_task' is in the middle of list */
- p_b->delta_time += p_task->delta_time;
- p_task->p_dlnk->p_blnk = p_b;
- p_task->p_dlnk = NULL;
- }
- else {
- /* 'p_task' is at the end of list */
- p_b->delta_time = 0;
- }
- p_task->p_blnk = NULL;
- }
-}
-
-
-/*--------------------------- rt_psq_enq ------------------------------------*/
-
-void rt_psq_enq (OS_ID entry, U32 arg) {
- /* Insert post service request "entry" into ps-queue. */
- U32 idx;
-
- idx = rt_inc_qi (os_psq->size, &os_psq->count, &os_psq->first);
- if (idx < os_psq->size) {
- os_psq->q[idx].id = entry;
- os_psq->q[idx].arg = arg;
- }
- else {
- os_error (OS_ERR_FIFO_OVF);
- }
-}
-
-
-/*----------------------------------------------------------------------------
- * end of file
- *---------------------------------------------------------------------------*/
-
diff --git a/rtos/rtx/TARGET_ARM7/rt_List.h b/rtos/rtx/TARGET_ARM7/rt_List.h
deleted file mode 100644
index 385123b470..0000000000
--- a/rtos/rtx/TARGET_ARM7/rt_List.h
+++ /dev/null
@@ -1,67 +0,0 @@
-/*----------------------------------------------------------------------------
- * RL-ARM - RTX
- *----------------------------------------------------------------------------
- * Name: RT_LIST.H
- * Purpose: Functions for the management of different lists
- * Rev.: V4.60
- *----------------------------------------------------------------------------
- *
- * Copyright (c) 1999-2009 KEIL, 2009-2015 ARM Germany GmbH
- * All rights reserved.
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- * - Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * - 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.
- * - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
- *---------------------------------------------------------------------------*/
-
-/* Definitions */
-
-/* Values for 'cb_type' */
-#define TCB 0
-#define MCB 1
-#define SCB 2
-#define MUCB 3
-#define HCB 4
-
-/* Variables */
-extern struct OS_XCB os_rdy;
-extern struct OS_XCB os_dly;
-
-/* Functions */
-extern void rt_put_prio (P_XCB p_CB, P_TCB p_task);
-extern P_TCB rt_get_first (P_XCB p_CB);
-extern void rt_put_rdy_first (P_TCB p_task);
-extern P_TCB rt_get_same_rdy_prio (void);
-extern void rt_resort_prio (P_TCB p_task);
-extern void rt_put_dly (P_TCB p_task, U16 delay);
-extern void rt_dec_dly (void);
-extern void rt_rmv_list (P_TCB p_task);
-extern void rt_rmv_dly (P_TCB p_task);
-extern void rt_psq_enq (OS_ID entry, U32 arg);
-
-/* This is a fast macro generating in-line code */
-#define rt_rdy_prio(void) (os_rdy.p_lnk->prio)
-
-
-/*----------------------------------------------------------------------------
- * end of file
- *---------------------------------------------------------------------------*/
-
diff --git a/rtos/rtx/TARGET_ARM7/rt_Mailbox.c b/rtos/rtx/TARGET_ARM7/rt_Mailbox.c
deleted file mode 100644
index b351bd1951..0000000000
--- a/rtos/rtx/TARGET_ARM7/rt_Mailbox.c
+++ /dev/null
@@ -1,292 +0,0 @@
-/*----------------------------------------------------------------------------
- * RL-ARM - RTX
- *----------------------------------------------------------------------------
- * Name: RT_MAILBOX.C
- * Purpose: Implements waits and wake-ups for mailbox messages
- * Rev.: V4.60
- *----------------------------------------------------------------------------
- *
- * Copyright (c) 1999-2009 KEIL, 2009-2015 ARM Germany GmbH
- * All rights reserved.
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- * - Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * - 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.
- * - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
- *---------------------------------------------------------------------------*/
-
-#include "rt_TypeDef.h"
-#include "RTX_Conf.h"
-#include "rt_System.h"
-#include "rt_List.h"
-#include "rt_Mailbox.h"
-#include "rt_MemBox.h"
-#include "rt_Task.h"
-#include "rt_HAL_CM.h"
-
-
-/*----------------------------------------------------------------------------
- * Functions
- *---------------------------------------------------------------------------*/
-
-
-/*--------------------------- rt_mbx_init -----------------------------------*/
-
-void rt_mbx_init (OS_ID mailbox, U16 mbx_size) {
- /* Initialize a mailbox */
- P_MCB p_MCB = mailbox;
-
- p_MCB->cb_type = MCB;
- p_MCB->state = 0;
- p_MCB->isr_st = 0;
- p_MCB->p_lnk = NULL;
- p_MCB->first = 0;
- p_MCB->last = 0;
- p_MCB->count = 0;
- p_MCB->size = (mbx_size + sizeof(void *) - sizeof(struct OS_MCB)) /
- (U32)sizeof (void *);
-}
-
-
-/*--------------------------- rt_mbx_send -----------------------------------*/
-
-OS_RESULT rt_mbx_send (OS_ID mailbox, void *p_msg, U16 timeout) {
- /* Send message to a mailbox */
- P_MCB p_MCB = mailbox;
- P_TCB p_TCB;
-
- if ((p_MCB->p_lnk != NULL) && (p_MCB->state == 1)) {
- /* A task is waiting for message */
- p_TCB = rt_get_first ((P_XCB)p_MCB);
-#ifdef __CMSIS_RTOS
- rt_ret_val2(p_TCB, 0x10/*osEventMessage*/, (U32)p_msg);
-#else
- *p_TCB->msg = p_msg;
- rt_ret_val (p_TCB, OS_R_MBX);
-#endif
- rt_rmv_dly (p_TCB);
- rt_dispatch (p_TCB);
- }
- else {
- /* Store message in mailbox queue */
- if (p_MCB->count == p_MCB->size) {
- /* No free message entry, wait for one. If message queue is full, */
- /* then no task is waiting for message. The 'p_MCB->p_lnk' list */
- /* pointer can now be reused for send message waits task list. */
- if (timeout == 0) {
- return (OS_R_TMO);
- }
- if (p_MCB->p_lnk != NULL) {
- rt_put_prio ((P_XCB)p_MCB, os_tsk.run);
- }
- else {
- p_MCB->p_lnk = os_tsk.run;
- os_tsk.run->p_lnk = NULL;
- os_tsk.run->p_rlnk = (P_TCB)p_MCB;
- /* Task is waiting to send a message */
- p_MCB->state = 2;
- }
- os_tsk.run->msg = p_msg;
- rt_block (timeout, WAIT_MBX);
- return (OS_R_TMO);
- }
- /* Yes, there is a free entry in a mailbox. */
- p_MCB->msg[p_MCB->first] = p_msg;
- rt_inc (&p_MCB->count);
- if (++p_MCB->first == p_MCB->size) {
- p_MCB->first = 0;
- }
- }
- return (OS_R_OK);
-}
-
-
-/*--------------------------- rt_mbx_wait -----------------------------------*/
-
-OS_RESULT rt_mbx_wait (OS_ID mailbox, void **message, U16 timeout) {
- /* Receive a message; possibly wait for it */
- P_MCB p_MCB = mailbox;
- P_TCB p_TCB;
-
- /* If a message is available in the fifo buffer */
- /* remove it from the fifo buffer and return. */
- if (p_MCB->count) {
- *message = p_MCB->msg[p_MCB->last];
- if (++p_MCB->last == p_MCB->size) {
- p_MCB->last = 0;
- }
- if ((p_MCB->p_lnk != NULL) && (p_MCB->state == 2)) {
- /* A task is waiting to send message */
- p_TCB = rt_get_first ((P_XCB)p_MCB);
-#ifdef __CMSIS_RTOS
- rt_ret_val(p_TCB, 0/*osOK*/);
-#else
- rt_ret_val(p_TCB, OS_R_OK);
-#endif
- p_MCB->msg[p_MCB->first] = p_TCB->msg;
- if (++p_MCB->first == p_MCB->size) {
- p_MCB->first = 0;
- }
- rt_rmv_dly (p_TCB);
- rt_dispatch (p_TCB);
- }
- else {
- rt_dec (&p_MCB->count);
- }
- return (OS_R_OK);
- }
- /* No message available: wait for one */
- if (timeout == 0) {
- return (OS_R_TMO);
- }
- if (p_MCB->p_lnk != NULL) {
- rt_put_prio ((P_XCB)p_MCB, os_tsk.run);
- }
- else {
- p_MCB->p_lnk = os_tsk.run;
- os_tsk.run->p_lnk = NULL;
- os_tsk.run->p_rlnk = (P_TCB)p_MCB;
- /* Task is waiting to receive a message */
- p_MCB->state = 1;
- }
- rt_block(timeout, WAIT_MBX);
-#ifndef __CMSIS_RTOS
- os_tsk.run->msg = message;
-#endif
- return (OS_R_TMO);
-}
-
-
-/*--------------------------- rt_mbx_check ----------------------------------*/
-
-OS_RESULT rt_mbx_check (OS_ID mailbox) {
- /* Check for free space in a mailbox. Returns the number of messages */
- /* that can be stored to a mailbox. It returns 0 when mailbox is full. */
- P_MCB p_MCB = mailbox;
-
- return (p_MCB->size - p_MCB->count);
-}
-
-
-/*--------------------------- isr_mbx_send ----------------------------------*/
-
-void isr_mbx_send (OS_ID mailbox, void *p_msg) {
- /* Same function as "os_mbx_send", but to be called by ISRs. */
- P_MCB p_MCB = mailbox;
-
- rt_psq_enq (p_MCB, (U32)p_msg);
- rt_psh_req ();
-}
-
-
-/*--------------------------- isr_mbx_receive -------------------------------*/
-
-OS_RESULT isr_mbx_receive (OS_ID mailbox, void **message) {
- /* Receive a message in the interrupt function. The interrupt function */
- /* should not wait for a message since this would block the rtx os. */
- P_MCB p_MCB = mailbox;
-
- if (p_MCB->count) {
- /* A message is available in the fifo buffer. */
- *message = p_MCB->msg[p_MCB->last];
- if (p_MCB->state == 2) {
- /* A task is locked waiting to send message */
- rt_psq_enq (p_MCB, 0);
- rt_psh_req ();
- }
- rt_dec (&p_MCB->count);
- if (++p_MCB->last == p_MCB->size) {
- p_MCB->last = 0;
- }
- return (OS_R_MBX);
- }
- return (OS_R_OK);
-}
-
-
-/*--------------------------- rt_mbx_psh ------------------------------------*/
-
-void rt_mbx_psh (P_MCB p_CB, void *p_msg) {
- /* Store the message to the mailbox queue or pass it to task directly. */
- P_TCB p_TCB;
- void *mem;
-
- if (p_CB->p_lnk != NULL) switch (p_CB->state) {
-#ifdef __CMSIS_RTOS
- case 3:
- /* Task is waiting to allocate memory, remove it from the waiting list */
- mem = rt_alloc_box(p_msg);
- if (mem == NULL) break;
- p_TCB = rt_get_first ((P_XCB)p_CB);
- rt_ret_val(p_TCB, (U32)mem);
- p_TCB->state = READY;
- rt_rmv_dly (p_TCB);
- rt_put_prio (&os_rdy, p_TCB);
- break;
-#endif
- case 2:
- /* Task is waiting to send a message, remove it from the waiting list */
- p_TCB = rt_get_first ((P_XCB)p_CB);
-#ifdef __CMSIS_RTOS
- rt_ret_val(p_TCB, 0/*osOK*/);
-#else
- rt_ret_val(p_TCB, OS_R_OK);
-#endif
- p_CB->msg[p_CB->first] = p_TCB->msg;
- rt_inc (&p_CB->count);
- if (++p_CB->first == p_CB->size) {
- p_CB->first = 0;
- }
- p_TCB->state = READY;
- rt_rmv_dly (p_TCB);
- rt_put_prio (&os_rdy, p_TCB);
- break;
- case 1:
- /* Task is waiting for a message, pass the message to the task directly */
- p_TCB = rt_get_first ((P_XCB)p_CB);
-#ifdef __CMSIS_RTOS
- rt_ret_val2(p_TCB, 0x10/*osEventMessage*/, (U32)p_msg);
-#else
- *p_TCB->msg = p_msg;
- rt_ret_val (p_TCB, OS_R_MBX);
-#endif
- p_TCB->state = READY;
- rt_rmv_dly (p_TCB);
- rt_put_prio (&os_rdy, p_TCB);
- break;
- } else {
- /* No task is waiting for a message, store it to the mailbox queue */
- if (p_CB->count < p_CB->size) {
- p_CB->msg[p_CB->first] = p_msg;
- rt_inc (&p_CB->count);
- if (++p_CB->first == p_CB->size) {
- p_CB->first = 0;
- }
- }
- else {
- os_error (OS_ERR_MBX_OVF);
- }
- }
-}
-
-/*----------------------------------------------------------------------------
- * end of file
- *---------------------------------------------------------------------------*/
-
diff --git a/rtos/rtx/TARGET_ARM7/rt_Mailbox.h b/rtos/rtx/TARGET_ARM7/rt_Mailbox.h
deleted file mode 100644
index 4862f5e3c7..0000000000
--- a/rtos/rtx/TARGET_ARM7/rt_Mailbox.h
+++ /dev/null
@@ -1,48 +0,0 @@
-/*----------------------------------------------------------------------------
- * RL-ARM - RTX
- *----------------------------------------------------------------------------
- * Name: RT_MAILBOX.H
- * Purpose: Implements waits and wake-ups for mailbox messages
- * Rev.: V4.60
- *----------------------------------------------------------------------------
- *
- * Copyright (c) 1999-2009 KEIL, 2009-2015 ARM Germany GmbH
- * All rights reserved.
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- * - Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * - 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.
- * - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
- *---------------------------------------------------------------------------*/
-
-/* Functions */
-extern void rt_mbx_init (OS_ID mailbox, U16 mbx_size);
-extern OS_RESULT rt_mbx_send (OS_ID mailbox, void *p_msg, U16 timeout);
-extern OS_RESULT rt_mbx_wait (OS_ID mailbox, void **message, U16 timeout);
-extern OS_RESULT rt_mbx_check (OS_ID mailbox);
-extern void isr_mbx_send (OS_ID mailbox, void *p_msg);
-extern OS_RESULT isr_mbx_receive (OS_ID mailbox, void **message);
-extern void rt_mbx_psh (P_MCB p_CB, void *p_msg);
-
-
-/*----------------------------------------------------------------------------
- * end of file
- *---------------------------------------------------------------------------*/
-
diff --git a/rtos/rtx/TARGET_ARM7/rt_MemBox.c b/rtos/rtx/TARGET_ARM7/rt_MemBox.c
deleted file mode 100644
index 9b5a00fb0a..0000000000
--- a/rtos/rtx/TARGET_ARM7/rt_MemBox.c
+++ /dev/null
@@ -1,166 +0,0 @@
-/*----------------------------------------------------------------------------
- * RL-ARM - RTX
- *----------------------------------------------------------------------------
- * Name: RT_MEMBOX.C
- * Purpose: Interface functions for fixed memory block management system
- * Rev.: V4.60
- *----------------------------------------------------------------------------
- *
- * Copyright (c) 1999-2009 KEIL, 2009-2015 ARM Germany GmbH
- * All rights reserved.
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- * - Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * - 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.
- * - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
- *---------------------------------------------------------------------------*/
-
-#include "rt_TypeDef.h"
-#include "RTX_Conf.h"
-#include "rt_System.h"
-#include "rt_MemBox.h"
-#include "rt_HAL_CM.h"
-
-/*----------------------------------------------------------------------------
- * Global Functions
- *---------------------------------------------------------------------------*/
-
-
-/*--------------------------- _init_box -------------------------------------*/
-
-int _init_box (void *box_mem, U32 box_size, U32 blk_size) {
- /* Initialize memory block system, returns 0 if OK, 1 if fails. */
- void *end;
- void *blk;
- void *next;
- U32 sizeof_bm;
-
- /* Create memory structure. */
- if (blk_size & BOX_ALIGN_8) {
- /* Memory blocks 8-byte aligned. */
- blk_size = ((blk_size & ~BOX_ALIGN_8) + 7) & ~7;
- sizeof_bm = (sizeof (struct OS_BM) + 7) & ~7;
- }
- else {
- /* Memory blocks 4-byte aligned. */
- blk_size = (blk_size + 3) & ~3;
- sizeof_bm = sizeof (struct OS_BM);
- }
- if (blk_size == 0) {
- return (1);
- }
- if ((blk_size + sizeof_bm) > box_size) {
- return (1);
- }
- /* Create a Memory structure. */
- blk = ((U8 *) box_mem) + sizeof_bm;
- ((P_BM) box_mem)->free = blk;
- end = ((U8 *) box_mem) + box_size;
- ((P_BM) box_mem)->end = end;
- ((P_BM) box_mem)->blk_size = blk_size;
-
- /* Link all free blocks using offsets. */
- end = ((U8 *) end) - blk_size;
- while (1) {
- next = ((U8 *) blk) + blk_size;
- if (next > end) break;
- *((void **)blk) = next;
- blk = next;
- }
- /* end marker */
- *((void **)blk) = 0;
- return (0);
-}
-
-/*--------------------------- rt_alloc_box ----------------------------------*/
-
-void *rt_alloc_box (void *box_mem) {
- /* Allocate a memory block and return start address. */
- void **free;
-#ifndef __USE_EXCLUSIVE_ACCESS
- int irq_dis;
-
- irq_dis = __disable_irq ();
- free = ((P_BM) box_mem)->free;
- if (free) {
- ((P_BM) box_mem)->free = *free;
- }
- if (!irq_dis) __enable_irq ();
-#else
- do {
- if ((free = (void **)__ldrex(&((P_BM) box_mem)->free)) == 0) {
- __clrex();
- break;
- }
- } while (__strex((U32)*free, &((P_BM) box_mem)->free));
-#endif
- return (free);
-}
-
-
-/*--------------------------- _calloc_box -----------------------------------*/
-
-void *_calloc_box (void *box_mem) {
- /* Allocate a 0-initialized memory block and return start address. */
- void *free;
- U32 *p;
- U32 i;
-
- free = _alloc_box (box_mem);
- if (free) {
- p = free;
- for (i = ((P_BM) box_mem)->blk_size; i; i -= 4) {
- *p = 0;
- p++;
- }
- }
- return (free);
-}
-
-
-/*--------------------------- rt_free_box -----------------------------------*/
-
-int rt_free_box (void *box_mem, void *box) {
- /* Free a memory block, returns 0 if OK, 1 if box does not belong to box_mem */
-#ifndef __USE_EXCLUSIVE_ACCESS
- int irq_dis;
-#endif
-
- if (box < box_mem || box >= ((P_BM) box_mem)->end) {
- return (1);
- }
-
-#ifndef __USE_EXCLUSIVE_ACCESS
- irq_dis = __disable_irq ();
- *((void **)box) = ((P_BM) box_mem)->free;
- ((P_BM) box_mem)->free = box;
- if (!irq_dis) __enable_irq ();
-#else
- do {
- *((void **)box) = (void *)__ldrex(&((P_BM) box_mem)->free);
- } while (__strex ((U32)box, &((P_BM) box_mem)->free));
-#endif
- return (0);
-}
-
-/*----------------------------------------------------------------------------
- * end of file
- *---------------------------------------------------------------------------*/
-
diff --git a/rtos/rtx/TARGET_ARM7/rt_MemBox.h b/rtos/rtx/TARGET_ARM7/rt_MemBox.h
deleted file mode 100644
index d761c41aca..0000000000
--- a/rtos/rtx/TARGET_ARM7/rt_MemBox.h
+++ /dev/null
@@ -1,46 +0,0 @@
-/*----------------------------------------------------------------------------
- * RL-ARM - RTX
- *----------------------------------------------------------------------------
- * Name: RT_MEMBOX.H
- * Purpose: Interface functions for fixed memory block management system
- * Rev.: V4.60
- *----------------------------------------------------------------------------
- *
- * Copyright (c) 1999-2009 KEIL, 2009-2015 ARM Germany GmbH
- * All rights reserved.
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- * - Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * - 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.
- * - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
- *---------------------------------------------------------------------------*/
-
-/* Functions */
-#define rt_init_box _init_box
-#define rt_calloc_box _calloc_box
-extern int _init_box (void *box_mem, U32 box_size, U32 blk_size);
-extern void *rt_alloc_box (void *box_mem);
-extern void * _calloc_box (void *box_mem);
-extern int rt_free_box (void *box_mem, void *box);
-
-/*----------------------------------------------------------------------------
- * end of file
- *---------------------------------------------------------------------------*/
-
diff --git a/rtos/rtx/TARGET_ARM7/rt_Mutex.c b/rtos/rtx/TARGET_ARM7/rt_Mutex.c
deleted file mode 100644
index 87398adb1e..0000000000
--- a/rtos/rtx/TARGET_ARM7/rt_Mutex.c
+++ /dev/null
@@ -1,197 +0,0 @@
-/*----------------------------------------------------------------------------
- * RL-ARM - RTX
- *----------------------------------------------------------------------------
- * Name: RT_MUTEX.C
- * Purpose: Implements mutex synchronization objects
- * Rev.: V4.60
- *----------------------------------------------------------------------------
- *
- * Copyright (c) 1999-2009 KEIL, 2009-2015 ARM Germany GmbH
- * All rights reserved.
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- * - Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * - 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.
- * - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
- *---------------------------------------------------------------------------*/
-
-#include "rt_TypeDef.h"
-#include "RTX_Conf.h"
-#include "rt_List.h"
-#include "rt_Task.h"
-#include "rt_Mutex.h"
-#include "rt_HAL_CM.h"
-
-
-/*----------------------------------------------------------------------------
- * Functions
- *---------------------------------------------------------------------------*/
-
-
-/*--------------------------- rt_mut_init -----------------------------------*/
-
-void rt_mut_init (OS_ID mutex) {
- /* Initialize a mutex object */
- P_MUCB p_MCB = mutex;
-
- p_MCB->cb_type = MUCB;
- p_MCB->prio = 0;
- p_MCB->level = 0;
- p_MCB->p_lnk = NULL;
- p_MCB->owner = NULL;
-}
-
-
-/*--------------------------- rt_mut_delete ---------------------------------*/
-
-#ifdef __CMSIS_RTOS
-OS_RESULT rt_mut_delete (OS_ID mutex) {
- /* Delete a mutex object */
- P_MUCB p_MCB = mutex;
- P_TCB p_TCB;
-
- /* Restore owner task's priority. */
- if (p_MCB->level != 0) {
- p_MCB->owner->prio = p_MCB->prio;
- if (p_MCB->owner != os_tsk.run) {
- rt_resort_prio (p_MCB->owner);
- }
- }
-
- while (p_MCB->p_lnk != NULL) {
- /* A task is waiting for mutex. */
- p_TCB = rt_get_first ((P_XCB)p_MCB);
- rt_ret_val(p_TCB, 0/*osOK*/);
- rt_rmv_dly(p_TCB);
- p_TCB->state = READY;
- rt_put_prio (&os_rdy, p_TCB);
- }
-
- if (os_rdy.p_lnk && (os_rdy.p_lnk->prio > os_tsk.run->prio)) {
- /* preempt running task */
- rt_put_prio (&os_rdy, os_tsk.run);
- os_tsk.run->state = READY;
- rt_dispatch (NULL);
- }
-
- p_MCB->cb_type = 0;
-
- return (OS_R_OK);
-}
-#endif
-
-
-/*--------------------------- rt_mut_release --------------------------------*/
-
-OS_RESULT rt_mut_release (OS_ID mutex) {
- /* Release a mutex object */
- P_MUCB p_MCB = mutex;
- P_TCB p_TCB;
-
- if (p_MCB->level == 0 || p_MCB->owner != os_tsk.run) {
- /* Unbalanced mutex release or task is not the owner */
- return (OS_R_NOK);
- }
- if (--p_MCB->level != 0) {
- return (OS_R_OK);
- }
- /* Restore owner task's priority. */
- os_tsk.run->prio = p_MCB->prio;
- if (p_MCB->p_lnk != NULL) {
- /* A task is waiting for mutex. */
- p_TCB = rt_get_first ((P_XCB)p_MCB);
-#ifdef __CMSIS_RTOS
- rt_ret_val(p_TCB, 0/*osOK*/);
-#else
- rt_ret_val(p_TCB, OS_R_MUT);
-#endif
- rt_rmv_dly (p_TCB);
- /* A waiting task becomes the owner of this mutex. */
- p_MCB->level = 1;
- p_MCB->owner = p_TCB;
- p_MCB->prio = p_TCB->prio;
- /* Priority inversion, check which task continues. */
- if (os_tsk.run->prio >= rt_rdy_prio()) {
- rt_dispatch (p_TCB);
- }
- else {
- /* Ready task has higher priority than running task. */
- rt_put_prio (&os_rdy, os_tsk.run);
- rt_put_prio (&os_rdy, p_TCB);
- os_tsk.run->state = READY;
- p_TCB->state = READY;
- rt_dispatch (NULL);
- }
- }
- else {
- /* Check if own priority raised by priority inversion. */
- if (rt_rdy_prio() > os_tsk.run->prio) {
- rt_put_prio (&os_rdy, os_tsk.run);
- os_tsk.run->state = READY;
- rt_dispatch (NULL);
- }
- }
- return (OS_R_OK);
-}
-
-
-/*--------------------------- rt_mut_wait -----------------------------------*/
-
-OS_RESULT rt_mut_wait (OS_ID mutex, U16 timeout) {
- /* Wait for a mutex, continue when mutex is free. */
- P_MUCB p_MCB = mutex;
-
- if (p_MCB->level == 0) {
- p_MCB->owner = os_tsk.run;
- p_MCB->prio = os_tsk.run->prio;
- goto inc;
- }
- if (p_MCB->owner == os_tsk.run) {
- /* OK, running task is the owner of this mutex. */
-inc:p_MCB->level++;
- return (OS_R_OK);
- }
- /* Mutex owned by another task, wait until released. */
- if (timeout == 0) {
- return (OS_R_TMO);
- }
- /* Raise the owner task priority if lower than current priority. */
- /* This priority inversion is called priority inheritance. */
- if (p_MCB->prio < os_tsk.run->prio) {
- p_MCB->owner->prio = os_tsk.run->prio;
- rt_resort_prio (p_MCB->owner);
- }
- if (p_MCB->p_lnk != NULL) {
- rt_put_prio ((P_XCB)p_MCB, os_tsk.run);
- }
- else {
- p_MCB->p_lnk = os_tsk.run;
- os_tsk.run->p_lnk = NULL;
- os_tsk.run->p_rlnk = (P_TCB)p_MCB;
- }
- rt_block(timeout, WAIT_MUT);
- return (OS_R_TMO);
-}
-
-
-/*----------------------------------------------------------------------------
- * end of file
- *---------------------------------------------------------------------------*/
-
diff --git a/rtos/rtx/TARGET_ARM7/rt_Mutex.h b/rtos/rtx/TARGET_ARM7/rt_Mutex.h
deleted file mode 100644
index a2f8916edb..0000000000
--- a/rtos/rtx/TARGET_ARM7/rt_Mutex.h
+++ /dev/null
@@ -1,44 +0,0 @@
-/*----------------------------------------------------------------------------
- * RL-ARM - RTX
- *----------------------------------------------------------------------------
- * Name: RT_MUTEX.H
- * Purpose: Implements mutex synchronization objects
- * Rev.: V4.60
- *----------------------------------------------------------------------------
- *
- * Copyright (c) 1999-2009 KEIL, 2009-2015 ARM Germany GmbH
- * All rights reserved.
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- * - Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * - 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.
- * - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
- *---------------------------------------------------------------------------*/
-
-/* Functions */
-extern void rt_mut_init (OS_ID mutex);
-extern OS_RESULT rt_mut_delete (OS_ID mutex);
-extern OS_RESULT rt_mut_release (OS_ID mutex);
-extern OS_RESULT rt_mut_wait (OS_ID mutex, U16 timeout);
-
-/*----------------------------------------------------------------------------
- * end of file
- *---------------------------------------------------------------------------*/
-
diff --git a/rtos/rtx/TARGET_ARM7/rt_Robin.c b/rtos/rtx/TARGET_ARM7/rt_Robin.c
deleted file mode 100644
index ed58ea06dc..0000000000
--- a/rtos/rtx/TARGET_ARM7/rt_Robin.c
+++ /dev/null
@@ -1,84 +0,0 @@
-/*----------------------------------------------------------------------------
- * RL-ARM - RTX
- *----------------------------------------------------------------------------
- * Name: RT_ROBIN.C
- * Purpose: Round Robin Task switching
- * Rev.: V4.60
- *----------------------------------------------------------------------------
- *
- * Copyright (c) 1999-2009 KEIL, 2009-2015 ARM Germany GmbH
- * All rights reserved.
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- * - Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * - 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.
- * - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
- *---------------------------------------------------------------------------*/
-
-#include "rt_TypeDef.h"
-#include "RTX_Conf.h"
-#include "rt_List.h"
-#include "rt_Task.h"
-#include "rt_Time.h"
-#include "rt_Robin.h"
-#include "rt_HAL_CM.h"
-
-/*----------------------------------------------------------------------------
- * Global Variables
- *---------------------------------------------------------------------------*/
-
-struct OS_ROBIN os_robin;
-
-
-/*----------------------------------------------------------------------------
- * Global Functions
- *---------------------------------------------------------------------------*/
-
-/*--------------------------- rt_init_robin ---------------------------------*/
-
-__weak void rt_init_robin (void) {
- /* Initialize Round Robin variables. */
- os_robin.task = NULL;
- os_robin.tout = (U16)os_rrobin;
-}
-
-/*--------------------------- rt_chk_robin ----------------------------------*/
-
-__weak void rt_chk_robin (void) {
- /* Check if Round Robin timeout expired and switch to the next ready task.*/
- P_TCB p_new;
-
- if (os_robin.task != os_rdy.p_lnk) {
- /* New task was suspended, reset Round Robin timeout. */
- os_robin.task = os_rdy.p_lnk;
- os_robin.time = (U16)os_time + os_robin.tout - 1;
- }
- if (os_robin.time == (U16)os_time) {
- /* Round Robin timeout has expired, swap Robin tasks. */
- os_robin.task = NULL;
- p_new = rt_get_first (&os_rdy);
- rt_put_prio ((P_XCB)&os_rdy, p_new);
- }
-}
-
-/*----------------------------------------------------------------------------
- * end of file
- *---------------------------------------------------------------------------*/
-
diff --git a/rtos/rtx/TARGET_ARM7/rt_Robin.h b/rtos/rtx/TARGET_ARM7/rt_Robin.h
deleted file mode 100644
index 9eebaf042d..0000000000
--- a/rtos/rtx/TARGET_ARM7/rt_Robin.h
+++ /dev/null
@@ -1,45 +0,0 @@
-/*----------------------------------------------------------------------------
- * RL-ARM - RTX
- *----------------------------------------------------------------------------
- * Name: RT_ROBIN.H
- * Purpose: Round Robin Task switching definitions
- * Rev.: V4.60
- *----------------------------------------------------------------------------
- *
- * Copyright (c) 1999-2009 KEIL, 2009-2015 ARM Germany GmbH
- * All rights reserved.
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- * - Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * - 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.
- * - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
- *---------------------------------------------------------------------------*/
-
-/* Variables */
-extern struct OS_ROBIN os_robin;
-
-/* Functions */
-extern void rt_init_robin (void);
-extern void rt_chk_robin (void);
-
-/*----------------------------------------------------------------------------
- * end of file
- *---------------------------------------------------------------------------*/
-
diff --git a/rtos/rtx/TARGET_ARM7/rt_Semaphore.c b/rtos/rtx/TARGET_ARM7/rt_Semaphore.c
deleted file mode 100644
index 5bf65258e9..0000000000
--- a/rtos/rtx/TARGET_ARM7/rt_Semaphore.c
+++ /dev/null
@@ -1,183 +0,0 @@
-/*----------------------------------------------------------------------------
- * RL-ARM - RTX
- *----------------------------------------------------------------------------
- * Name: RT_SEMAPHORE.C
- * Purpose: Implements binary and counting semaphores
- * Rev.: V4.60
- *----------------------------------------------------------------------------
- *
- * Copyright (c) 1999-2009 KEIL, 2009-2015 ARM Germany GmbH
- * All rights reserved.
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- * - Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * - 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.
- * - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
- *---------------------------------------------------------------------------*/
-
-#include "rt_TypeDef.h"
-#include "RTX_Conf.h"
-#include "rt_System.h"
-#include "rt_List.h"
-#include "rt_Task.h"
-#include "rt_Semaphore.h"
-#include "rt_HAL_CM.h"
-
-
-/*----------------------------------------------------------------------------
- * Functions
- *---------------------------------------------------------------------------*/
-
-
-/*--------------------------- rt_sem_init -----------------------------------*/
-
-void rt_sem_init (OS_ID semaphore, U16 token_count) {
- /* Initialize a semaphore */
- P_SCB p_SCB = semaphore;
-
- p_SCB->cb_type = SCB;
- p_SCB->p_lnk = NULL;
- p_SCB->tokens = token_count;
-}
-
-
-/*--------------------------- rt_sem_delete ---------------------------------*/
-
-#ifdef __CMSIS_RTOS
-OS_RESULT rt_sem_delete (OS_ID semaphore) {
- /* Delete semaphore */
- P_SCB p_SCB = semaphore;
- P_TCB p_TCB;
-
- while (p_SCB->p_lnk != NULL) {
- /* A task is waiting for token */
- p_TCB = rt_get_first ((P_XCB)p_SCB);
- rt_ret_val(p_TCB, 0);
- rt_rmv_dly(p_TCB);
- p_TCB->state = READY;
- rt_put_prio (&os_rdy, p_TCB);
- }
-
- if (os_rdy.p_lnk && (os_rdy.p_lnk->prio > os_tsk.run->prio)) {
- /* preempt running task */
- rt_put_prio (&os_rdy, os_tsk.run);
- os_tsk.run->state = READY;
- rt_dispatch (NULL);
- }
-
- p_SCB->cb_type = 0;
-
- return (OS_R_OK);
-}
-#endif
-
-
-/*--------------------------- rt_sem_send -----------------------------------*/
-
-OS_RESULT rt_sem_send (OS_ID semaphore) {
- /* Return a token to semaphore */
- P_SCB p_SCB = semaphore;
- P_TCB p_TCB;
-
- if (p_SCB->p_lnk != NULL) {
- /* A task is waiting for token */
- p_TCB = rt_get_first ((P_XCB)p_SCB);
-#ifdef __CMSIS_RTOS
- rt_ret_val(p_TCB, 1);
-#else
- rt_ret_val(p_TCB, OS_R_SEM);
-#endif
- rt_rmv_dly (p_TCB);
- rt_dispatch (p_TCB);
- }
- else {
- /* Store token. */
- p_SCB->tokens++;
- }
- return (OS_R_OK);
-}
-
-
-/*--------------------------- rt_sem_wait -----------------------------------*/
-
-OS_RESULT rt_sem_wait (OS_ID semaphore, U16 timeout) {
- /* Obtain a token; possibly wait for it */
- P_SCB p_SCB = semaphore;
-
- if (p_SCB->tokens) {
- p_SCB->tokens--;
- return (OS_R_OK);
- }
- /* No token available: wait for one */
- if (timeout == 0) {
- return (OS_R_TMO);
- }
- if (p_SCB->p_lnk != NULL) {
- rt_put_prio ((P_XCB)p_SCB, os_tsk.run);
- }
- else {
- p_SCB->p_lnk = os_tsk.run;
- os_tsk.run->p_lnk = NULL;
- os_tsk.run->p_rlnk = (P_TCB)p_SCB;
- }
- rt_block(timeout, WAIT_SEM);
- return (OS_R_TMO);
-}
-
-
-/*--------------------------- isr_sem_send ----------------------------------*/
-
-void isr_sem_send (OS_ID semaphore) {
- /* Same function as "os_sem"send", but to be called by ISRs */
- P_SCB p_SCB = semaphore;
-
- rt_psq_enq (p_SCB, 0);
- rt_psh_req ();
-}
-
-
-/*--------------------------- rt_sem_psh ------------------------------------*/
-
-void rt_sem_psh (P_SCB p_CB) {
- /* Check if task has to be waken up */
- P_TCB p_TCB;
-
- if (p_CB->p_lnk != NULL) {
- /* A task is waiting for token */
- p_TCB = rt_get_first ((P_XCB)p_CB);
- rt_rmv_dly (p_TCB);
- p_TCB->state = READY;
-#ifdef __CMSIS_RTOS
- rt_ret_val(p_TCB, 1);
-#else
- rt_ret_val(p_TCB, OS_R_SEM);
-#endif
- rt_put_prio (&os_rdy, p_TCB);
- }
- else {
- /* Store token */
- p_CB->tokens++;
- }
-}
-
-/*----------------------------------------------------------------------------
- * end of file
- *---------------------------------------------------------------------------*/
-
diff --git a/rtos/rtx/TARGET_ARM7/rt_Semaphore.h b/rtos/rtx/TARGET_ARM7/rt_Semaphore.h
deleted file mode 100644
index ed553a7701..0000000000
--- a/rtos/rtx/TARGET_ARM7/rt_Semaphore.h
+++ /dev/null
@@ -1,46 +0,0 @@
-/*----------------------------------------------------------------------------
- * RL-ARM - RTX
- *----------------------------------------------------------------------------
- * Name: RT_SEMAPHORE.H
- * Purpose: Implements binary and counting semaphores
- * Rev.: V4.60
- *----------------------------------------------------------------------------
- *
- * Copyright (c) 1999-2009 KEIL, 2009-2015 ARM Germany GmbH
- * All rights reserved.
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- * - Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * - 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.
- * - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
- *---------------------------------------------------------------------------*/
-
-/* Functions */
-extern void rt_sem_init (OS_ID semaphore, U16 token_count);
-extern OS_RESULT rt_sem_delete(OS_ID semaphore);
-extern OS_RESULT rt_sem_send (OS_ID semaphore);
-extern OS_RESULT rt_sem_wait (OS_ID semaphore, U16 timeout);
-extern void isr_sem_send (OS_ID semaphore);
-extern void rt_sem_psh (P_SCB p_CB);
-
-/*----------------------------------------------------------------------------
- * end of file
- *---------------------------------------------------------------------------*/
-
diff --git a/rtos/rtx/TARGET_ARM7/rt_System.c b/rtos/rtx/TARGET_ARM7/rt_System.c
deleted file mode 100644
index 2482701b97..0000000000
--- a/rtos/rtx/TARGET_ARM7/rt_System.c
+++ /dev/null
@@ -1,293 +0,0 @@
-/*----------------------------------------------------------------------------
- * RL-ARM - RTX
- *----------------------------------------------------------------------------
- * Name: RT_SYSTEM.C
- * Purpose: System Task Manager
- * Rev.: V4.60
- *----------------------------------------------------------------------------
- *
- * Copyright (c) 1999-2009 KEIL, 2009-2015 ARM Germany GmbH
- * All rights reserved.
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- * - Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * - 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.
- * - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
- *---------------------------------------------------------------------------*/
-
-#include "rt_TypeDef.h"
-#include "RTX_Conf.h"
-#include "rt_Task.h"
-#include "rt_System.h"
-#include "rt_Event.h"
-#include "rt_List.h"
-#include "rt_Mailbox.h"
-#include "rt_Semaphore.h"
-#include "rt_Time.h"
-#include "rt_Robin.h"
-#include "rt_HAL_CM.h"
-
-/*----------------------------------------------------------------------------
- * Global Variables
- *---------------------------------------------------------------------------*/
-
-int os_tick_irqn;
-
-/*----------------------------------------------------------------------------
- * Local Variables
- *---------------------------------------------------------------------------*/
-
-static volatile BIT os_lock;
-static volatile BIT os_psh_flag;
-static U8 pend_flags;
-
-/*----------------------------------------------------------------------------
- * Global Functions
- *---------------------------------------------------------------------------*/
-
-#if defined (__CC_ARM)
-__asm void $$RTX$$version (void) {
- /* Export a version number symbol for a version control. */
-
- EXPORT __RL_RTX_VER
-
-__RL_RTX_VER EQU 0x450
-}
-#endif
-
-
-/*--------------------------- rt_suspend ------------------------------------*/
-U32 rt_suspend (void) {
- /* Suspend OS scheduler */
- U32 delta = 0xFFFF;
-
- rt_tsk_lock();
-
- if (os_dly.p_dlnk) {
- delta = os_dly.delta_time;
- }
-#ifndef __CMSIS_RTOS
- if (os_tmr.next) {
- if (os_tmr.tcnt < delta) delta = os_tmr.tcnt;
- }
-#endif
-
- return (delta);
-}
-
-
-/*--------------------------- rt_resume -------------------------------------*/
-void rt_resume (U32 sleep_time) {
- /* Resume OS scheduler after suspend */
- P_TCB next;
- U32 delta;
-
- os_tsk.run->state = READY;
- rt_put_rdy_first (os_tsk.run);
-
- os_robin.task = NULL;
-
- /* Update delays. */
- if (os_dly.p_dlnk) {
- delta = sleep_time;
- if (delta >= os_dly.delta_time) {
- delta -= os_dly.delta_time;
- os_time += os_dly.delta_time;
- os_dly.delta_time = 1;
- while (os_dly.p_dlnk) {
- rt_dec_dly();
- if (delta == 0) break;
- delta--;
- os_time++;
- }
- } else {
- os_time += delta;
- os_dly.delta_time -= delta;
- }
- } else {
- os_time += sleep_time;
- }
-
-#ifndef __CMSIS_RTOS
- /* Check the user timers. */
- if (os_tmr.next) {
- delta = sleep_time;
- if (delta >= os_tmr.tcnt) {
- delta -= os_tmr.tcnt;
- os_tmr.tcnt = 1;
- while (os_tmr.next) {
- rt_tmr_tick();
- if (delta == 0) break;
- delta--;
- }
- } else {
- os_tmr.tcnt -= delta;
- }
- }
-#endif
-
- /* Switch back to highest ready task */
- next = rt_get_first (&os_rdy);
- rt_switch_req (next);
-
- rt_tsk_unlock();
-}
-
-
-/*--------------------------- rt_tsk_lock -----------------------------------*/
-
-void rt_tsk_lock (void) {
- /* Prevent task switching by locking out scheduler */
- OS_X_LOCK(os_tick_irqn);
- os_lock = __TRUE;
- OS_X_UNPEND (&pend_flags);
-}
-
-
-/*--------------------------- rt_tsk_unlock ---------------------------------*/
-
-void rt_tsk_unlock (void) {
- /* Unlock scheduler and re-enable task switching */
- OS_X_UNLOCK(os_tick_irqn);
- os_lock = __FALSE;
- OS_X_PEND (pend_flags, os_psh_flag);
- os_psh_flag = __FALSE;
-}
-
-
-/*--------------------------- rt_psh_req ------------------------------------*/
-
-void rt_psh_req (void) {
- /* Initiate a post service handling request if required. */
- if (os_lock == __FALSE) {
- OS_PEND_IRQ ();
- }
- else {
- os_psh_flag = __TRUE;
- }
-}
-
-
-/*--------------------------- rt_pop_req ------------------------------------*/
-
-void rt_pop_req (void) {
- /* Process an ISR post service requests. */
- struct OS_XCB *p_CB;
- P_TCB next;
- U32 idx;
-
- os_tsk.run->state = READY;
- rt_put_rdy_first (os_tsk.run);
-
- idx = os_psq->last;
- while (os_psq->count) {
- p_CB = os_psq->q[idx].id;
- if (p_CB->cb_type == TCB) {
- /* Is of TCB type */
- rt_evt_psh ((P_TCB)p_CB, (U16)os_psq->q[idx].arg);
- }
- else if (p_CB->cb_type == MCB) {
- /* Is of MCB type */
- rt_mbx_psh ((P_MCB)p_CB, (void *)os_psq->q[idx].arg);
- }
- else {
- /* Must be of SCB type */
- rt_sem_psh ((P_SCB)p_CB);
- }
- if (++idx == os_psq->size) idx = 0;
- rt_dec (&os_psq->count);
- }
- os_psq->last = idx;
-
- next = rt_get_first (&os_rdy);
- rt_switch_req (next);
-}
-
-
-/*--------------------------- os_tick_init ----------------------------------*/
-
-__weak int os_tick_init (void) {
- /* Initialize SysTick timer as system tick timer. */
- rt_systick_init ();
- return (SYS_TICK_IRQn); /* Return IRQ number of SysTick timer */
-}
-
-
-/*--------------------------- os_tick_irqack --------------------------------*/
-
-__weak void os_tick_irqack (void) {
- /* Acknowledge timer interrupt. */
-}
-
-
-/*--------------------------- rt_systick ------------------------------------*/
-
-extern void sysTimerTick(void);
-
-void rt_systick (void) {
- if(NVIC_Pending(SYS_TICK_IRQn)){
- rt_pop_req();
- NVIC_UnpendIRQ(SYS_TICK_IRQn);
- SYS_TICK_TIMER->IR = 0xF; // clear timer interrupt
- return;
- }
- /* Check for system clock update, suspend running task. */
- P_TCB next;
-
- os_tsk.run->state = READY;
- rt_put_rdy_first (os_tsk.run);
-
- /* Check Round Robin timeout. */
- rt_chk_robin ();
-
- /* Update delays. */
- os_time++;
- rt_dec_dly ();
-
- /* Check the user timers. */
-#ifdef __CMSIS_RTOS
- sysTimerTick();
-#else
- rt_tmr_tick ();
-#endif
-
- /* Switch back to highest ready task */
- next = rt_get_first (&os_rdy);
- rt_switch_req (next);
- SYS_TICK_TIMER->IR = 0xF; // clear timer interrupt
-}
-
-/*--------------------------- rt_stk_check ----------------------------------*/
-__weak void rt_stk_check (void) {
- /* Check for stack overflow. */
- if (os_tsk.run->task_id == 0x01) {
- // TODO: For the main thread the check should be done against the main heap pointer
- } else {
- if ((os_tsk.run->tsk_stack < (U32)os_tsk.run->stack) ||
- (os_tsk.run->stack[0] != MAGIC_WORD)) {
- os_error (OS_ERR_STK_OVF);
- }
- }
-}
-
-/*----------------------------------------------------------------------------
- * end of file
- *---------------------------------------------------------------------------*/
-
diff --git a/rtos/rtx/TARGET_ARM7/rt_System.h b/rtos/rtx/TARGET_ARM7/rt_System.h
deleted file mode 100644
index e73ef4d0b9..0000000000
--- a/rtos/rtx/TARGET_ARM7/rt_System.h
+++ /dev/null
@@ -1,52 +0,0 @@
-/*----------------------------------------------------------------------------
- * RL-ARM - RTX
- *----------------------------------------------------------------------------
- * Name: RT_SYSTEM.H
- * Purpose: System Task Manager definitions
- * Rev.: V4.60
- *----------------------------------------------------------------------------
- *
- * Copyright (c) 1999-2009 KEIL, 2009-2015 ARM Germany GmbH
- * All rights reserved.
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- * - Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * - 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.
- * - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
- *---------------------------------------------------------------------------*/
-
-/* Variables */
-#define os_psq ((P_PSQ)&os_fifo)
-extern int os_tick_irqn;
-
-/* Functions */
-extern U32 rt_suspend (void);
-extern void rt_resume (U32 sleep_time);
-extern void rt_tsk_lock (void);
-extern void rt_tsk_unlock (void);
-extern void rt_psh_req (void);
-extern void rt_pop_req (void);
-extern void rt_systick (void);
-extern void rt_stk_check (void);
-
-/*----------------------------------------------------------------------------
- * end of file
- *---------------------------------------------------------------------------*/
-
diff --git a/rtos/rtx/TARGET_ARM7/rt_Task.c b/rtos/rtx/TARGET_ARM7/rt_Task.c
deleted file mode 100644
index d9e4d3ffad..0000000000
--- a/rtos/rtx/TARGET_ARM7/rt_Task.c
+++ /dev/null
@@ -1,341 +0,0 @@
-/*----------------------------------------------------------------------------
- * RL-ARM - RTX
- *----------------------------------------------------------------------------
- * Name: RT_TASK.C
- * Purpose: Task functions and system start up.
- * Rev.: V4.60
- *----------------------------------------------------------------------------
- *
- * Copyright (c) 1999-2009 KEIL, 2009-2015 ARM Germany GmbH
- * All rights reserved.
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- * - Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * - 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.
- * - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
- *---------------------------------------------------------------------------*/
-
-#include "rt_TypeDef.h"
-#include "RTX_Conf.h"
-#include "rt_System.h"
-#include "rt_Task.h"
-#include "rt_List.h"
-#include "rt_MemBox.h"
-#include "rt_Robin.h"
-#include "rt_HAL_CM.h"
-
-/*----------------------------------------------------------------------------
- * Global Variables
- *---------------------------------------------------------------------------*/
-
-/* Running and next task info. */
-struct OS_TSK os_tsk;
-
-/* Task Control Blocks of idle demon */
-struct OS_TCB os_idle_TCB;
-
-
-/*----------------------------------------------------------------------------
- * Local Functions
- *---------------------------------------------------------------------------*/
-
-OS_TID rt_get_TID (void) {
- U32 tid;
-
- for (tid = 1; tid <= os_maxtaskrun; tid++) {
- if (os_active_TCB[tid-1] == NULL) {
- return ((OS_TID)tid);
- }
- }
- return (0);
-}
-
-#if defined (__CC_ARM) && !defined (__MICROLIB)
-/*--------------------------- __user_perthread_libspace ---------------------*/
-extern void *__libspace_start;
-
-void *__user_perthread_libspace (void) {
- /* Provide a separate libspace for each task. */
- if (os_tsk.run == NULL) {
- /* RTX not running yet. */
- return (&__libspace_start);
- }
- return (void *)(os_tsk.run->std_libspace);
-}
-#endif
-
-/*--------------------------- rt_init_context -------------------------------*/
-
-void rt_init_context (P_TCB p_TCB, U8 priority, FUNCP task_body) {
- /* Initialize general part of the Task Control Block. */
- p_TCB->cb_type = TCB;
- p_TCB->state = READY;
- p_TCB->prio = priority;
- p_TCB->p_lnk = NULL;
- p_TCB->p_rlnk = NULL;
- p_TCB->p_dlnk = NULL;
- p_TCB->p_blnk = NULL;
- p_TCB->delta_time = 0;
- p_TCB->interval_time = 0;
- p_TCB->events = 0;
- p_TCB->waits = 0;
- p_TCB->stack_frame = 0;
-
- rt_init_stack (p_TCB, task_body);
-}
-
-
-/*--------------------------- rt_switch_req ---------------------------------*/
-
-void rt_switch_req (P_TCB p_new) {
- /* Switch to next task (identified by "p_new"). */
- os_tsk.new_tsk = p_new;
- p_new->state = RUNNING;
- DBG_TASK_SWITCH(p_new->task_id);
-}
-
-
-/*--------------------------- rt_dispatch -----------------------------------*/
-
-void rt_dispatch (P_TCB next_TCB) {
- /* Dispatch next task if any identified or dispatch highest ready task */
- /* "next_TCB" identifies a task to run or has value NULL (=no next task) */
- if (next_TCB == NULL) {
- /* Running task was blocked: continue with highest ready task */
- next_TCB = rt_get_first (&os_rdy);
- rt_switch_req (next_TCB);
- }
- else {
- /* Check which task continues */
- if (next_TCB->prio > os_tsk.run->prio) {
- /* preempt running task */
- rt_put_rdy_first (os_tsk.run);
- os_tsk.run->state = READY;
- rt_switch_req (next_TCB);
- }
- else {
- /* put next task into ready list, no task switch takes place */
- next_TCB->state = READY;
- rt_put_prio (&os_rdy, next_TCB);
- }
- }
-}
-
-
-/*--------------------------- rt_block --------------------------------------*/
-
-void rt_block (U16 timeout, U8 block_state) {
- /* Block running task and choose next ready task. */
- /* "timeout" sets a time-out value or is 0xffff (=no time-out). */
- /* "block_state" defines the appropriate task state */
- P_TCB next_TCB;
-
- if (timeout) {
- if (timeout < 0xffff) {
- rt_put_dly (os_tsk.run, timeout);
- }
- os_tsk.run->state = block_state;
- next_TCB = rt_get_first (&os_rdy);
- rt_switch_req (next_TCB);
- }
-}
-
-
-/*--------------------------- rt_tsk_pass -----------------------------------*/
-
-void rt_tsk_pass (void) {
- /* Allow tasks of same priority level to run cooperatively.*/
- P_TCB p_new;
-
- p_new = rt_get_same_rdy_prio();
- if (p_new != NULL) {
- rt_put_prio ((P_XCB)&os_rdy, os_tsk.run);
- os_tsk.run->state = READY;
- rt_switch_req (p_new);
- }
-}
-
-
-/*--------------------------- rt_tsk_self -----------------------------------*/
-
-OS_TID rt_tsk_self (void) {
- /* Return own task identifier value. */
- if (os_tsk.run == NULL) {
- return (0);
- }
- return (os_tsk.run->task_id);
-}
-
-
-/*--------------------------- rt_tsk_prio -----------------------------------*/
-
-OS_RESULT rt_tsk_prio (OS_TID task_id, U8 new_prio) {
- /* Change execution priority of a task to "new_prio". */
- P_TCB p_task;
-
- if (task_id == 0) {
- /* Change execution priority of calling task. */
- os_tsk.run->prio = new_prio;
-run:if (rt_rdy_prio() > new_prio) {
- rt_put_prio (&os_rdy, os_tsk.run);
- os_tsk.run->state = READY;
- rt_dispatch (NULL);
- }
- return (OS_R_OK);
- }
-
- /* Find the task in the "os_active_TCB" array. */
- if (task_id > os_maxtaskrun || os_active_TCB[task_id-1] == NULL) {
- /* Task with "task_id" not found or not started. */
- return (OS_R_NOK);
- }
- p_task = os_active_TCB[task_id-1];
- p_task->prio = new_prio;
- if (p_task == os_tsk.run) {
- goto run;
- }
- rt_resort_prio (p_task);
- if (p_task->state == READY) {
- /* Task enqueued in a ready list. */
- p_task = rt_get_first (&os_rdy);
- rt_dispatch (p_task);
- }
- return (OS_R_OK);
-}
-
-/*--------------------------- rt_tsk_delete ---------------------------------*/
-
-OS_RESULT rt_tsk_delete (OS_TID task_id) {
- /* Terminate the task identified with "task_id". */
- P_TCB task_context;
-
- if (task_id == 0 || task_id == os_tsk.run->task_id) {
- /* Terminate itself. */
- os_tsk.run->state = INACTIVE;
- os_tsk.run->tsk_stack = 0;
- rt_stk_check ();
- os_active_TCB[os_tsk.run->task_id-1] = NULL;
-
- os_tsk.run->stack = NULL;
- DBG_TASK_NOTIFY(os_tsk.run, __FALSE);
- os_tsk.run = NULL;
- rt_dispatch (NULL);
- /* The program should never come to this point. */
- }
- else {
- /* Find the task in the "os_active_TCB" array. */
- if (task_id > os_maxtaskrun || os_active_TCB[task_id-1] == NULL) {
- /* Task with "task_id" not found or not started. */
- return (OS_R_NOK);
- }
- task_context = os_active_TCB[task_id-1];
- rt_rmv_list (task_context);
- rt_rmv_dly (task_context);
- os_active_TCB[task_id-1] = NULL;
-
- task_context->stack = NULL;
- DBG_TASK_NOTIFY(task_context, __FALSE);
- }
- return (OS_R_OK);
-}
-
-
-/*--------------------------- rt_sys_init -----------------------------------*/
-
-#ifdef __CMSIS_RTOS
-void rt_sys_init (void) {
-#else
-void rt_sys_init (FUNCP first_task, U32 prio_stksz, void *stk) {
-#endif
- /* Initialize system and start up task declared with "first_task". */
- U32 i;
-
- DBG_INIT();
-
- /* Initialize dynamic memory and task TCB pointers to NULL. */
- for (i = 0; i < os_maxtaskrun; i++) {
- os_active_TCB[i] = NULL;
- }
-
- /* Set up TCB of idle demon */
- os_idle_TCB.task_id = 255;
- os_idle_TCB.priv_stack = idle_task_stack_size;
- os_idle_TCB.stack = idle_task_stack;
- rt_init_context (&os_idle_TCB, 0, os_idle_demon);
-
- /* Set up ready list: initially empty */
- os_rdy.cb_type = HCB;
- os_rdy.p_lnk = NULL;
- /* Set up delay list: initially empty */
- os_dly.cb_type = HCB;
- os_dly.p_dlnk = NULL;
- os_dly.p_blnk = NULL;
- os_dly.delta_time = 0;
-
- /* Fix SP and systemvariables to assume idle task is running */
- /* Transform main program into idle task by assuming idle TCB */
-#ifndef __CMSIS_RTOS
- rt_set_PSP (os_idle_TCB.tsk_stack);
-#endif
- os_tsk.run = &os_idle_TCB;
- os_tsk.run->state = RUNNING;
-
- /* Initialize ps queue */
- os_psq->first = 0;
- os_psq->last = 0;
- os_psq->size = os_fifo_size;
-
- rt_init_robin ();
-
- /* Intitialize SVC and PendSV */
- rt_svc_init ();
-
-#ifndef __CMSIS_RTOS
- /* Intitialize and start system clock timer */
- os_tick_irqn = os_tick_init ();
- if (os_tick_irqn >= 0) {
- OS_X_INIT(os_tick_irqn);
- }
-
- /* Start up first user task before entering the endless loop */
- rt_tsk_create (first_task, prio_stksz, stk, NULL);
-#endif
-}
-
-
-/*--------------------------- rt_sys_start ----------------------------------*/
-
-#ifdef __CMSIS_RTOS
-void rt_sys_start (void) {
- /* Start system */
-
- /* Intitialize and start system clock timer */
- os_tick_irqn = os_tick_init ();
- if (os_tick_irqn >= 0) {
- OS_X_INIT(os_tick_irqn);
- }
- extern void RestoreContext();
- RestoreContext(); // Start the first task
-}
-#endif
-
-/*----------------------------------------------------------------------------
- * end of file
- *---------------------------------------------------------------------------*/
diff --git a/rtos/rtx/TARGET_ARM7/rt_Task.h b/rtos/rtx/TARGET_ARM7/rt_Task.h
deleted file mode 100644
index 0e70c7844a..0000000000
--- a/rtos/rtx/TARGET_ARM7/rt_Task.h
+++ /dev/null
@@ -1,73 +0,0 @@
-/*----------------------------------------------------------------------------
- * RL-ARM - RTX
- *----------------------------------------------------------------------------
- * Name: RT_TASK.H
- * Purpose: Task functions and system start up.
- * Rev.: V4.60
- *----------------------------------------------------------------------------
- *
- * Copyright (c) 1999-2009 KEIL, 2009-2015 ARM Germany GmbH
- * All rights reserved.
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- * - Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * - 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.
- * - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
- *---------------------------------------------------------------------------*/
-
-/* Definitions */
-#define __CMSIS_RTOS 1
-
-/* Values for 'state' */
-#define INACTIVE 0
-#define READY 1
-#define RUNNING 2
-#define WAIT_DLY 3
-#define WAIT_ITV 4
-#define WAIT_OR 5
-#define WAIT_AND 6
-#define WAIT_SEM 7
-#define WAIT_MBX 8
-#define WAIT_MUT 9
-
-/* Return codes */
-#define OS_R_TMO 0x01
-#define OS_R_EVT 0x02
-#define OS_R_SEM 0x03
-#define OS_R_MBX 0x04
-#define OS_R_MUT 0x05
-
-#define OS_R_OK 0x00
-#define OS_R_NOK 0xff
-
-/* Variables */
-extern struct OS_TSK os_tsk;
-extern struct OS_TCB os_idle_TCB;
-
-/* Functions */
-extern void rt_switch_req (P_TCB p_new);
-extern void rt_dispatch (P_TCB next_TCB);
-extern void rt_block (U16 timeout, U8 block_state);
-extern void rt_tsk_pass (void);
-extern OS_TID rt_tsk_self (void);
-extern OS_RESULT rt_tsk_prio (OS_TID task_id, U8 new_prio);
-extern OS_RESULT rt_tsk_delete (OS_TID task_id);
-extern void rt_sys_init (void);
-extern void rt_sys_start (void);
diff --git a/rtos/rtx/TARGET_ARM7/rt_Time.c b/rtos/rtx/TARGET_ARM7/rt_Time.c
deleted file mode 100644
index 075f2e5188..0000000000
--- a/rtos/rtx/TARGET_ARM7/rt_Time.c
+++ /dev/null
@@ -1,94 +0,0 @@
-/*----------------------------------------------------------------------------
- * RL-ARM - RTX
- *----------------------------------------------------------------------------
- * Name: RT_TIME.C
- * Purpose: Delay and interval wait functions
- * Rev.: V4.60
- *----------------------------------------------------------------------------
- *
- * Copyright (c) 1999-2009 KEIL, 2009-2015 ARM Germany GmbH
- * All rights reserved.
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- * - Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * - 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.
- * - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
- *---------------------------------------------------------------------------*/
-
-#include "rt_TypeDef.h"
-#include "RTX_Conf.h"
-#include "rt_Task.h"
-#include "rt_Time.h"
-
-/*----------------------------------------------------------------------------
- * Global Variables
- *---------------------------------------------------------------------------*/
-
-/* Free running system tick counter */
-U32 os_time;
-
-
-/*----------------------------------------------------------------------------
- * Functions
- *---------------------------------------------------------------------------*/
-
-
-/*--------------------------- rt_time_get -----------------------------------*/
-
-U32 rt_time_get (void) {
- /* Get system time tick */
- return (os_time);
-}
-
-
-/*--------------------------- rt_dly_wait -----------------------------------*/
-
-void rt_dly_wait (U16 delay_time) {
- /* Delay task by "delay_time" */
- rt_block (delay_time, WAIT_DLY);
-}
-
-
-/*--------------------------- rt_itv_set ------------------------------------*/
-
-void rt_itv_set (U16 interval_time) {
- /* Set interval length and define start of first interval */
- os_tsk.run->interval_time = interval_time;
- os_tsk.run->delta_time = interval_time + (U16)os_time;
-}
-
-
-/*--------------------------- rt_itv_wait -----------------------------------*/
-
-void rt_itv_wait (void) {
- /* Wait for interval end and define start of next one */
- U16 delta;
-
- delta = os_tsk.run->delta_time - (U16)os_time;
- os_tsk.run->delta_time += os_tsk.run->interval_time;
- if ((delta & 0x8000) == 0) {
- rt_block (delta, WAIT_ITV);
- }
-}
-
-/*----------------------------------------------------------------------------
- * end of file
- *---------------------------------------------------------------------------*/
-
diff --git a/rtos/rtx/TARGET_ARM7/rt_Time.h b/rtos/rtx/TARGET_ARM7/rt_Time.h
deleted file mode 100644
index addac58d24..0000000000
--- a/rtos/rtx/TARGET_ARM7/rt_Time.h
+++ /dev/null
@@ -1,47 +0,0 @@
-/*----------------------------------------------------------------------------
- * RL-ARM - RTX
- *----------------------------------------------------------------------------
- * Name: RT_TIME.H
- * Purpose: Delay and interval wait functions definitions
- * Rev.: V4.60
- *----------------------------------------------------------------------------
- *
- * Copyright (c) 1999-2009 KEIL, 2009-2015 ARM Germany GmbH
- * All rights reserved.
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- * - Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * - 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.
- * - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
- *---------------------------------------------------------------------------*/
-
-/* Variables */
-extern U32 os_time;
-
-/* Functions */
-extern U32 rt_time_get (void);
-extern void rt_dly_wait (U16 delay_time);
-extern void rt_itv_set (U16 interval_time);
-extern void rt_itv_wait (void);
-
-/*----------------------------------------------------------------------------
- * end of file
- *---------------------------------------------------------------------------*/
-
diff --git a/rtos/rtx/TARGET_ARM7/rt_TypeDef.h b/rtos/rtx/TARGET_ARM7/rt_TypeDef.h
deleted file mode 100644
index 33ed708163..0000000000
--- a/rtos/rtx/TARGET_ARM7/rt_TypeDef.h
+++ /dev/null
@@ -1,128 +0,0 @@
-/*----------------------------------------------------------------------------
- * RL-ARM - RTX
- *----------------------------------------------------------------------------
- * Name: RT_TYPEDEF.H
- * Purpose: Type Definitions
- * Rev.: V4.60
- *----------------------------------------------------------------------------
- *
- * Copyright (c) 1999-2009 KEIL, 2009-2015 ARM Germany GmbH
- * All rights reserved.
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- * - Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * - 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.
- * - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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 RT_TYPE_DEF_H
-#define RT_TYPE_DEF_H
-
-#include "os_tcb.h"
-
-typedef U32 OS_TID;
-typedef void *OS_ID;
-typedef U32 OS_RESULT;
-
-#define TCB_STACKF 32 /* 'stack_frame' offset */
-#define TCB_TSTACK 40 /* 'tsk_stack' offset */
-
-typedef struct OS_PSFE { /* Post Service Fifo Entry */
- void *id; /* Object Identification */
- U32 arg; /* Object Argument */
-} *P_PSFE;
-
-typedef struct OS_PSQ { /* Post Service Queue */
- U8 first; /* FIFO Head Index */
- U8 last; /* FIFO Tail Index */
- U8 count; /* Number of stored items in FIFO */
- U8 size; /* FIFO Size */
- struct OS_PSFE q[1]; /* FIFO Content */
-} *P_PSQ;
-
-typedef struct OS_TSK {
- P_TCB run; /* Current running task */
- P_TCB new_tsk; /* Scheduled task to run */
-} *P_TSK;
-
-typedef struct OS_ROBIN { /* Round Robin Control */
- P_TCB task; /* Round Robin task */
- U16 time; /* Round Robin switch time */
- U16 tout; /* Round Robin timeout */
-} *P_ROBIN;
-
-typedef struct OS_XCB {
- U8 cb_type; /* Control Block Type */
- struct OS_TCB *p_lnk; /* Link pointer for ready/sem. wait list */
- struct OS_TCB *p_rlnk; /* Link pointer for sem./mbx lst backwards */
- struct OS_TCB *p_dlnk; /* Link pointer for delay list */
- struct OS_TCB *p_blnk; /* Link pointer for delay list backwards */
- U16 delta_time; /* Time until time out */
-} *P_XCB;
-
-typedef struct OS_MCB {
- U8 cb_type; /* Control Block Type */
- U8 state; /* State flag variable */
- U8 isr_st; /* State flag variable for isr functions */
- struct OS_TCB *p_lnk; /* Chain of tasks waiting for message */
- U16 first; /* Index of the message list begin */
- U16 last; /* Index of the message list end */
- U16 count; /* Actual number of stored messages */
- U16 size; /* Maximum number of stored messages */
- void *msg[1]; /* FIFO for Message pointers 1st element */
-} *P_MCB;
-
-typedef struct OS_SCB {
- U8 cb_type; /* Control Block Type */
- U8 mask; /* Semaphore token mask */
- U16 tokens; /* Semaphore tokens */
- struct OS_TCB *p_lnk; /* Chain of tasks waiting for tokens */
-} *P_SCB;
-
-typedef struct OS_MUCB {
- U8 cb_type; /* Control Block Type */
- U8 prio; /* Owner task default priority */
- U16 level; /* Call nesting level */
- struct OS_TCB *p_lnk; /* Chain of tasks waiting for mutex */
- struct OS_TCB *owner; /* Mutex owner task */
-} *P_MUCB;
-
-typedef struct OS_XTMR {
- struct OS_TMR *next;
- U16 tcnt;
-} *P_XTMR;
-
-typedef struct OS_TMR {
- struct OS_TMR *next; /* Link pointer to Next timer */
- U16 tcnt; /* Timer delay count */
- U16 info; /* User defined call info */
-} *P_TMR;
-
-typedef struct OS_BM {
- void *free; /* Pointer to first free memory block */
- void *end; /* Pointer to memory block end */
- U32 blk_size; /* Memory block size */
-} *P_BM;
-
-/* Definitions */
-#define __TRUE 1
-#define __FALSE 0
-#define NULL ((void *) 0)
-
-#endif
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/PeripheralNames.h b/targets/TARGET_NXP/TARGET_LPC23XX/PeripheralNames.h
deleted file mode 100644
index 285837eedf..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/PeripheralNames.h
+++ /dev/null
@@ -1,110 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2013 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-#ifndef MBED_PERIPHERALNAMES_H
-#define MBED_PERIPHERALNAMES_H
-
-#include "cmsis.h"
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-typedef enum {
- UART_0 = (int)LPC_UART0_BASE,
- UART_1 = (int)LPC_UART1_BASE,
- UART_2 = (int)LPC_UART2_BASE,
- UART_3 = (int)LPC_UART3_BASE
-} UARTName;
-
-typedef enum {
- ADC0_0 = 0,
- ADC0_1,
- ADC0_2,
- ADC0_3,
- ADC0_4,
- ADC0_5,
- ADC0_6,
- ADC0_7
-} ADCName;
-
-typedef enum {
- DAC_0 = 0
-} DACName;
-
-typedef enum {
- SPI_0 = (int)LPC_SSP0_BASE,
- SPI_1 = (int)LPC_SSP1_BASE
-} SPIName;
-
-typedef enum {
- I2C_0 = (int)LPC_I2C0_BASE,
- I2C_1 = (int)LPC_I2C1_BASE,
- I2C_2 = (int)LPC_I2C2_BASE
-} I2CName;
-
-typedef enum {
- PWM_1 = 1,
- PWM_2,
- PWM_3,
- PWM_4,
- PWM_5,
- PWM_6
-} PWMName;
-
-typedef enum {
- CAN_1 = (int)LPC_CAN1_BASE,
- CAN_2 = (int)LPC_CAN2_BASE
-} CANName;
-
-#define STDIO_UART_TX USBTX
-#define STDIO_UART_RX USBRX
-#define STDIO_UART UART_0
-
-// Default peripherals
-#define MBED_SPI0 p5, p6, p7, p8
-#define MBED_SPI1 p11, p12, p13, p14
-
-#define MBED_UART0 p9, p10
-#define MBED_UART1 p13, p14
-#define MBED_UART2 p28, p27
-#define MBED_UARTUSB USBTX, USBRX
-
-#define MBED_I2C0 p28, p27
-#define MBED_I2C1 p9, p10
-
-#define MBED_CAN0 p30, p29
-
-#define MBED_ANALOGOUT0 p18
-
-#define MBED_ANALOGIN0 p15
-#define MBED_ANALOGIN1 p16
-#define MBED_ANALOGIN2 p17
-#define MBED_ANALOGIN3 p18
-#define MBED_ANALOGIN4 p19
-#define MBED_ANALOGIN5 p20
-
-#define MBED_PWMOUT0 p26
-#define MBED_PWMOUT1 p25
-#define MBED_PWMOUT2 p24
-#define MBED_PWMOUT3 p23
-#define MBED_PWMOUT4 p22
-#define MBED_PWMOUT5 p21
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/PinNames.h b/targets/TARGET_NXP/TARGET_LPC23XX/PinNames.h
deleted file mode 100644
index 2b85b9ca27..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/PinNames.h
+++ /dev/null
@@ -1,104 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2013 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-
-#ifndef MBED_PINNAMES_H
-#define MBED_PINNAMES_H
-
-#include "cmsis.h"
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-typedef enum {
- PIN_INPUT,
- PIN_OUTPUT
-} PinDirection;
-
-#define PORT_SHIFT 5
-
-typedef enum {
- // LPC Pin Names
- P0_0 = LPC_GPIO0_BASE,
- P0_1, P0_2, P0_3, P0_4, P0_5, P0_6, P0_7, P0_8, P0_9, P0_10, P0_11, P0_12, P0_13, P0_14, P0_15, P0_16, P0_17, P0_18, P0_19, P0_20, P0_21, P0_22, P0_23, P0_24, P0_25, P0_26, P0_27, P0_28, P0_29, P0_30, P0_31,
- P1_0, P1_1, P1_2, P1_3, P1_4, P1_5, P1_6, P1_7, P1_8, P1_9, P1_10, P1_11, P1_12, P1_13, P1_14, P1_15, P1_16, P1_17, P1_18, P1_19, P1_20, P1_21, P1_22, P1_23, P1_24, P1_25, P1_26, P1_27, P1_28, P1_29, P1_30, P1_31,
- P2_0, P2_1, P2_2, P2_3, P2_4, P2_5, P2_6, P2_7, P2_8, P2_9, P2_10, P2_11, P2_12, P2_13, P2_14, P2_15, P2_16, P2_17, P2_18, P2_19, P2_20, P2_21, P2_22, P2_23, P2_24, P2_25, P2_26, P2_27, P2_28, P2_29, P2_30, P2_31,
- P3_0, P3_1, P3_2, P3_3, P3_4, P3_5, P3_6, P3_7, P3_8, P3_9, P3_10, P3_11, P3_12, P3_13, P3_14, P3_15, P3_16, P3_17, P3_18, P3_19, P3_20, P3_21, P3_22, P3_23, P3_24, P3_25, P3_26, P3_27, P3_28, P3_29, P3_30, P3_31,
- P4_0, P4_1, P4_2, P4_3, P4_4, P4_5, P4_6, P4_7, P4_8, P4_9, P4_10, P4_11, P4_12, P4_13, P4_14, P4_15, P4_16, P4_17, P4_18, P4_19, P4_20, P4_21, P4_22, P4_23, P4_24, P4_25, P4_26, P4_27, P4_28, P4_29, P4_30, P4_31,
-
- // mbed DIP Pin Names
- p5 = P0_9,
- p6 = P0_8,
- p7 = P0_7,
- p8 = P0_6,
- p9 = P0_0,
- p10 = P0_1,
- p11 = P0_18,
- p12 = P0_17,
- p13 = P0_15,
- p14 = P0_16,
- p15 = P0_23,
- p16 = P0_24,
- p17 = P0_25,
- p18 = P0_26,
- p19 = P1_30,
- p20 = P1_31,
- p21 = P2_5,
- p22 = P2_4,
- p23 = P2_3,
- p24 = P2_2,
- p25 = P2_1,
- p26 = P2_0,
- p27 = P0_11,
- p28 = P0_10,
- p29 = P0_5,
- p30 = P0_4,
-
- // Other mbed Pin Names
- LED1 = P1_18,
- LED2 = P1_20,
- LED3 = P1_21,
- LED4 = P1_23,
-
- USBTX = P0_2,
- USBRX = P0_3,
-
- // Not connected
- NC = (int)0xFFFFFFFF
-} PinName;
-
-typedef enum {
- PullUp = 0,
- PullDown = 3,
- PullNone = 2,
- OpenDrain = 4,
- PullDefault = PullDown
-} PinMode;
-
-// version of PINCON_TypeDef using register arrays
-typedef struct {
- __IO uint32_t PINSEL[11];
- uint32_t RESERVED0[5];
- __IO uint32_t PINMODE[10];
-} PINCONARRAY_TypeDef;
-
-#define PINCONARRAY ((PINCONARRAY_TypeDef *)LPC_PINCON_BASE)
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/PortNames.h b/targets/TARGET_NXP/TARGET_LPC23XX/PortNames.h
deleted file mode 100644
index 270cdeecb0..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/PortNames.h
+++ /dev/null
@@ -1,34 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2013 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-#ifndef MBED_PORTNAMES_H
-#define MBED_PORTNAMES_H
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-typedef enum {
- Port0 = 0,
- Port1 = 1,
- Port2 = 2,
- Port3 = 3,
- Port4 = 4
-} PortName;
-
-#ifdef __cplusplus
-}
-#endif
-#endif
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/analogin_api.c b/targets/TARGET_NXP/TARGET_LPC23XX/analogin_api.c
deleted file mode 100644
index 4c3770e836..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/analogin_api.c
+++ /dev/null
@@ -1,123 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2013 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-#include "mbed_assert.h"
-#include "analogin_api.h"
-#include "cmsis.h"
-#include "pinmap.h"
-
-#define ANALOGIN_MEDIAN_FILTER 1
-
-#define ADC_10BIT_RANGE 0x3FF
-#define ADC_12BIT_RANGE 0xFFF
-
-static inline int div_round_up(int x, int y) {
- return (x + (y - 1)) / y;
-}
-
-static const PinMap PinMap_ADC[] = {
- {P0_23, ADC0_0, 1},
- {P0_24, ADC0_1, 1},
- {P0_25, ADC0_2, 1},
- {P0_26, ADC0_3, 1},
- {P1_30, ADC0_4, 3},
- {P1_31, ADC0_5, 3},
- {NC, NC, 0}
-};
-
-#define ADC_RANGE ADC_10BIT_RANGE
-
-
-void analogin_init(analogin_t *obj, PinName pin) {
- obj->adc = (ADCName)pinmap_peripheral(pin, PinMap_ADC);
- MBED_ASSERT(obj->adc != (ADCName)NC);
-
- // ensure power is turned on
- LPC_SC->PCONP |= (1 << 12);
-
- // set PCLK of ADC to /1
- LPC_SC->PCLKSEL0 &= ~(0x3 << 24);
- LPC_SC->PCLKSEL0 |= (0x1 << 24);
- uint32_t PCLK = SystemCoreClock;
-
- // calculate minimum clock divider
- // clkdiv = divider - 1
- uint32_t MAX_ADC_CLK = 13000000;
- uint32_t clkdiv = div_round_up(PCLK, MAX_ADC_CLK) - 1;
-
- // Set the generic software-controlled ADC settings
- LPC_ADC->ADCR = (0 << 0) // SEL: 0 = no channels selected
- | (clkdiv << 8) // CLKDIV: PCLK max ~= 25MHz, /25 to give safe 1MHz at fastest
- | (0 << 16) // BURST: 0 = software control
- | (0 << 17) // CLKS: not applicable
- | (1 << 21) // PDN: 1 = operational
- | (0 << 24) // START: 0 = no start
- | (0 << 27); // EDGE: not applicable
-
- pinmap_pinout(pin, PinMap_ADC);
-}
-
-static inline uint32_t adc_read(analogin_t *obj) {
- // Select the appropriate channel and start conversion
- LPC_ADC->ADCR &= ~0xFF;
- LPC_ADC->ADCR |= 1 << (int)obj->adc;
- LPC_ADC->ADCR |= 1 << 24;
-
- // Repeatedly get the sample data until DONE bit
- unsigned int data;
- do {
- data = LPC_ADC->ADGDR;
- } while ((data & ((unsigned int)1 << 31)) == 0);
-
- // Stop conversion
- LPC_ADC->ADCR &= ~(1 << 24);
-
- return (data >> 6) & ADC_RANGE; // 10 bit
-}
-
-static inline void order(uint32_t *a, uint32_t *b) {
- if (*a > *b) {
- uint32_t t = *a;
- *a = *b;
- *b = t;
- }
-}
-
-static inline uint32_t adc_read_u32(analogin_t *obj) {
- uint32_t value;
-#if ANALOGIN_MEDIAN_FILTER
- uint32_t v1 = adc_read(obj);
- uint32_t v2 = adc_read(obj);
- uint32_t v3 = adc_read(obj);
- order(&v1, &v2);
- order(&v2, &v3);
- order(&v1, &v2);
- value = v2;
-#else
- value = adc_read(obj);
-#endif
- return value;
-}
-
-uint16_t analogin_read_u16(analogin_t *obj) {
- uint32_t value = adc_read_u32(obj);
-
- return (value << 6) | ((value >> 4) & 0x003F); // 10 bit
-}
-
-float analogin_read(analogin_t *obj) {
- uint32_t value = adc_read_u32(obj);
- return (float)value * (1.0f / (float)ADC_RANGE);
-}
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/analogout_api.c b/targets/TARGET_NXP/TARGET_LPC23XX/analogout_api.c
deleted file mode 100644
index 66c77ceace..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/analogout_api.c
+++ /dev/null
@@ -1,75 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2013 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-#include "mbed_assert.h"
-#include "analogout_api.h"
-#include "cmsis.h"
-#include "pinmap.h"
-
-static const PinMap PinMap_DAC[] = {
- {P0_26, DAC_0, 2},
- {NC , NC , 0}
-};
-
-void analogout_init(dac_t *obj, PinName pin) {
- obj->dac = (DACName)pinmap_peripheral(pin, PinMap_DAC);
- MBED_ASSERT(obj->dac != (DACName)NC);
-
- // power is on by default, set DAC clk divider is /4
- LPC_SC->PCLKSEL0 &= ~(0x3 << 22);
-
- // map out (must be done before accessing registers)
- pinmap_pinout(pin, PinMap_DAC);
-
- analogout_write_u16(obj, 0);
-}
-
-void analogout_free(dac_t *obj) {}
-
-static inline void dac_write(int value) {
- value &= 0x3FF; // 10-bit
-
- // Set the DAC output
- LPC_DAC->DACR = (0 << 16) // bias = 0
- | (value << 6);
-}
-
-static inline int dac_read() {
- return (LPC_DAC->DACR >> 6) & 0x3FF;
-}
-
-void analogout_write(dac_t *obj, float value) {
- if (value < 0.0f) {
- dac_write(0);
- } else if (value > 1.0f) {
- dac_write(0x3FF);
- } else {
- dac_write(value * (float)0x3FF);
- }
-}
-
-void analogout_write_u16(dac_t *obj, uint16_t value) {
- dac_write(value >> 6); // 10-bit
-}
-
-float analogout_read(dac_t *obj) {
- uint32_t value = dac_read();
- return (float)value * (1.0f / (float)0x3FF);
-}
-
-uint16_t analogout_read_u16(dac_t *obj) {
- uint32_t value = dac_read(); // 10-bit
- return (value << 6) | ((value >> 4) & 0x003F);
-}
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/can_api.c b/targets/TARGET_NXP/TARGET_LPC23XX/can_api.c
deleted file mode 100644
index a3170acc1d..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/can_api.c
+++ /dev/null
@@ -1,303 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2013 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-#include "mbed_assert.h"
-#include "can_api.h"
-#include "cmsis.h"
-#include "pinmap.h"
-
-#include
-#include
-
-/* Acceptance filter mode in AFMR register */
-#define ACCF_OFF 0x01
-#define ACCF_BYPASS 0x02
-#define ACCF_ON 0x00
-#define ACCF_FULLCAN 0x04
-
-/* There are several bit timing calculators on the internet.
-http://www.port.de/engl/canprod/sv_req_form.html
-http://www.kvaser.com/can/index.htm
-*/
-
-static const PinMap PinMap_CAN_RD[] = {
- {P0_0 , CAN_1, 1},
- {P0_4 , CAN_2, 2},
- {P0_21, CAN_1, 3},
- {P2_7 , CAN_2, 1},
- {NC , NC , 0}
-};
-
-static const PinMap PinMap_CAN_TD[] = {
- {P0_1 , CAN_1, 1},
- {P0_5 , CAN_2, 2},
- {P0_22, CAN_1, 3},
- {P2_8 , CAN_2, 1},
- {NC , NC , 0}
-};
-
-// Type definition to hold a CAN message
-struct CANMsg {
- unsigned int reserved1 : 16;
- unsigned int dlc : 4; // Bits 16..19: DLC - Data Length Counter
- unsigned int reserved0 : 10;
- unsigned int rtr : 1; // Bit 30: Set if this is a RTR message
- unsigned int type : 1; // Bit 31: Set if this is a 29-bit ID message
- unsigned int id; // CAN Message ID (11-bit or 29-bit)
- unsigned char data[8]; // CAN Message Data Bytes 0-7
-};
-typedef struct CANMsg CANMsg;
-
-static uint32_t can_disable(can_t *obj) {
- uint32_t sm = obj->dev->MOD;
- obj->dev->MOD |= 1;
- return sm;
-}
-
-static inline void can_enable(can_t *obj) {
- if (obj->dev->MOD & 1) {
- obj->dev->MOD &= ~(1);
- }
-}
-
-int can_mode(can_t *obj, CanMode mode) {
- return 0; // not implemented
-}
-
-int can_filter(can_t *obj, uint32_t id, uint32_t mask, CANFormat format, int32_t handle) {
- return 0; // not implemented
-}
-
-static int can_pclk(can_t *obj) {
- int value = 0;
- switch ((int)obj->dev) {
- case CAN_1: value = (LPC_SC->PCLKSEL0 & (0x3 << 26)) >> 26; break;
- case CAN_2: value = (LPC_SC->PCLKSEL0 & (0x3 << 28)) >> 28; break;
- }
-
- switch (value) {
- case 1: return 1;
- case 2: return 2;
- case 3: return 6;
- default: return 4;
- }
-}
-
-// This table has the sampling points as close to 75% as possible. The first
-// value is TSEG1, the second TSEG2.
-static const int timing_pts[23][2] = {
- {0x0, 0x0}, // 2, 50%
- {0x1, 0x0}, // 3, 67%
- {0x2, 0x0}, // 4, 75%
- {0x3, 0x0}, // 5, 80%
- {0x3, 0x1}, // 6, 67%
- {0x4, 0x1}, // 7, 71%
- {0x5, 0x1}, // 8, 75%
- {0x6, 0x1}, // 9, 78%
- {0x6, 0x2}, // 10, 70%
- {0x7, 0x2}, // 11, 73%
- {0x8, 0x2}, // 12, 75%
- {0x9, 0x2}, // 13, 77%
- {0x9, 0x3}, // 14, 71%
- {0xA, 0x3}, // 15, 73%
- {0xB, 0x3}, // 16, 75%
- {0xC, 0x3}, // 17, 76%
- {0xD, 0x3}, // 18, 78%
- {0xD, 0x4}, // 19, 74%
- {0xE, 0x4}, // 20, 75%
- {0xF, 0x4}, // 21, 76%
- {0xF, 0x5}, // 22, 73%
- {0xF, 0x6}, // 23, 70%
- {0xF, 0x7}, // 24, 67%
-};
-
-static unsigned int can_speed(unsigned int sclk, unsigned int pclk, unsigned int cclk, unsigned char psjw) {
- uint32_t btr;
- uint16_t brp = 0;
- uint32_t calcbit;
- uint32_t bitwidth;
- int hit = 0;
- int bits;
-
- bitwidth = sclk / (pclk * cclk);
-
- brp = bitwidth / 0x18;
- while ((!hit) && (brp < bitwidth / 4)) {
- brp++;
- for (bits = 22; bits > 0; bits--) {
- calcbit = (bits + 3) * (brp + 1);
- if (calcbit == bitwidth) {
- hit = 1;
- break;
- }
- }
- }
-
- if (hit) {
- btr = ((timing_pts[bits][1] << 20) & 0x00700000)
- | ((timing_pts[bits][0] << 16) & 0x000F0000)
- | ((psjw << 14) & 0x0000C000)
- | ((brp << 0) & 0x000003FF);
- } else {
- btr = 0xFFFFFFFF;
- }
-
- return btr;
-}
-
-void can_init(can_t *obj, PinName rd, PinName td) {
- CANName can_rd = (CANName)pinmap_peripheral(rd, PinMap_CAN_RD);
- CANName can_td = (CANName)pinmap_peripheral(td, PinMap_CAN_TD);
- obj->dev = (LPC_CAN_TypeDef *)pinmap_merge(can_rd, can_td);
- MBED_ASSERT((int)obj->dev != NC);
-
- switch ((int)obj->dev) {
- case CAN_1: LPC_SC->PCONP |= 1 << 13; break;
- case CAN_2: LPC_SC->PCONP |= 1 << 14; break;
- }
-
- pinmap_pinout(rd, PinMap_CAN_RD);
- pinmap_pinout(td, PinMap_CAN_TD);
-
- can_reset(obj);
- obj->dev->IER = 0; // Disable Interrupts
- can_frequency(obj, 100000);
-
- LPC_CANAF->AFMR = ACCF_BYPASS; // Bypass Filter
-}
-
-void can_free(can_t *obj) {
- switch ((int)obj->dev) {
- case CAN_1: LPC_SC->PCONP &= ~(1 << 13); break;
- case CAN_2: LPC_SC->PCONP &= ~(1 << 14); break;
- }
-}
-
-int can_frequency(can_t *obj, int f) {
- int pclk = can_pclk(obj);
- int btr = can_speed(SystemCoreClock, pclk, (unsigned int)f, 1);
-
- if (btr > 0) {
- uint32_t modmask = can_disable(obj);
- obj->dev->BTR = btr;
- obj->dev->MOD = modmask;
- return 1;
- } else {
- return 0;
- }
-}
-
-int can_write(can_t *obj, CAN_Message msg, int cc) {
- unsigned int CANStatus;
- CANMsg m;
-
- can_enable(obj);
-
- m.id = msg.id ;
- m.dlc = msg.len & 0xF;
- m.rtr = msg.type;
- m.type = msg.format;
- memcpy(m.data, msg.data, msg.len);
- const unsigned int *buf = (const unsigned int *)&m;
-
- CANStatus = obj->dev->SR;
- if (CANStatus & 0x00000004) {
- obj->dev->TFI1 = buf[0] & 0xC00F0000;
- obj->dev->TID1 = buf[1];
- obj->dev->TDA1 = buf[2];
- obj->dev->TDB1 = buf[3];
- if (cc) {
- obj->dev->CMR = 0x30;
- } else {
- obj->dev->CMR = 0x21;
- }
- return 1;
-
- } else if (CANStatus & 0x00000400) {
- obj->dev->TFI2 = buf[0] & 0xC00F0000;
- obj->dev->TID2 = buf[1];
- obj->dev->TDA2 = buf[2];
- obj->dev->TDB2 = buf[3];
- if (cc) {
- obj->dev->CMR = 0x50;
- } else {
- obj->dev->CMR = 0x41;
- }
- return 1;
-
- } else if (CANStatus & 0x00040000) {
- obj->dev->TFI3 = buf[0] & 0xC00F0000;
- obj->dev->TID3 = buf[1];
- obj->dev->TDA3 = buf[2];
- obj->dev->TDB3 = buf[3];
- if (cc) {
- obj->dev->CMR = 0x90;
- } else {
- obj->dev->CMR = 0x81;
- }
- return 1;
- }
-
- return 0;
-}
-
-int can_read(can_t *obj, CAN_Message *msg, int handle) {
- CANMsg x;
- unsigned int *i = (unsigned int *)&x;
-
- can_enable(obj);
-
- if (obj->dev->GSR & 0x1) {
- *i++ = obj->dev->RFS; // Frame
- *i++ = obj->dev->RID; // ID
- *i++ = obj->dev->RDA; // Data A
- *i++ = obj->dev->RDB; // Data B
- obj->dev->CMR = 0x04; // release receive buffer
-
- msg->id = x.id;
- msg->len = x.dlc;
- msg->format = (x.type)? CANExtended : CANStandard;
- msg->type = (x.rtr)? CANRemote: CANData;
- memcpy(msg->data,x.data,x.dlc);
- return 1;
- }
-
- return 0;
-}
-
-void can_reset(can_t *obj) {
- can_disable(obj);
- obj->dev->GSR = 0; // Reset error counter when CAN1MOD is in reset
-}
-
-unsigned char can_rderror(can_t *obj) {
- return (obj->dev->GSR >> 16) & 0xFF;
-}
-
-unsigned char can_tderror(can_t *obj) {
- return (obj->dev->GSR >> 24) & 0xFF;
-}
-
-void can_monitor(can_t *obj, int silent) {
- uint32_t mod_mask = can_disable(obj);
- if (silent) {
- obj->dev->MOD |= (1 << 1);
- } else {
- obj->dev->MOD &= ~(1 << 1);
- }
- if (!(mod_mask & 1)) {
- can_enable(obj);
- }
-}
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/device.h b/targets/TARGET_NXP/TARGET_LPC23XX/device.h
deleted file mode 100644
index 5d57c9de57..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/device.h
+++ /dev/null
@@ -1,40 +0,0 @@
-// The 'features' section in 'target.json' is now used to create the device's hardware preprocessor switches.
-// Check the 'features' section of the target description in 'targets.json' for more details.
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2013 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-#ifndef MBED_DEVICE_H
-#define MBED_DEVICE_H
-
-
-
-
-
-
-
-
-
-
-
-#define DEVICE_ID_LENGTH 32
-#define DEVICE_MAC_OFFSET 20
-
-
-
-
-
-#include "objects.h"
-
-#endif
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/device/LPC23xx.h b/targets/TARGET_NXP/TARGET_LPC23XX/device/LPC23xx.h
deleted file mode 100644
index 9adaac4886..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/device/LPC23xx.h
+++ /dev/null
@@ -1,864 +0,0 @@
-/* mbed Microcontroller Library - LPC23xx CMSIS-like structs
- * Copyright (C) 2009 ARM Limited. All rights reserved.
- *
- * An LPC23xx header file, based on the CMSIS LPC17xx.h and old LPC23xx.h
- */
-
-#ifndef __LPC23xx_H
-#define __LPC23xx_H
-
-#ifdef __cplusplus
- extern "C" {
-#endif
-
-/*
- * ==========================================================================
- * ---------- Interrupt Number Definition -----------------------------------
- * ==========================================================================
- */
-
-typedef enum IRQn
-{
-/****** LPC23xx Specific Interrupt Numbers *******************************************************/
- WDT_IRQn = 0, /*!< Watchdog Timer Interrupt */
-
- TIMER0_IRQn = 4, /*!< Timer0 Interrupt */
- TIMER1_IRQn = 5, /*!< Timer1 Interrupt */
- UART0_IRQn = 6, /*!< UART0 Interrupt */
- UART1_IRQn = 7, /*!< UART1 Interrupt */
- PWM1_IRQn = 8, /*!< PWM1 Interrupt */
- I2C0_IRQn = 9, /*!< I2C0 Interrupt */
- SPI_IRQn = 10, /*!< SPI Interrupt */
- SSP0_IRQn = 10, /*!< SSP0 Interrupt */
- SSP1_IRQn = 11, /*!< SSP1 Interrupt */
- PLL0_IRQn = 12, /*!< PLL0 Lock (Main PLL) Interrupt */
- RTC_IRQn = 13, /*!< Real Time Clock Interrupt */
- EINT0_IRQn = 14, /*!< External Interrupt 0 Interrupt */
- EINT1_IRQn = 15, /*!< External Interrupt 1 Interrupt */
- EINT2_IRQn = 16, /*!< External Interrupt 2 Interrupt */
- EINT3_IRQn = 17, /*!< External Interrupt 3 Interrupt */
- ADC_IRQn = 18, /*!< A/D Converter Interrupt */
- I2C1_IRQn = 19, /*!< I2C1 Interrupt */
- BOD_IRQn = 20, /*!< Brown-Out Detect Interrupt */
- ENET_IRQn = 21, /*!< Ethernet Interrupt */
- USB_IRQn = 22, /*!< USB Interrupt */
- CAN_IRQn = 23, /*!< CAN Interrupt */
- MIC_IRQn = 24, /*!< Multimedia Interface Controler */
- DMA_IRQn = 25, /*!< General Purpose DMA Interrupt */
- TIMER2_IRQn = 26, /*!< Timer2 Interrupt */
- TIMER3_IRQn = 27, /*!< Timer3 Interrupt */
- UART2_IRQn = 28, /*!< UART2 Interrupt */
- UART3_IRQn = 29, /*!< UART3 Interrupt */
- I2C2_IRQn = 30, /*!< I2C2 Interrupt */
- I2S_IRQn = 31, /*!< I2S Interrupt */
-} IRQn_Type;
-
-/*
- * ==========================================================================
- * ----------- Processor and Core Peripheral Section ------------------------
- * ==========================================================================
- */
-
-/* Configuration of the ARM7 Processor and Core Peripherals */
-#define __MPU_PRESENT 0 /*!< MPU present or not */
-#define __NVIC_PRIO_BITS 4 /*!< Number of Bits used for Priority Levels */
-#define __Vendor_SysTickConfig 0 /*!< Set to 1 if different SysTick Config is used */
-
-
-#include
-#include "system_LPC23xx.h" /* System Header */
-
-
-/******************************************************************************/
-/* Device Specific Peripheral registers structures */
-/******************************************************************************/
-#if defined ( __CC_ARM )
- #pragma anon_unions
-#endif
-
-/*------------- Vector Interupt Controler (VIC) ------------------------------*/
-typedef struct
-{
- __I uint32_t IRQStatus;
- __I uint32_t FIQStatus;
- __I uint32_t RawIntr;
- __IO uint32_t IntSelect;
- __IO uint32_t IntEnable;
- __O uint32_t IntEnClr;
- __IO uint32_t SoftInt;
- __O uint32_t SoftIntClr;
- __IO uint32_t Protection;
- __IO uint32_t SWPriorityMask;
- __IO uint32_t RESERVED0[54];
- __IO uint32_t VectAddr[32];
- __IO uint32_t RESERVED1[32];
- __IO uint32_t VectPriority[32];
- __IO uint32_t RESERVED2[800];
- __IO uint32_t Address;
-} LPC_VIC_TypeDef;
-
-/*------------- System Control (SC) ------------------------------------------*/
-typedef struct
-{
- __IO uint32_t MAMCR;
- __IO uint32_t MAMTIM;
- uint32_t RESERVED0[14];
- __IO uint32_t MEMMAP;
- uint32_t RESERVED1[15];
- __IO uint32_t PLL0CON; /* Clocking and Power Control */
- __IO uint32_t PLL0CFG;
- __I uint32_t PLL0STAT;
- __O uint32_t PLL0FEED;
- uint32_t RESERVED2[12];
- __IO uint32_t PCON;
- __IO uint32_t PCONP;
- uint32_t RESERVED3[15];
- __IO uint32_t CCLKCFG;
- __IO uint32_t USBCLKCFG;
- __IO uint32_t CLKSRCSEL;
- uint32_t RESERVED4[12];
- __IO uint32_t EXTINT; /* External Interrupts */
- __IO uint32_t INTWAKE;
- __IO uint32_t EXTMODE;
- __IO uint32_t EXTPOLAR;
- uint32_t RESERVED6[12];
- __IO uint32_t RSID; /* Reset */
- __IO uint32_t CSPR;
- __IO uint32_t AHBCFG1;
- __IO uint32_t AHBCFG2;
- uint32_t RESERVED7[4];
- __IO uint32_t SCS; /* Syscon Miscellaneous Registers */
- __IO uint32_t IRCTRIM; /* Clock Dividers */
- __IO uint32_t PCLKSEL0;
- __IO uint32_t PCLKSEL1;
- uint32_t RESERVED8[4];
- __IO uint32_t USBIntSt; /* USB Device/OTG Interrupt Register */
- uint32_t RESERVED9;
-// __IO uint32_t CLKOUTCFG; /* Clock Output Configuration */
- } LPC_SC_TypeDef;
-
-/*------------- Pin Connect Block (PINCON) -----------------------------------*/
-typedef struct
-{
- __IO uint32_t PINSEL0;
- __IO uint32_t PINSEL1;
- __IO uint32_t PINSEL2;
- __IO uint32_t PINSEL3;
- __IO uint32_t PINSEL4;
- __IO uint32_t PINSEL5;
- __IO uint32_t PINSEL6;
- __IO uint32_t PINSEL7;
- __IO uint32_t PINSEL8;
- __IO uint32_t PINSEL9;
- __IO uint32_t PINSEL10;
- uint32_t RESERVED0[5];
- __IO uint32_t PINMODE0;
- __IO uint32_t PINMODE1;
- __IO uint32_t PINMODE2;
- __IO uint32_t PINMODE3;
- __IO uint32_t PINMODE4;
- __IO uint32_t PINMODE5;
- __IO uint32_t PINMODE6;
- __IO uint32_t PINMODE7;
- __IO uint32_t PINMODE8;
- __IO uint32_t PINMODE9;
- __IO uint32_t PINMODE_OD0;
- __IO uint32_t PINMODE_OD1;
- __IO uint32_t PINMODE_OD2;
- __IO uint32_t PINMODE_OD3;
- __IO uint32_t PINMODE_OD4;
-} LPC_PINCON_TypeDef;
-
-/*------------- General Purpose Input/Output (GPIO) --------------------------*/
-typedef struct
-{
- __IO uint32_t FIODIR;
- uint32_t RESERVED0[3];
- __IO uint32_t FIOMASK;
- __IO uint32_t FIOPIN;
- __IO uint32_t FIOSET;
- __O uint32_t FIOCLR;
-} LPC_GPIO_TypeDef;
-
-typedef struct
-{
- __I uint32_t IntStatus;
- __I uint32_t IO0IntStatR;
- __I uint32_t IO0IntStatF;
- __O uint32_t IO0IntClr;
- __IO uint32_t IO0IntEnR;
- __IO uint32_t IO0IntEnF;
- uint32_t RESERVED0[3];
- __I uint32_t IO2IntStatR;
- __I uint32_t IO2IntStatF;
- __O uint32_t IO2IntClr;
- __IO uint32_t IO2IntEnR;
- __IO uint32_t IO2IntEnF;
-} LPC_GPIOINT_TypeDef;
-
-/*------------- Timer (TIM) --------------------------------------------------*/
-typedef struct
-{
- __IO uint32_t IR;
- __IO uint32_t TCR;
- __IO uint32_t TC;
- __IO uint32_t PR;
- __IO uint32_t PC;
- __IO uint32_t MCR;
- __IO uint32_t MR0;
- __IO uint32_t MR1;
- __IO uint32_t MR2;
- __IO uint32_t MR3;
- __IO uint32_t CCR;
- __I uint32_t CR0;
- __I uint32_t CR1;
- uint32_t RESERVED0[2];
- __IO uint32_t EMR;
- uint32_t RESERVED1[12];
- __IO uint32_t CTCR;
-} LPC_TIM_TypeDef;
-
-/*------------- Pulse-Width Modulation (PWM) ---------------------------------*/
-typedef struct
-{
- __IO uint32_t IR;
- __IO uint32_t TCR;
- __IO uint32_t TC;
- __IO uint32_t PR;
- __IO uint32_t PC;
- __IO uint32_t MCR;
- __IO uint32_t MR0;
- __IO uint32_t MR1;
- __IO uint32_t MR2;
- __IO uint32_t MR3;
- __IO uint32_t CCR;
- __I uint32_t CR0;
- __I uint32_t CR1;
- __I uint32_t CR2;
- __I uint32_t CR3;
- uint32_t RESERVED0;
- __IO uint32_t MR4;
- __IO uint32_t MR5;
- __IO uint32_t MR6;
- __IO uint32_t PCR;
- __IO uint32_t LER;
- uint32_t RESERVED1[7];
- __IO uint32_t CTCR;
-} LPC_PWM_TypeDef;
-
-/*------------- Universal Asynchronous Receiver Transmitter (UART) -----------*/
-typedef struct
-{
- union {
- __I uint8_t RBR;
- __O uint8_t THR;
- __IO uint8_t DLL;
- uint32_t RESERVED0;
- };
- union {
- __IO uint8_t DLM;
- __IO uint32_t IER;
- };
- union {
- __I uint32_t IIR;
- __O uint8_t FCR;
- };
- __IO uint8_t LCR;
- uint8_t RESERVED1[7];
- __IO uint8_t LSR;
- uint8_t RESERVED2[7];
- __IO uint8_t SCR;
- uint8_t RESERVED3[3];
- __IO uint32_t ACR;
- __IO uint8_t ICR;
- uint8_t RESERVED4[3];
- __IO uint8_t FDR;
- uint8_t RESERVED5[7];
- __IO uint8_t TER;
- uint8_t RESERVED6[27];
- __IO uint8_t RS485CTRL;
- uint8_t RESERVED7[3];
- __IO uint8_t ADRMATCH;
-} LPC_UART_TypeDef;
-
-typedef struct
-{
- union {
- __I uint8_t RBR;
- __O uint8_t THR;
- __IO uint8_t DLL;
- uint32_t RESERVED0;
- };
- union {
- __IO uint8_t DLM;
- __IO uint32_t IER;
- };
- union {
- __I uint32_t IIR;
- __O uint8_t FCR;
- };
- __IO uint8_t LCR;
- uint8_t RESERVED1[3];
- __IO uint8_t MCR;
- uint8_t RESERVED2[3];
- __IO uint8_t LSR;
- uint8_t RESERVED3[3];
- __IO uint8_t MSR;
- uint8_t RESERVED4[3];
- __IO uint8_t SCR;
- uint8_t RESERVED5[3];
- __IO uint32_t ACR;
- uint32_t RESERVED6;
- __IO uint32_t FDR;
- uint32_t RESERVED7;
- __IO uint8_t TER;
- uint8_t RESERVED8[27];
- __IO uint8_t RS485CTRL;
- uint8_t RESERVED9[3];
- __IO uint8_t ADRMATCH;
- uint8_t RESERVED10[3];
- __IO uint8_t RS485DLY;
-} LPC_UART1_TypeDef;
-
-/*------------- Serial Peripheral Interface (SPI) ----------------------------*/
-typedef struct
-{
- __IO uint32_t SPCR;
- __I uint32_t SPSR;
- __IO uint32_t SPDR;
- __IO uint32_t SPCCR;
- uint32_t RESERVED0[3];
- __IO uint32_t SPINT;
-} LPC_SPI_TypeDef;
-
-/*------------- Synchronous Serial Communication (SSP) -----------------------*/
-typedef struct
-{
- __IO uint32_t CR0;
- __IO uint32_t CR1;
- __IO uint32_t DR;
- __I uint32_t SR;
- __IO uint32_t CPSR;
- __IO uint32_t IMSC;
- __IO uint32_t RIS;
- __IO uint32_t MIS;
- __IO uint32_t ICR;
- __IO uint32_t DMACR;
-} LPC_SSP_TypeDef;
-
-/*------------- Inter-Integrated Circuit (I2C) -------------------------------*/
-typedef struct
-{
- __IO uint32_t I2CONSET;
- __I uint32_t I2STAT;
- __IO uint32_t I2DAT;
- __IO uint32_t I2ADR0;
- __IO uint32_t I2SCLH;
- __IO uint32_t I2SCLL;
- __O uint32_t I2CONCLR;
- __IO uint32_t MMCTRL;
- __IO uint32_t I2ADR1;
- __IO uint32_t I2ADR2;
- __IO uint32_t I2ADR3;
- __I uint32_t I2DATA_BUFFER;
- __IO uint32_t I2MASK0;
- __IO uint32_t I2MASK1;
- __IO uint32_t I2MASK2;
- __IO uint32_t I2MASK3;
-} LPC_I2C_TypeDef;
-
-/*------------- Inter IC Sound (I2S) -----------------------------------------*/
-typedef struct
-{
- __IO uint32_t I2SDAO;
- __I uint32_t I2SDAI;
- __O uint32_t I2STXFIFO;
- __I uint32_t I2SRXFIFO;
- __I uint32_t I2SSTATE;
- __IO uint32_t I2SDMA1;
- __IO uint32_t I2SDMA2;
- __IO uint32_t I2SIRQ;
- __IO uint32_t I2STXRATE;
- __IO uint32_t I2SRXRATE;
- __IO uint32_t I2STXBITRATE;
- __IO uint32_t I2SRXBITRATE;
- __IO uint32_t I2STXMODE;
- __IO uint32_t I2SRXMODE;
-} LPC_I2S_TypeDef;
-
-/*------------- Real-Time Clock (RTC) ----------------------------------------*/
-typedef struct
-{
- __IO uint8_t ILR;
- uint8_t RESERVED0[3];
- __IO uint8_t CTC;
- uint8_t RESERVED1[3];
- __IO uint8_t CCR;
- uint8_t RESERVED2[3];
- __IO uint8_t CIIR;
- uint8_t RESERVED3[3];
- __IO uint8_t AMR;
- uint8_t RESERVED4[3];
- __I uint32_t CTIME0;
- __I uint32_t CTIME1;
- __I uint32_t CTIME2;
- __IO uint8_t SEC;
- uint8_t RESERVED5[3];
- __IO uint8_t MIN;
- uint8_t RESERVED6[3];
- __IO uint8_t HOUR;
- uint8_t RESERVED7[3];
- __IO uint8_t DOM;
- uint8_t RESERVED8[3];
- __IO uint8_t DOW;
- uint8_t RESERVED9[3];
- __IO uint16_t DOY;
- uint16_t RESERVED10;
- __IO uint8_t MONTH;
- uint8_t RESERVED11[3];
- __IO uint16_t YEAR;
- uint16_t RESERVED12;
- __IO uint32_t CALIBRATION;
- __IO uint32_t GPREG0;
- __IO uint32_t GPREG1;
- __IO uint32_t GPREG2;
- __IO uint32_t GPREG3;
- __IO uint32_t GPREG4;
- __IO uint8_t WAKEUPDIS;
- uint8_t RESERVED13[3];
- __IO uint8_t PWRCTRL;
- uint8_t RESERVED14[3];
- __IO uint8_t ALSEC;
- uint8_t RESERVED15[3];
- __IO uint8_t ALMIN;
- uint8_t RESERVED16[3];
- __IO uint8_t ALHOUR;
- uint8_t RESERVED17[3];
- __IO uint8_t ALDOM;
- uint8_t RESERVED18[3];
- __IO uint8_t ALDOW;
- uint8_t RESERVED19[3];
- __IO uint16_t ALDOY;
- uint16_t RESERVED20;
- __IO uint8_t ALMON;
- uint8_t RESERVED21[3];
- __IO uint16_t ALYEAR;
- uint16_t RESERVED22;
-} LPC_RTC_TypeDef;
-
-/*------------- Watchdog Timer (WDT) -----------------------------------------*/
-typedef struct
-{
- __IO uint8_t WDMOD;
- uint8_t RESERVED0[3];
- __IO uint32_t WDTC;
- __O uint8_t WDFEED;
- uint8_t RESERVED1[3];
- __I uint32_t WDTV;
- __IO uint32_t WDCLKSEL;
-} LPC_WDT_TypeDef;
-
-/*------------- Analog-to-Digital Converter (ADC) ----------------------------*/
-typedef struct
-{
- __IO uint32_t ADCR;
- __IO uint32_t ADGDR;
- uint32_t RESERVED0;
- __IO uint32_t ADINTEN;
- __I uint32_t ADDR0;
- __I uint32_t ADDR1;
- __I uint32_t ADDR2;
- __I uint32_t ADDR3;
- __I uint32_t ADDR4;
- __I uint32_t ADDR5;
- __I uint32_t ADDR6;
- __I uint32_t ADDR7;
- __I uint32_t ADSTAT;
- __IO uint32_t ADTRM;
-} LPC_ADC_TypeDef;
-
-/*------------- Digital-to-Analog Converter (DAC) ----------------------------*/
-typedef struct
-{
- __IO uint32_t DACR;
- __IO uint32_t DACCTRL;
- __IO uint16_t DACCNTVAL;
-} LPC_DAC_TypeDef;
-
-/*------------- Multimedia Card Interface (MCI) ------------------------------*/
-typedef struct
-{
- __IO uint32_t MCIPower; /* Power control */
- __IO uint32_t MCIClock; /* Clock control */
- __IO uint32_t MCIArgument;
- __IO uint32_t MMCCommand;
- __I uint32_t MCIRespCmd;
- __I uint32_t MCIResponse0;
- __I uint32_t MCIResponse1;
- __I uint32_t MCIResponse2;
- __I uint32_t MCIResponse3;
- __IO uint32_t MCIDataTimer;
- __IO uint32_t MCIDataLength;
- __IO uint32_t MCIDataCtrl;
- __I uint32_t MCIDataCnt;
-} LPC_MCI_TypeDef;
-
-/*------------- Controller Area Network (CAN) --------------------------------*/
-typedef struct
-{
- __IO uint32_t mask[512]; /* ID Masks */
-} LPC_CANAF_RAM_TypeDef;
-
-typedef struct /* Acceptance Filter Registers */
-{
- __IO uint32_t AFMR;
- __IO uint32_t SFF_sa;
- __IO uint32_t SFF_GRP_sa;
- __IO uint32_t EFF_sa;
- __IO uint32_t EFF_GRP_sa;
- __IO uint32_t ENDofTable;
- __I uint32_t LUTerrAd;
- __I uint32_t LUTerr;
-} LPC_CANAF_TypeDef;
-
-typedef struct /* Central Registers */
-{
- __I uint32_t CANTxSR;
- __I uint32_t CANRxSR;
- __I uint32_t CANMSR;
-} LPC_CANCR_TypeDef;
-
-typedef struct /* Controller Registers */
-{
- __IO uint32_t MOD;
- __O uint32_t CMR;
- __IO uint32_t GSR;
- __I uint32_t ICR;
- __IO uint32_t IER;
- __IO uint32_t BTR;
- __IO uint32_t EWL;
- __I uint32_t SR;
- __IO uint32_t RFS;
- __IO uint32_t RID;
- __IO uint32_t RDA;
- __IO uint32_t RDB;
- __IO uint32_t TFI1;
- __IO uint32_t TID1;
- __IO uint32_t TDA1;
- __IO uint32_t TDB1;
- __IO uint32_t TFI2;
- __IO uint32_t TID2;
- __IO uint32_t TDA2;
- __IO uint32_t TDB2;
- __IO uint32_t TFI3;
- __IO uint32_t TID3;
- __IO uint32_t TDA3;
- __IO uint32_t TDB3;
-} LPC_CAN_TypeDef;
-
-/*------------- General Purpose Direct Memory Access (GPDMA) -----------------*/
-typedef struct /* Common Registers */
-{
- __I uint32_t DMACIntStat;
- __I uint32_t DMACIntTCStat;
- __O uint32_t DMACIntTCClear;
- __I uint32_t DMACIntErrStat;
- __O uint32_t DMACIntErrClr;
- __I uint32_t DMACRawIntTCStat;
- __I uint32_t DMACRawIntErrStat;
- __I uint32_t DMACEnbldChns;
- __IO uint32_t DMACSoftBReq;
- __IO uint32_t DMACSoftSReq;
- __IO uint32_t DMACSoftLBReq;
- __IO uint32_t DMACSoftLSReq;
- __IO uint32_t DMACConfig;
- __IO uint32_t DMACSync;
-} LPC_GPDMA_TypeDef;
-
-typedef struct /* Channel Registers */
-{
- __IO uint32_t DMACCSrcAddr;
- __IO uint32_t DMACCDestAddr;
- __IO uint32_t DMACCLLI;
- __IO uint32_t DMACCControl;
- __IO uint32_t DMACCConfig;
-} LPC_GPDMACH_TypeDef;
-
-/*------------- Universal Serial Bus (USB) -----------------------------------*/
-typedef struct
-{
- __I uint32_t HcRevision; /* USB Host Registers */
- __IO uint32_t HcControl;
- __IO uint32_t HcCommandStatus;
- __IO uint32_t HcInterruptStatus;
- __IO uint32_t HcInterruptEnable;
- __IO uint32_t HcInterruptDisable;
- __IO uint32_t HcHCCA;
- __I uint32_t HcPeriodCurrentED;
- __IO uint32_t HcControlHeadED;
- __IO uint32_t HcControlCurrentED;
- __IO uint32_t HcBulkHeadED;
- __IO uint32_t HcBulkCurrentED;
- __I uint32_t HcDoneHead;
- __IO uint32_t HcFmInterval;
- __I uint32_t HcFmRemaining;
- __I uint32_t HcFmNumber;
- __IO uint32_t HcPeriodicStart;
- __IO uint32_t HcLSTreshold;
- __IO uint32_t HcRhDescriptorA;
- __IO uint32_t HcRhDescriptorB;
- __IO uint32_t HcRhStatus;
- __IO uint32_t HcRhPortStatus1;
- __IO uint32_t HcRhPortStatus2;
- uint32_t RESERVED0[40];
- __I uint32_t Module_ID;
-
- __I uint32_t OTGIntSt; /* USB On-The-Go Registers */
- __IO uint32_t OTGIntEn;
- __O uint32_t OTGIntSet;
- __O uint32_t OTGIntClr;
- __IO uint32_t OTGStCtrl;
- __IO uint32_t OTGTmr;
- uint32_t RESERVED1[58];
-
- __I uint32_t USBDevIntSt; /* USB Device Interrupt Registers */
- __IO uint32_t USBDevIntEn;
- __O uint32_t USBDevIntClr;
- __O uint32_t USBDevIntSet;
-
- __O uint32_t USBCmdCode; /* USB Device SIE Command Registers */
- __I uint32_t USBCmdData;
-
- __I uint32_t USBRxData; /* USB Device Transfer Registers */
- __O uint32_t USBTxData;
- __I uint32_t USBRxPLen;
- __O uint32_t USBTxPLen;
- __IO uint32_t USBCtrl;
- __O uint32_t USBDevIntPri;
-
- __I uint32_t USBEpIntSt; /* USB Device Endpoint Interrupt Regs */
- __IO uint32_t USBEpIntEn;
- __O uint32_t USBEpIntClr;
- __O uint32_t USBEpIntSet;
- __O uint32_t USBEpIntPri;
-
- __IO uint32_t USBReEp; /* USB Device Endpoint Realization Reg*/
- __O uint32_t USBEpInd;
- __IO uint32_t USBMaxPSize;
-
- __I uint32_t USBDMARSt; /* USB Device DMA Registers */
- __O uint32_t USBDMARClr;
- __O uint32_t USBDMARSet;
- uint32_t RESERVED2[9];
- __IO uint32_t USBUDCAH;
- __I uint32_t USBEpDMASt;
- __O uint32_t USBEpDMAEn;
- __O uint32_t USBEpDMADis;
- __I uint32_t USBDMAIntSt;
- __IO uint32_t USBDMAIntEn;
- uint32_t RESERVED3[2];
- __I uint32_t USBEoTIntSt;
- __O uint32_t USBEoTIntClr;
- __O uint32_t USBEoTIntSet;
- __I uint32_t USBNDDRIntSt;
- __O uint32_t USBNDDRIntClr;
- __O uint32_t USBNDDRIntSet;
- __I uint32_t USBSysErrIntSt;
- __O uint32_t USBSysErrIntClr;
- __O uint32_t USBSysErrIntSet;
- uint32_t RESERVED4[15];
-
- __I uint32_t I2C_RX; /* USB OTG I2C Registers */
- __O uint32_t I2C_WO;
- __I uint32_t I2C_STS;
- __IO uint32_t I2C_CTL;
- __IO uint32_t I2C_CLKHI;
- __O uint32_t I2C_CLKLO;
- uint32_t RESERVED5[823];
-
- union {
- __IO uint32_t USBClkCtrl; /* USB Clock Control Registers */
- __IO uint32_t OTGClkCtrl;
- };
- union {
- __I uint32_t USBClkSt;
- __I uint32_t OTGClkSt;
- };
-} LPC_USB_TypeDef;
-
-/*------------- Ethernet Media Access Controller (EMAC) ----------------------*/
-typedef struct
-{
- __IO uint32_t MAC1; /* MAC Registers */
- __IO uint32_t MAC2;
- __IO uint32_t IPGT;
- __IO uint32_t IPGR;
- __IO uint32_t CLRT;
- __IO uint32_t MAXF;
- __IO uint32_t SUPP;
- __IO uint32_t TEST;
- __IO uint32_t MCFG;
- __IO uint32_t MCMD;
- __IO uint32_t MADR;
- __O uint32_t MWTD;
- __I uint32_t MRDD;
- __I uint32_t MIND;
- uint32_t RESERVED0[2];
- __IO uint32_t SA0;
- __IO uint32_t SA1;
- __IO uint32_t SA2;
- uint32_t RESERVED1[45];
- __IO uint32_t Command; /* Control Registers */
- __I uint32_t Status;
- __IO uint32_t RxDescriptor;
- __IO uint32_t RxStatus;
- __IO uint32_t RxDescriptorNumber;
- __I uint32_t RxProduceIndex;
- __IO uint32_t RxConsumeIndex;
- __IO uint32_t TxDescriptor;
- __IO uint32_t TxStatus;
- __IO uint32_t TxDescriptorNumber;
- __IO uint32_t TxProduceIndex;
- __I uint32_t TxConsumeIndex;
- uint32_t RESERVED2[10];
- __I uint32_t TSV0;
- __I uint32_t TSV1;
- __I uint32_t RSV;
- uint32_t RESERVED3[3];
- __IO uint32_t FlowControlCounter;
- __I uint32_t FlowControlStatus;
- uint32_t RESERVED4[34];
- __IO uint32_t RxFilterCtrl; /* Rx Filter Registers */
- __IO uint32_t RxFilterWoLStatus;
- __IO uint32_t RxFilterWoLClear;
- uint32_t RESERVED5;
- __IO uint32_t HashFilterL;
- __IO uint32_t HashFilterH;
- uint32_t RESERVED6[882];
- __I uint32_t IntStatus; /* Module Control Registers */
- __IO uint32_t IntEnable;
- __O uint32_t IntClear;
- __O uint32_t IntSet;
- uint32_t RESERVED7;
- __IO uint32_t PowerDown;
- uint32_t RESERVED8;
- __IO uint32_t Module_ID;
-} LPC_EMAC_TypeDef;
-
-#if defined ( __CC_ARM )
- #pragma no_anon_unions
-#endif
-
-/******************************************************************************/
-/* Peripheral memory map */
-/******************************************************************************/
-/* Base addresses */
-
-/* AHB Peripheral # 0 */
-
-/*
-#define FLASH_BASE (0x00000000UL)
-#define RAM_BASE (0x10000000UL)
-#define GPIO_BASE (0x2009C000UL)
-#define APB0_BASE (0x40000000UL)
-#define APB1_BASE (0x40080000UL)
-#define AHB_BASE (0x50000000UL)
-#define CM3_BASE (0xE0000000UL)
-*/
-
-// TODO - #define VIC_BASE_ADDR 0xFFFFF000
-
-#define LPC_WDT_BASE (0xE0000000)
-#define LPC_TIM0_BASE (0xE0004000)
-#define LPC_TIM1_BASE (0xE0008000)
-#define LPC_UART0_BASE (0xE000C000)
-#define LPC_UART1_BASE (0xE0010000)
-#define LPC_PWM1_BASE (0xE0018000)
-#define LPC_I2C0_BASE (0xE001C000)
-#define LPC_SPI_BASE (0xE0020000)
-#define LPC_RTC_BASE (0xE0024000)
-#define LPC_GPIOINT_BASE (0xE0028080)
-#define LPC_PINCON_BASE (0xE002C000)
-#define LPC_SSP1_BASE (0xE0030000)
-#define LPC_ADC_BASE (0xE0034000)
-#define LPC_CANAF_RAM_BASE (0xE0038000)
-#define LPC_CANAF_BASE (0xE003C000)
-#define LPC_CANCR_BASE (0xE0040000)
-#define LPC_CAN1_BASE (0xE0044000)
-#define LPC_CAN2_BASE (0xE0048000)
-#define LPC_I2C1_BASE (0xE005C000)
-#define LPC_SSP0_BASE (0xE0068000)
-#define LPC_DAC_BASE (0xE006C000)
-#define LPC_TIM2_BASE (0xE0070000)
-#define LPC_TIM3_BASE (0xE0074000)
-#define LPC_UART2_BASE (0xE0078000)
-#define LPC_UART3_BASE (0xE007C000)
-#define LPC_I2C2_BASE (0xE0080000)
-#define LPC_I2S_BASE (0xE0088000)
-#define LPC_MCI_BASE (0xE008C000)
-#define LPC_SC_BASE (0xE01FC000)
-#define LPC_EMAC_BASE (0xFFE00000)
-#define LPC_GPDMA_BASE (0xFFE04000)
-#define LPC_GPDMACH0_BASE (0xFFE04100)
-#define LPC_GPDMACH1_BASE (0xFFE04120)
-#define LPC_USB_BASE (0xFFE0C000)
-#define LPC_VIC_BASE (0xFFFFF000)
-
-/* GPIOs */
-#define LPC_GPIO0_BASE (0x3FFFC000)
-#define LPC_GPIO1_BASE (0x3FFFC020)
-#define LPC_GPIO2_BASE (0x3FFFC040)
-#define LPC_GPIO3_BASE (0x3FFFC060)
-#define LPC_GPIO4_BASE (0x3FFFC080)
-
-
-/******************************************************************************/
-/* Peripheral declaration */
-/******************************************************************************/
-#define LPC_SC (( LPC_SC_TypeDef *) LPC_SC_BASE)
-#define LPC_GPIO0 (( LPC_GPIO_TypeDef *) LPC_GPIO0_BASE)
-#define LPC_GPIO1 (( LPC_GPIO_TypeDef *) LPC_GPIO1_BASE)
-#define LPC_GPIO2 (( LPC_GPIO_TypeDef *) LPC_GPIO2_BASE)
-#define LPC_GPIO3 (( LPC_GPIO_TypeDef *) LPC_GPIO3_BASE)
-#define LPC_GPIO4 (( LPC_GPIO_TypeDef *) LPC_GPIO4_BASE)
-#define LPC_WDT (( LPC_WDT_TypeDef *) LPC_WDT_BASE)
-#define LPC_TIM0 (( LPC_TIM_TypeDef *) LPC_TIM0_BASE)
-#define LPC_TIM1 (( LPC_TIM_TypeDef *) LPC_TIM1_BASE)
-#define LPC_TIM2 (( LPC_TIM_TypeDef *) LPC_TIM2_BASE)
-#define LPC_TIM3 (( LPC_TIM_TypeDef *) LPC_TIM3_BASE)
-#define LPC_UART0 (( LPC_UART_TypeDef *) LPC_UART0_BASE)
-#define LPC_UART1 (( LPC_UART1_TypeDef *) LPC_UART1_BASE)
-#define LPC_UART2 (( LPC_UART_TypeDef *) LPC_UART2_BASE)
-#define LPC_UART3 (( LPC_UART_TypeDef *) LPC_UART3_BASE)
-#define LPC_PWM1 (( LPC_PWM_TypeDef *) LPC_PWM1_BASE)
-#define LPC_I2C0 (( LPC_I2C_TypeDef *) LPC_I2C0_BASE)
-#define LPC_I2C1 (( LPC_I2C_TypeDef *) LPC_I2C1_BASE)
-#define LPC_I2C2 (( LPC_I2C_TypeDef *) LPC_I2C2_BASE)
-#define LPC_I2S (( LPC_I2S_TypeDef *) LPC_I2S_BASE)
-#define LPC_SPI (( LPC_SPI_TypeDef *) LPC_SPI_BASE)
-#define LPC_RTC (( LPC_RTC_TypeDef *) LPC_RTC_BASE)
-#define LPC_GPIOINT (( LPC_GPIOINT_TypeDef *) LPC_GPIOINT_BASE)
-#define LPC_PINCON (( LPC_PINCON_TypeDef *) LPC_PINCON_BASE)
-#define LPC_SSP0 (( LPC_SSP_TypeDef *) LPC_SSP0_BASE)
-#define LPC_SSP1 (( LPC_SSP_TypeDef *) LPC_SSP1_BASE)
-#define LPC_ADC (( LPC_ADC_TypeDef *) LPC_ADC_BASE)
-#define LPC_DAC (( LPC_DAC_TypeDef *) LPC_DAC_BASE)
-#define LPC_CANAF_RAM ((LPC_CANAF_RAM_TypeDef *) LPC_CANAF_RAM_BASE)
-#define LPC_CANAF (( LPC_CANAF_TypeDef *) LPC_CANAF_BASE)
-#define LPC_CANCR (( LPC_CANCR_TypeDef *) LPC_CANCR_BASE)
-#define LPC_CAN1 (( LPC_CAN_TypeDef *) LPC_CAN1_BASE)
-#define LPC_CAN2 (( LPC_CAN_TypeDef *) LPC_CAN2_BASE)
-#define LPC_MCI (( LPC_MCI_TypeDef *) LPC_MCI_BASE)
-#define LPC_EMAC (( LPC_EMAC_TypeDef *) LPC_EMAC_BASE)
-#define LPC_GPDMA (( LPC_GPDMA_TypeDef *) LPC_GPDMA_BASE)
-#define LPC_GPDMACH0 (( LPC_GPDMACH_TypeDef *) LPC_GPDMACH0_BASE)
-#define LPC_GPDMACH1 (( LPC_GPDMACH_TypeDef *) LPC_GPDMACH1_BASE)
-#define LPC_USB (( LPC_USB_TypeDef *) LPC_USB_BASE)
-#define LPC_VIC (( LPC_VIC_TypeDef *) LPC_VIC_BASE)
-
-#ifdef __cplusplus
- }
-#endif
-
-#endif // __LPC23xx_H
-
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_ARM_MICRO/LPC2368.sct b/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_ARM_MICRO/LPC2368.sct
deleted file mode 100644
index e2fdfdc09f..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_ARM_MICRO/LPC2368.sct
+++ /dev/null
@@ -1,24 +0,0 @@
-
-LR_IROM1 0x00000000 0x80000 { ; load region size_region
- ER_IROM1 0x00000000 0x80000 { ; load address = execution address
- *.o (RESET, +First)
- *(InRoot$$Sections)
- .ANY (+RO)
- }
- RW_IRAM1 0x40000120 0x7EE0 { ; RW data, inc space for realmonitor
- .ANY (+RW +ZI)
- }
- RW_IRAM2 0x7FD00000 0x2000 { ; RW data, USB RAM
- .ANY (AHBSRAM0)
- }
- RW_IRAM3 0x7FE00000 0x4000 { ; RW data, ETH RAM
- .ANY (AHBSRAM1)
- }
- RW_IRAM4 0xE0038000 0x0800 { ; RW data, CAN RAM
- .ANY (CANRAM)
- }
- RW_IRAM5 0xE0084000 0x0800 { ; RW data, RTC RAM
- .ANY (RTCRAM)
- }
-}
-
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_ARM_MICRO/sys.cpp b/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_ARM_MICRO/sys.cpp
deleted file mode 100644
index 2f1024ace8..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_ARM_MICRO/sys.cpp
+++ /dev/null
@@ -1,31 +0,0 @@
-/* mbed Microcontroller Library - stackheap
- * Copyright (C) 2009-2011 ARM Limited. All rights reserved.
- *
- * Setup a fixed single stack/heap memory model,
- * between the top of the RW/ZI region and the stackpointer
- */
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-#include
-#include
-
-extern char Image$$RW_IRAM1$$ZI$$Limit[];
-
-extern __value_in_regs struct __initial_stackheap __user_setup_stackheap(uint32_t R0, uint32_t R1, uint32_t R2, uint32_t R3) {
- uint32_t zi_limit = (uint32_t)Image$$RW_IRAM1$$ZI$$Limit;
- uint32_t sp_limit = __current_sp();
-
- zi_limit = (zi_limit + 7) & ~0x7; // ensure zi_limit is 8-byte aligned
-
- struct __initial_stackheap r;
- r.heap_base = zi_limit;
- r.heap_limit = sp_limit;
- return r;
-}
-
-#ifdef __cplusplus
-}
-#endif
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_ARM_MICRO/vector_functions.S b/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_ARM_MICRO/vector_functions.S
deleted file mode 100644
index 462eb73c10..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_ARM_MICRO/vector_functions.S
+++ /dev/null
@@ -1,248 +0,0 @@
-;/* mbed Microcontroller Library - InterruptIn
-; * Copyright (c) 2006-2009 ARM Limited. All rights reserved.
-; */
-
-#line 1 "vector_functions.s"
-;
-;
-;
-
-#line 1 "vector_defns.h"
-
-
-
-
-
-
-
-
-
-#line 21 "vector_defns.h"
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-#line 47 "vector_defns.h"
-
-
-#line 58 "vector_defns.h"
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-#line 6 "vector_functions.s"
-
-
- AREA VECFUNCS, CODE, READONLY
- ARM
- PRESERVE8
-
-
-
-
-
- EXPORT __mbed_fiq [WEAK]
- EXPORT __mbed_undef [WEAK]
- EXPORT __mbed_prefetch_abort [WEAK]
- EXPORT __mbed_data_abort [WEAK]
- EXPORT __mbed_irq [WEAK]
- EXPORT __mbed_swi [WEAK]
- EXPORT __mbed_dcc_irq [WEAK]
- EXPORT __mbed_reset [WEAK]
- IMPORT __mbed_init_realmonitor
-
-;
-;
-__mbed_fiq
- B __mbed_fiq
-
-;
-;
-__mbed_undef
- LDR PC, =0x7fffffa0
-
-;
-;
-__mbed_prefetch_abort
- LDR PC, =0x7fffffb0
-
-;
-;
-__mbed_data_abort
- LDR PC, =0x7fffffc0
-
-;
-;
-;
-;
-;
-;
-;
-;
-;
-__mbed_irq
- ;
- MSR CPSR_c, #0x1F:OR:0x80:OR:0x40
-
- ;
- STMDB sp!, {r0-r3,r12,lr}
-
- ;
- MOV r0, #0xFFFFFF00
- LDR r0, [r0]
-
- ;
- MOV lr, pc
- BX r0
-
- ;
- MOV r0, #0xFFFFFF00
- STR r0, [r0] ;
-
- ;
- LDMFD sp!,{r0-r3,r12,lr}
-
- ;
- MSR CPSR_c, #0x12:OR:0x80:OR:0x40
-
- ;
- SUBS pc, lr, #4
-
-;
-;
-;
-;
-__mbed_swi
- ;
- ;
- STMFD sp!, {a4, r4, ip, lr}
-
- ;
- LDR r4, =0x40000040
-
- ;
- ;
- LDR a4, =0x00940000
- LDR PC, =0x7ffff820
-
-;
-;
-;
-;
-__mbed_dcc_irq
-
- ;
-
- ;
- LDMFD sp!,{r0-r3,r12,lr}
-
- ;
- MSR CPSR_c, #0x12:OR:0x80:OR:0x40
-
- ;
-
- ;
- SUB lr, lr, #4 ;
- STMFD sp!, {ip,lr} ;
-
- ;
- LDR LR, =0xfffff000
- STR LR, [LR, #0xf00]
-
- ;
- ;
- ;
- ;
- LDR PC, =0x7fffffe0
-
-;
-; __mbed_reset is called after reset
-; we setup the stacks and realmonitor, then call Reset_Handler like on M3
-
-; Reset Handler
-
-Reset_Handler PROC
- EXPORT Reset_Handler [WEAK]
- IMPORT SystemInit
- IMPORT __main
- LDR R0, =SystemInit
- MOV LR, PC
- BX R0
- LDR R0, =__main
- BX R0
- ENDP
-
-__mbed_reset
-
- ;
-
- LDR R0, =(0x40000000 + 0x8000)
-
- ;
- MSR CPSR_c, #0x1B:OR:0x80:OR:0x40
- MOV SP, R0
- SUB R0, R0, #0x00000040
-
- ;
- MSR CPSR_c, #0x17:OR:0x80:OR:0x40
- MOV SP, R0
- SUB R0, R0, #0x00000040
-
- ;
- MSR CPSR_c, #0x11:OR:0x80:OR:0x40
- MOV SP, R0
- SUB R0, R0, #0x00000000
-
- ;
- MSR CPSR_c, #0x12:OR:0x80:OR:0x40
- MOV SP, R0
- SUB R0, R0, #0x00000040
-
- ;
- MSR CPSR_c, #0x13:OR:0x80:OR:0x40
- MOV SP, R0
- SUB R0, R0, #0x00000040
-
- ;
- MSR CPSR_c, #0x10
- MOV SP, R0
-
- ;
- LDR R0, =__mbed_init_realmonitor
- MOV LR, PC
- BX R0
-
- ;
- LDR R0, =Reset_Handler
- BX R0
-
-
- END
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_ARM_MICRO/vector_table.S b/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_ARM_MICRO/vector_table.S
deleted file mode 100644
index 2fca324728..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_ARM_MICRO/vector_table.S
+++ /dev/null
@@ -1,99 +0,0 @@
-;/* mbed Microcontroller Library - InterruptIn
-; * Copyright (c) 2006-2009 ARM Limited. All rights reserved.
-; */
-
-#line 1 "vector_table.s"
-;
-
-
-
-
-#line 1 "vector_defns.h"
-
-
-
-
-
-
-
-
-
-#line 21 "vector_defns.h"
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-#line 47 "vector_defns.h"
-
-
-#line 58 "vector_defns.h"
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-#line 7 "vector_table.s"
-
-;
-
-
- AREA RESET, CODE, READONLY
- ARM
-; ENTRY
- PRESERVE8
-
-
-
-
-
-; EXPORT __main
- IMPORT __mbed_reset
- IMPORT __mbed_undef
- IMPORT __mbed_swi
- IMPORT __mbed_prefetch_abort
- IMPORT __mbed_data_abort
- IMPORT __mbed_irq
- IMPORT __mbed_fiq
-
-;
-
-
-;__main
- LDR PC, =__mbed_reset
- LDR PC, =__mbed_undef
- LDR PC, =__mbed_swi
- LDR PC, =__mbed_prefetch_abort
- LDR PC, =__mbed_data_abort
- NOP ;
- LDR PC, =__mbed_irq
- LDR PC, =__mbed_fiq
-
-
- END
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_ARM_STD/LPC2368.sct b/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_ARM_STD/LPC2368.sct
deleted file mode 100644
index e2fdfdc09f..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_ARM_STD/LPC2368.sct
+++ /dev/null
@@ -1,24 +0,0 @@
-
-LR_IROM1 0x00000000 0x80000 { ; load region size_region
- ER_IROM1 0x00000000 0x80000 { ; load address = execution address
- *.o (RESET, +First)
- *(InRoot$$Sections)
- .ANY (+RO)
- }
- RW_IRAM1 0x40000120 0x7EE0 { ; RW data, inc space for realmonitor
- .ANY (+RW +ZI)
- }
- RW_IRAM2 0x7FD00000 0x2000 { ; RW data, USB RAM
- .ANY (AHBSRAM0)
- }
- RW_IRAM3 0x7FE00000 0x4000 { ; RW data, ETH RAM
- .ANY (AHBSRAM1)
- }
- RW_IRAM4 0xE0038000 0x0800 { ; RW data, CAN RAM
- .ANY (CANRAM)
- }
- RW_IRAM5 0xE0084000 0x0800 { ; RW data, RTC RAM
- .ANY (RTCRAM)
- }
-}
-
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_ARM_STD/sys.cpp b/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_ARM_STD/sys.cpp
deleted file mode 100644
index 2f1024ace8..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_ARM_STD/sys.cpp
+++ /dev/null
@@ -1,31 +0,0 @@
-/* mbed Microcontroller Library - stackheap
- * Copyright (C) 2009-2011 ARM Limited. All rights reserved.
- *
- * Setup a fixed single stack/heap memory model,
- * between the top of the RW/ZI region and the stackpointer
- */
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-#include
-#include
-
-extern char Image$$RW_IRAM1$$ZI$$Limit[];
-
-extern __value_in_regs struct __initial_stackheap __user_setup_stackheap(uint32_t R0, uint32_t R1, uint32_t R2, uint32_t R3) {
- uint32_t zi_limit = (uint32_t)Image$$RW_IRAM1$$ZI$$Limit;
- uint32_t sp_limit = __current_sp();
-
- zi_limit = (zi_limit + 7) & ~0x7; // ensure zi_limit is 8-byte aligned
-
- struct __initial_stackheap r;
- r.heap_base = zi_limit;
- r.heap_limit = sp_limit;
- return r;
-}
-
-#ifdef __cplusplus
-}
-#endif
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_ARM_STD/vector_functions.S b/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_ARM_STD/vector_functions.S
deleted file mode 100644
index 462eb73c10..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_ARM_STD/vector_functions.S
+++ /dev/null
@@ -1,248 +0,0 @@
-;/* mbed Microcontroller Library - InterruptIn
-; * Copyright (c) 2006-2009 ARM Limited. All rights reserved.
-; */
-
-#line 1 "vector_functions.s"
-;
-;
-;
-
-#line 1 "vector_defns.h"
-
-
-
-
-
-
-
-
-
-#line 21 "vector_defns.h"
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-#line 47 "vector_defns.h"
-
-
-#line 58 "vector_defns.h"
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-#line 6 "vector_functions.s"
-
-
- AREA VECFUNCS, CODE, READONLY
- ARM
- PRESERVE8
-
-
-
-
-
- EXPORT __mbed_fiq [WEAK]
- EXPORT __mbed_undef [WEAK]
- EXPORT __mbed_prefetch_abort [WEAK]
- EXPORT __mbed_data_abort [WEAK]
- EXPORT __mbed_irq [WEAK]
- EXPORT __mbed_swi [WEAK]
- EXPORT __mbed_dcc_irq [WEAK]
- EXPORT __mbed_reset [WEAK]
- IMPORT __mbed_init_realmonitor
-
-;
-;
-__mbed_fiq
- B __mbed_fiq
-
-;
-;
-__mbed_undef
- LDR PC, =0x7fffffa0
-
-;
-;
-__mbed_prefetch_abort
- LDR PC, =0x7fffffb0
-
-;
-;
-__mbed_data_abort
- LDR PC, =0x7fffffc0
-
-;
-;
-;
-;
-;
-;
-;
-;
-;
-__mbed_irq
- ;
- MSR CPSR_c, #0x1F:OR:0x80:OR:0x40
-
- ;
- STMDB sp!, {r0-r3,r12,lr}
-
- ;
- MOV r0, #0xFFFFFF00
- LDR r0, [r0]
-
- ;
- MOV lr, pc
- BX r0
-
- ;
- MOV r0, #0xFFFFFF00
- STR r0, [r0] ;
-
- ;
- LDMFD sp!,{r0-r3,r12,lr}
-
- ;
- MSR CPSR_c, #0x12:OR:0x80:OR:0x40
-
- ;
- SUBS pc, lr, #4
-
-;
-;
-;
-;
-__mbed_swi
- ;
- ;
- STMFD sp!, {a4, r4, ip, lr}
-
- ;
- LDR r4, =0x40000040
-
- ;
- ;
- LDR a4, =0x00940000
- LDR PC, =0x7ffff820
-
-;
-;
-;
-;
-__mbed_dcc_irq
-
- ;
-
- ;
- LDMFD sp!,{r0-r3,r12,lr}
-
- ;
- MSR CPSR_c, #0x12:OR:0x80:OR:0x40
-
- ;
-
- ;
- SUB lr, lr, #4 ;
- STMFD sp!, {ip,lr} ;
-
- ;
- LDR LR, =0xfffff000
- STR LR, [LR, #0xf00]
-
- ;
- ;
- ;
- ;
- LDR PC, =0x7fffffe0
-
-;
-; __mbed_reset is called after reset
-; we setup the stacks and realmonitor, then call Reset_Handler like on M3
-
-; Reset Handler
-
-Reset_Handler PROC
- EXPORT Reset_Handler [WEAK]
- IMPORT SystemInit
- IMPORT __main
- LDR R0, =SystemInit
- MOV LR, PC
- BX R0
- LDR R0, =__main
- BX R0
- ENDP
-
-__mbed_reset
-
- ;
-
- LDR R0, =(0x40000000 + 0x8000)
-
- ;
- MSR CPSR_c, #0x1B:OR:0x80:OR:0x40
- MOV SP, R0
- SUB R0, R0, #0x00000040
-
- ;
- MSR CPSR_c, #0x17:OR:0x80:OR:0x40
- MOV SP, R0
- SUB R0, R0, #0x00000040
-
- ;
- MSR CPSR_c, #0x11:OR:0x80:OR:0x40
- MOV SP, R0
- SUB R0, R0, #0x00000000
-
- ;
- MSR CPSR_c, #0x12:OR:0x80:OR:0x40
- MOV SP, R0
- SUB R0, R0, #0x00000040
-
- ;
- MSR CPSR_c, #0x13:OR:0x80:OR:0x40
- MOV SP, R0
- SUB R0, R0, #0x00000040
-
- ;
- MSR CPSR_c, #0x10
- MOV SP, R0
-
- ;
- LDR R0, =__mbed_init_realmonitor
- MOV LR, PC
- BX R0
-
- ;
- LDR R0, =Reset_Handler
- BX R0
-
-
- END
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_ARM_STD/vector_table.S b/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_ARM_STD/vector_table.S
deleted file mode 100644
index 2fca324728..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_ARM_STD/vector_table.S
+++ /dev/null
@@ -1,99 +0,0 @@
-;/* mbed Microcontroller Library - InterruptIn
-; * Copyright (c) 2006-2009 ARM Limited. All rights reserved.
-; */
-
-#line 1 "vector_table.s"
-;
-
-
-
-
-#line 1 "vector_defns.h"
-
-
-
-
-
-
-
-
-
-#line 21 "vector_defns.h"
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-#line 47 "vector_defns.h"
-
-
-#line 58 "vector_defns.h"
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-#line 7 "vector_table.s"
-
-;
-
-
- AREA RESET, CODE, READONLY
- ARM
-; ENTRY
- PRESERVE8
-
-
-
-
-
-; EXPORT __main
- IMPORT __mbed_reset
- IMPORT __mbed_undef
- IMPORT __mbed_swi
- IMPORT __mbed_prefetch_abort
- IMPORT __mbed_data_abort
- IMPORT __mbed_irq
- IMPORT __mbed_fiq
-
-;
-
-
-;__main
- LDR PC, =__mbed_reset
- LDR PC, =__mbed_undef
- LDR PC, =__mbed_swi
- LDR PC, =__mbed_prefetch_abort
- LDR PC, =__mbed_data_abort
- NOP ;
- LDR PC, =__mbed_irq
- LDR PC, =__mbed_fiq
-
-
- END
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_GCC_ARM/LPC2368.ld b/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_GCC_ARM/LPC2368.ld
deleted file mode 100644
index 503141fd5f..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_GCC_ARM/LPC2368.ld
+++ /dev/null
@@ -1,208 +0,0 @@
-OUTPUT_FORMAT("elf32-littlearm", "elf32-bigarm", "elf32-littlearm")
-OUTPUT_ARCH(arm)
-ENTRY(vectors)
-
-/* Memory Definitions: */
-MEMORY
-{
- Flash (rx) : ORIGIN = 0x00000000, LENGTH = 512k
- Ram (rwx) : ORIGIN = 0x40000000, LENGTH = 32k
- UsbRam (rw) : ORIGIN = 0x7FD00000, LENGTH = 8k
- EthRam (rw) : ORIGIN = 0x7FE00000, LENGTH = 16k
- CanRam (rw) : ORIGIN = 0xE0038000, LENGTH = 2k
- BatRam (rw) : ORIGIN = 0xE0084000, LENGTH = 2k
-}
-
-/* Stack sizes: */
-UND_Stack_Size = 16;
-SVC_Stack_Size = 512;
-ABT_Stack_Size = 16;
-FIQ_Stack_Size = 16;
-IRQ_Stack_Size = 256;
-Stack_Size_Total = UND_Stack_Size + SVC_Stack_Size + ABT_Stack_Size + FIQ_Stack_Size + IRQ_Stack_Size;
-
-/* Stack tops for each mode: */
-__und_stack_top__ = __stacks_top__;
-__abt_stack_top__ = __und_stack_top__ - UND_Stack_Size ;
-__fiq_stack_top__ = __abt_stack_top__ - ABT_Stack_Size ;
-__irq_stack_top__ = __fiq_stack_top__ - FIQ_Stack_Size ;
-__svc_stack_top__ = __irq_stack_top__ - IRQ_Stack_Size ;
-
-/* C-accessible symbols for memory address ranges: */
-__FLASH_segment_start__ = ORIGIN( Flash );
-__FLASH_segment_end__ = ORIGIN( Flash ) + LENGTH( Flash );
-__SRAM_segment_start__ = ORIGIN( Ram );
-__SRAM_segment_end__ = ORIGIN( Ram ) + LENGTH( Ram );
-
-/* Stacks (full descending) at top of RAM, grows downward:
- *
- * __stack_min__ is used by the malloc implementation to ensure heap never collides
- * with stack (assuming stack never grows beyond Stack_Size_Total in length) */
-__stacks_top__ = __SRAM_segment_end__;
-__stacks_min__ = __SRAM_segment_end__ - Stack_Size_Total;
-
-SECTIONS
-{
- /* first section is .text which is used for code */
- __text_start__ = . ;
- .text : {
- __privileged_code_start__ = . ;
- KEEP( *( .vectors ) )
- *( .privileged_code )
-
- __privileged_code_end__ = .;
-
- *( .text .text.* .gnu.linkonce.t.* )
- *( .plt )
- *( .gnu.warning )
- *( .glue_7t ) *( .glue_7 ) *( .vfp11_veneer )
-
- *( .rodata .rodata.* .gnu.linkonce.r.* )
-
- *(.ARM.extab* .gnu.linkonce.armextab.*)
- *(.gcc_except_table)
- *(.eh_frame_hdr)
- *(.eh_frame)
-
- . = ALIGN( 4 ) ;
- KEEP( *( .init ) )
- . = ALIGN( 4 ) ;
- __preinit_array_start = . ;
- KEEP( *( .preinit_array ) )
- __preinit_array_end = . ;
- . = ALIGN( 4 ) ;
- __init_array_start = . ;
- KEEP( *( SORT( .init_array.* ) ) )
- KEEP( *( .init_array ) )
- __init_array_end = . ;
-
- . = ALIGN( 4 ) ;
- KEEP( *crtbegin.o( .ctors ) )
- KEEP( *( EXCLUDE_FILE( *crtend.o ) .ctors ) )
- KEEP( *( SORT( .ctors.* ) ) )
- KEEP( *crtend.o( .ctors ) )
-
- . = ALIGN( 4 ) ;
- KEEP( *( .fini ) )
- . = ALIGN( 4 ) ;
- __fini_array_start = . ;
- KEEP( *( .fini_array ) )
- KEEP( *( SORT( .fini_array.* ) ) )
- __fini_array_end = . ;
-
- KEEP( *crtbegin.o( .dtors ) )
- KEEP( *( EXCLUDE_FILE( *crtend.o ) .dtors ) )
- KEEP( *( SORT( .dtors.* ) ) )
- KEEP( *crtend.o( .dtors ) )
-
- } >Flash
-
- __exidx_start = . ;
- .ARM.exidx : {
- *( .ARM.exidx* .gnu.linkonce.armexidx.* )
- } >Flash
- __exidx_end = . ;
-
- .text.align : { . = ALIGN( 8 ) ; } >Flash /* Alignment schenanigans */
- __text_end__ = . ;
-
- /* .bss section -- used for uninitialized data */
- /* Located at the start of RAM */
- .bss (NOLOAD) : {
- __bss_start__ = . ;
- *crt0.o( .ram_vectors )
-
- __user_bss_start__ = . ;
- *( .user_bss )
- __user_bss_end__ = . ;
-
- *( .shbss )
- *( .bss .bss.* .gnu.linkonce.b.* )
- *( COMMON )
- *( .ram.b )
- . = ALIGN( 8 ) ;
-
- __bss_end__ = . ;
- } >Ram AT>Flash
-
- /* .data section -- used for initialized data */
- .data : {
- __data_start__ = . ;
- KEEP( *( .jcr ) )
- *( .got.plt ) *( .got )
- *( .shdata )
- *( .data .data.* .gnu.linkonce.d.* )
- *( .ram )
- . = ALIGN( 8 ) ;
- __data_end__ = . ;
- } >Ram AT>Flash
-
- __data_init_start__ = LOADADDR( .data ) ;
-
- /* Heap starts here and grows up in memory */
- . = ALIGN( 8 ) ;
- __heap_start__ = . ;
- end = . ;
- __end__ = . ;
-
- .stab 0 (NOLOAD) : { *(.stab) }
- .stabstr 0 (NOLOAD) : { *(.stabstr) }
- /* DWARF debug sections. */
- /* Symbols in the DWARF debugging sections are relative to the */
- /* beginning of the section so we begin them at 0. */
- /* DWARF 1 */
- .debug 0 : { *(.debug) }
- .line 0 : { *(.line) }
- /* GNU DWARF 1 extensions */
- .debug_srcinfo 0 : { *(.debug_srcinfo) }
- .debug_sfnames 0 : { *(.debug_sfnames) }
- /* DWARF 1.1 and DWARF 2 */
- .debug_aranges 0 : { *(.debug_aranges) }
- .debug_pubnames 0 : { *(.debug_pubnames) }
- /* DWARF 2 */
- .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) }
- .debug_abbrev 0 : { *(.debug_abbrev) }
- .debug_line 0 : { *(.debug_line) }
- .debug_frame 0 : { *(.debug_frame) }
- .debug_str 0 : { *(.debug_str) }
- .debug_loc 0 : { *(.debug_loc) }
- .debug_macinfo 0 : { *(.debug_macinfo) }
- /* SGI/MIPS DWARF 2 extensions */
- .debug_weaknames 0 : { *(.debug_weaknames) }
- .debug_funcnames 0 : { *(.debug_funcnames) }
- .debug_typenames 0 : { *(.debug_typenames) }
- .debug_varnames 0 : { *(.debug_varnames) }
- /* DWARF 3 */
- .debug_pubtypes 0 : { *(.debug_pubtypes) }
- .debug_ranges 0 : { *(.debug_ranges) }
-
- .note.gnu.arm.ident 0 : { KEEP( *( .note.gnu.arm.ident ) ) }
- .ARM.attributes 0 : {
- KEEP( *( .ARM.attributes ) )
- KEEP( *( .gnu.attributes ) )
- }
- /DISCARD/ : { *( .note.GNU-stack ) }
-
- /* C data can be defined as being in special purpose RAMs using
- * __attribute__ ((section ("ethram"))) for example. */
- .usbram (NOLOAD):
- {
- *( .usbram )
- *( .usbram.* )
- } > UsbRam
- .ethram (NOLOAD):
- {
- *( .ethram )
- *( .ethram.* )
- } > EthRam
- .canram (NOLOAD):
- {
- *( .canram )
- *( .canram.* )
- } > CanRam
- .batram (NOLOAD):
- {
- *( .batram )
- *( .batram.* )
- } > BatRam
-}
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_GCC_ARM/vector_functions.S b/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_GCC_ARM/vector_functions.S
deleted file mode 100644
index a3803a0f2b..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_GCC_ARM/vector_functions.S
+++ /dev/null
@@ -1,148 +0,0 @@
-/* .include "vector_defns.h" */
-
-
-
-.section .privileged_code, "ax"
-.arm
-
-
-.weak __mbed_fiq
-.weak __mbed_undef
-.weak __mbed_prefetch_abort
-.weak __mbed_data_abort
-.weak __mbed_irq
-.weak __mbed_swi
-.weak __mbed_dcc_irq
-.weak __mbed_reset
-.global __mbed_init_realmonitor
-/* .global __mbed_init */
-
-
-
-
-__mbed_fiq:
- B __mbed_fiq
-__mbed_undef:
- LDR PC, =0x7fffffa0
-__mbed_prefetch_abort:
- LDR PC, =0x7fffffb0
-__mbed_data_abort:
- LDR PC, =0x7fffffc0
-__mbed_irq:
- MSR CPSR_c, #0x1F|0x80|0x40
-
- STMDB sp!, {r0-r3,r12,lr}
-
- MOV r0, #0xFFFFFF00
- LDR r0, [r0]
-
- MOV lr, pc
- BX r0
-
- MOV r0, #0xFFFFFF00
- STR r0, [r0]
-
- LDMFD sp!,{r0-r3,r12,lr}
-
- MSR CPSR_c, #0x12|0x80|0x40
-
- SUBS pc, lr, #4
-__mbed_swi:
- STMFD sp!, {a4, r4, ip, lr}
-
- LDR r4, =0x40000040
-
- LDR a4, =0x00940000
- LDR PC, =0x7ffff820
-__mbed_dcc_irq:
- LDMFD sp!,{r0-r3,r12,lr}
-
- MSR CPSR_c, #0x12|0x80|0x40
-
- SUB lr, lr, #4
- STMFD sp!, {ip,lr}
-
- LDR LR, =0xfffff000
- STR LR, [LR, #0xf00]
-
- LDR PC, =0x7fffffe0
-/*
- __mbed_reset is called after reset
- we setup the stacks and realmonitor, then call Reset_Handler like on M3
-*/
-
-.section .text, "ax"
-.arm
-.global Reset_handler
-Reset_Handler:
- .extern __libc_init_array
- .extern SystemInit
- LDR R0, =SystemInit
- MOV LR, PC
- BX R0
-
- LDR R0, =__libc_init_array
- MOV LR, PC
- BX R0
-
- LDR R0, =main
- BX R0
-
-__mbed_reset:
- LDR R0, =( __SRAM_segment_end__ )
-
- MSR CPSR_c, #0x1B|0x80|0x40
- MOV SP, R0
- SUB R0, R0, #0x00000040
-
- MSR CPSR_c, #0x17|0x80|0x40
- MOV SP, R0
- SUB R0, R0, #0x00000040
-
- MSR CPSR_c, #0x11|0x80|0x40
- MOV SP, R0
- SUB R0, R0, #0x00000000
-
- MSR CPSR_c, #0x12|0x80|0x40
- MOV SP, R0
- SUB R0, R0, #0x00000040
-
- MSR CPSR_c, #0x13|0x80|0x40
- MOV SP, R0
- SUB R0, R0, #0x00000040
-
- MSR CPSR_c, #0x10
- MOV SP, R0
-
-/* Relocate .data section (Copy from ROM to RAM) */
- LDR R1, =__text_end__ /* _etext */
- LDR R2, =__data_start__ /* _data */
- LDR R3, =__data_end__ /* _edata */
- CMP R2, R3
- BEQ DataIsEmpty
-LoopRel: CMP R2, R3
- LDRLO R0, [R1], #4
- STRLO R0, [R2], #4
- BLO LoopRel
-DataIsEmpty:
-
-/* Clear .bss section (Zero init) */
- MOV R0, #0
- LDR R1, =__bss_start__
- LDR R2, =__bss_end__
- CMP R1,R2
- BEQ BSSIsEmpty
-LoopZI: CMP R1, R2
- STRLO R0, [R1], #4
- BLO LoopZI
-BSSIsEmpty:
-
-
-/* Init realmonitor */
- LDR R0, =__mbed_init_realmonitor
- MOV LR, PC
- BX R0
-
-/* Go to Reset_Handler */
- LDR R0, =Reset_Handler
- BX R0
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_GCC_ARM/vector_table.S b/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_GCC_ARM/vector_table.S
deleted file mode 100644
index d797c3794d..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_GCC_ARM/vector_table.S
+++ /dev/null
@@ -1,45 +0,0 @@
-# 1 "vector_table.s"
-# 1 ""
-# 1 ""
-# 1 "vector_table.s"
-;
-
-
-
-
-# 1 "vector_defns.h" 1
-# 7 "vector_table.s" 2
-
-;
-
-
-
-
-
-
-
- .section .vectors, "ax"
- .arm
-
-
- .global __main
- .global __mbed_reset
- .global __mbed_undef
- .global __mbed_swi
- .global __mbed_prefetch_abort
- .global __mbed_data_abort
- .global __mbed_irq
- .global __mbed_fiq
-
-;
-
-
-_start:
- LDR PC, =__mbed_reset
- LDR PC, =__mbed_undef
- LDR PC, =__mbed_swi
- LDR PC, =__mbed_prefetch_abort
- LDR PC, =__mbed_data_abort
- NOP ;
- LDR PC, =__mbed_irq
- LDR PC, =__mbed_fiq
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_GCC_CR/LPC2368.ld b/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_GCC_CR/LPC2368.ld
deleted file mode 100644
index 29c738fbf5..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_GCC_CR/LPC2368.ld
+++ /dev/null
@@ -1,210 +0,0 @@
-OUTPUT_FORMAT("elf32-littlearm", "elf32-bigarm", "elf32-littlearm")
-OUTPUT_ARCH(arm)
-ENTRY(vectors)
-
-GROUP( libgcc.a libc.a libm.a libcr_newlib_nohost.a crti.o crtn.o crtbegin.o crtend.o )
-
-/* Memory Definitions: */
-MEMORY
-{
- Flash (rx) : ORIGIN = 0x00000000, LENGTH = 512k
- Ram (rwx) : ORIGIN = 0x40000000, LENGTH = 32k
- UsbRam (rw) : ORIGIN = 0x7FD00000, LENGTH = 8k
- EthRam (rw) : ORIGIN = 0x7FE00000, LENGTH = 16k
- CanRam (rw) : ORIGIN = 0xE0038000, LENGTH = 2k
- BatRam (rw) : ORIGIN = 0xE0084000, LENGTH = 2k
-}
-
-/* Stack sizes: */
-UND_Stack_Size = 16;
-SVC_Stack_Size = 512;
-ABT_Stack_Size = 16;
-FIQ_Stack_Size = 16;
-IRQ_Stack_Size = 256;
-Stack_Size_Total = UND_Stack_Size + SVC_Stack_Size + ABT_Stack_Size + FIQ_Stack_Size + IRQ_Stack_Size;
-
-/* Stack tops for each mode: */
-__und_stack_top__ = __stacks_top__;
-__abt_stack_top__ = __und_stack_top__ - UND_Stack_Size ;
-__fiq_stack_top__ = __abt_stack_top__ - ABT_Stack_Size ;
-__irq_stack_top__ = __fiq_stack_top__ - FIQ_Stack_Size ;
-__svc_stack_top__ = __irq_stack_top__ - IRQ_Stack_Size ;
-
-/* C-accessible symbols for memory address ranges: */
-__FLASH_segment_start__ = ORIGIN( Flash );
-__FLASH_segment_end__ = ORIGIN( Flash ) + LENGTH( Flash );
-__SRAM_segment_start__ = ORIGIN( Ram );
-__SRAM_segment_end__ = ORIGIN( Ram ) + LENGTH( Ram );
-
-/* Stacks (full descending) at top of RAM, grows downward:
- *
- * __stack_min__ is used by the malloc implementation to ensure heap never collides
- * with stack (assuming stack never grows beyond Stack_Size_Total in length) */
-__stacks_top__ = __SRAM_segment_end__;
-__stacks_min__ = __SRAM_segment_end__ - Stack_Size_Total;
-
-SECTIONS
-{
- /* first section is .text which is used for code */
- __text_start__ = . ;
- .text : {
- __privileged_code_start__ = . ;
- KEEP( *( .vectors ) )
- *( .privileged_code )
-
- __privileged_code_end__ = .;
-
- *( .text .text.* .gnu.linkonce.t.* )
- *( .plt )
- *( .gnu.warning )
- *( .glue_7t ) *( .glue_7 ) *( .vfp11_veneer )
-
- *( .rodata .rodata.* .gnu.linkonce.r.* )
-
- *(.ARM.extab* .gnu.linkonce.armextab.*)
- *(.gcc_except_table)
- *(.eh_frame_hdr)
- *(.eh_frame)
-
- . = ALIGN( 4 ) ;
- KEEP( *( .init ) )
- . = ALIGN( 4 ) ;
- __preinit_array_start = . ;
- KEEP( *( .preinit_array ) )
- __preinit_array_end = . ;
- . = ALIGN( 4 ) ;
- __init_array_start = . ;
- KEEP( *( SORT( .init_array.* ) ) )
- KEEP( *( .init_array ) )
- __init_array_end = . ;
-
- . = ALIGN( 4 ) ;
- KEEP( *crtbegin.o( .ctors ) )
- KEEP( *( EXCLUDE_FILE( *crtend.o ) .ctors ) )
- KEEP( *( SORT( .ctors.* ) ) )
- KEEP( *crtend.o( .ctors ) )
-
- . = ALIGN( 4 ) ;
- KEEP( *( .fini ) )
- . = ALIGN( 4 ) ;
- __fini_array_start = . ;
- KEEP( *( .fini_array ) )
- KEEP( *( SORT( .fini_array.* ) ) )
- __fini_array_end = . ;
-
- KEEP( *crtbegin.o( .dtors ) )
- KEEP( *( EXCLUDE_FILE( *crtend.o ) .dtors ) )
- KEEP( *( SORT( .dtors.* ) ) )
- KEEP( *crtend.o( .dtors ) )
-
- } >Flash
-
- __exidx_start = . ;
- .ARM.exidx : {
- *( .ARM.exidx* .gnu.linkonce.armexidx.* )
- } >Flash
- __exidx_end = . ;
-
- .text.align : { . = ALIGN( 8 ) ; } >Flash /* Alignment schenanigans */
- __text_end__ = . ;
-
- /* .bss section -- used for uninitialized data */
- /* Located at the start of RAM */
- .bss (NOLOAD) : {
- __bss_start__ = . ;
- *crt0.o( .ram_vectors )
-
- __user_bss_start__ = . ;
- *( .user_bss )
- __user_bss_end__ = . ;
-
- *( .shbss )
- *( .bss .bss.* .gnu.linkonce.b.* )
- *( COMMON )
- *( .ram.b )
- . = ALIGN( 8 ) ;
-
- __bss_end__ = . ;
- } >Ram AT>Flash
-
- /* .data section -- used for initialized data */
- .data : {
- __data_start__ = . ;
- KEEP( *( .jcr ) )
- *( .got.plt ) *( .got )
- *( .shdata )
- *( .data .data.* .gnu.linkonce.d.* )
- *( .ram )
- . = ALIGN( 8 ) ;
- __data_end__ = . ;
- } >Ram AT>Flash
-
- __data_init_start__ = LOADADDR( .data ) ;
-
- /* Heap starts here and grows up in memory */
- . = ALIGN( 8 ) ;
- __heap_start__ = . ;
- _pvHeapStart = . ;
- end = . ;
-
- .stab 0 (NOLOAD) : { *(.stab) }
- .stabstr 0 (NOLOAD) : { *(.stabstr) }
- /* DWARF debug sections. */
- /* Symbols in the DWARF debugging sections are relative to the */
- /* beginning of the section so we begin them at 0. */
- /* DWARF 1 */
- .debug 0 : { *(.debug) }
- .line 0 : { *(.line) }
- /* GNU DWARF 1 extensions */
- .debug_srcinfo 0 : { *(.debug_srcinfo) }
- .debug_sfnames 0 : { *(.debug_sfnames) }
- /* DWARF 1.1 and DWARF 2 */
- .debug_aranges 0 : { *(.debug_aranges) }
- .debug_pubnames 0 : { *(.debug_pubnames) }
- /* DWARF 2 */
- .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) }
- .debug_abbrev 0 : { *(.debug_abbrev) }
- .debug_line 0 : { *(.debug_line) }
- .debug_frame 0 : { *(.debug_frame) }
- .debug_str 0 : { *(.debug_str) }
- .debug_loc 0 : { *(.debug_loc) }
- .debug_macinfo 0 : { *(.debug_macinfo) }
- /* SGI/MIPS DWARF 2 extensions */
- .debug_weaknames 0 : { *(.debug_weaknames) }
- .debug_funcnames 0 : { *(.debug_funcnames) }
- .debug_typenames 0 : { *(.debug_typenames) }
- .debug_varnames 0 : { *(.debug_varnames) }
- /* DWARF 3 */
- .debug_pubtypes 0 : { *(.debug_pubtypes) }
- .debug_ranges 0 : { *(.debug_ranges) }
-
- .note.gnu.arm.ident 0 : { KEEP( *( .note.gnu.arm.ident ) ) }
- .ARM.attributes 0 : {
- KEEP( *( .ARM.attributes ) )
- KEEP( *( .gnu.attributes ) )
- }
- /DISCARD/ : { *( .note.GNU-stack ) }
-
- /* C data can be defined as being in special purpose RAMs using
- * __attribute__ ((section ("ethram"))) for example. */
- .usbram (NOLOAD):
- {
- *( .usbram )
- *( .usbram.* )
- } > UsbRam
- .ethram (NOLOAD):
- {
- *( .ethram )
- *( .ethram.* )
- } > EthRam
- .canram (NOLOAD):
- {
- *( .canram )
- *( .canram.* )
- } > CanRam
- .batram (NOLOAD):
- {
- *( .batram )
- *( .batram.* )
- } > BatRam
-}
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_GCC_CR/vector_functions.S b/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_GCC_CR/vector_functions.S
deleted file mode 100644
index 6e99ec8e08..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_GCC_CR/vector_functions.S
+++ /dev/null
@@ -1,149 +0,0 @@
-/* .include "vector_defns.h" */
-
-
-
-.section .privileged_code, "ax"
-.arm
-
-
-.weak __mbed_fiq
-.weak __mbed_undef
-.weak __mbed_prefetch_abort
-.weak __mbed_data_abort
-.weak __mbed_irq
-.weak __mbed_swi
-.weak __mbed_dcc_irq
-.weak __mbed_reset
-.global __mbed_init_realmonitor
-/* .global __mbed_init */
-
-
-
-
-__mbed_fiq:
- B __mbed_fiq
-__mbed_undef:
- LDR PC, =0x7fffffa0
-__mbed_prefetch_abort:
- LDR PC, =0x7fffffb0
-__mbed_data_abort:
- LDR PC, =0x7fffffc0
-__mbed_irq:
- MSR CPSR_c, #0x1F|0x80|0x40
-
- STMDB sp!, {r0-r3,r12,lr}
-
- MOV r0, #0xFFFFFF00
- LDR r0, [r0]
-
- MOV lr, pc
- BX r0
-
- MOV r0, #0xFFFFFF00
- STR r0, [r0]
-
- LDMFD sp!,{r0-r3,r12,lr}
-
- MSR CPSR_c, #0x12|0x80|0x40
-
- SUBS pc, lr, #4
-__mbed_swi:
- STMFD sp!, {a4, r4, ip, lr}
-
- LDR r4, =0x40000040
-
- LDR a4, =0x00940000
- LDR PC, =0x7ffff820
-__mbed_dcc_irq:
- LDMFD sp!,{r0-r3,r12,lr}
-
- MSR CPSR_c, #0x12|0x80|0x40
-
- SUB lr, lr, #4
- STMFD sp!, {ip,lr}
-
- LDR LR, =0xfffff000
- STR LR, [LR, #0xf00]
-
- LDR PC, =0x7fffffe0
-/*
- __mbed_reset is called after reset
- we setup the stacks and realmonitor, then call Reset_Handler like on M3
-*/
-
-.section .text, "ax"
-.arm
-.global Reset_handler
-Reset_Handler:
- .extern __libc_init_array
- .extern SystemInit
- .extern __wrap_main
- LDR R0, =SystemInit
- MOV LR, PC
- BX R0
-
- LDR R0, =__libc_init_array
- MOV LR, PC
- BX R0
-
- LDR R0, =__wrap_main
- BX R0
-
-__mbed_reset:
- LDR R0, =( __SRAM_segment_end__ )
-
- MSR CPSR_c, #0x1B|0x80|0x40
- MOV SP, R0
- SUB R0, R0, #0x00000040
-
- MSR CPSR_c, #0x17|0x80|0x40
- MOV SP, R0
- SUB R0, R0, #0x00000040
-
- MSR CPSR_c, #0x11|0x80|0x40
- MOV SP, R0
- SUB R0, R0, #0x00000000
-
- MSR CPSR_c, #0x12|0x80|0x40
- MOV SP, R0
- SUB R0, R0, #0x00000040
-
- MSR CPSR_c, #0x13|0x80|0x40
- MOV SP, R0
- SUB R0, R0, #0x00000040
-
- MSR CPSR_c, #0x10
- MOV SP, R0
-
-/* Relocate .data section (Copy from ROM to RAM) */
- LDR R1, =__text_end__ /* _etext */
- LDR R2, =__data_start__ /* _data */
- LDR R3, =__data_end__ /* _edata */
- CMP R2, R3
- BEQ DataIsEmpty
-LoopRel: CMP R2, R3
- LDRLO R0, [R1], #4
- STRLO R0, [R2], #4
- BLO LoopRel
-DataIsEmpty:
-
-/* Clear .bss section (Zero init) */
- MOV R0, #0
- LDR R1, =__bss_start__
- LDR R2, =__bss_end__
- CMP R1,R2
- BEQ BSSIsEmpty
-LoopZI: CMP R1, R2
- STRLO R0, [R1], #4
- BLO LoopZI
-BSSIsEmpty:
-
-
-/* Init realmonitor */
- LDR R0, =__mbed_init_realmonitor
- MOV LR, PC
- BX R0
-
-/* Go to Reset_Handler */
- LDR R0, =Reset_Handler
- BX R0
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_GCC_CR/vector_table.S b/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_GCC_CR/vector_table.S
deleted file mode 100644
index d797c3794d..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_GCC_CR/vector_table.S
+++ /dev/null
@@ -1,45 +0,0 @@
-# 1 "vector_table.s"
-# 1 ""
-# 1 ""
-# 1 "vector_table.s"
-;
-
-
-
-
-# 1 "vector_defns.h" 1
-# 7 "vector_table.s" 2
-
-;
-
-
-
-
-
-
-
- .section .vectors, "ax"
- .arm
-
-
- .global __main
- .global __mbed_reset
- .global __mbed_undef
- .global __mbed_swi
- .global __mbed_prefetch_abort
- .global __mbed_data_abort
- .global __mbed_irq
- .global __mbed_fiq
-
-;
-
-
-_start:
- LDR PC, =__mbed_reset
- LDR PC, =__mbed_undef
- LDR PC, =__mbed_swi
- LDR PC, =__mbed_prefetch_abort
- LDR PC, =__mbed_data_abort
- NOP ;
- LDR PC, =__mbed_irq
- LDR PC, =__mbed_fiq
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_GCC_CS/LPC2368.ld b/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_GCC_CS/LPC2368.ld
deleted file mode 100644
index fcac826485..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_GCC_CS/LPC2368.ld
+++ /dev/null
@@ -1,207 +0,0 @@
-OUTPUT_FORMAT("elf32-littlearm", "elf32-bigarm", "elf32-littlearm")
-OUTPUT_ARCH(arm)
-ENTRY(vectors)
-GROUP(-lsupc++ -lm -lc -lcs3unhosted -lcs3 -lgcc)
-
-/* Memory Definitions: */
-MEMORY
-{
- Flash (rx) : ORIGIN = 0x00000000, LENGTH = 512k
- Ram (rwx) : ORIGIN = 0x40000000, LENGTH = 32k
- UsbRam (rw) : ORIGIN = 0x7FD00000, LENGTH = 8k
- EthRam (rw) : ORIGIN = 0x7FE00000, LENGTH = 16k
- CanRam (rw) : ORIGIN = 0xE0038000, LENGTH = 2k
- BatRam (rw) : ORIGIN = 0xE0084000, LENGTH = 2k
-}
-
-/* Stack sizes: */
-UND_Stack_Size = 16;
-SVC_Stack_Size = 512;
-ABT_Stack_Size = 16;
-FIQ_Stack_Size = 16;
-IRQ_Stack_Size = 256;
-Stack_Size_Total = UND_Stack_Size + SVC_Stack_Size + ABT_Stack_Size + FIQ_Stack_Size + IRQ_Stack_Size;
-
-/* Stack tops for each mode: */
-__und_stack_top__ = __stacks_top__;
-__abt_stack_top__ = __und_stack_top__ - UND_Stack_Size ;
-__fiq_stack_top__ = __abt_stack_top__ - ABT_Stack_Size ;
-__irq_stack_top__ = __fiq_stack_top__ - FIQ_Stack_Size ;
-__svc_stack_top__ = __irq_stack_top__ - IRQ_Stack_Size ;
-
-/* C-accessible symbols for memory address ranges: */
-__FLASH_segment_start__ = ORIGIN( Flash );
-__FLASH_segment_end__ = ORIGIN( Flash ) + LENGTH( Flash );
-__SRAM_segment_start__ = ORIGIN( Ram );
-__SRAM_segment_end__ = ORIGIN( Ram ) + LENGTH( Ram );
-
-/* Stacks (full descending) at top of RAM, grows downward:
- *
- * __stack_min__ is used by the malloc implementation to ensure heap never collides
- * with stack (assuming stack never grows beyond Stack_Size_Total in length) */
-__stacks_top__ = __SRAM_segment_end__;
-__stacks_min__ = __SRAM_segment_end__ - Stack_Size_Total;
-
-SECTIONS
-{
- /* first section is .text which is used for code */
- __text_start__ = . ;
- .text : {
- __privileged_code_start__ = . ;
- KEEP( *( .vectors ) )
- *( .privileged_code )
-
- __privileged_code_end__ = .;
-
- *( .text .text.* .gnu.linkonce.t.* )
- *( .plt )
- *( .gnu.warning )
- *( .glue_7t ) *( .glue_7 ) *( .vfp11_veneer )
-
- *( .rodata .rodata.* .gnu.linkonce.r.* )
-
- *(.ARM.extab* .gnu.linkonce.armextab.*)
- *(.gcc_except_table)
- *(.eh_frame_hdr)
- *(.eh_frame)
-
- . = ALIGN( 4 ) ;
- KEEP( *( .init ) )
- . = ALIGN( 4 ) ;
- __preinit_array_start = . ;
- KEEP( *( .preinit_array ) )
- __preinit_array_end = . ;
- . = ALIGN( 4 ) ;
- __init_array_start = . ;
- KEEP( *( SORT( .init_array.* ) ) )
- KEEP( *( .init_array ) )
- __init_array_end = . ;
-
- . = ALIGN( 4 ) ;
- KEEP( *crtbegin.o( .ctors ) )
- KEEP( *( EXCLUDE_FILE( *crtend.o ) .ctors ) )
- KEEP( *( SORT( .ctors.* ) ) )
- KEEP( *crtend.o( .ctors ) )
-
- . = ALIGN( 4 ) ;
- KEEP( *( .fini ) )
- . = ALIGN( 4 ) ;
- __fini_array_start = . ;
- KEEP( *( .fini_array ) )
- KEEP( *( SORT( .fini_array.* ) ) )
- __fini_array_end = . ;
-
- KEEP( *crtbegin.o( .dtors ) )
- KEEP( *( EXCLUDE_FILE( *crtend.o ) .dtors ) )
- KEEP( *( SORT( .dtors.* ) ) )
- KEEP( *crtend.o( .dtors ) )
-
- } >Flash
-
- __exidx_start = . ;
- .ARM.exidx : {
- *( .ARM.exidx* .gnu.linkonce.armexidx.* )
- } >Flash
- __exidx_end = . ;
-
- .text.align : { . = ALIGN( 8 ) ; } >Flash /* Alignment schenanigans */
- __text_end__ = . ;
-
- /* .bss section -- used for uninitialized data */
- /* Located at the start of RAM */
- .bss (NOLOAD) : {
- __bss_start__ = . ;
- *crt0.o( .ram_vectors )
-
- __user_bss_start__ = . ;
- *( .user_bss )
- __user_bss_end__ = . ;
-
- *( .shbss )
- *( .bss .bss.* .gnu.linkonce.b.* )
- *( COMMON )
- *( .ram.b )
- . = ALIGN( 8 ) ;
-
- __bss_end__ = . ;
- } >Ram AT>Flash
-
- /* .data section -- used for initialized data */
- .data : {
- __data_start__ = . ;
- KEEP( *( .jcr ) )
- *( .got.plt ) *( .got )
- *( .shdata )
- *( .data .data.* .gnu.linkonce.d.* )
- *( .ram )
- . = ALIGN( 8 ) ;
- __data_end__ = . ;
- } >Ram AT>Flash
-
- __data_init_start__ = LOADADDR( .data ) ;
-
- /* Heap starts here and grows up in memory */
- . = ALIGN( 8 ) ;
- __heap_start__ = . ;
-
- .stab 0 (NOLOAD) : { *(.stab) }
- .stabstr 0 (NOLOAD) : { *(.stabstr) }
- /* DWARF debug sections. */
- /* Symbols in the DWARF debugging sections are relative to the */
- /* beginning of the section so we begin them at 0. */
- /* DWARF 1 */
- .debug 0 : { *(.debug) }
- .line 0 : { *(.line) }
- /* GNU DWARF 1 extensions */
- .debug_srcinfo 0 : { *(.debug_srcinfo) }
- .debug_sfnames 0 : { *(.debug_sfnames) }
- /* DWARF 1.1 and DWARF 2 */
- .debug_aranges 0 : { *(.debug_aranges) }
- .debug_pubnames 0 : { *(.debug_pubnames) }
- /* DWARF 2 */
- .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) }
- .debug_abbrev 0 : { *(.debug_abbrev) }
- .debug_line 0 : { *(.debug_line) }
- .debug_frame 0 : { *(.debug_frame) }
- .debug_str 0 : { *(.debug_str) }
- .debug_loc 0 : { *(.debug_loc) }
- .debug_macinfo 0 : { *(.debug_macinfo) }
- /* SGI/MIPS DWARF 2 extensions */
- .debug_weaknames 0 : { *(.debug_weaknames) }
- .debug_funcnames 0 : { *(.debug_funcnames) }
- .debug_typenames 0 : { *(.debug_typenames) }
- .debug_varnames 0 : { *(.debug_varnames) }
- /* DWARF 3 */
- .debug_pubtypes 0 : { *(.debug_pubtypes) }
- .debug_ranges 0 : { *(.debug_ranges) }
-
- .note.gnu.arm.ident 0 : { KEEP( *( .note.gnu.arm.ident ) ) }
- .ARM.attributes 0 : {
- KEEP( *( .ARM.attributes ) )
- KEEP( *( .gnu.attributes ) )
- }
- /DISCARD/ : { *( .note.GNU-stack ) }
-
- /* C data can be defined as being in special purpose RAMs using
- * __attribute__ ((section ("ethram"))) for example. */
- .usbram (NOLOAD):
- {
- *( .usbram )
- *( .usbram.* )
- } > UsbRam
- .ethram (NOLOAD):
- {
- *( .ethram )
- *( .ethram.* )
- } > EthRam
- .canram (NOLOAD):
- {
- *( .canram )
- *( .canram.* )
- } > CanRam
- .batram (NOLOAD):
- {
- *( .batram )
- *( .batram.* )
- } > BatRam
-}
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_GCC_CS/vector_functions.S b/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_GCC_CS/vector_functions.S
deleted file mode 100644
index 0751c50591..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_GCC_CS/vector_functions.S
+++ /dev/null
@@ -1,180 +0,0 @@
-# 1 "vector_functions.s"
-# 1 ""
-# 1 ""
-# 1 "vector_functions.s"
-;
-;
-;
-
-# 1 "vector_defns.h" 1
-# 6 "vector_functions.s" 2
-
-
-
-
-
-
- .section VECFUNCS, "ax"
- .arm
-
-
- .weak __mbed_fiq
- .weak __mbed_undef
- .weak __mbed_prefetch_abort
- .weak __mbed_data_abort
- .weak __mbed_irq
- .weak __mbed_swi
- .weak __mbed_dcc_irq
- .weak __mbed_reset
- .global __mbed_init_realmonitor
- .global __mbed_init
-
-;
-;
-__mbed_fiq:
- B __mbed_fiq
-
-;
-;
-__mbed_undef:
- LDR PC, =0x7fffffa0
-
-;
-;
-__mbed_prefetch_abort:
- LDR PC, =0x7fffffb0
-
-;
-;
-__mbed_data_abort:
- LDR PC, =0x7fffffc0
-
-;
-;
-;
-;
-;
-;
-;
-;
-;
-__mbed_irq:
- ;
- MSR CPSR_c, #0x1F|0x80|0x40
-
- ;
- STMDB sp!, {r0-r3,r12,lr}
-
- ;
- MOV r0, #0xFFFFFF00
- LDR r0, [r0]
-
- ;
- MOV lr, pc
- BX r0
-
- ;
- MOV r0, #0xFFFFFF00
- STR r0, [r0] ;
-
- ;
- LDMFD sp!,{r0-r3,r12,lr}
-
- ;
- MSR CPSR_c, #0x12|0x80|0x40
-
- ;
- SUBS pc, lr, #4
-
-;
-;
-;
-;
-__mbed_swi:
- ;
- ;
- STMFD sp!, {a4, r4, ip, lr}
-
- ;
- LDR r4, =0x40000040
-
- ;
- ;
- LDR a4, =0x00940000
- LDR PC, =0x7ffff820
-
-;
-;
-;
-;
-__mbed_dcc_irq:
-
- ;
-
- ;
- LDMFD sp!,{r0-r3,r12,lr}
-
- ;
- MSR CPSR_c, #0x12|0x80|0x40
-
- ;
-
- ;
- SUB lr, lr, #4 ;
- STMFD sp!, {ip,lr} ;
-
- ;
- LDR LR, =0xfffff000
- STR LR, [LR, #0xf00]
-
- ;
- ;
- ;
- ;
- LDR PC, =0x7fffffe0
-
-;
-;
-__mbed_reset:
-
- ;
-
- LDR R0, =(0x40000000 + 0x8000)
-
- ;
- MSR CPSR_c, #0x1B|0x80|0x40
- MOV SP, R0
- SUB R0, R0, #0x00000040
-
- ;
- MSR CPSR_c, #0x17|0x80|0x40
- MOV SP, R0
- SUB R0, R0, #0x00000040
-
- ;
- MSR CPSR_c, #0x11|0x80|0x40
- MOV SP, R0
- SUB R0, R0, #0x00000000
-
- ;
- MSR CPSR_c, #0x12|0x80|0x40
- MOV SP, R0
- SUB R0, R0, #0x00000040
-
- ;
- MSR CPSR_c, #0x13|0x80|0x40
- MOV SP, R0
- SUB R0, R0, #0x00000040
-
- ;
- MSR CPSR_c, #0x10
- MOV SP, R0
-
- ;
- LDR R0, =__mbed_init_realmonitor
- MOV LR, PC
- BX R0
-
- ;
- LDR R0, =__mbed_init
- BX R0
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_GCC_CS/vector_table.S b/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_GCC_CS/vector_table.S
deleted file mode 100644
index 281e7a9bd4..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/device/TOOLCHAIN_GCC_CS/vector_table.S
+++ /dev/null
@@ -1,45 +0,0 @@
-# 1 "vector_table.s"
-# 1 ""
-# 1 ""
-# 1 "vector_table.s"
-;
-
-
-
-
-# 1 "vector_defns.h" 1
-# 7 "vector_table.s" 2
-
-;
-
-
-
-
-
-
-
- .section VECTOR_TABLE, "ax"
- .arm
-
-
- .global __main
- .global __mbed_reset
- .global __mbed_undef
- .global __mbed_swi
- .global __mbed_prefetch_abort
- .global __mbed_data_abort
- .global __mbed_irq
- .global __mbed_fiq
-
-;
-
-
-__main:
- LDR PC, =__mbed_reset
- LDR PC, =__mbed_undef
- LDR PC, =__mbed_swi
- LDR PC, =__mbed_prefetch_abort
- LDR PC, =__mbed_data_abort
- NOP ;
- LDR PC, =__mbed_irq
- LDR PC, =__mbed_fiq
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/device/cmsis.h b/targets/TARGET_NXP/TARGET_LPC23XX/device/cmsis.h
deleted file mode 100644
index 3926baf40a..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/device/cmsis.h
+++ /dev/null
@@ -1,13 +0,0 @@
-/* mbed Microcontroller Library - CMSIS
- * Copyright (C) 2009-2011 ARM Limited. All rights reserved.
- *
- * A generic CMSIS include header, pulling in LPC2368 specifics
- */
-
-#ifndef MBED_CMSIS_H
-#define MBED_CMSIS_H
-
-#include "LPC23xx.h"
-#include "cmsis_nvic.h"
-
-#endif
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/device/cmsis_nvic.c b/targets/TARGET_NXP/TARGET_LPC23XX/device/cmsis_nvic.c
deleted file mode 100644
index 6df47d1b3e..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/device/cmsis_nvic.c
+++ /dev/null
@@ -1,40 +0,0 @@
-/* mbed Microcontroller Library
- * CMSIS-style functionality to support dynamic vectors
- *******************************************************************************
- * Copyright (c) 2011 ARM Limited. All rights reserved.
- * All rights reserved.
- *
- * 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 of ARM Limited 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 HOLDER 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.
- *******************************************************************************
- */
-#include "cmsis_nvic.h"
-
-void NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) {
- LPC_VIC->VectAddr[(int)IRQn] = vector;
-}
-
-uint32_t NVIC_GetVector(IRQn_Type IRQn) {
- return LPC_VIC->VectAddr[(int)IRQn];
-}
-
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/device/cmsis_nvic.h b/targets/TARGET_NXP/TARGET_LPC23XX/device/cmsis_nvic.h
deleted file mode 100644
index a4ab256498..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/device/cmsis_nvic.h
+++ /dev/null
@@ -1,51 +0,0 @@
-/* mbed Microcontroller Library
- * CMSIS-style functionality to support dynamic vectors
- *******************************************************************************
- * Copyright (c) 2011 ARM Limited. All rights reserved.
- * All rights reserved.
- *
- * 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 of ARM Limited 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 HOLDER 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 MBED_CMSIS_NVIC_H
-#define MBED_CMSIS_NVIC_H
-
-#define NVIC_NUM_VECTORS 32
-#define NVIC_USER_IRQ_OFFSET 0
-
-#include "cmsis.h"
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-void NVIC_SetVector(IRQn_Type IRQn, uint32_t vector);
-uint32_t NVIC_GetVector(IRQn_Type IRQn);
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/device/core_arm7.c b/targets/TARGET_NXP/TARGET_LPC23XX/device/core_arm7.c
deleted file mode 100644
index 3ed1daeeb4..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/device/core_arm7.c
+++ /dev/null
@@ -1,44 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (C) 2008-2009 ARM Limited. All rights reserved.
- *
- * ARM7 version of CMSIS-like functionality - not advised for use outside mbed!
- * based on core_cm3.h, V1.20
- */
-
-#include
-
-
-/* define compiler specific symbols */
-#if defined ( __CC_ARM )
- #define __ASM __asm /*!< asm keyword for armcc */
- #define __INLINE __inline /*!< inline keyword for armcc */
-
-#elif defined ( __ICCARM__ )
- #define __ASM __asm /*!< asm keyword for iarcc */
- #define __INLINE inline /*!< inline keyword for iarcc. Only avaiable in High optimization mode! */
-
-#elif defined ( __GNUC__ )
- #define __ASM __asm /*!< asm keyword for gcc */
- #define __INLINE inline /*!< inline keyword for gcc */
-
-#elif defined ( __TASKING__ )
- #define __ASM __asm /*!< asm keyword for TASKING Compiler */
- #define __INLINE inline /*!< inline keyword for TASKING Compiler */
-
-#endif
-
-#if defined ( __CC_ARM )
-/**
- * @brief Return the Main Stack Pointer (return current ARM7 stack)
- *
- * @param none
- * @return uint32_t Main Stack Pointer
- *
- * Return the current value of the MSP (main stack pointer)
- * Cortex processor register
- */
-uint32_t __get_MSP(void)
-{
- return __current_sp();
-}
-#endif
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/device/core_arm7.h b/targets/TARGET_NXP/TARGET_LPC23XX/device/core_arm7.h
deleted file mode 100644
index 9655813058..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/device/core_arm7.h
+++ /dev/null
@@ -1,276 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (C) 2008-2009 ARM Limited. All rights reserved.
- *
- * ARM7 version of CMSIS-like functionality - not advised for use outside mbed!
- * based on core_cm3.h, V1.20
- */
-
-#ifndef __ARM7_CORE_H__
-#define __ARM7_CORE_H__
-
-#include "vector_defns.h"
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-#define __CM3_CMSIS_VERSION_MAIN (0x01) /*!< [31:16] CMSIS HAL main version */
-#define __CM3_CMSIS_VERSION_SUB (0x20) /*!< [15:0] CMSIS HAL sub version */
-#define __CM3_CMSIS_VERSION ((__CM3_CMSIS_VERSION_MAIN << 16) | __CM3_CMSIS_VERSION_SUB) /*!< CMSIS HAL version number */
-
-#define __CORTEX_M (0x03) /*!< Cortex core */
-
-/**
- * Lint configuration \n
- * ----------------------- \n
- *
- * The following Lint messages will be suppressed and not shown: \n
- * \n
- * --- Error 10: --- \n
- * register uint32_t __regBasePri __asm("basepri"); \n
- * Error 10: Expecting ';' \n
- * \n
- * --- Error 530: --- \n
- * return(__regBasePri); \n
- * Warning 530: Symbol '__regBasePri' (line 264) not initialized \n
- * \n
- * --- Error 550: --- \n
- * __regBasePri = (basePri & 0x1ff); \n
- * } \n
- * Warning 550: Symbol '__regBasePri' (line 271) not accessed \n
- * \n
- * --- Error 754: --- \n
- * uint32_t RESERVED0[24]; \n
- * Info 754: local structure member '' (line 109, file ./cm3_core.h) not referenced \n
- * \n
- * --- Error 750: --- \n
- * #define __CM3_CORE_H__ \n
- * Info 750: local macro '__CM3_CORE_H__' (line 43, file./cm3_core.h) not referenced \n
- * \n
- * --- Error 528: --- \n
- * static __INLINE void NVIC_DisableIRQ(uint32_t IRQn) \n
- * Warning 528: Symbol 'NVIC_DisableIRQ(unsigned int)' (line 419, file ./cm3_core.h) not referenced \n
- * \n
- * --- Error 751: --- \n
- * } InterruptType_Type; \n
- * Info 751: local typedef 'InterruptType_Type' (line 170, file ./cm3_core.h) not referenced \n
- * \n
- * \n
- * Note: To re-enable a Message, insert a space before 'lint' * \n
- *
- */
-
-/*lint -save */
-/*lint -e10 */
-/*lint -e530 */
-/*lint -e550 */
-/*lint -e754 */
-/*lint -e750 */
-/*lint -e528 */
-/*lint -e751 */
-
-#include /* Include standard types */
-
-#if defined ( __CC_ARM )
-/**
- * @brief Return the Main Stack Pointer (current ARM7 stack)
- *
- * @param none
- * @return uint32_t Main Stack Pointer
- *
- * Return the current value of the MSP (main stack pointer)
- * Cortex processor register
- */
-extern uint32_t __get_MSP(void);
-#endif
-
-
-#if defined (__ICCARM__)
- #include /* IAR Intrinsics */
-#endif
-
-
-#ifndef __NVIC_PRIO_BITS
- #define __NVIC_PRIO_BITS 4 /*!< standard definition for NVIC Priority Bits */
-#endif
-
-typedef struct
-{
- uint32_t IRQStatus;
- uint32_t FIQStatus;
- uint32_t RawIntr;
- uint32_t IntSelect;
- uint32_t IntEnable;
- uint32_t IntEnClr;
- uint32_t SoftInt;
- uint32_t SoftIntClr;
- uint32_t Protection;
- uint32_t SWPriorityMask;
- uint32_t RESERVED0[54];
- uint32_t VectAddr[32];
- uint32_t RESERVED1[32];
- uint32_t VectPriority[32];
- uint32_t RESERVED2[800];
- uint32_t Address;
-} NVIC_TypeDef;
-
-#define NVIC_BASE (0xFFFFF000)
-#define NVIC (( NVIC_TypeDef *) NVIC_BASE)
-
-
-
-/**
- * IO definitions
- *
- * define access restrictions to peripheral registers
- */
-
-#ifdef __cplusplus
-#define __I volatile /*!< defines 'read only' permissions */
-#else
-#define __I volatile const /*!< defines 'read only' permissions */
-#endif
-#define __O volatile /*!< defines 'write only' permissions */
-#define __IO volatile /*!< defines 'read / write' permissions */
-
-
-
-
-
-#if defined ( __CC_ARM )
- #define __ASM __asm /*!< asm keyword for ARM Compiler */
- #define __INLINE __inline /*!< inline keyword for ARM Compiler */
-
-#elif defined ( __ICCARM__ )
- #define __ASM __asm /*!< asm keyword for IAR Compiler */
- #define __INLINE inline /*!< inline keyword for IAR Compiler. Only avaiable in High optimization mode! */
-
-#elif defined ( __GNUC__ )
- #define __ASM __asm /*!< asm keyword for GNU Compiler */
- #define __INLINE inline /*!< inline keyword for GNU Compiler */
-
-#elif defined ( __TASKING__ )
- #define __ASM __asm /*!< asm keyword for TASKING Compiler */
- #define __INLINE inline /*!< inline keyword for TASKING Compiler */
-
-#endif
-
-
-/* ################### Compiler specific Intrinsics ########################### */
-
-#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/
-/* ARM armcc specific functions */
-
-#define __enable_fault_irq __enable_fiq
-#define __disable_fault_irq __disable_fiq
-
-#define __NOP __nop
-//#define __WFI __wfi
-//#define __WFE __wfe
-//#define __SEV __sev
-//#define __ISB() __isb(0)
-//#define __DSB() __dsb(0)
-//#define __DMB() __dmb(0)
-//#define __REV __rev
-//#define __RBIT __rbit
-#define __LDREXB(ptr) ((unsigned char ) __ldrex(ptr))
-#define __LDREXH(ptr) ((unsigned short) __ldrex(ptr))
-#define __LDREXW(ptr) ((unsigned int ) __ldrex(ptr))
-#define __STREXB(value, ptr) __strex(value, ptr)
-#define __STREXH(value, ptr) __strex(value, ptr)
-#define __STREXW(value, ptr) __strex(value, ptr)
-
-#define __disable_irq() unsigned tmp_IntEnable = LPC_VIC->IntEnable; \
- LPC_VIC->IntEnClr = 0xffffffff
-
-#define __enable_irq() LPC_VIC->IntEnable = tmp_IntEnable
-
-#elif (defined (__ICCARM__)) /*------------------ ICC Compiler -------------------*/
-
-#define __enable_irq __enable_interrupt /*!< global Interrupt enable */
-#define __disable_irq __disable_interrupt /*!< global Interrupt disable */
-#define __NOP __no_operation() /*!< no operation intrinsic in IAR Compiler */
-
-#elif (defined (__GNUC__)) /*------------------ GNU Compiler ---------------------*/
-
-static __INLINE void __enable_irq() {
- unsigned long temp;
- __asm__ __volatile__("mrs %0, cpsr\n"
- "bic %0, %0, #0x80\n"
- "msr cpsr_c, %0"
- : "=r" (temp)
- :
- : "memory");
-}
-
-static __INLINE void __disable_irq() {
- unsigned long old,temp;
- __asm__ __volatile__("mrs %0, cpsr\n"
- "orr %1, %0, #0xc0\n"
- "msr cpsr_c, %1"
- : "=r" (old), "=r" (temp)
- :
- : "memory");
- // return (old & 0x80) == 0;
-}
-
-static __INLINE void __NOP() { __ASM volatile ("nop"); }
-
-#elif (defined (__TASKING__)) /*------------------ TASKING Compiler ---------------------*/
-/* TASKING carm specific functions */
-
-/*
- * The CMSIS functions have been implemented as intrinsics in the compiler.
- * Please use "carm -?i" to get an up to date list of all instrinsics,
- * Including the CMSIS ones.
- */
-
-#endif
-
-
-/**
- * @brief Enable Interrupt in NVIC Interrupt Controller
- *
- * @param IRQn_Type IRQn specifies the interrupt number
- * @return none
- *
- * Enable a device specific interupt in the NVIC interrupt controller.
- * The interrupt number cannot be a negative value.
- */
-static __INLINE void NVIC_EnableIRQ(IRQn_Type IRQn)
-{
- NVIC->IntEnable = 1 << (uint32_t)IRQn;
-}
-
-
-/**
- * @brief Disable the interrupt line for external interrupt specified
- *
- * @param IRQn_Type IRQn is the positive number of the external interrupt
- * @return none
- *
- * Disable a device specific interupt in the NVIC interrupt controller.
- * The interrupt number cannot be a negative value.
- */
-static __INLINE void NVIC_DisableIRQ(IRQn_Type IRQn)
-{
- NVIC->IntEnClr = 1 << (uint32_t)IRQn;
-}
-
-static __INLINE uint32_t __get_IPSR(void)
-{
- unsigned i;
-
- for(i = 0; i < 32; i ++)
- if(NVIC->Address == NVIC->VectAddr[i])
- return i;
- return 1; // 1 is an invalid entry in the interrupt table on LPC2368
-}
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif /* __ARM7_CORE_H__ */
-
-/*lint -restore */
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/device/system_LPC23xx.c b/targets/TARGET_NXP/TARGET_LPC23XX/device/system_LPC23xx.c
deleted file mode 100644
index fc5d804ab2..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/device/system_LPC23xx.c
+++ /dev/null
@@ -1,144 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (C) 2008-2009 ARM Limited. All rights reserved.
- *
- * ARM7 version of CMSIS-like functionality - not advised for use outside mbed!
- */
-
-#include
-#include "LPC23xx.h"
-
-#define CLOCK_SETUP 1
-#define SCS_Val 0x00000020
-#define CLKSRCSEL_Val 0x00000001
-
-#define PLL0_SETUP 1
-#define PLL0CFG_Val 0x00000013
-#define CCLKCFG_Val 0x00000007
-#define USBCLKCFG_Val 0x00000009
-#define PCLKSEL0_Val 0x00000000
-#define PCLKSEL1_Val 0x00000000
-#define PCONP_Val 0x042887DE
-#define CLKOUTCFG_Val 0x00000000
-#define MAMCR_Val 0x00000001 // there is a bug in the MAM so it should never be fully enabled (only disabled or partially enabled)
-#define MAMTIM_Val 0x00000004
-
-/*----------------------------------------------------------------------------
- DEFINES
- *----------------------------------------------------------------------------*/
-
-#define XTAL (12000000UL) /* Oscillator frequency */
-#define OSC_CLK ( XTAL) /* Main oscillator frequency */
-#define RTC_CLK ( 32000UL) /* RTC oscillator frequency */
-#define IRC_OSC ( 4000000UL) /* Internal RC oscillator frequency */
-
-/* F_cco0 = (2 * M * F_in) / N */
-#define __M (((PLL0CFG_Val ) & 0x7FFF) + 1)
-#define __N (((PLL0CFG_Val >> 16) & 0x00FF) + 1)
-#define __FCCO(__F_IN) ((2 * __M * __F_IN) / __N)
-#define __CCLK_DIV (((CCLKCFG_Val ) & 0x00FF) + 1)
-
-/* Determine core clock frequency according to settings */
- #if (PLL0_SETUP)
- #if ((CLKSRCSEL_Val & 0x03) == 1)
- #define __CORE_CLK (__FCCO(OSC_CLK) / __CCLK_DIV)
- #elif ((CLKSRCSEL_Val & 0x03) == 2)
- #define __CORE_CLK (__FCCO(RTC_CLK) / __CCLK_DIV)
- #else
- #define __CORE_CLK (__FCCO(IRC_OSC) / __CCLK_DIV)
- #endif
- #endif
-
-
-/*----------------------------------------------------------------------------
- Clock Variable definitions
- *----------------------------------------------------------------------------*/
-uint32_t SystemCoreClock = __CORE_CLK;/*!< System Clock Frequency (Core Clock)*/
-
-/*----------------------------------------------------------------------------
- Clock functions
- *----------------------------------------------------------------------------*/
-void SystemCoreClockUpdate (void) /* Get Core Clock Frequency */
-{
- /* Determine clock frequency according to clock register values */
- if (((LPC_SC->PLL0STAT >> 24) & 3) == 3) { /* If PLL0 enabled and connected */
- switch (LPC_SC->CLKSRCSEL & 0x03) {
- case 0: /* Int. RC oscillator => PLL0 */
- case 3: /* Reserved, default to Int. RC */
- SystemCoreClock = (IRC_OSC *
- (((2 * ((LPC_SC->PLL0STAT & 0x7FFF) + 1))) /
- (((LPC_SC->PLL0STAT >> 16) & 0xFF) + 1)) /
- ((LPC_SC->CCLKCFG & 0xFF)+ 1));
- break;
- case 1: /* Main oscillator => PLL0 */
- SystemCoreClock = (OSC_CLK *
- (((2 * ((LPC_SC->PLL0STAT & 0x7FFF) + 1))) /
- (((LPC_SC->PLL0STAT >> 16) & 0xFF) + 1)) /
- ((LPC_SC->CCLKCFG & 0xFF)+ 1));
- break;
- case 2: /* RTC oscillator => PLL0 */
- SystemCoreClock = (RTC_CLK *
- (((2 * ((LPC_SC->PLL0STAT & 0x7FFF) + 1))) /
- (((LPC_SC->PLL0STAT >> 16) & 0xFF) + 1)) /
- ((LPC_SC->CCLKCFG & 0xFF)+ 1));
- break;
- }
- } else {
- switch (LPC_SC->CLKSRCSEL & 0x03) {
- case 0: /* Int. RC oscillator => PLL0 */
- case 3: /* Reserved, default to Int. RC */
- SystemCoreClock = IRC_OSC / ((LPC_SC->CCLKCFG & 0xFF)+ 1);
- break;
- case 1: /* Main oscillator => PLL0 */
- SystemCoreClock = OSC_CLK / ((LPC_SC->CCLKCFG & 0xFF)+ 1);
- break;
- case 2: /* RTC oscillator => PLL0 */
- SystemCoreClock = RTC_CLK / ((LPC_SC->CCLKCFG & 0xFF)+ 1);
- break;
- }
- }
-}
-
-/**
- * Initialize the system
- *
- * @param none
- * @return none
- *
- * @brief Setup the microcontroller system.
- * Initialize the System and update the SystemFrequency variable.
- */
-void SystemInit (void)
-{
-#if (CLOCK_SETUP) /* Clock Setup */
- LPC_SC->SCS = SCS_Val;
- if (SCS_Val & (1 << 5)) { /* If Main Oscillator is enabled */
- while ((LPC_SC->SCS & (1 << 6)) == 0); /* Wait for Oscillator to be ready */
- }
-
- LPC_SC->CCLKCFG = CCLKCFG_Val; /* Setup Clock Divider */
-
-#if (PLL0_SETUP)
- LPC_SC->CLKSRCSEL = CLKSRCSEL_Val; /* Select Clock Source for PLL0 */
- LPC_SC->PLL0CFG = PLL0CFG_Val;
- LPC_SC->PLL0CON = 0x01; /* PLL0 Enable */
- LPC_SC->PLL0FEED = 0xAA;
- LPC_SC->PLL0FEED = 0x55;
- while (!(LPC_SC->PLL0STAT & (1 << 26))); /* Wait for PLOCK0 */
-
- LPC_SC->PLL0CON = 0x03; /* PLL0 Enable & Connect */
- LPC_SC->PLL0FEED = 0xAA;
- LPC_SC->PLL0FEED = 0x55;
-#endif
-
- LPC_SC->USBCLKCFG = USBCLKCFG_Val; /* Setup USB Clock Divider */
-#endif
-
- LPC_SC->PCLKSEL0 = PCLKSEL0_Val; /* Peripheral Clock Selection */
- LPC_SC->PCLKSEL1 = PCLKSEL1_Val;
-
- LPC_SC->PCONP = PCONP_Val; /* Power Control for Peripherals */
-
- // Setup MAM
- LPC_SC->MAMTIM = MAMTIM_Val;
- LPC_SC->MAMCR = MAMCR_Val;
-}
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/device/system_LPC23xx.h b/targets/TARGET_NXP/TARGET_LPC23XX/device/system_LPC23xx.h
deleted file mode 100644
index f14b72a83b..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/device/system_LPC23xx.h
+++ /dev/null
@@ -1,44 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (C) 2008-2009 ARM Limited. All rights reserved.
- *
- * ARM7 version of CMSIS-like functionality - not advised for use outside mbed!
- * based on cmsis system_LPC17xx.h
- */
-
-#ifndef __SYSTEM_LPC23xx_H
-#define __SYSTEM_LPC23xx_H
-
-#ifdef __cplusplus
- extern "C" {
-#endif
-
-extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
-
-/**
- * Initialize the system
- *
- * @param none
- * @return none
- *
- * @brief Setup the microcontroller system.
- * Initialize the System and update the SystemCoreClock variable.
- */
-extern void SystemInit (void);
-
-/**
- * Update SystemCoreClock variable
- *
- * @param none
- * @return none
- *
- * @brief Updates the SystemCoreClock with current core Clock
- * retrieved from cpu registers.
- */
-extern void SystemCoreClockUpdate (void);
-
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/device/vector_defns.h b/targets/TARGET_NXP/TARGET_LPC23XX/device/vector_defns.h
deleted file mode 100644
index 10b0b6a056..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/device/vector_defns.h
+++ /dev/null
@@ -1,77 +0,0 @@
-/* mbed Microcontroller Library - Vectors
- * Copyright (c) 2006-2009 ARM Limited. All rights reserved.
- */
-
-#ifndef MBED_VECTOR_DEFNS_H
-#define MBED_VECTOR_DEFNS_H
-
-// Assember Macros
-#ifdef __ARMCC_VERSION
-#define EXPORT(x) EXPORT x
-#define WEAK_EXPORT(x) EXPORT x [WEAK]
-#define IMPORT(x) IMPORT x
-#define LABEL(x) x
-#else
-#define EXPORT(x) .global x
-#define WEAK_EXPORT(x) .weak x
-#define IMPORT(x) .global x
-#define LABEL(x) x:
-#endif
-
-// RealMonitor
-// Requires RAM (0x40000040-0x4000011F) to be allocated by the linker
-
-// RealMonitor entry points
-#define rm_init_entry 0x7fffff91
-#define rm_undef_handler 0x7fffffa0
-#define rm_prefetchabort_handler 0x7fffffb0
-#define rm_dataabort_handler 0x7fffffc0
-#define rm_irqhandler2 0x7fffffe0
-//#define rm_RunningToStopped 0x7ffff808 // ARM - MBED64
-#define rm_RunningToStopped 0x7ffff820 // ARM - PHAT40
-
-// Unofficial RealMonitor entry points and variables
-#define RM_MSG_SWI 0x00940000
-#define StateP 0x40000040
-
-// VIC register addresses
-#define VIC_Base 0xfffff000
-#define VICAddress_Offset 0xf00
-#define VICVectAddr0_Offset 0x100
-#define VICVectAddr2_Offset 0x108
-#define VICVectAddr3_Offset 0x10c
-#define VICVectAddr31_Offset 0x17c
-#define VICIntEnClr_Offset 0x014
-#define VICIntEnClr (*(volatile unsigned long *)(VIC_Base + 0x014))
-#define VICVectAddr2 (*(volatile unsigned long *)(VIC_Base + 0x108))
-#define VICVectAddr3 (*(volatile unsigned long *)(VIC_Base + 0x10C))
-
-// ARM Mode bits and Interrupt flags in PSRs
-#define Mode_USR 0x10
-#define Mode_FIQ 0x11
-#define Mode_IRQ 0x12
-#define Mode_SVC 0x13
-#define Mode_ABT 0x17
-#define Mode_UND 0x1B
-#define Mode_SYS 0x1F
-#define I_Bit 0x80 // when I bit is set, IRQ is disabled
-#define F_Bit 0x40 // when F bit is set, FIQ is disabled
-
-// MCU RAM
-#define LPC2368_RAM_ADDRESS 0x40000000 // RAM Base
-#define LPC2368_RAM_SIZE 0x8000 // 32KB
-
-// ISR Stack Allocation
-#define UND_stack_size 0x00000040
-#define SVC_stack_size 0x00000040
-#define ABT_stack_size 0x00000040
-#define FIQ_stack_size 0x00000000
-#define IRQ_stack_size 0x00000040
-
-#define ISR_stack_size (UND_stack_size + SVC_stack_size + ABT_stack_size + FIQ_stack_size + IRQ_stack_size)
-
-// Full Descending Stack, so top-most stack points to just above the top of RAM
-#define LPC2368_STACK_TOP (LPC2368_RAM_ADDRESS + LPC2368_RAM_SIZE)
-#define USR_STACK_TOP (LPC2368_STACK_TOP - ISR_stack_size)
-
-#endif
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/device/vector_realmonitor.c b/targets/TARGET_NXP/TARGET_LPC23XX/device/vector_realmonitor.c
deleted file mode 100644
index 921fe43299..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/device/vector_realmonitor.c
+++ /dev/null
@@ -1,22 +0,0 @@
-/* mbed Microcontroller Library - RealMonitor
- * Copyright (c) 2006-2009 ARM Limited. All rights reserved.
- */
-#include "vector_defns.h"
-
-extern void __mbed_dcc_irq(void);
-
-/* Function: __mbed_init_realmonitor
- * Setup the RealMonitor DCC Interrupt Handlers
- */
-void __mbed_init_realmonitor(void) __attribute__((weak));
-void __mbed_init_realmonitor() {
- // Disable all interrupts
- VICIntEnClr = 0xffffffff;
-
- // Set DCC interrupt vector addresses
- VICVectAddr2 = (unsigned)&__mbed_dcc_irq;
- VICVectAddr3 = (unsigned)&__mbed_dcc_irq;
-
- // Initialise RealMonitor
- ((void (*)(void))rm_init_entry)();
-}
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/ethernet_api.c b/targets/TARGET_NXP/TARGET_LPC23XX/ethernet_api.c
deleted file mode 100644
index ef88270233..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/ethernet_api.c
+++ /dev/null
@@ -1,935 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2013 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-#include
-
-#include "ethernet_api.h"
-#include "cmsis.h"
-#include "mbed_interface.h"
-#include "mbed_toolchain.h"
-#include "mbed_error.h"
-
-#define NEW_LOGIC 0
-#define NEW_ETH_BUFFER 0
-
-#if NEW_ETH_BUFFER
-
-#define NUM_RX_FRAG 4 // Number of Rx Fragments (== packets)
-#define NUM_TX_FRAG 3 // Number of Tx Fragments (== packets)
-
-#define ETH_MAX_FLEN 1536 // Maximum Ethernet Frame Size
-#define ETH_FRAG_SIZE ETH_MAX_FLEN // Packet Fragment size (same as packet length)
-
-#else
-
-// Memfree calculation:
-// (16 * 1024) - ((2 * 4 * NUM_RX) + (2 * 4 * NUM_RX) + (0x300 * NUM_RX) +
-// (2 * 4 * NUM_TX) + (1 * 4 * NUM_TX) + (0x300 * NUM_TX)) = 8556
-/* EMAC Memory Buffer configuration for 16K Ethernet RAM. */
-#define NUM_RX_FRAG 4 /* Num.of RX Fragments 4*1536= 6.0kB */
-#define NUM_TX_FRAG 3 /* Num.of TX Fragments 3*1536= 4.6kB */
-//#define ETH_FRAG_SIZE 1536 /* Packet Fragment size 1536 Bytes */
-
-//#define ETH_MAX_FLEN 1536 /* Max. Ethernet Frame Size */
-#define ETH_FRAG_SIZE 0x300 /* Packet Fragment size 1536/2 Bytes */
-#define ETH_MAX_FLEN 0x300 /* Max. Ethernet Frame Size */
-
-const int ethernet_MTU_SIZE = 0x300;
-
-#endif
-
-#define ETHERNET_ADDR_SIZE 6
-
-PACKED struct RX_DESC_TypeDef { /* RX Descriptor struct */
- unsigned int Packet;
- unsigned int Ctrl;
-};
-typedef struct RX_DESC_TypeDef RX_DESC_TypeDef;
-
-PACKED struct RX_STAT_TypeDef { /* RX Status struct */
- unsigned int Info;
- unsigned int HashCRC;
-};
-typedef struct RX_STAT_TypeDef RX_STAT_TypeDef;
-
-PACKED struct TX_DESC_TypeDef { /* TX Descriptor struct */
- unsigned int Packet;
- unsigned int Ctrl;
-};
-typedef struct TX_DESC_TypeDef TX_DESC_TypeDef;
-
-PACKED struct TX_STAT_TypeDef { /* TX Status struct */
- unsigned int Info;
-};
-typedef struct TX_STAT_TypeDef TX_STAT_TypeDef;
-
-/* MAC Configuration Register 1 */
-#define MAC1_REC_EN 0x00000001 /* Receive Enable */
-#define MAC1_PASS_ALL 0x00000002 /* Pass All Receive Frames */
-#define MAC1_RX_FLOWC 0x00000004 /* RX Flow Control */
-#define MAC1_TX_FLOWC 0x00000008 /* TX Flow Control */
-#define MAC1_LOOPB 0x00000010 /* Loop Back Mode */
-#define MAC1_RES_TX 0x00000100 /* Reset TX Logic */
-#define MAC1_RES_MCS_TX 0x00000200 /* Reset MAC TX Control Sublayer */
-#define MAC1_RES_RX 0x00000400 /* Reset RX Logic */
-#define MAC1_RES_MCS_RX 0x00000800 /* Reset MAC RX Control Sublayer */
-#define MAC1_SIM_RES 0x00004000 /* Simulation Reset */
-#define MAC1_SOFT_RES 0x00008000 /* Soft Reset MAC */
-
-/* MAC Configuration Register 2 */
-#define MAC2_FULL_DUP 0x00000001 /* Full Duplex Mode */
-#define MAC2_FRM_LEN_CHK 0x00000002 /* Frame Length Checking */
-#define MAC2_HUGE_FRM_EN 0x00000004 /* Huge Frame Enable */
-#define MAC2_DLY_CRC 0x00000008 /* Delayed CRC Mode */
-#define MAC2_CRC_EN 0x00000010 /* Append CRC to every Frame */
-#define MAC2_PAD_EN 0x00000020 /* Pad all Short Frames */
-#define MAC2_VLAN_PAD_EN 0x00000040 /* VLAN Pad Enable */
-#define MAC2_ADET_PAD_EN 0x00000080 /* Auto Detect Pad Enable */
-#define MAC2_PPREAM_ENF 0x00000100 /* Pure Preamble Enforcement */
-#define MAC2_LPREAM_ENF 0x00000200 /* Long Preamble Enforcement */
-#define MAC2_NO_BACKOFF 0x00001000 /* No Backoff Algorithm */
-#define MAC2_BACK_PRESSURE 0x00002000 /* Backoff Presurre / No Backoff */
-#define MAC2_EXCESS_DEF 0x00004000 /* Excess Defer */
-
-/* Back-to-Back Inter-Packet-Gap Register */
-#define IPGT_FULL_DUP 0x00000015 /* Recommended value for Full Duplex */
-#define IPGT_HALF_DUP 0x00000012 /* Recommended value for Half Duplex */
-
-/* Non Back-to-Back Inter-Packet-Gap Register */
-#define IPGR_DEF 0x00000012 /* Recommended value */
-
-/* Collision Window/Retry Register */
-#define CLRT_DEF 0x0000370F /* Default value */
-
-/* PHY Support Register */
-#define SUPP_SPEED 0x00000100 /* Reduced MII Logic Current Speed */
-//#define SUPP_RES_RMII 0x00000800 /* Reset Reduced MII Logic */
-#define SUPP_RES_RMII 0x00000000 /* Reset Reduced MII Logic */
-
-/* Test Register */
-#define TEST_SHCUT_PQUANTA 0x00000001 /* Shortcut Pause Quanta */
-#define TEST_TST_PAUSE 0x00000002 /* Test Pause */
-#define TEST_TST_BACKP 0x00000004 /* Test Back Pressure */
-
-/* MII Management Configuration Register */
-#define MCFG_SCAN_INC 0x00000001 /* Scan Increment PHY Address */
-#define MCFG_SUPP_PREAM 0x00000002 /* Suppress Preamble */
-#define MCFG_CLK_SEL 0x0000003C /* Clock Select Mask */
-#define MCFG_RES_MII 0x00008000 /* Reset MII Management Hardware */
-
-/* MII Management Command Register */
-#define MCMD_READ 0x00000001 /* MII Read */
-#define MCMD_SCAN 0x00000002 /* MII Scan continuously */
-
-#define MII_WR_TOUT 0x00050000 /* MII Write timeout count */
-#define MII_RD_TOUT 0x00050000 /* MII Read timeout count */
-
-/* MII Management Address Register */
-#define MADR_REG_ADR 0x0000001F /* MII Register Address Mask */
-#define MADR_PHY_ADR 0x00001F00 /* PHY Address Mask */
-
-/* MII Management Indicators Register */
-#define MIND_BUSY 0x00000001 /* MII is Busy */
-#define MIND_SCAN 0x00000002 /* MII Scanning in Progress */
-#define MIND_NOT_VAL 0x00000004 /* MII Read Data not valid */
-#define MIND_MII_LINK_FAIL 0x00000008 /* MII Link Failed */
-
-/* Command Register */
-#define CR_RX_EN 0x00000001 /* Enable Receive */
-#define CR_TX_EN 0x00000002 /* Enable Transmit */
-#define CR_REG_RES 0x00000008 /* Reset Host Registers */
-#define CR_TX_RES 0x00000010 /* Reset Transmit Datapath */
-#define CR_RX_RES 0x00000020 /* Reset Receive Datapath */
-#define CR_PASS_RUNT_FRM 0x00000040 /* Pass Runt Frames */
-#define CR_PASS_RX_FILT 0x00000080 /* Pass RX Filter */
-#define CR_TX_FLOW_CTRL 0x00000100 /* TX Flow Control */
-#define CR_RMII 0x00000200 /* Reduced MII Interface */
-#define CR_FULL_DUP 0x00000400 /* Full Duplex */
-
-/* Status Register */
-#define SR_RX_EN 0x00000001 /* Enable Receive */
-#define SR_TX_EN 0x00000002 /* Enable Transmit */
-
-/* Transmit Status Vector 0 Register */
-#define TSV0_CRC_ERR 0x00000001 /* CRC error */
-#define TSV0_LEN_CHKERR 0x00000002 /* Length Check Error */
-#define TSV0_LEN_OUTRNG 0x00000004 /* Length Out of Range */
-#define TSV0_DONE 0x00000008 /* Tramsmission Completed */
-#define TSV0_MCAST 0x00000010 /* Multicast Destination */
-#define TSV0_BCAST 0x00000020 /* Broadcast Destination */
-#define TSV0_PKT_DEFER 0x00000040 /* Packet Deferred */
-#define TSV0_EXC_DEFER 0x00000080 /* Excessive Packet Deferral */
-#define TSV0_EXC_COLL 0x00000100 /* Excessive Collision */
-#define TSV0_LATE_COLL 0x00000200 /* Late Collision Occured */
-#define TSV0_GIANT 0x00000400 /* Giant Frame */
-#define TSV0_UNDERRUN 0x00000800 /* Buffer Underrun */
-#define TSV0_BYTES 0x0FFFF000 /* Total Bytes Transferred */
-#define TSV0_CTRL_FRAME 0x10000000 /* Control Frame */
-#define TSV0_PAUSE 0x20000000 /* Pause Frame */
-#define TSV0_BACK_PRESS 0x40000000 /* Backpressure Method Applied */
-#define TSV0_VLAN 0x80000000 /* VLAN Frame */
-
-/* Transmit Status Vector 1 Register */
-#define TSV1_BYTE_CNT 0x0000FFFF /* Transmit Byte Count */
-#define TSV1_COLL_CNT 0x000F0000 /* Transmit Collision Count */
-
-/* Receive Status Vector Register */
-#define RSV_BYTE_CNT 0x0000FFFF /* Receive Byte Count */
-#define RSV_PKT_IGNORED 0x00010000 /* Packet Previously Ignored */
-#define RSV_RXDV_SEEN 0x00020000 /* RXDV Event Previously Seen */
-#define RSV_CARR_SEEN 0x00040000 /* Carrier Event Previously Seen */
-#define RSV_REC_CODEV 0x00080000 /* Receive Code Violation */
-#define RSV_CRC_ERR 0x00100000 /* CRC Error */
-#define RSV_LEN_CHKERR 0x00200000 /* Length Check Error */
-#define RSV_LEN_OUTRNG 0x00400000 /* Length Out of Range */
-#define RSV_REC_OK 0x00800000 /* Frame Received OK */
-#define RSV_MCAST 0x01000000 /* Multicast Frame */
-#define RSV_BCAST 0x02000000 /* Broadcast Frame */
-#define RSV_DRIB_NIBB 0x04000000 /* Dribble Nibble */
-#define RSV_CTRL_FRAME 0x08000000 /* Control Frame */
-#define RSV_PAUSE 0x10000000 /* Pause Frame */
-#define RSV_UNSUPP_OPC 0x20000000 /* Unsupported Opcode */
-#define RSV_VLAN 0x40000000 /* VLAN Frame */
-
-/* Flow Control Counter Register */
-#define FCC_MIRR_CNT 0x0000FFFF /* Mirror Counter */
-#define FCC_PAUSE_TIM 0xFFFF0000 /* Pause Timer */
-
-/* Flow Control Status Register */
-#define FCS_MIRR_CNT 0x0000FFFF /* Mirror Counter Current */
-
-/* Receive Filter Control Register */
-#define RFC_UCAST_EN 0x00000001 /* Accept Unicast Frames Enable */
-#define RFC_BCAST_EN 0x00000002 /* Accept Broadcast Frames Enable */
-#define RFC_MCAST_EN 0x00000004 /* Accept Multicast Frames Enable */
-#define RFC_UCAST_HASH_EN 0x00000008 /* Accept Unicast Hash Filter Frames */
-#define RFC_MCAST_HASH_EN 0x00000010 /* Accept Multicast Hash Filter Fram.*/
-#define RFC_PERFECT_EN 0x00000020 /* Accept Perfect Match Enable */
-#define RFC_MAGP_WOL_EN 0x00001000 /* Magic Packet Filter WoL Enable */
-#define RFC_PFILT_WOL_EN 0x00002000 /* Perfect Filter WoL Enable */
-
-/* Receive Filter WoL Status/Clear Registers */
-#define WOL_UCAST 0x00000001 /* Unicast Frame caused WoL */
-#define WOL_BCAST 0x00000002 /* Broadcast Frame caused WoL */
-#define WOL_MCAST 0x00000004 /* Multicast Frame caused WoL */
-#define WOL_UCAST_HASH 0x00000008 /* Unicast Hash Filter Frame WoL */
-#define WOL_MCAST_HASH 0x00000010 /* Multicast Hash Filter Frame WoL */
-#define WOL_PERFECT 0x00000020 /* Perfect Filter WoL */
-#define WOL_RX_FILTER 0x00000080 /* RX Filter caused WoL */
-#define WOL_MAG_PACKET 0x00000100 /* Magic Packet Filter caused WoL */
-
-/* Interrupt Status/Enable/Clear/Set Registers */
-#define INT_RX_OVERRUN 0x00000001 /* Overrun Error in RX Queue */
-#define INT_RX_ERR 0x00000002 /* Receive Error */
-#define INT_RX_FIN 0x00000004 /* RX Finished Process Descriptors */
-#define INT_RX_DONE 0x00000008 /* Receive Done */
-#define INT_TX_UNDERRUN 0x00000010 /* Transmit Underrun */
-#define INT_TX_ERR 0x00000020 /* Transmit Error */
-#define INT_TX_FIN 0x00000040 /* TX Finished Process Descriptors */
-#define INT_TX_DONE 0x00000080 /* Transmit Done */
-#define INT_SOFT_INT 0x00001000 /* Software Triggered Interrupt */
-#define INT_WAKEUP 0x00002000 /* Wakeup Event Interrupt */
-
-/* Power Down Register */
-#define PD_POWER_DOWN 0x80000000 /* Power Down MAC */
-
-/* RX Descriptor Control Word */
-#define RCTRL_SIZE 0x000007FF /* Buffer size mask */
-#define RCTRL_INT 0x80000000 /* Generate RxDone Interrupt */
-
-/* RX Status Hash CRC Word */
-#define RHASH_SA 0x000001FF /* Hash CRC for Source Address */
-#define RHASH_DA 0x001FF000 /* Hash CRC for Destination Address */
-
-/* RX Status Information Word */
-#define RINFO_SIZE 0x000007FF /* Data size in bytes */
-#define RINFO_CTRL_FRAME 0x00040000 /* Control Frame */
-#define RINFO_VLAN 0x00080000 /* VLAN Frame */
-#define RINFO_FAIL_FILT 0x00100000 /* RX Filter Failed */
-#define RINFO_MCAST 0x00200000 /* Multicast Frame */
-#define RINFO_BCAST 0x00400000 /* Broadcast Frame */
-#define RINFO_CRC_ERR 0x00800000 /* CRC Error in Frame */
-#define RINFO_SYM_ERR 0x01000000 /* Symbol Error from PHY */
-#define RINFO_LEN_ERR 0x02000000 /* Length Error */
-#define RINFO_RANGE_ERR 0x04000000 /* Range Error (exceeded max. size) */
-#define RINFO_ALIGN_ERR 0x08000000 /* Alignment Error */
-#define RINFO_OVERRUN 0x10000000 /* Receive overrun */
-#define RINFO_NO_DESCR 0x20000000 /* No new Descriptor available */
-#define RINFO_LAST_FLAG 0x40000000 /* Last Fragment in Frame */
-#define RINFO_ERR 0x80000000 /* Error Occured (OR of all errors) */
-
-//#define RINFO_ERR_MASK (RINFO_FAIL_FILT | RINFO_CRC_ERR | RINFO_SYM_ERR | RINFO_LEN_ERR | RINFO_ALIGN_ERR | RINFO_OVERRUN)
-#define RINFO_ERR_MASK (RINFO_FAIL_FILT | RINFO_SYM_ERR | \
- RINFO_LEN_ERR | RINFO_ALIGN_ERR | RINFO_OVERRUN)
-
-
-/* TX Descriptor Control Word */
-#define TCTRL_SIZE 0x000007FF /* Size of data buffer in bytes */
-#define TCTRL_OVERRIDE 0x04000000 /* Override Default MAC Registers */
-#define TCTRL_HUGE 0x08000000 /* Enable Huge Frame */
-#define TCTRL_PAD 0x10000000 /* Pad short Frames to 64 bytes */
-#define TCTRL_CRC 0x20000000 /* Append a hardware CRC to Frame */
-#define TCTRL_LAST 0x40000000 /* Last Descriptor for TX Frame */
-#define TCTRL_INT 0x80000000 /* Generate TxDone Interrupt */
-
-/* TX Status Information Word */
-#define TINFO_COL_CNT 0x01E00000 /* Collision Count */
-#define TINFO_DEFER 0x02000000 /* Packet Deferred (not an error) */
-#define TINFO_EXCESS_DEF 0x04000000 /* Excessive Deferral */
-#define TINFO_EXCESS_COL 0x08000000 /* Excessive Collision */
-#define TINFO_LATE_COL 0x10000000 /* Late Collision Occured */
-#define TINFO_UNDERRUN 0x20000000 /* Transmit Underrun */
-#define TINFO_NO_DESCR 0x40000000 /* No new Descriptor available */
-#define TINFO_ERR 0x80000000 /* Error Occured (OR of all errors) */
-
-/* ENET Device Revision ID */
-#define OLD_EMAC_MODULE_ID 0x39022000 /* Rev. ID for first rev '-' */
-
-/* DP83848C PHY Registers */
-#define PHY_REG_BMCR 0x00 /* Basic Mode Control Register */
-#define PHY_REG_BMSR 0x01 /* Basic Mode Status Register */
-#define PHY_REG_IDR1 0x02 /* PHY Identifier 1 */
-#define PHY_REG_IDR2 0x03 /* PHY Identifier 2 */
-#define PHY_REG_ANAR 0x04 /* Auto-Negotiation Advertisement */
-#define PHY_REG_ANLPAR 0x05 /* Auto-Neg. Link Partner Abitily */
-#define PHY_REG_ANER 0x06 /* Auto-Neg. Expansion Register */
-#define PHY_REG_ANNPTR 0x07 /* Auto-Neg. Next Page TX */
-
-/* PHY Extended Registers */
-#define PHY_REG_STS 0x10 /* Status Register */
-#define PHY_REG_MICR 0x11 /* MII Interrupt Control Register */
-#define PHY_REG_MISR 0x12 /* MII Interrupt Status Register */
-#define PHY_REG_FCSCR 0x14 /* False Carrier Sense Counter */
-#define PHY_REG_RECR 0x15 /* Receive Error Counter */
-#define PHY_REG_PCSR 0x16 /* PCS Sublayer Config. and Status */
-#define PHY_REG_RBR 0x17 /* RMII and Bypass Register */
-#define PHY_REG_LEDCR 0x18 /* LED Direct Control Register */
-#define PHY_REG_PHYCR 0x19 /* PHY Control Register */
-#define PHY_REG_10BTSCR 0x1A /* 10Base-T Status/Control Register */
-#define PHY_REG_CDCTRL1 0x1B /* CD Test Control and BIST Extens. */
-#define PHY_REG_EDCR 0x1D /* Energy Detect Control Register */
-
-#define PHY_REG_SCSR 0x1F /* PHY Special Control/Status Register */
-
-#define PHY_FULLD_100M 0x2100 /* Full Duplex 100Mbit */
-#define PHY_HALFD_100M 0x2000 /* Half Duplex 100Mbit */
-#define PHY_FULLD_10M 0x0100 /* Full Duplex 10Mbit */
-#define PHY_HALFD_10M 0x0000 /* Half Duplex 10MBit */
-#define PHY_AUTO_NEG 0x3000 /* Select Auto Negotiation */
-
-#define DP83848C_DEF_ADR 0x0100 /* Default PHY device address */
-#define DP83848C_ID 0x20005C90 /* PHY Identifier - DP83848C */
-
-#define LAN8720_ID 0x0007C0F0 /* PHY Identifier - LAN8720 */
-
-#define PHY_STS_LINK 0x0001 /* PHY Status Link Mask */
-#define PHY_STS_SPEED 0x0002 /* PHY Status Speed Mask */
-#define PHY_STS_DUPLEX 0x0004 /* PHY Status Duplex Mask */
-
-#define PHY_BMCR_RESET 0x8000 /* PHY Reset */
-
-#define PHY_BMSR_LINK 0x0004 /* PHY BMSR Link valid */
-
-#define PHY_SCSR_100MBIT 0x0008 /* Speed: 1=100 MBit, 0=10Mbit */
-#define PHY_SCSR_DUPLEX 0x0010 /* PHY Duplex Mask */
-
-
-static int phy_read(unsigned int PhyReg);
-static int phy_write(unsigned int PhyReg, unsigned short Data);
-
-static void txdscr_init(void);
-static void rxdscr_init(void);
-
-#if defined (__ICCARM__)
-# define AHBSRAM1
-#elif defined(TOOLCHAIN_GCC_CR)
-# define AHBSRAM1 __attribute__((section(".data.$RamPeriph32")))
-#else
-# define AHBSRAM1 __attribute__((section("AHBSRAM1"),aligned))
-#endif
-
-AHBSRAM1 volatile uint8_t rxbuf[NUM_RX_FRAG][ETH_FRAG_SIZE];
-AHBSRAM1 volatile uint8_t txbuf[NUM_TX_FRAG][ETH_FRAG_SIZE];
-AHBSRAM1 volatile RX_DESC_TypeDef rxdesc[NUM_RX_FRAG];
-AHBSRAM1 volatile RX_STAT_TypeDef rxstat[NUM_RX_FRAG];
-AHBSRAM1 volatile TX_DESC_TypeDef txdesc[NUM_TX_FRAG];
-AHBSRAM1 volatile TX_STAT_TypeDef txstat[NUM_TX_FRAG];
-
-
-#if NEW_LOGIC
-static int rx_consume_offset = -1;
-static int tx_produce_offset = -1;
-#else
-static int send_doff = 0;
-static int send_idx = -1;
-static int send_size = 0;
-
-static int receive_soff = 0;
-static int receive_idx = -1;
-#endif
-
-static uint32_t phy_id = 0;
-
-static inline int rinc(int idx, int mod) {
- ++idx;
- idx %= mod;
- return idx;
-}
-
-//extern unsigned int SystemFrequency;
-static inline unsigned int clockselect() {
- if(SystemCoreClock < 10000000) {
- return 1;
- } else if(SystemCoreClock < 15000000) {
- return 2;
- } else if(SystemCoreClock < 20000000) {
- return 3;
- } else if(SystemCoreClock < 25000000) {
- return 4;
- } else if(SystemCoreClock < 35000000) {
- return 5;
- } else if(SystemCoreClock < 50000000) {
- return 6;
- } else if(SystemCoreClock < 70000000) {
- return 7;
- } else if(SystemCoreClock < 80000000) {
- return 8;
- } else if(SystemCoreClock < 90000000) {
- return 9;
- } else if(SystemCoreClock < 100000000) {
- return 10;
- } else if(SystemCoreClock < 120000000) {
- return 11;
- } else if(SystemCoreClock < 130000000) {
- return 12;
- } else if(SystemCoreClock < 140000000) {
- return 13;
- } else if(SystemCoreClock < 150000000) {
- return 15;
- } else if(SystemCoreClock < 160000000) {
- return 16;
- } else {
- return 0;
- }
-}
-
-#ifndef min
-#define min(x, y) (((x)<(y))?(x):(y))
-#endif
-
-/*----------------------------------------------------------------------------
- Ethernet Device initialize
- *----------------------------------------------------------------------------*/
-int ethernet_init() {
- int regv, tout;
- char mac[ETHERNET_ADDR_SIZE];
- unsigned int clock = clockselect();
-
- LPC_SC->PCONP |= 0x40000000; /* Power Up the EMAC controller. */
-
- LPC_PINCON->PINSEL2 = 0x50150105; /* Enable P1 Ethernet Pins. */
- LPC_PINCON->PINSEL3 = (LPC_PINCON->PINSEL3 & ~0x0000000F) | 0x00000005;
-
- /* Reset all EMAC internal modules. */
- LPC_EMAC->MAC1 = MAC1_RES_TX | MAC1_RES_MCS_TX | MAC1_RES_RX |
- MAC1_RES_MCS_RX | MAC1_SIM_RES | MAC1_SOFT_RES;
- LPC_EMAC->Command = CR_REG_RES | CR_TX_RES | CR_RX_RES | CR_PASS_RUNT_FRM;
-
- for(tout = 100; tout; tout--) __NOP(); /* A short delay after reset. */
-
- LPC_EMAC->MAC1 = MAC1_PASS_ALL; /* Initialize MAC control registers. */
- LPC_EMAC->MAC2 = MAC2_CRC_EN | MAC2_PAD_EN;
- LPC_EMAC->MAXF = ETH_MAX_FLEN;
- LPC_EMAC->CLRT = CLRT_DEF;
- LPC_EMAC->IPGR = IPGR_DEF;
-
- LPC_EMAC->Command = CR_RMII | CR_PASS_RUNT_FRM; /* Enable Reduced MII interface. */
-
- LPC_EMAC->MCFG = (clock << 0x2) & MCFG_CLK_SEL; /* Set clock */
- LPC_EMAC->MCFG |= MCFG_RES_MII; /* and reset */
-
- for(tout = 100; tout; tout--) __NOP(); /* A short delay */
-
- LPC_EMAC->MCFG = (clock << 0x2) & MCFG_CLK_SEL;
- LPC_EMAC->MCMD = 0;
-
- LPC_EMAC->SUPP = SUPP_RES_RMII; /* Reset Reduced MII Logic. */
-
- for (tout = 100; tout; tout--) __NOP(); /* A short delay */
-
- LPC_EMAC->SUPP = 0;
-
- phy_write(PHY_REG_BMCR, PHY_BMCR_RESET); /* perform PHY reset */
- for(tout = 0x20000; ; tout--) { /* Wait for hardware reset to end. */
- regv = phy_read(PHY_REG_BMCR);
- if(regv < 0 || tout == 0) {
- return -1; /* Error */
- }
- if(!(regv & PHY_BMCR_RESET)) {
- break; /* Reset complete. */
- }
- }
-
- phy_id = (phy_read(PHY_REG_IDR1) << 16);
- phy_id |= (phy_read(PHY_REG_IDR2) & 0XFFF0);
-
- if (phy_id != DP83848C_ID && phy_id != LAN8720_ID) {
- error("Unknown Ethernet PHY (%x)", (unsigned int)phy_id);
- }
-
- ethernet_set_link(-1, 0);
-
- /* Set the Ethernet MAC Address registers */
- ethernet_address(mac);
- LPC_EMAC->SA0 = ((uint32_t)mac[5] << 8) | (uint32_t)mac[4];
- LPC_EMAC->SA1 = ((uint32_t)mac[3] << 8) | (uint32_t)mac[2];
- LPC_EMAC->SA2 = ((uint32_t)mac[1] << 8) | (uint32_t)mac[0];
-
- txdscr_init(); /* initialize DMA TX Descriptor */
- rxdscr_init(); /* initialize DMA RX Descriptor */
-
- LPC_EMAC->RxFilterCtrl = RFC_UCAST_EN | RFC_MCAST_EN | RFC_BCAST_EN | RFC_PERFECT_EN;
- /* Receive Broadcast, Perfect Match Packets */
-
- LPC_EMAC->IntEnable = INT_RX_DONE | INT_TX_DONE; /* Enable EMAC interrupts. */
- LPC_EMAC->IntClear = 0xFFFF; /* Reset all interrupts */
-
-
- LPC_EMAC->Command |= (CR_RX_EN | CR_TX_EN); /* Enable receive and transmit mode of MAC Ethernet core */
- LPC_EMAC->MAC1 |= MAC1_REC_EN;
-
-#if NEW_LOGIC
- rx_consume_offset = -1;
- tx_produce_offset = -1;
-#else
- send_doff = 0;
- send_idx = -1;
- send_size = 0;
-
- receive_soff = 0;
- receive_idx = -1;
-#endif
-
- return 0;
-}
-
-/*----------------------------------------------------------------------------
- Ethernet Device Uninitialize
- *----------------------------------------------------------------------------*/
-void ethernet_free() {
- LPC_EMAC->IntEnable &= ~(INT_RX_DONE | INT_TX_DONE);
- LPC_EMAC->IntClear = 0xFFFF;
-
- LPC_SC->PCONP &= ~0x40000000; /* Power down the EMAC controller. */
-
- LPC_PINCON->PINSEL2 &= ~0x50150105; /* Disable P1 ethernet pins. */
- LPC_PINCON->PINSEL3 = (LPC_PINCON->PINSEL3 & ~0x0000000F) | 0x00000000;
-}
-
-// if(TxProduceIndex == TxConsumeIndex) buffer array is empty
-// if(TxProduceIndex == TxConsumeIndex - 1) buffer is full, should not fill
-// TxProduceIndex - The buffer that will/is being fileld by driver, s/w increment
-// TxConsumeIndex - The buffer that will/is beign sent by hardware
-
-int ethernet_write(const char *data, int slen) {
-
-#if NEW_LOGIC
-
- if(tx_produce_offset < 0) { // mark as active if not already
- tx_produce_offset = 0;
- }
-
- int index = LPC_EMAC->TxProduceIndex;
-
- int remaining = ETH_MAX_FLEN - tx_produce_offset - 4; // bytes written plus checksum
- int requested = slen;
- int ncopy = min(remaining, requested);
-
- void *pdst = (void *)(txdesc[index].Packet + tx_produce_offset);
- void *psrc = (void *)(data);
-
- if(ncopy > 0 ){
- if(data != NULL) {
- memcpy(pdst, psrc, ncopy);
- } else {
- memset(pdst, 0, ncopy);
- }
- }
-
- tx_produce_offset += ncopy;
-
- return ncopy;
-
-#else
- void *pdst, *psrc;
- const int dlen = ETH_FRAG_SIZE;
- int copy = 0;
- int soff = 0;
-
- if(send_idx == -1) {
- send_idx = LPC_EMAC->TxProduceIndex;
- }
-
- if(slen + send_doff > ethernet_MTU_SIZE) {
- return -1;
- }
-
- do {
- copy = min(slen - soff, dlen - send_doff);
- pdst = (void *)(txdesc[send_idx].Packet + send_doff);
- psrc = (void *)(data + soff);
- if(send_doff + copy > ETH_FRAG_SIZE) {
- txdesc[send_idx].Ctrl = (send_doff-1) | (TCTRL_INT);
- send_idx = rinc(send_idx, NUM_TX_FRAG);
- send_doff = 0;
- }
-
- if(data != NULL) {
- memcpy(pdst, psrc, copy);
- } else {
- memset(pdst, 0, copy);
- }
-
- soff += copy;
- send_doff += copy;
- send_size += copy;
- } while(soff != slen);
-
- return soff;
-#endif
-}
-
-int ethernet_send() {
-
-#if NEW_LOGIC
- if(tx_produce_offset < 0) { // no buffer active
- return -1;
- }
-
- // ensure there is a link
- if(!ethernet_link()) {
- return -2;
- }
-
- // we have been writing in to a buffer, so finalise it
- int size = tx_produce_offset;
- int index = LPC_EMAC->TxProduceIndex;
- txdesc[index].Ctrl = (tx_produce_offset-1) | (TCTRL_INT | TCTRL_LAST);
-
- // Increment ProduceIndex to allow it to be sent
- // We can only do this if the next slot is free
- int next = rinc(index, NUM_TX_FRAG);
- while(next == LPC_EMAC->TxConsumeIndex) {
- for(int i=0; i<1000; i++) { __NOP(); }
- }
-
- LPC_EMAC->TxProduceIndex = next;
- tx_produce_offset = -1;
- return size;
-
-#else
- int s = send_size;
- txdesc[send_idx].Ctrl = (send_doff-1) | (TCTRL_INT | TCTRL_LAST);
- send_idx = rinc(send_idx, NUM_TX_FRAG);
- LPC_EMAC->TxProduceIndex = send_idx;
- send_doff = 0;
- send_idx = -1;
- send_size = 0;
- return s;
-#endif
-}
-
-// RxConsmeIndex - The index of buffer the driver will/is reading from. Driver should inc once read
-// RxProduceIndex - The index of buffer that will/is being filled by MAC. H/w will inc once rxd
-//
-// if(RxConsumeIndex == RxProduceIndex) buffer array is empty
-// if(RxConsumeIndex == RxProduceIndex + 1) buffer array is full
-
-// Recevies an arrived ethernet packet.
-// Receiving an ethernet packet will drop the last received ethernet packet
-// and make a new ethernet packet ready to read.
-// Returns size of packet, else 0 if nothing to receive
-
-// We read from RxConsumeIndex from position rx_consume_offset
-// if rx_consume_offset < 0, then we have not recieved the RxConsumeIndex packet for reading
-// rx_consume_offset = -1 // no frame
-// rx_consume_offset = 0 // start of frame
-// Assumption: A fragment should alway be a whole frame
-
-int ethernet_receive() {
-#if NEW_LOGIC
-
- // if we are currently reading a valid RxConsume buffer, increment to the next one
- if(rx_consume_offset >= 0) {
- LPC_EMAC->RxConsumeIndex = rinc(LPC_EMAC->RxConsumeIndex, NUM_RX_FRAG);
- }
-
- // if the buffer is empty, mark it as no valid buffer
- if(LPC_EMAC->RxConsumeIndex == LPC_EMAC->RxProduceIndex) {
- rx_consume_offset = -1;
- return 0;
- }
-
- uint32_t info = rxstat[LPC_EMAC->RxConsumeIndex].Info;
- rx_consume_offset = 0;
-
- // check if it is not marked as last or for errors
- if(!(info & RINFO_LAST_FLAG) || (info & RINFO_ERR_MASK)) {
- return -1;
- }
-
- int size = (info & RINFO_SIZE) + 1;
- return size - 4; // don't include checksum bytes
-
-#else
- if(receive_idx == -1) {
- receive_idx = LPC_EMAC->RxConsumeIndex;
- } else {
- while(!(rxstat[receive_idx].Info & RINFO_LAST_FLAG) && ((uint32_t)receive_idx != LPC_EMAC->RxProduceIndex)) {
- receive_idx = rinc(receive_idx, NUM_RX_FRAG);
- }
- unsigned int info = rxstat[receive_idx].Info;
- int slen = (info & RINFO_SIZE) + 1;
-
- if(slen > ethernet_MTU_SIZE || (info & RINFO_ERR_MASK)) {
- /* Invalid frame, ignore it and free buffer. */
- receive_idx = rinc(receive_idx, NUM_RX_FRAG);
- }
- receive_idx = rinc(receive_idx, NUM_RX_FRAG);
- receive_soff = 0;
-
- LPC_EMAC->RxConsumeIndex = receive_idx;
- }
-
- if((uint32_t)receive_idx == LPC_EMAC->RxProduceIndex) {
- receive_idx = -1;
- return 0;
- }
-
- return (rxstat[receive_idx].Info & RINFO_SIZE) - 3;
-#endif
-}
-
-// Read from an recevied ethernet packet.
-// After receive returnd a number bigger than 0 it is
-// possible to read bytes from this packet.
-// Read will write up to size bytes into data.
-// It is possible to use read multible times.
-// Each time read will start reading after the last read byte before.
-
-int ethernet_read(char *data, int dlen) {
-#if NEW_LOGIC
- // Check we have a valid buffer to read
- if(rx_consume_offset < 0) {
- return 0;
- }
-
- // Assume 1 fragment block
- uint32_t info = rxstat[LPC_EMAC->RxConsumeIndex].Info;
- int size = (info & RINFO_SIZE) + 1 - 4; // exclude checksum
-
- int remaining = size - rx_consume_offset;
- int requested = dlen;
- int ncopy = min(remaining, requested);
-
- void *psrc = (void *)(rxdesc[LPC_EMAC->RxConsumeIndex].Packet + rx_consume_offset);
- void *pdst = (void *)(data);
-
- if(data != NULL && ncopy > 0) {
- memcpy(pdst, psrc, ncopy);
- }
-
- rx_consume_offset += ncopy;
-
- return ncopy;
-#else
- int slen;
- int copy = 0;
- unsigned int more;
- unsigned int info;
- void *pdst, *psrc;
- int doff = 0;
-
- if((uint32_t)receive_idx == LPC_EMAC->RxProduceIndex || receive_idx == -1) {
- return 0;
- }
-
- do {
- info = rxstat[receive_idx].Info;
- more = !(info & RINFO_LAST_FLAG);
- slen = (info & RINFO_SIZE) + 1;
-
- if(slen > ethernet_MTU_SIZE || (info & RINFO_ERR_MASK)) {
- /* Invalid frame, ignore it and free buffer. */
- receive_idx = rinc(receive_idx, NUM_RX_FRAG);
- } else {
-
- copy = min(slen - receive_soff, dlen - doff);
- psrc = (void *)(rxdesc[receive_idx].Packet + receive_soff);
- pdst = (void *)(data + doff);
-
- if(data != NULL) {
- /* check if Buffer available */
- memcpy(pdst, psrc, copy);
- }
-
- receive_soff += copy;
- doff += copy;
-
- if((more && (receive_soff == slen))) {
- receive_idx = rinc(receive_idx, NUM_RX_FRAG);
- receive_soff = 0;
- }
- }
- } while(more && !(doff == dlen) && !receive_soff);
-
- return doff;
-#endif
-}
-
-int ethernet_link(void) {
- if (phy_id == DP83848C_ID) {
- return (phy_read(PHY_REG_STS) & PHY_STS_LINK);
- }
- else { // LAN8720_ID
- return (phy_read(PHY_REG_BMSR) & PHY_BMSR_LINK);
- }
-}
-
-static int phy_write(unsigned int PhyReg, unsigned short Data) {
- unsigned int timeOut;
-
- LPC_EMAC->MADR = DP83848C_DEF_ADR | PhyReg;
- LPC_EMAC->MWTD = Data;
-
- for(timeOut = 0; timeOut < MII_WR_TOUT; timeOut++) { /* Wait until operation completed */
- if((LPC_EMAC->MIND & MIND_BUSY) == 0) {
- return 0;
- }
- }
-
- return -1;
-}
-
-static int phy_read(unsigned int PhyReg) {
- unsigned int timeOut;
-
- LPC_EMAC->MADR = DP83848C_DEF_ADR | PhyReg;
- LPC_EMAC->MCMD = MCMD_READ;
-
- for(timeOut = 0; timeOut < MII_RD_TOUT; timeOut++) { /* Wait until operation completed */
- if((LPC_EMAC->MIND & MIND_BUSY) == 0) {
- LPC_EMAC->MCMD = 0;
- return LPC_EMAC->MRDD; /* Return a 16-bit value. */
- }
- }
-
- return -1;
-}
-
-
-static void txdscr_init() {
- int i;
-
- for(i = 0; i < NUM_TX_FRAG; i++) {
- txdesc[i].Packet = (uint32_t)&txbuf[i];
- txdesc[i].Ctrl = 0;
- txstat[i].Info = 0;
- }
-
- LPC_EMAC->TxDescriptor = (uint32_t)txdesc; /* Set EMAC Transmit Descriptor Registers. */
- LPC_EMAC->TxStatus = (uint32_t)txstat;
- LPC_EMAC->TxDescriptorNumber = NUM_TX_FRAG-1;
-
- LPC_EMAC->TxProduceIndex = 0; /* Tx Descriptors Point to 0 */
-}
-
-static void rxdscr_init() {
- int i;
-
- for(i = 0; i < NUM_RX_FRAG; i++) {
- rxdesc[i].Packet = (uint32_t)&rxbuf[i];
- rxdesc[i].Ctrl = RCTRL_INT | (ETH_FRAG_SIZE-1);
- rxstat[i].Info = 0;
- rxstat[i].HashCRC = 0;
- }
-
- LPC_EMAC->RxDescriptor = (uint32_t)rxdesc; /* Set EMAC Receive Descriptor Registers. */
- LPC_EMAC->RxStatus = (uint32_t)rxstat;
- LPC_EMAC->RxDescriptorNumber = NUM_RX_FRAG-1;
-
- LPC_EMAC->RxConsumeIndex = 0; /* Rx Descriptors Point to 0 */
-}
-
-void ethernet_address(char *mac) {
- mbed_mac_address(mac);
-}
-
-void ethernet_set_link(int speed, int duplex) {
- unsigned short phy_data;
- int tout;
-
- if((speed < 0) || (speed > 1)) {
- phy_data = PHY_AUTO_NEG;
- } else {
- phy_data = (((unsigned short) speed << 13) |
- ((unsigned short) duplex << 8));
- }
-
- phy_write(PHY_REG_BMCR, phy_data);
-
- for(tout = 100; tout; tout--) { __NOP(); } /* A short delay */
-
- switch(phy_id) {
- case DP83848C_ID:
- phy_data = phy_read(PHY_REG_STS);
-
- if(phy_data & PHY_STS_DUPLEX) {
- LPC_EMAC->MAC2 |= MAC2_FULL_DUP;
- LPC_EMAC->Command |= CR_FULL_DUP;
- LPC_EMAC->IPGT = IPGT_FULL_DUP;
- } else {
- LPC_EMAC->MAC2 &= ~MAC2_FULL_DUP;
- LPC_EMAC->Command &= ~CR_FULL_DUP;
- LPC_EMAC->IPGT = IPGT_HALF_DUP;
- }
-
- if(phy_data & PHY_STS_SPEED) {
- LPC_EMAC->SUPP &= ~SUPP_SPEED;
- } else {
- LPC_EMAC->SUPP |= SUPP_SPEED;
- }
- break;
-
- case LAN8720_ID:
- phy_data = phy_read(PHY_REG_SCSR);
-
- if (phy_data & PHY_SCSR_DUPLEX) {
- LPC_EMAC->MAC2 |= MAC2_FULL_DUP;
- LPC_EMAC->Command |= CR_FULL_DUP;
- LPC_EMAC->IPGT = IPGT_FULL_DUP;
- } else {
- LPC_EMAC->Command &= ~CR_FULL_DUP;
- LPC_EMAC->IPGT = IPGT_HALF_DUP;
- }
-
- if(phy_data & PHY_SCSR_100MBIT) {
- LPC_EMAC->SUPP |= SUPP_SPEED;
- } else {
- LPC_EMAC->SUPP &= ~SUPP_SPEED;
- }
- break;
- }
-}
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/gpio_api.c b/targets/TARGET_NXP/TARGET_LPC23XX/gpio_api.c
deleted file mode 100644
index 10ac3664fc..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/gpio_api.c
+++ /dev/null
@@ -1,53 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2013 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-#include "mbed_assert.h"
-#include "gpio_api.h"
-#include "pinmap.h"
-
-uint32_t gpio_set(PinName pin) {
- LPC_SC->SCS |= 1; // High speed GPIO is enabled on ports 0 and 1
-
- pin_function(pin, 0);
-
- return (1 << ((int)pin & 0x1F));
-}
-
-void gpio_init(gpio_t *obj, PinName pin) {
- if (pin == (PinName)NC)
- return;
- obj->pin = pin;
- obj->mask = gpio_set(pin);
-
- LPC_GPIO_TypeDef *port_reg = (LPC_GPIO_TypeDef *) ((int)pin & ~0x1F);
-
- obj->reg_set = &port_reg->FIOSET;
- obj->reg_clr = &port_reg->FIOCLR;
- obj->reg_in = &port_reg->FIOPIN;
- obj->reg_dir = &port_reg->FIODIR;
-}
-
-void gpio_mode(gpio_t *obj, PinMode mode) {
- pin_mode(obj->pin, mode);
-}
-
-void gpio_dir(gpio_t *obj, PinDirection direction) {
- if (obj->pin == (PinName)NC)
- return;
- switch (direction) {
- case PIN_INPUT : *obj->reg_dir &= ~obj->mask; break;
- case PIN_OUTPUT: *obj->reg_dir |= obj->mask; break;
- }
-}
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/gpio_irq_api.c b/targets/TARGET_NXP/TARGET_LPC23XX/gpio_irq_api.c
deleted file mode 100644
index 40fcaa6dbe..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/gpio_irq_api.c
+++ /dev/null
@@ -1,154 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2013 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-#include "gpio_irq_api.h"
-#include "mbed_error.h"
-#include
-#include "cmsis.h"
-
-#define CHANNEL_NUM 48
-
-static uint32_t channel_ids[CHANNEL_NUM] = {0};
-static gpio_irq_handler irq_handler;
-
-static void handle_interrupt_in(void) {
- // Read in all current interrupt registers. We do this once as the
- // GPIO interrupt registers are on the APB bus, and this is slow.
- uint32_t rise0 = LPC_GPIOINT->IO0IntStatR;
- uint32_t fall0 = LPC_GPIOINT->IO0IntStatF;
- uint32_t rise2 = LPC_GPIOINT->IO2IntStatR;
- uint32_t fall2 = LPC_GPIOINT->IO2IntStatF;
- uint32_t mask0 = 0;
- uint32_t mask2 = 0;
- int i;
-
- // P0.0-0.31
- for (i = 0; i < 32; i++) {
- uint32_t pmask = (1 << i);
- if (rise0 & pmask) {
- mask0 |= pmask;
- if (channel_ids[i] != 0)
- irq_handler(channel_ids[i], IRQ_RISE);
- }
- if (fall0 & pmask) {
- mask0 |= pmask;
- if (channel_ids[i] != 0)
- irq_handler(channel_ids[i], IRQ_FALL);
- }
- }
-
- // P2.0-2.15
- for (i = 0; i < 16; i++) {
- uint32_t pmask = (1 << i);
- int channel_index = i + 32;
- if (rise2 & pmask) {
- mask2 |= pmask;
- if (channel_ids[channel_index] != 0)
- irq_handler(channel_ids[channel_index], IRQ_RISE);
- }
- if (fall2 & pmask) {
- mask2 |= pmask;
- if (channel_ids[channel_index] != 0)
- irq_handler(channel_ids[channel_index], IRQ_FALL);
- }
- }
-
- // Clear the interrupts we just handled
- LPC_GPIOINT->IO0IntClr = mask0;
- LPC_GPIOINT->IO2IntClr = mask2;
-}
-
-int gpio_irq_init(gpio_irq_t *obj, PinName pin, gpio_irq_handler handler, uint32_t id) {
- if (pin == NC) return -1;
-
- irq_handler = handler;
-
- obj->port = (int)pin & ~0x1F;
- obj->pin = (int)pin & 0x1F;
-
- // Interrupts available only on GPIO0 and GPIO2
- if (obj->port != LPC_GPIO0_BASE && obj->port != LPC_GPIO2_BASE) {
- error("pins on this port cannot generate interrupts");
- }
-
- // put us in the interrupt table
- int index = (obj->port == LPC_GPIO0_BASE) ? obj->pin : obj->pin + 32;
- channel_ids[index] = id;
- obj->ch = index;
-
- NVIC_SetVector(EINT3_IRQn, (uint32_t)handle_interrupt_in);
- NVIC_EnableIRQ(EINT3_IRQn);
-
- return 0;
-}
-
-void gpio_irq_free(gpio_irq_t *obj) {
- channel_ids[obj->ch] = 0;
-}
-
-void gpio_irq_set(gpio_irq_t *obj, gpio_irq_event event, uint32_t enable) {
- // ensure nothing is pending
- switch (obj->port) {
- case LPC_GPIO0_BASE: LPC_GPIOINT->IO0IntClr = 1 << obj->pin; break;
- case LPC_GPIO2_BASE: LPC_GPIOINT->IO2IntClr = 1 << obj->pin; break;
- }
-
- // enable the pin interrupt
- if (event == IRQ_RISE) {
- switch (obj->port) {
- case LPC_GPIO0_BASE:
- if (enable) {
- LPC_GPIOINT->IO0IntEnR |= 1 << obj->pin;
- } else {
- LPC_GPIOINT->IO0IntEnR &= ~(1 << obj->pin);
- }
- break;
- case LPC_GPIO2_BASE:
- if (enable) {
- LPC_GPIOINT->IO2IntEnR |= 1 << obj->pin;
- } else {
- LPC_GPIOINT->IO2IntEnR &= ~(1 << obj->pin);
- }
- break;
- }
- } else {
- switch (obj->port) {
- case LPC_GPIO0_BASE:
- if (enable) {
- LPC_GPIOINT->IO0IntEnF |= 1 << obj->pin;
- } else {
- LPC_GPIOINT->IO0IntEnF &= ~(1 << obj->pin);
- }
- break;
-
- case LPC_GPIO2_BASE:
- if (enable) {
- LPC_GPIOINT->IO2IntEnF |= 1 << obj->pin;
- } else {
- LPC_GPIOINT->IO2IntEnF &= ~(1 << obj->pin);
- }
- break;
- }
- }
-}
-
-void gpio_irq_enable(gpio_irq_t *obj) {
- NVIC_EnableIRQ(EINT3_IRQn);
-}
-
-void gpio_irq_disable(gpio_irq_t *obj) {
- NVIC_DisableIRQ(EINT3_IRQn);
-}
-
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/gpio_object.h b/targets/TARGET_NXP/TARGET_LPC23XX/gpio_object.h
deleted file mode 100644
index fe6d6c1e05..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/gpio_object.h
+++ /dev/null
@@ -1,56 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2013 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-#ifndef MBED_GPIO_OBJECT_H
-#define MBED_GPIO_OBJECT_H
-
-#include "mbed_assert.h"
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-typedef struct {
- PinName pin;
- uint32_t mask;
-
- __IO uint32_t *reg_dir;
- __IO uint32_t *reg_set;
- __IO uint32_t *reg_clr;
- __I uint32_t *reg_in;
-} gpio_t;
-
-static inline void gpio_write(gpio_t *obj, int value) {
- MBED_ASSERT(obj->pin != (PinName)NC);
- if (value)
- *obj->reg_set = obj->mask;
- else
- *obj->reg_clr = obj->mask;
-}
-
-static inline int gpio_read(gpio_t *obj) {
- MBED_ASSERT(obj->pin != (PinName)NC);
- return ((*obj->reg_in & obj->mask) ? 1 : 0);
-}
-
-static inline int gpio_is_connected(const gpio_t *obj) {
- return obj->pin != (PinName)NC;
-}
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/i2c_api.c b/targets/TARGET_NXP/TARGET_LPC23XX/i2c_api.c
deleted file mode 100644
index e24978dcb2..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/i2c_api.c
+++ /dev/null
@@ -1,399 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2013 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-#include "i2c_api.h"
-#include "cmsis.h"
-#include "pinmap.h"
-
-static const PinMap PinMap_I2C_SDA[] = {
- {P0_0 , I2C_1, 3},
- {P0_10, I2C_2, 2},
- {P0_19, I2C_1, 3},
- {P0_27, I2C_0, 1},
- {NC , NC , 0}
-};
-
-static const PinMap PinMap_I2C_SCL[] = {
- {P0_1 , I2C_1, 3},
- {P0_11, I2C_2, 2},
- {P0_20, I2C_1, 3},
- {P0_28, I2C_0, 1},
- {NC , NC, 0}
-};
-
-#define I2C_CONSET(x) (x->i2c->I2CONSET)
-#define I2C_CONCLR(x) (x->i2c->I2CONCLR)
-#define I2C_STAT(x) (x->i2c->I2STAT)
-#define I2C_DAT(x) (x->i2c->I2DAT)
-#define I2C_SCLL(x, val) (x->i2c->I2SCLL = val)
-#define I2C_SCLH(x, val) (x->i2c->I2SCLH = val)
-
-static const uint32_t I2C_addr_offset[2][4] = {
- {0x0C, 0x20, 0x24, 0x28},
- {0x30, 0x34, 0x38, 0x3C}
-};
-
-static inline void i2c_conclr(i2c_t *obj, int start, int stop, int interrupt, int acknowledge) {
- I2C_CONCLR(obj) = (start << 5)
- | (stop << 4)
- | (interrupt << 3)
- | (acknowledge << 2);
-}
-
-static inline void i2c_conset(i2c_t *obj, int start, int stop, int interrupt, int acknowledge) {
- I2C_CONSET(obj) = (start << 5)
- | (stop << 4)
- | (interrupt << 3)
- | (acknowledge << 2);
-}
-
-// Clear the Serial Interrupt (SI)
-static inline void i2c_clear_SI(i2c_t *obj) {
- i2c_conclr(obj, 0, 0, 1, 0);
-}
-
-static inline int i2c_status(i2c_t *obj) {
- return I2C_STAT(obj);
-}
-
-// Wait until the Serial Interrupt (SI) is set
-static int i2c_wait_SI(i2c_t *obj) {
- int timeout = 0;
- while (!(I2C_CONSET(obj) & (1 << 3))) {
- timeout++;
- if (timeout > 100000) return -1;
- }
- return 0;
-}
-
-static inline void i2c_interface_enable(i2c_t *obj) {
- I2C_CONSET(obj) = 0x40;
-}
-
-static inline void i2c_power_enable(i2c_t *obj) {
- switch ((int)obj->i2c) {
- case I2C_0: LPC_SC->PCONP |= 1 << 7; break;
- case I2C_1: LPC_SC->PCONP |= 1 << 19; break;
- case I2C_2: LPC_SC->PCONP |= 1 << 26; break;
- }
-}
-
-void i2c_init(i2c_t *obj, PinName sda, PinName scl) {
- // determine the SPI to use
- I2CName i2c_sda = (I2CName)pinmap_peripheral(sda, PinMap_I2C_SDA);
- I2CName i2c_scl = (I2CName)pinmap_peripheral(scl, PinMap_I2C_SCL);
- obj->i2c = (LPC_I2C_TypeDef *)pinmap_merge(i2c_sda, i2c_scl);
- MBED_ASSERT((int)obj->i2c != NC);
-
- // enable power
- i2c_power_enable(obj);
-
- // set default frequency at 100k
- i2c_frequency(obj, 100000);
- i2c_conclr(obj, 1, 1, 1, 1);
- i2c_interface_enable(obj);
-
- pinmap_pinout(sda, PinMap_I2C_SDA);
- pinmap_pinout(scl, PinMap_I2C_SCL);
-}
-
-inline int i2c_start(i2c_t *obj) {
- int status = 0;
- int isInterrupted = I2C_CONSET(obj) & (1 << 3);
-
- // 8.1 Before master mode can be entered, I2CON must be initialised to:
- // - I2EN STA STO SI AA - -
- // - 1 0 0 x x - -
- // if AA = 0, it can't enter slave mode
- i2c_conclr(obj, 1, 1, 0, 1);
-
- // The master mode may now be entered by setting the STA bit
- // this will generate a start condition when the bus becomes free
- i2c_conset(obj, 1, 0, 0, 1);
- // Clearing SI bit when it wasn't set on entry can jump past state
- // 0x10 or 0x08 and erroneously send uninitialized slave address.
- if (isInterrupted)
- i2c_clear_SI(obj);
-
- i2c_wait_SI(obj);
- status = i2c_status(obj);
-
- // Clear start bit now that it's transmitted
- i2c_conclr(obj, 1, 0, 0, 0);
- return status;
-}
-
-inline int i2c_stop(i2c_t *obj) {
- int timeout = 0;
-
- // write the stop bit
- i2c_conset(obj, 0, 1, 0, 0);
- i2c_clear_SI(obj);
-
- // wait for STO bit to reset
- while (I2C_CONSET(obj) & (1 << 4)) {
- timeout ++;
- if (timeout > 100000) return 1;
- }
-
- return 0;
-}
-
-static inline int i2c_do_write(i2c_t *obj, int value, uint8_t addr) {
- // write the data
- I2C_DAT(obj) = value;
-
- // clear SI to init a send
- i2c_clear_SI(obj);
-
- // wait and return status
- i2c_wait_SI(obj);
- return i2c_status(obj);
-}
-
-static inline int i2c_do_read(i2c_t *obj, int last) {
- // we are in state 0x40 (SLA+R tx'd) or 0x50 (data rx'd and ack)
- if (last) {
- i2c_conclr(obj, 0, 0, 0, 1); // send a NOT ACK
- } else {
- i2c_conset(obj, 0, 0, 0, 1); // send a ACK
- }
-
- // accept byte
- i2c_clear_SI(obj);
-
- // wait for it to arrive
- i2c_wait_SI(obj);
-
- // return the data
- return (I2C_DAT(obj) & 0xFF);
-}
-
-void i2c_frequency(i2c_t *obj, int hz) {
- // [TODO] set pclk to /4
- uint32_t PCLK = SystemCoreClock / 4;
-
- uint32_t pulse = PCLK / (hz * 2);
-
- // I2C Rate
- I2C_SCLL(obj, pulse);
- I2C_SCLH(obj, pulse);
-}
-
-// The I2C does a read or a write as a whole operation
-// There are two types of error conditions it can encounter
-// 1) it can not obtain the bus
-// 2) it gets error responses at part of the transmission
-//
-// We tackle them as follows:
-// 1) we retry until we get the bus. we could have a "timeout" if we can not get it
-// which basically turns it in to a 2)
-// 2) on error, we use the standard error mechanisms to report/debug
-//
-// Therefore an I2C transaction should always complete. If it doesn't it is usually
-// because something is setup wrong (e.g. wiring), and we don't need to programatically
-// check for that
-int i2c_read(i2c_t *obj, int address, char *data, int length, int stop) {
- int count, status;
-
- status = i2c_start(obj);
-
- if ((status != 0x10) && (status != 0x08)) {
- i2c_stop(obj);
- return I2C_ERROR_BUS_BUSY;
- }
-
- status = i2c_do_write(obj, (address | 0x01), 1);
- if (status != 0x40) {
- i2c_stop(obj);
- return I2C_ERROR_NO_SLAVE;
- }
-
- // Read in all except last byte
- for (count = 0; count < (length - 1); count++) {
- int value = i2c_do_read(obj, 0);
- status = i2c_status(obj);
- if (status != 0x50) {
- i2c_stop(obj);
- return count;
- }
- data[count] = (char) value;
- }
-
- // read in last byte
- int value = i2c_do_read(obj, 1);
- status = i2c_status(obj);
- if (status != 0x58) {
- i2c_stop(obj);
- return length - 1;
- }
-
- data[count] = (char) value;
-
- // If not repeated start, send stop.
- if (stop) {
- i2c_stop(obj);
- }
-
- return length;
-}
-
-int i2c_write(i2c_t *obj, int address, const char *data, int length, int stop) {
- int i, status;
-
- status = i2c_start(obj);
-
- if ((status != 0x10) && (status != 0x08)) {
- i2c_stop(obj);
- return I2C_ERROR_BUS_BUSY;
- }
-
- status = i2c_do_write(obj, (address & 0xFE), 1);
- if (status != 0x18) {
- i2c_stop(obj);
- return I2C_ERROR_NO_SLAVE;
- }
-
- for (i=0; i= 0) && (idx <= 3)) {
- addr = ((uint32_t)obj->i2c) + I2C_addr_offset[0][idx];
- *((uint32_t *) addr) = address & 0xFF;
- }
-}
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/objects.h b/targets/TARGET_NXP/TARGET_LPC23XX/objects.h
deleted file mode 100644
index 41d717adc6..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/objects.h
+++ /dev/null
@@ -1,78 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2013 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-#ifndef MBED_OBJECTS_H
-#define MBED_OBJECTS_H
-
-#include "cmsis.h"
-#include "PortNames.h"
-#include "PeripheralNames.h"
-#include "PinNames.h"
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-struct gpio_irq_s {
- uint32_t port;
- uint32_t pin;
- uint32_t ch;
-};
-
-struct port_s {
- __IO uint32_t *reg_dir;
- __IO uint32_t *reg_out;
- __I uint32_t *reg_in;
- PortName port;
- uint32_t mask;
-};
-
-struct pwmout_s {
- __IO uint32_t *MR;
- PWMName pwm;
-};
-
-struct serial_s {
- LPC_UART_TypeDef *uart;
- int index;
-};
-
-struct analogin_s {
- ADCName adc;
-};
-
-struct dac_s {
- DACName dac;
-};
-
-struct can_s {
- LPC_CAN_TypeDef *dev;
-};
-
-struct i2c_s {
- LPC_I2C_TypeDef *i2c;
-};
-
-struct spi_s {
- LPC_SSP_TypeDef *spi;
-};
-
-#include "gpio_object.h"
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/pinmap.c b/targets/TARGET_NXP/TARGET_LPC23XX/pinmap.c
deleted file mode 100644
index 12636f5d69..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/pinmap.c
+++ /dev/null
@@ -1,46 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2013 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-#include "mbed_assert.h"
-#include "pinmap.h"
-#include "mbed_error.h"
-
-void pin_function(PinName pin, int function) {
- MBED_ASSERT(pin != (PinName)NC);
-
- uint32_t pin_number = (uint32_t)pin - (uint32_t)P0_0;
- int index = pin_number >> 4;
- int offset = (pin_number & 0xF) << 1;
-
- PINCONARRAY->PINSEL[index] &= ~(0x3 << offset);
- PINCONARRAY->PINSEL[index] |= function << offset;
-}
-
-void pin_mode(PinName pin, PinMode mode) {
- MBED_ASSERT((pin != (PinName)NC) && (mode != OpenDrain));
-
- uint32_t pin_number = (uint32_t)pin - (uint32_t)P0_0;
- int index = pin_number >> 5;
- int offset = pin_number & 0x1F;
- uint32_t drain = ((uint32_t) mode & (uint32_t) OpenDrain) >> 2;
-
- if (!drain) {
- index = pin_number >> 4;
- offset = (pin_number & 0xF) << 1;
-
- PINCONARRAY->PINMODE[index] &= ~(0x3 << offset);
- PINCONARRAY->PINMODE[index] |= (uint32_t)mode << offset;
- }
-}
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/port_api.c b/targets/TARGET_NXP/TARGET_LPC23XX/port_api.c
deleted file mode 100644
index 2a84a3ffc4..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/port_api.c
+++ /dev/null
@@ -1,71 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2013 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-#include "port_api.h"
-#include "pinmap.h"
-#include "gpio_api.h"
-
-PinName port_pin(PortName port, int pin_n) {
- return (PinName)(LPC_GPIO0_BASE + ((port << PORT_SHIFT) | pin_n));
-}
-
-void port_init(port_t *obj, PortName port, int mask, PinDirection dir) {
- obj->port = port;
- obj->mask = mask;
-
- LPC_GPIO_TypeDef *port_reg = (LPC_GPIO_TypeDef *)(LPC_GPIO0_BASE + ((int)port * 0x20));
-
- // Do not use masking, because it prevents the use of the unmasked pins
- // port_reg->FIOMASK = ~mask;
-
- obj->reg_out = &port_reg->FIOPIN;
- obj->reg_in = &port_reg->FIOPIN;
- obj->reg_dir = &port_reg->FIODIR;
-
- uint32_t i;
- // The function is set per pin: reuse gpio logic
- for (i=0; i<32; i++) {
- if (obj->mask & (1<port, i));
- }
- }
-
- port_dir(obj, dir);
-}
-
-void port_mode(port_t *obj, PinMode mode) {
- uint32_t i;
- // The mode is set per pin: reuse pinmap logic
- for (i=0; i<32; i++) {
- if (obj->mask & (1<port, i), mode);
- }
- }
-}
-
-void port_dir(port_t *obj, PinDirection dir) {
- switch (dir) {
- case PIN_INPUT : *obj->reg_dir &= ~obj->mask; break;
- case PIN_OUTPUT: *obj->reg_dir |= obj->mask; break;
- }
-}
-
-void port_write(port_t *obj, int value) {
- *obj->reg_out = (*obj->reg_in & ~obj->mask) | (value & obj->mask);
-}
-
-int port_read(port_t *obj) {
- return (*obj->reg_in & obj->mask);
-}
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/pwmout_api.c b/targets/TARGET_NXP/TARGET_LPC23XX/pwmout_api.c
deleted file mode 100644
index 3773d7e6b7..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/pwmout_api.c
+++ /dev/null
@@ -1,171 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2013 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-#include "mbed_assert.h"
-#include "pwmout_api.h"
-#include "cmsis.h"
-#include "pinmap.h"
-
-#define TCR_CNT_EN 0x00000001
-#define TCR_RESET 0x00000002
-
-// PORT ID, PWM ID, Pin function
-static const PinMap PinMap_PWM[] = {
- {P1_18, PWM_1, 2},
- {P1_20, PWM_2, 2},
- {P1_21, PWM_3, 2},
- {P1_23, PWM_4, 2},
- {P1_24, PWM_5, 2},
- {P1_26, PWM_6, 2},
- {P2_0 , PWM_1, 1},
- {P2_1 , PWM_2, 1},
- {P2_2 , PWM_3, 1},
- {P2_3 , PWM_4, 1},
- {P2_4 , PWM_5, 1},
- {P2_5 , PWM_6, 1},
- {P3_25, PWM_2, 3},
- {P3_26, PWM_3, 3},
- {NC, NC, 0}
-};
-
-__IO uint32_t *PWM_MATCH[] = {
- &(LPC_PWM1->MR0),
- &(LPC_PWM1->MR1),
- &(LPC_PWM1->MR2),
- &(LPC_PWM1->MR3),
- &(LPC_PWM1->MR4),
- &(LPC_PWM1->MR5),
- &(LPC_PWM1->MR6)
-};
-
-#define TCR_PWM_EN 0x00000008
-
-static unsigned int pwm_clock_mhz;
-
-void pwmout_init(pwmout_t* obj, PinName pin) {
- // determine the channel
- PWMName pwm = (PWMName)pinmap_peripheral(pin, PinMap_PWM);
- MBED_ASSERT(pwm != (PWMName)NC);
-
- obj->pwm = pwm;
- obj->MR = PWM_MATCH[pwm];
-
- // ensure the power is on
- LPC_SC->PCONP |= 1 << 6;
-
- // ensure clock to /4
- LPC_SC->PCLKSEL0 &= ~(0x3 << 12); // pclk = /4
- LPC_PWM1->PR = 0; // no pre-scale
-
- // ensure single PWM mode
- LPC_PWM1->MCR = 1 << 1; // reset TC on match 0
-
- // enable the specific PWM output
- LPC_PWM1->PCR |= 1 << (8 + pwm);
-
- pwm_clock_mhz = SystemCoreClock / 4000000;
-
- // default to 20ms: standard for servos, and fine for e.g. brightness control
- pwmout_period_ms(obj, 20);
- pwmout_write (obj, 0);
-
- // Wire pinout
- pinmap_pinout(pin, PinMap_PWM);
-}
-
-void pwmout_free(pwmout_t* obj) {
- // [TODO]
-}
-
-void pwmout_write(pwmout_t* obj, float value) {
- if (value < 0.0f) {
- value = 0.0;
- } else if (value > 1.0f) {
- value = 1.0;
- }
-
- // set channel match to percentage
- uint32_t v = (uint32_t)((float)(LPC_PWM1->MR0) * value);
-
- // workaround for PWM1[1] - Never make it equal MR0, else we get 1 cycle dropout
- if (v == LPC_PWM1->MR0) {
- v++;
- }
-
- *obj->MR = v;
-
- // accept on next period start
- LPC_PWM1->LER |= 1 << obj->pwm;
-}
-
-float pwmout_read(pwmout_t* obj) {
- float v = (float)(*obj->MR) / (float)(LPC_PWM1->MR0);
- return (v > 1.0f) ? (1.0f) : (v);
-}
-
-void pwmout_period(pwmout_t* obj, float seconds) {
- pwmout_period_us(obj, seconds * 1000000.0f);
-}
-
-void pwmout_period_ms(pwmout_t* obj, int ms) {
- pwmout_period_us(obj, ms * 1000);
-}
-
-// Set the PWM period, keeping the duty cycle the same.
-void pwmout_period_us(pwmout_t* obj, int us) {
- // calculate number of ticks
- uint32_t ticks = pwm_clock_mhz * us;
-
- // set reset
- LPC_PWM1->TCR = TCR_RESET;
-
- // set the global match register
- LPC_PWM1->MR0 = ticks;
-
- // Scale the pulse width to preserve the duty ratio
- if (LPC_PWM1->MR0 > 0) {
- *obj->MR = (*obj->MR * ticks) / LPC_PWM1->MR0;
- }
-
- // set the channel latch to update value at next period start
- LPC_PWM1->LER |= 1 << 0;
-
- // enable counter and pwm, clear reset
- LPC_PWM1->TCR = TCR_CNT_EN | TCR_PWM_EN;
-}
-
-void pwmout_pulsewidth(pwmout_t* obj, float seconds) {
- pwmout_pulsewidth_us(obj, seconds * 1000000.0f);
-}
-
-void pwmout_pulsewidth_ms(pwmout_t* obj, int ms) {
- pwmout_pulsewidth_us(obj, ms * 1000);
-}
-
-void pwmout_pulsewidth_us(pwmout_t* obj, int us) {
- // calculate number of ticks
- uint32_t v = pwm_clock_mhz * us;
-
- // workaround for PWM1[1] - Never make it equal MR0, else we get 1 cycle dropout
- if (v == LPC_PWM1->MR0) {
- v++;
- }
-
- // set the match register value
- *obj->MR = v;
-
- // set the channel latch to update value at next period start
- LPC_PWM1->LER |= 1 << obj->pwm;
-}
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/rtc_api.c b/targets/TARGET_NXP/TARGET_LPC23XX/rtc_api.c
deleted file mode 100644
index a4e7b96a61..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/rtc_api.c
+++ /dev/null
@@ -1,117 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2013 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-#include "rtc_api.h"
-
-// ensure rtc is running (unchanged if already running)
-
-/* Setup the RTC based on a time structure, ensuring RTC is enabled
- *
- * Can be clocked by a 32.768KHz oscillator or prescale divider based on the APB clock
- * - We want to use the 32khz clock, allowing for sleep mode
- *
- * Most registers are not changed by a Reset
- * - We must initialize these registers between power-on and setting the RTC into operation
-
- * Clock Control Register
- * RTC_CCR[0] : Enable - 0 = Disabled, 1 = Enabled
- * RTC_CCR[1] : Reset - 0 = Normal, 1 = Reset
- * RTC_CCR[4] : Clock Source - 0 = Prescaler, 1 = 32k Xtal
- *
- * The RTC may already be running, so we should set it up
- * without impacting if it is the case
- */
-void rtc_init(void) {
- LPC_SC->PCONP |= 0x200; // Ensure power is on
- LPC_RTC->CCR = 0x00;
-
- // clock source on 2368 is special test mode on 1768!
- LPC_RTC->CCR |= 1 << 4; // Ensure clock source is 32KHz Xtal
-
- LPC_RTC->CCR |= 1 << 0; // Ensure the RTC is enabled
-}
-
-void rtc_free(void) {
- // [TODO]
-}
-
-/*
- * Little check routine to see if the RTC has been enabled
- *
- * Clock Control Register
- * RTC_CCR[0] : 0 = Disabled, 1 = Enabled
- *
- */
-
-int rtc_isenabled(void) {
- return(((LPC_RTC->CCR) & 0x01) != 0);
-}
-
-/*
- * RTC Registers
- * RTC_SEC Seconds 0-59
- * RTC_MIN Minutes 0-59
- * RTC_HOUR Hour 0-23
- * RTC_DOM Day of Month 1-28..31
- * RTC_DOW Day of Week 0-6
- * RTC_DOY Day of Year 1-365
- * RTC_MONTH Month 1-12
- * RTC_YEAR Year 0-4095
- *
- * struct tm
- * tm_sec seconds after the minute 0-61
- * tm_min minutes after the hour 0-59
- * tm_hour hours since midnight 0-23
- * tm_mday day of the month 1-31
- * tm_mon months since January 0-11
- * tm_year years since 1900
- * tm_wday days since Sunday 0-6
- * tm_yday days since January 1 0-365
- * tm_isdst Daylight Saving Time flag
- */
-time_t rtc_read(void) {
- // Setup a tm structure based on the RTC
- struct tm timeinfo;
- timeinfo.tm_sec = LPC_RTC->SEC;
- timeinfo.tm_min = LPC_RTC->MIN;
- timeinfo.tm_hour = LPC_RTC->HOUR;
- timeinfo.tm_mday = LPC_RTC->DOM;
- timeinfo.tm_mon = LPC_RTC->MONTH - 1;
- timeinfo.tm_year = LPC_RTC->YEAR - 1900;
-
- // Convert to timestamp
- time_t t = mktime(&timeinfo);
-
- return t;
-}
-
-void rtc_write(time_t t) {
- // Convert the time in to a tm
- struct tm *timeinfo = localtime(&t);
-
- // Pause clock, and clear counter register (clears us count)
- LPC_RTC->CCR |= 2;
-
- // Set the RTC
- LPC_RTC->SEC = timeinfo->tm_sec;
- LPC_RTC->MIN = timeinfo->tm_min;
- LPC_RTC->HOUR = timeinfo->tm_hour;
- LPC_RTC->DOM = timeinfo->tm_mday;
- LPC_RTC->MONTH = timeinfo->tm_mon + 1;
- LPC_RTC->YEAR = timeinfo->tm_year + 1900;
-
- // Restart clock
- LPC_RTC->CCR &= ~((uint32_t)2);
-}
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/serial_api.c b/targets/TARGET_NXP/TARGET_LPC23XX/serial_api.c
deleted file mode 100644
index 12142ab59f..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/serial_api.c
+++ /dev/null
@@ -1,337 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2013 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-// math.h required for floating point operations for baud rate calculation
-#include "mbed_assert.h"
-#include
-#include
-#include
-
-#include "serial_api.h"
-#include "cmsis.h"
-#include "pinmap.h"
-
-/******************************************************************************
- * INITIALIZATION
- ******************************************************************************/
-#define UART_NUM 4
-
-static const PinMap PinMap_UART_TX[] = {
- {P0_0, UART_3, 2},
- {P0_2, UART_0, 1},
- {P0_10, UART_2, 1},
- {P0_15, UART_1, 1},
- {P0_25, UART_3, 3},
- {P2_0 , UART_1, 2},
- {P2_8 , UART_2, 2},
- {P4_28, UART_3, 3},
- {NC , NC , 0}
-};
-
-static const PinMap PinMap_UART_RX[] = {
- {P0_1 , UART_3, 2},
- {P0_3 , UART_0, 1},
- {P0_11, UART_2, 1},
- {P0_16, UART_1, 1},
- {P0_26, UART_3, 3},
- {P2_1 , UART_1, 2},
- {P2_9 , UART_2, 2},
- {P4_29, UART_3, 3},
- {NC , NC , 0}
-};
-
-static uint32_t serial_irq_ids[UART_NUM] = {0};
-static uart_irq_handler irq_handler;
-
-int stdio_uart_inited = 0;
-serial_t stdio_uart;
-
-void serial_init(serial_t *obj, PinName tx, PinName rx) {
- int is_stdio_uart = 0;
-
- // determine the UART to use
- UARTName uart_tx = (UARTName)pinmap_peripheral(tx, PinMap_UART_TX);
- UARTName uart_rx = (UARTName)pinmap_peripheral(rx, PinMap_UART_RX);
- UARTName uart = (UARTName)pinmap_merge(uart_tx, uart_rx);
- MBED_ASSERT((int)uart != NC);
-
- obj->uart = (LPC_UART_TypeDef *)uart;
- // enable power
- switch (uart) {
- case UART_0: LPC_SC->PCONP |= 1 << 3; break;
- case UART_1: LPC_SC->PCONP |= 1 << 4; break;
- case UART_2: LPC_SC->PCONP |= 1 << 24; break;
- case UART_3: LPC_SC->PCONP |= 1 << 25; break;
- }
-
- // enable fifos and default rx trigger level
- obj->uart->FCR = 1 << 0 // FIFO Enable - 0 = Disables, 1 = Enabled
- | 0 << 1 // Rx Fifo Reset
- | 0 << 2 // Tx Fifo Reset
- | 0 << 6; // Rx irq trigger level - 0 = 1 char, 1 = 4 chars, 2 = 8 chars, 3 = 14 chars
-
- // disable irqs
- obj->uart->IER = 0 << 0 // Rx Data available irq enable
- | 0 << 1 // Tx Fifo empty irq enable
- | 0 << 2; // Rx Line Status irq enable
-
- // set default baud rate and format
- serial_baud (obj, 9600);
- serial_format(obj, 8, ParityNone, 1);
-
- // pinout the chosen uart
- pinmap_pinout(tx, PinMap_UART_TX);
- pinmap_pinout(rx, PinMap_UART_RX);
-
- // set rx/tx pins in PullUp mode
- if (tx != NC) {
- pin_mode(tx, PullUp);
- }
- if (rx != NC) {
- pin_mode(rx, PullUp);
- }
-
- switch (uart) {
- case UART_0: obj->index = 0; break;
- case UART_1: obj->index = 1; break;
- case UART_2: obj->index = 2; break;
- case UART_3: obj->index = 3; break;
- }
-
- is_stdio_uart = (uart == STDIO_UART) ? (1) : (0);
-
- if (is_stdio_uart) {
- stdio_uart_inited = 1;
- memcpy(&stdio_uart, obj, sizeof(serial_t));
- }
-}
-
-void serial_free(serial_t *obj) {
- serial_irq_ids[obj->index] = 0;
-}
-
-// serial_baud
-// set the baud rate, taking in to account the current SystemFrequency
-void serial_baud(serial_t *obj, int baudrate) {
- MBED_ASSERT((int)obj->uart <= UART_3);
- // The LPC2300 and LPC1700 have a divider and a fractional divider to control the
- // baud rate. The formula is:
- //
- // Baudrate = (1 / PCLK) * 16 * DL * (1 + DivAddVal / MulVal)
- // where:
- // 1 < MulVal <= 15
- // 0 <= DivAddVal < 14
- // DivAddVal < MulVal
- //
- // set pclk to /1
- switch ((int)obj->uart) {
- case UART_0: LPC_SC->PCLKSEL0 &= ~(0x3 << 6); LPC_SC->PCLKSEL0 |= (0x1 << 6); break;
- case UART_1: LPC_SC->PCLKSEL0 &= ~(0x3 << 8); LPC_SC->PCLKSEL0 |= (0x1 << 8); break;
- case UART_2: LPC_SC->PCLKSEL1 &= ~(0x3 << 16); LPC_SC->PCLKSEL1 |= (0x1 << 16); break;
- case UART_3: LPC_SC->PCLKSEL1 &= ~(0x3 << 18); LPC_SC->PCLKSEL1 |= (0x1 << 18); break;
- default: break;
- }
-
- uint32_t PCLK = SystemCoreClock;
-
- // First we check to see if the basic divide with no DivAddVal/MulVal
- // ratio gives us an integer result. If it does, we set DivAddVal = 0,
- // MulVal = 1. Otherwise, we search the valid ratio value range to find
- // the closest match. This could be more elegant, using search methods
- // and/or lookup tables, but the brute force method is not that much
- // slower, and is more maintainable.
- uint16_t DL = PCLK / (16 * baudrate);
-
- uint8_t DivAddVal = 0;
- uint8_t MulVal = 1;
- int hit = 0;
- uint16_t dlv;
- uint8_t mv, dav;
- if ((PCLK % (16 * baudrate)) != 0) { // Checking for zero remainder
- int err_best = baudrate, b;
- for (mv = 1; mv < 16 && !hit; mv++)
- {
- for (dav = 0; dav < mv; dav++)
- {
- // baudrate = PCLK / (16 * dlv * (1 + (DivAdd / Mul))
- // solving for dlv, we get dlv = mul * PCLK / (16 * baudrate * (divadd + mul))
- // mul has 4 bits, PCLK has 27 so we have 1 bit headroom which can be used for rounding
- // for many values of mul and PCLK we have 2 or more bits of headroom which can be used to improve precision
- // note: X / 32 doesn't round correctly. Instead, we use ((X / 16) + 1) / 2 for correct rounding
-
- if ((mv * PCLK * 2) & 0x80000000) // 1 bit headroom
- dlv = ((((2 * mv * PCLK) / (baudrate * (dav + mv))) / 16) + 1) / 2;
- else // 2 bits headroom, use more precision
- dlv = ((((4 * mv * PCLK) / (baudrate * (dav + mv))) / 32) + 1) / 2;
-
- // datasheet says if DLL==DLM==0, then 1 is used instead since divide by zero is ungood
- if (dlv == 0)
- dlv = 1;
-
- // datasheet says if dav > 0 then DL must be >= 2
- if ((dav > 0) && (dlv < 2))
- dlv = 2;
-
- // integer rearrangement of the baudrate equation (with rounding)
- b = ((PCLK * mv / (dlv * (dav + mv) * 8)) + 1) / 2;
-
- // check to see how we went
- b = abs(b - baudrate);
- if (b < err_best)
- {
- err_best = b;
-
- DL = dlv;
- MulVal = mv;
- DivAddVal = dav;
-
- if (b == baudrate)
- {
- hit = 1;
- break;
- }
- }
- }
- }
- }
-
- // set LCR[DLAB] to enable writing to divider registers
- obj->uart->LCR |= (1 << 7);
-
- // set divider values
- obj->uart->DLM = (DL >> 8) & 0xFF;
- obj->uart->DLL = (DL >> 0) & 0xFF;
- obj->uart->FDR = (uint32_t) DivAddVal << 0
- | (uint32_t) MulVal << 4;
-
- // clear LCR[DLAB]
- obj->uart->LCR &= ~(1 << 7);
-}
-
-void serial_format(serial_t *obj, int data_bits, SerialParity parity, int stop_bits) {
- MBED_ASSERT((stop_bits == 1) || (stop_bits == 2)); // 0: 1 stop bits, 1: 2 stop bits
- MBED_ASSERT((data_bits > 4) && (data_bits < 9)); // 0: 5 data bits ... 3: 8 data bits
- MBED_ASSERT((parity == ParityNone) || (parity == ParityOdd) || (parity == ParityEven) ||
- (parity == ParityForced1) || (parity == ParityForced0));
-
- stop_bits -= 1;
- data_bits -= 5;
-
- int parity_enable = 0, parity_select = 0;
- switch (parity) {
- case ParityNone: parity_enable = 0; parity_select = 0; break;
- case ParityOdd : parity_enable = 1; parity_select = 0; break;
- case ParityEven: parity_enable = 1; parity_select = 1; break;
- case ParityForced1: parity_enable = 1; parity_select = 2; break;
- case ParityForced0: parity_enable = 1; parity_select = 3; break;
- default:
- break;
- }
-
- obj->uart->LCR = data_bits << 0
- | stop_bits << 2
- | parity_enable << 3
- | parity_select << 4;
-}
-
-/******************************************************************************
- * INTERRUPTS HANDLING
- ******************************************************************************/
-static inline void uart_irq(uint32_t iir, uint32_t index) {
- // [Chapter 14] LPC17xx UART0/2/3: UARTn Interrupt Handling
- SerialIrq irq_type;
- switch (iir) {
- case 1: irq_type = TxIrq; break;
- case 2: irq_type = RxIrq; break;
- default: return;
- }
-
- if (serial_irq_ids[index] != 0)
- irq_handler(serial_irq_ids[index], irq_type);
-}
-
-void uart0_irq() {uart_irq((LPC_UART0->IIR >> 1) & 0x7, 0);}
-void uart1_irq() {uart_irq((LPC_UART1->IIR >> 1) & 0x7, 1);}
-void uart2_irq() {uart_irq((LPC_UART2->IIR >> 1) & 0x7, 2);}
-void uart3_irq() {uart_irq((LPC_UART3->IIR >> 1) & 0x7, 3);}
-
-void serial_irq_handler(serial_t *obj, uart_irq_handler handler, uint32_t id) {
- irq_handler = handler;
- serial_irq_ids[obj->index] = id;
-}
-
-void serial_irq_set(serial_t *obj, SerialIrq irq, uint32_t enable) {
- IRQn_Type irq_n = (IRQn_Type)0;
- uint32_t vector = 0;
- switch ((int)obj->uart) {
- case UART_0: irq_n=UART0_IRQn; vector = (uint32_t)&uart0_irq; break;
- case UART_1: irq_n=UART1_IRQn; vector = (uint32_t)&uart1_irq; break;
- case UART_2: irq_n=UART2_IRQn; vector = (uint32_t)&uart2_irq; break;
- case UART_3: irq_n=UART3_IRQn; vector = (uint32_t)&uart3_irq; break;
- }
-
- if (enable) {
- obj->uart->IER |= 1 << irq;
- NVIC_SetVector(irq_n, vector);
- NVIC_EnableIRQ(irq_n);
- } else { // disable
- int all_disabled = 0;
- SerialIrq other_irq = (irq == RxIrq) ? (TxIrq) : (RxIrq);
- obj->uart->IER &= ~(1 << irq);
- all_disabled = (obj->uart->IER & (1 << other_irq)) == 0;
- if (all_disabled)
- NVIC_DisableIRQ(irq_n);
- }
-}
-
-/******************************************************************************
- * READ/WRITE
- ******************************************************************************/
-int serial_getc(serial_t *obj) {
- while (!serial_readable(obj));
- return obj->uart->RBR;
-}
-
-void serial_putc(serial_t *obj, int c) {
- while (!serial_writable(obj));
- obj->uart->THR = c;
-}
-
-int serial_readable(serial_t *obj) {
- return obj->uart->LSR & 0x01;
-}
-
-int serial_writable(serial_t *obj) {
- return obj->uart->LSR & 0x20;
-}
-
-void serial_clear(serial_t *obj) {
- obj->uart->FCR = 1 << 1 // rx FIFO reset
- | 1 << 2 // tx FIFO reset
- | 0 << 6; // interrupt depth
-}
-
-void serial_pinout_tx(PinName tx) {
- pinmap_pinout(tx, PinMap_UART_TX);
-}
-
-void serial_break_set(serial_t *obj) {
- obj->uart->LCR |= (1 << 6);
-}
-
-void serial_break_clear(serial_t *obj) {
- obj->uart->LCR &= ~(1 << 6);
-}
-
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/spi_api.c b/targets/TARGET_NXP/TARGET_LPC23XX/spi_api.c
deleted file mode 100644
index 7768e11046..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/spi_api.c
+++ /dev/null
@@ -1,208 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2013 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-#include "mbed_assert.h"
-#include
-
-#include "spi_api.h"
-#include "cmsis.h"
-#include "pinmap.h"
-#include "mbed_error.h"
-
-static const PinMap PinMap_SPI_SCLK[] = {
- {P0_7 , SPI_1, 2},
- {P0_15, SPI_0, 2},
- {P1_20, SPI_0, 3},
- {P1_31, SPI_1, 2},
- {NC , NC , 0}
-};
-
-static const PinMap PinMap_SPI_MOSI[] = {
- {P0_9 , SPI_1, 2},
- {P0_13, SPI_1, 2},
- {P0_18, SPI_0, 2},
- {P1_24, SPI_0, 3},
- {NC , NC , 0}
-};
-
-static const PinMap PinMap_SPI_MISO[] = {
- {P0_8 , SPI_1, 2},
- {P0_12, SPI_1, 2},
- {P0_17, SPI_0, 2},
- {P1_23, SPI_0, 3},
- {NC , NC , 0}
-};
-
-static const PinMap PinMap_SPI_SSEL[] = {
- {P0_6 , SPI_1, 2},
- {P0_11, SPI_1, 2},
- {P0_16, SPI_0, 2},
- {P1_21, SPI_0, 3},
- {NC , NC , 0}
-};
-
-static inline int ssp_disable(spi_t *obj);
-static inline int ssp_enable(spi_t *obj);
-
-void spi_init(spi_t *obj, PinName mosi, PinName miso, PinName sclk, PinName ssel) {
- // determine the SPI to use
- SPIName spi_mosi = (SPIName)pinmap_peripheral(mosi, PinMap_SPI_MOSI);
- SPIName spi_miso = (SPIName)pinmap_peripheral(miso, PinMap_SPI_MISO);
- SPIName spi_sclk = (SPIName)pinmap_peripheral(sclk, PinMap_SPI_SCLK);
- SPIName spi_ssel = (SPIName)pinmap_peripheral(ssel, PinMap_SPI_SSEL);
- SPIName spi_data = (SPIName)pinmap_merge(spi_mosi, spi_miso);
- SPIName spi_cntl = (SPIName)pinmap_merge(spi_sclk, spi_ssel);
- obj->spi = (LPC_SSP_TypeDef*)pinmap_merge(spi_data, spi_cntl);
- MBED_ASSERT((int)obj->spi != NC);
-
- // enable power and clocking
- switch ((int)obj->spi) {
- case SPI_0: LPC_SC->PCONP |= 1 << 21; break;
- case SPI_1: LPC_SC->PCONP |= 1 << 10; break;
- }
-
- // pin out the spi pins
- pinmap_pinout(mosi, PinMap_SPI_MOSI);
- pinmap_pinout(miso, PinMap_SPI_MISO);
- pinmap_pinout(sclk, PinMap_SPI_SCLK);
- if (ssel != NC) {
- pinmap_pinout(ssel, PinMap_SPI_SSEL);
- }
-}
-
-void spi_free(spi_t *obj) {}
-
-void spi_format(spi_t *obj, int bits, int mode, int slave) {
- MBED_ASSERT(((bits >= 4) && (bits <= 16)) && ((mode >= 0) && (mode <= 3)));
- ssp_disable(obj);
-
- int polarity = (mode & 0x2) ? 1 : 0;
- int phase = (mode & 0x1) ? 1 : 0;
-
- // set it up
- int DSS = bits - 1; // DSS (data select size)
- int SPO = (polarity) ? 1 : 0; // SPO - clock out polarity
- int SPH = (phase) ? 1 : 0; // SPH - clock out phase
-
- int FRF = 0; // FRF (frame format) = SPI
- uint32_t tmp = obj->spi->CR0;
- tmp &= ~(0xFFFF);
- tmp |= DSS << 0
- | FRF << 4
- | SPO << 6
- | SPH << 7;
- obj->spi->CR0 = tmp;
-
- tmp = obj->spi->CR1;
- tmp &= ~(0xD);
- tmp |= 0 << 0 // LBM - loop back mode - off
- | ((slave) ? 1 : 0) << 2 // MS - master slave mode, 1 = slave
- | 0 << 3; // SOD - slave output disable - na
- obj->spi->CR1 = tmp;
-
- ssp_enable(obj);
-}
-
-void spi_frequency(spi_t *obj, int hz) {
- ssp_disable(obj);
-
- // setup the spi clock diveder to /1
- switch ((int)obj->spi) {
- case SPI_0:
- LPC_SC->PCLKSEL1 &= ~(3 << 10);
- LPC_SC->PCLKSEL1 |= (1 << 10);
- break;
- case SPI_1:
- LPC_SC->PCLKSEL0 &= ~(3 << 20);
- LPC_SC->PCLKSEL0 |= (1 << 20);
- break;
- }
-
- uint32_t PCLK = SystemCoreClock;
-
- int prescaler;
-
- for (prescaler = 2; prescaler <= 254; prescaler += 2) {
- int prescale_hz = PCLK / prescaler;
-
- // calculate the divider
- int divider = floor(((float)prescale_hz / (float)hz) + 0.5f);
-
- // check we can support the divider
- if (divider < 256) {
- // prescaler
- obj->spi->CPSR = prescaler;
-
- // divider
- obj->spi->CR0 &= ~(0xFFFF << 8);
- obj->spi->CR0 |= (divider - 1) << 8;
- ssp_enable(obj);
- return;
- }
- }
- error("Couldn't setup requested SPI frequency");
-}
-
-static inline int ssp_disable(spi_t *obj) {
- return obj->spi->CR1 &= ~(1 << 1);
-}
-
-static inline int ssp_enable(spi_t *obj) {
- return obj->spi->CR1 |= (1 << 1);
-}
-
-static inline int ssp_readable(spi_t *obj) {
- return obj->spi->SR & (1 << 2);
-}
-
-static inline int ssp_writeable(spi_t *obj) {
- return obj->spi->SR & (1 << 1);
-}
-
-static inline void ssp_write(spi_t *obj, int value) {
- while (!ssp_writeable(obj));
- obj->spi->DR = value;
-}
-
-static inline int ssp_read(spi_t *obj) {
- while (!ssp_readable(obj));
- return obj->spi->DR;
-}
-
-static inline int ssp_busy(spi_t *obj) {
- return (obj->spi->SR & (1 << 4)) ? (1) : (0);
-}
-
-int spi_master_write(spi_t *obj, int value) {
- ssp_write(obj, value);
- return ssp_read(obj);
-}
-
-int spi_slave_receive(spi_t *obj) {
- return (ssp_readable(obj) && !ssp_busy(obj)) ? (1) : (0);
-}
-
-int spi_slave_read(spi_t *obj) {
- return obj->spi->DR;
-}
-
-void spi_slave_write(spi_t *obj, int value) {
- while (ssp_writeable(obj) == 0) ;
- obj->spi->DR = value;
-}
-
-int spi_busy(spi_t *obj) {
- return ssp_busy(obj);
-}
diff --git a/targets/TARGET_NXP/TARGET_LPC23XX/us_ticker.c b/targets/TARGET_NXP/TARGET_LPC23XX/us_ticker.c
deleted file mode 100644
index b46d75e6bc..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC23XX/us_ticker.c
+++ /dev/null
@@ -1,64 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2013 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-#include
-#include "us_ticker_api.h"
-#include "PeripheralNames.h"
-
-#define US_TICKER_TIMER ((LPC_TIM_TypeDef *)LPC_TIM3_BASE)
-#define US_TICKER_TIMER_IRQn TIMER3_IRQn
-
-int us_ticker_inited = 0;
-
-void us_ticker_init(void) {
- if (us_ticker_inited) return;
- us_ticker_inited = 1;
-
- LPC_SC->PCONP |= 1 << 23; // Clock TIMER_3
-
- US_TICKER_TIMER->CTCR = 0x0; // timer mode
- uint32_t PCLK = SystemCoreClock / 4;
-
- US_TICKER_TIMER->TCR = 0x2; // reset
-
- uint32_t prescale = PCLK / 1000000; // default to 1MHz (1 us ticks)
- US_TICKER_TIMER->PR = prescale - 1;
- US_TICKER_TIMER->TCR = 1; // enable = 1, reset = 0
-
- NVIC_SetVector(US_TICKER_TIMER_IRQn, (uint32_t)us_ticker_irq_handler);
- NVIC_EnableIRQ(US_TICKER_TIMER_IRQn);
-}
-
-uint32_t us_ticker_read() {
- if (!us_ticker_inited)
- us_ticker_init();
-
- return US_TICKER_TIMER->TC;
-}
-
-void us_ticker_set_interrupt(timestamp_t timestamp) {
- // set match value
- US_TICKER_TIMER->MR0 = (uint32_t)timestamp;
- // enable match interrupt
- US_TICKER_TIMER->MCR |= 1;
-}
-
-void us_ticker_disable_interrupt(void) {
- US_TICKER_TIMER->MCR &= ~1;
-}
-
-void us_ticker_clear_interrupt(void) {
- US_TICKER_TIMER->IR = 1;
-}
diff --git a/targets/TARGET_NXP/TARGET_LPC2460/PeripheralNames.h b/targets/TARGET_NXP/TARGET_LPC2460/PeripheralNames.h
deleted file mode 100644
index 653aa9ea7c..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC2460/PeripheralNames.h
+++ /dev/null
@@ -1,120 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2015 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-#ifndef MBED_PERIPHERALNAMES_H
-#define MBED_PERIPHERALNAMES_H
-
-#include "cmsis.h"
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-typedef enum {
- UART_0 = (int)LPC_UART0_BASE,
- UART_1 = (int)LPC_UART1_BASE,
- UART_2 = (int)LPC_UART2_BASE,
- UART_3 = (int)LPC_UART3_BASE
-} UARTName;
-
-typedef enum {
- ADC0_0 = 0,
- ADC0_1,
- ADC0_2,
- ADC0_3,
- ADC0_4,
- ADC0_5,
- ADC0_6,
- ADC0_7
-} ADCName;
-
-typedef enum {
- DAC_0 = 0
-} DACName;
-
-typedef enum {
- SPI_0 = (int)LPC_SSP0_BASE,
- SPI_1 = (int)LPC_SSP1_BASE
-} SPIName;
-
-typedef enum {
- I2C_0 = (int)LPC_I2C0_BASE,
- I2C_1 = (int)LPC_I2C1_BASE,
- I2C_2 = (int)LPC_I2C2_BASE
-} I2CName;
-
-typedef enum {
- PWM_1 = 1,
- PWM_2,
- PWM_3,
- PWM_4,
- PWM_5,
- PWM_6
-} PWMName;
-
-typedef enum {
- CAN_1 = (int)LPC_CAN1_BASE,
- CAN_2 = (int)LPC_CAN2_BASE
-} CANName;
-
-#define STDIO_UART_TX USBTX
-#define STDIO_UART_RX USBRX
-#define STDIO_UART UART_2
-
-// Default peripherals
-#define MBED_SPI0 p5, p6, p7, p8
-//#define MBED_SPI1 p11, p12, p13, p14
-
-#define MBED_UART0 p9, p10
-#define MBED_UART1 p13, p14
-#define MBED_UART2 p15, p16
-#define MBED_UARTUSB USBTX, USBRX
-
-#define MBED_I2C0 p17, p18
-//#define MBED_I2C1 p9, p10
-
-#define MBED_CAN0 p19, p20
-
-#define MBED_ANALOGOUT0 p21
-
-#define MBED_ANALOGIN0 p22
-#define MBED_ANALOGIN1 p23
-//#define MBED_ANALOGIN2 p17
-//#define MBED_ANALOGIN3 p18
-//#define MBED_ANALOGIN4 p19
-//#define MBED_ANALOGIN5 p20
-
-#define MBED_PWMOUT0 p24
-#define MBED_PWMOUT1 p25
-#define MBED_PWMOUT2 p26
-#define MBED_PWMOUT3 p27
-//#define MBED_PWMOUT4 p22
-//#define MBED_PWMOUT5 p21
-
-#define MBED_USB_D_PLUS p28
-#define MBED_USB_D_MINUS p29
-
-#define MBED_MCICLK p30
-#define MBED_MCICMD p31
-#define MBED_MCIDAT0 p32
-#define MBED_MCIDAT1 p33
-#define MBED_MCIDAT2 p34
-#define MBED_MCIDAT3 p35
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif
diff --git a/targets/TARGET_NXP/TARGET_LPC2460/PinNames.h b/targets/TARGET_NXP/TARGET_LPC2460/PinNames.h
deleted file mode 100644
index 9527912197..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC2460/PinNames.h
+++ /dev/null
@@ -1,112 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2015 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-
-#ifndef MBED_PINNAMES_H
-#define MBED_PINNAMES_H
-
-#include "cmsis.h"
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-typedef enum {
- PIN_INPUT,
- PIN_OUTPUT
-} PinDirection;
-
-#define PORT_SHIFT 5
-
-typedef enum {
- // LPC Pin Names
- P0_0 = LPC_GPIO0_BASE,
- P0_1, P0_2, P0_3, P0_4, P0_5, P0_6, P0_7, P0_8, P0_9, P0_10, P0_11, P0_12, P0_13, P0_14, P0_15, P0_16, P0_17, P0_18, P0_19, P0_20, P0_21, P0_22, P0_23, P0_24, P0_25, P0_26, P0_27, P0_28, P0_29, P0_30, P0_31,
- P1_0, P1_1, P1_2, P1_3, P1_4, P1_5, P1_6, P1_7, P1_8, P1_9, P1_10, P1_11, P1_12, P1_13, P1_14, P1_15, P1_16, P1_17, P1_18, P1_19, P1_20, P1_21, P1_22, P1_23, P1_24, P1_25, P1_26, P1_27, P1_28, P1_29, P1_30, P1_31,
- P2_0, P2_1, P2_2, P2_3, P2_4, P2_5, P2_6, P2_7, P2_8, P2_9, P2_10, P2_11, P2_12, P2_13, P2_14, P2_15, P2_16, P2_17, P2_18, P2_19, P2_20, P2_21, P2_22, P2_23, P2_24, P2_25, P2_26, P2_27, P2_28, P2_29, P2_30, P2_31,
- P3_0, P3_1, P3_2, P3_3, P3_4, P3_5, P3_6, P3_7, P3_8, P3_9, P3_10, P3_11, P3_12, P3_13, P3_14, P3_15, P3_16, P3_17, P3_18, P3_19, P3_20, P3_21, P3_22, P3_23, P3_24, P3_25, P3_26, P3_27, P3_28, P3_29, P3_30, P3_31,
- P4_0, P4_1, P4_2, P4_3, P4_4, P4_5, P4_6, P4_7, P4_8, P4_9, P4_10, P4_11, P4_12, P4_13, P4_14, P4_15, P4_16, P4_17, P4_18, P4_19, P4_20, P4_21, P4_22, P4_23, P4_24, P4_25, P4_26, P4_27, P4_28, P4_29, P4_30, P4_31,
-
- // mbed DIP Pin Names
- p5 = P0_18,
- p6 = P0_17,
- p7 = P0_15,
- p8 = P0_16,
-
- p9 = P0_2,
- p10 = P0_3,
- p11 = P0_18,
- p12 = P0_17,
- p13 = P2_0,
- p14 = P2_1,
- p15 = P4_28,
- p16 = P4_29,
- p17 = P2_30,
- p18 = P2_31,
- p19 = P0_0,
- p20 = P0_1,
- p21 = P0_26,
- p22 = P0_12,
- p23 = P0_13,
- p24 = P1_20,
- p25 = P1_21,
- p26 = P1_23,
- p27 = P1_24,
- p28 = P0_29,
- p29 = P0_30,
- p30 = P1_2,
- p31 = P1_3,
- p32 = P1_6,
- p33 = P1_7,
- p34 = P1_11,
- p35 = P1_12,
-
- // Other mbed Pin Names
- LED1 = P1_19,
- LED2 = P2_26,
- LED3 = P2_27,
- LED4 = P2_27,
-
- USBTX = P2_8,
- USBRX = P2_9,
-
- EXT_WDT = P0_10,
-
- // Not connected
- NC = (int)0xFFFFFFFF
-} PinName;
-
-typedef enum {
- PullUp = 0,
- PullDown = 3,
- PullNone = 2,
- OpenDrain = 4,
- PullDefault = PullDown
-} PinMode;
-
-// version of PINCON_TypeDef using register arrays
-typedef struct {
- __IO uint32_t PINSEL[11];
- uint32_t RESERVED0[5];
- __IO uint32_t PINMODE[10];
-} PINCONARRAY_TypeDef;
-
-#define PINCONARRAY ((PINCONARRAY_TypeDef *)LPC_PINCON_BASE)
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif
diff --git a/targets/TARGET_NXP/TARGET_LPC2460/PortNames.h b/targets/TARGET_NXP/TARGET_LPC2460/PortNames.h
deleted file mode 100644
index c17e9de12e..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC2460/PortNames.h
+++ /dev/null
@@ -1,38 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2015 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-#ifndef MBED_PORTNAMES_H
-#define MBED_PORTNAMES_H
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-typedef enum {
- Port0 = 0,
- Port1 = 1,
- Port2 = 2,
- Port3 = 3,
- Port4 = 4
-} PortName;
-
-#define PORT_0 Port0
-#define PORT_1 Port1
-#define PORT_2 Port2
-#define PORT_3 Port3
-#ifdef __cplusplus
-}
-#endif
-#endif
diff --git a/targets/TARGET_NXP/TARGET_LPC2460/analogin_api.c b/targets/TARGET_NXP/TARGET_LPC2460/analogin_api.c
deleted file mode 100644
index 6293c3f5a4..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC2460/analogin_api.c
+++ /dev/null
@@ -1,125 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2015 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-#include "mbed_assert.h"
-#include "analogin_api.h"
-#include "cmsis.h"
-#include "pinmap.h"
-
-#define ANALOGIN_MEDIAN_FILTER 1
-
-#define ADC_10BIT_RANGE 0x3FF
-#define ADC_12BIT_RANGE 0xFFF
-
-static inline int div_round_up(int x, int y) {
- return (x + (y - 1)) / y;
-}
-
-static const PinMap PinMap_ADC[] = {
- {P0_23, ADC0_0, 1},
- {P0_24, ADC0_1, 1},
- {P0_25, ADC0_2, 1},
- {P0_26, ADC0_3, 1},
- {P1_30, ADC0_4, 3},
- {P1_31, ADC0_5, 3},
- {P0_12, ADC0_6, 3},
- {P0_13, ADC0_7, 3},
- {NC, NC, 0}
-};
-
-#define ADC_RANGE ADC_10BIT_RANGE
-
-
-void analogin_init(analogin_t *obj, PinName pin) {
- obj->adc = (ADCName)pinmap_peripheral(pin, PinMap_ADC);
- MBED_ASSERT(obj->adc != (ADCName)NC);
-
- // ensure power is turned on
- LPC_SC->PCONP |= (1 << PCADC);
-
- // set PCLK of ADC to /1
- LPC_SC->PCLKSEL0 &= ~(0x3 << 24);
- LPC_SC->PCLKSEL0 |= (0x1 << 24);
- uint32_t PCLK = SystemCoreClock;
-
- // calculate minimum clock divider
- // clkdiv = divider - 1
- uint32_t MAX_ADC_CLK = 4500000;
- uint32_t clkdiv = div_round_up(PCLK, MAX_ADC_CLK) - 1;
-
- // Set the generic software-controlled ADC settings
- LPC_ADC->ADCR = (0 << 0) // SEL: 0 = no channels selected
- | (clkdiv << 8) // CLKDIV: PCLK max ~= 25MHz, /25 to give safe 1MHz at fastest
- | (0 << 16) // BURST: 0 = software control
- | (0 << 17) // CLKS: not applicable
- | (1 << 21) // PDN: 1 = operational
- | (0 << 24) // START: 0 = no start
- | (0 << 27); // EDGE: not applicable
-
- pinmap_pinout(pin, PinMap_ADC);
-}
-
-static inline uint32_t adc_read(analogin_t *obj) {
- // Select the appropriate channel and start conversion
- LPC_ADC->ADCR &= ~0xFF;
- LPC_ADC->ADCR |= 1 << (int)obj->adc;
- LPC_ADC->ADCR |= 1 << 24;
-
- // Repeatedly get the sample data until DONE bit
- unsigned int data;
- do {
- data = LPC_ADC->ADGDR;
- } while ((data & ((unsigned int)1 << 31)) == 0);
-
- // Stop conversion
- LPC_ADC->ADCR &= ~(1 << 24);
-
- return (data >> 6) & ADC_RANGE; // 10 bit
-}
-
-static inline void order(uint32_t *a, uint32_t *b) {
- if (*a > *b) {
- uint32_t t = *a;
- *a = *b;
- *b = t;
- }
-}
-
-static inline uint32_t adc_read_u32(analogin_t *obj) {
- uint32_t value;
-#if ANALOGIN_MEDIAN_FILTER
- uint32_t v1 = adc_read(obj);
- uint32_t v2 = adc_read(obj);
- uint32_t v3 = adc_read(obj);
- order(&v1, &v2);
- order(&v2, &v3);
- order(&v1, &v2);
- value = v2;
-#else
- value = adc_read(obj);
-#endif
- return value;
-}
-
-uint16_t analogin_read_u16(analogin_t *obj) {
- uint32_t value = adc_read_u32(obj);
-
- return (value << 6) | ((value >> 4) & 0x003F); // 10 bit
-}
-
-float analogin_read(analogin_t *obj) {
- uint32_t value = adc_read_u32(obj);
- return (float)value * (1.0f / (float)ADC_RANGE);
-}
diff --git a/targets/TARGET_NXP/TARGET_LPC2460/analogout_api.c b/targets/TARGET_NXP/TARGET_LPC2460/analogout_api.c
deleted file mode 100644
index 2a6194d059..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC2460/analogout_api.c
+++ /dev/null
@@ -1,75 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2015 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-#include "mbed_assert.h"
-#include "analogout_api.h"
-#include "cmsis.h"
-#include "pinmap.h"
-
-static const PinMap PinMap_DAC[] = {
- {P0_26, DAC_0, 2},
- {NC , NC , 0}
-};
-
-void analogout_init(dac_t *obj, PinName pin) {
- obj->dac = (DACName)pinmap_peripheral(pin, PinMap_DAC);
- MBED_ASSERT(obj->dac != (DACName)NC);
-
- // power is on by default, set DAC clk divider is /4
- LPC_SC->PCLKSEL0 &= ~(0x3 << 22);
-
- // map out (must be done before accessing registers)
- pinmap_pinout(pin, PinMap_DAC);
-
- analogout_write_u16(obj, 0);
-}
-
-void analogout_free(dac_t *obj) {}
-
-static inline void dac_write(int value) {
- value &= 0x3FF; // 10-bit
-
- // Set the DAC output
- LPC_DAC->DACR = (0 << 16) // bias = 0
- | (value << 6);
-}
-
-static inline int dac_read() {
- return (LPC_DAC->DACR >> 6) & 0x3FF;
-}
-
-void analogout_write(dac_t *obj, float value) {
- if (value < 0.0f) {
- dac_write(0);
- } else if (value > 1.0f) {
- dac_write(0x3FF);
- } else {
- dac_write(value * (float)0x3FF);
- }
-}
-
-void analogout_write_u16(dac_t *obj, uint16_t value) {
- dac_write(value >> 6); // 10-bit
-}
-
-float analogout_read(dac_t *obj) {
- uint32_t value = dac_read();
- return (float)value * (1.0f / (float)0x3FF);
-}
-
-uint16_t analogout_read_u16(dac_t *obj) {
- uint32_t value = dac_read(); // 10-bit
- return (value << 6) | ((value >> 4) & 0x003F);
-}
diff --git a/targets/TARGET_NXP/TARGET_LPC2460/can_api.c b/targets/TARGET_NXP/TARGET_LPC2460/can_api.c
deleted file mode 100644
index 5107615f78..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC2460/can_api.c
+++ /dev/null
@@ -1,303 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2015 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-#include "mbed_assert.h"
-#include "can_api.h"
-#include "cmsis.h"
-#include "pinmap.h"
-
-#include
-#include
-
-/* Acceptance filter mode in AFMR register */
-#define ACCF_OFF 0x01
-#define ACCF_BYPASS 0x02
-#define ACCF_ON 0x00
-#define ACCF_FULLCAN 0x04
-
-/* There are several bit timing calculators on the internet.
-http://www.port.de/engl/canprod/sv_req_form.html
-http://www.kvaser.com/can/index.htm
-*/
-
-static const PinMap PinMap_CAN_RD[] = {
- {P0_0 , CAN_1, 1},
- {P0_4 , CAN_2, 2},
- {P0_21, CAN_1, 3},
- {P2_7 , CAN_2, 1},
- {NC , NC , 0}
-};
-
-static const PinMap PinMap_CAN_TD[] = {
- {P0_1 , CAN_1, 1},
- {P0_5 , CAN_2, 2},
- {P0_22, CAN_1, 3},
- {P2_8 , CAN_2, 1},
- {NC , NC , 0}
-};
-
-// Type definition to hold a CAN message
-struct CANMsg {
- unsigned int reserved1 : 16;
- unsigned int dlc : 4; // Bits 16..19: DLC - Data Length Counter
- unsigned int reserved0 : 10;
- unsigned int rtr : 1; // Bit 30: Set if this is a RTR message
- unsigned int type : 1; // Bit 31: Set if this is a 29-bit ID message
- unsigned int id; // CAN Message ID (11-bit or 29-bit)
- unsigned char data[8]; // CAN Message Data Bytes 0-7
-};
-typedef struct CANMsg CANMsg;
-
-static uint32_t can_disable(can_t *obj) {
- uint32_t sm = obj->dev->MOD;
- obj->dev->MOD |= 1;
- return sm;
-}
-
-static inline void can_enable(can_t *obj) {
- if (obj->dev->MOD & 1) {
- obj->dev->MOD &= ~(1);
- }
-}
-
-int can_mode(can_t *obj, CanMode mode) {
- return 0; // not implemented
-}
-
-int can_filter(can_t *obj, uint32_t id, uint32_t mask, CANFormat format, int32_t handle) {
- return 0; // not implemented
-}
-
-static int can_pclk(can_t *obj) {
- int value = 0;
- switch ((int)obj->dev) {
- case CAN_1: value = (LPC_SC->PCLKSEL0 & (0x3 << 26)) >> 26; break;
- case CAN_2: value = (LPC_SC->PCLKSEL0 & (0x3 << 28)) >> 28; break;
- }
-
- switch (value) {
- case 1: return 1;
- case 2: return 2;
- case 3: return 6;
- default: return 4;
- }
-}
-
-// This table has the sampling points as close to 75% as possible. The first
-// value is TSEG1, the second TSEG2.
-static const int timing_pts[23][2] = {
- {0x0, 0x0}, // 2, 50%
- {0x1, 0x0}, // 3, 67%
- {0x2, 0x0}, // 4, 75%
- {0x3, 0x0}, // 5, 80%
- {0x3, 0x1}, // 6, 67%
- {0x4, 0x1}, // 7, 71%
- {0x5, 0x1}, // 8, 75%
- {0x6, 0x1}, // 9, 78%
- {0x6, 0x2}, // 10, 70%
- {0x7, 0x2}, // 11, 73%
- {0x8, 0x2}, // 12, 75%
- {0x9, 0x2}, // 13, 77%
- {0x9, 0x3}, // 14, 71%
- {0xA, 0x3}, // 15, 73%
- {0xB, 0x3}, // 16, 75%
- {0xC, 0x3}, // 17, 76%
- {0xD, 0x3}, // 18, 78%
- {0xD, 0x4}, // 19, 74%
- {0xE, 0x4}, // 20, 75%
- {0xF, 0x4}, // 21, 76%
- {0xF, 0x5}, // 22, 73%
- {0xF, 0x6}, // 23, 70%
- {0xF, 0x7}, // 24, 67%
-};
-
-static unsigned int can_speed(unsigned int sclk, unsigned int pclk, unsigned int cclk, unsigned char psjw) {
- uint32_t btr;
- uint16_t brp = 0;
- uint32_t calcbit;
- uint32_t bitwidth;
- int hit = 0;
- int bits;
-
- bitwidth = sclk / (pclk * cclk);
-
- brp = bitwidth / 0x18;
- while ((!hit) && (brp < bitwidth / 4)) {
- brp++;
- for (bits = 22; bits > 0; bits--) {
- calcbit = (bits + 3) * (brp + 1);
- if (calcbit == bitwidth) {
- hit = 1;
- break;
- }
- }
- }
-
- if (hit) {
- btr = ((timing_pts[bits][1] << 20) & 0x00700000)
- | ((timing_pts[bits][0] << 16) & 0x000F0000)
- | ((psjw << 14) & 0x0000C000)
- | ((brp << 0) & 0x000003FF);
- } else {
- btr = 0xFFFFFFFF;
- }
-
- return btr;
-}
-
-void can_init(can_t *obj, PinName rd, PinName td) {
- CANName can_rd = (CANName)pinmap_peripheral(rd, PinMap_CAN_RD);
- CANName can_td = (CANName)pinmap_peripheral(td, PinMap_CAN_TD);
- obj->dev = (LPC_CAN_TypeDef *)pinmap_merge(can_rd, can_td);
- MBED_ASSERT((int)obj->dev != NC);
-
- switch ((int)obj->dev) {
- case CAN_1: LPC_SC->PCONP |= 1 << PCAN1; break;
- case CAN_2: LPC_SC->PCONP |= 1 << PCAN2; break;
- }
-
- pinmap_pinout(rd, PinMap_CAN_RD);
- pinmap_pinout(td, PinMap_CAN_TD);
-
- can_reset(obj);
- obj->dev->IER = 0; // Disable Interrupts
- can_frequency(obj, 100000);
-
- LPC_CANAF->AFMR = ACCF_BYPASS; // Bypass Filter
-}
-
-void can_free(can_t *obj) {
- switch ((int)obj->dev) {
- case CAN_1: LPC_SC->PCONP &= ~(1 << PCAN1); break;
- case CAN_2: LPC_SC->PCONP &= ~(1 << PCAN2); break;
- }
-}
-
-int can_frequency(can_t *obj, int f) {
- int pclk = can_pclk(obj);
- int btr = can_speed(SystemCoreClock, pclk, (unsigned int)f, 1);
-
- if (btr > 0) {
- uint32_t modmask = can_disable(obj);
- obj->dev->BTR = btr;
- obj->dev->MOD = modmask;
- return 1;
- } else {
- return 0;
- }
-}
-
-int can_write(can_t *obj, CAN_Message msg, int cc) {
- unsigned int CANStatus;
- CANMsg m;
-
- can_enable(obj);
-
- m.id = msg.id ;
- m.dlc = msg.len & 0xF;
- m.rtr = msg.type;
- m.type = msg.format;
- memcpy(m.data, msg.data, msg.len);
- const unsigned int *buf = (const unsigned int *)&m;
-
- CANStatus = obj->dev->SR;
- if (CANStatus & 0x00000004) {
- obj->dev->TFI1 = buf[0] & 0xC00F0000;
- obj->dev->TID1 = buf[1];
- obj->dev->TDA1 = buf[2];
- obj->dev->TDB1 = buf[3];
- if (cc) {
- obj->dev->CMR = 0x30;
- } else {
- obj->dev->CMR = 0x21;
- }
- return 1;
-
- } else if (CANStatus & 0x00000400) {
- obj->dev->TFI2 = buf[0] & 0xC00F0000;
- obj->dev->TID2 = buf[1];
- obj->dev->TDA2 = buf[2];
- obj->dev->TDB2 = buf[3];
- if (cc) {
- obj->dev->CMR = 0x50;
- } else {
- obj->dev->CMR = 0x41;
- }
- return 1;
-
- } else if (CANStatus & 0x00040000) {
- obj->dev->TFI3 = buf[0] & 0xC00F0000;
- obj->dev->TID3 = buf[1];
- obj->dev->TDA3 = buf[2];
- obj->dev->TDB3 = buf[3];
- if (cc) {
- obj->dev->CMR = 0x90;
- } else {
- obj->dev->CMR = 0x81;
- }
- return 1;
- }
-
- return 0;
-}
-
-int can_read(can_t *obj, CAN_Message *msg, int handle) {
- CANMsg x;
- unsigned int *i = (unsigned int *)&x;
-
- can_enable(obj);
-
- if (obj->dev->GSR & 0x1) {
- *i++ = obj->dev->RFS; // Frame
- *i++ = obj->dev->RID; // ID
- *i++ = obj->dev->RDA; // Data A
- *i++ = obj->dev->RDB; // Data B
- obj->dev->CMR = 0x04; // release receive buffer
-
- msg->id = x.id;
- msg->len = x.dlc;
- msg->format = (x.type)? CANExtended : CANStandard;
- msg->type = (x.rtr)? CANRemote: CANData;
- memcpy(msg->data,x.data,x.dlc);
- return 1;
- }
-
- return 0;
-}
-
-void can_reset(can_t *obj) {
- can_disable(obj);
- obj->dev->GSR = 0; // Reset error counter when CAN1MOD is in reset
-}
-
-unsigned char can_rderror(can_t *obj) {
- return (obj->dev->GSR >> 16) & 0xFF;
-}
-
-unsigned char can_tderror(can_t *obj) {
- return (obj->dev->GSR >> 24) & 0xFF;
-}
-
-void can_monitor(can_t *obj, int silent) {
- uint32_t mod_mask = can_disable(obj);
- if (silent) {
- obj->dev->MOD |= (1 << 1);
- } else {
- obj->dev->MOD &= ~(1 << 1);
- }
- if (!(mod_mask & 1)) {
- can_enable(obj);
- }
-}
diff --git a/targets/TARGET_NXP/TARGET_LPC2460/device.h b/targets/TARGET_NXP/TARGET_LPC2460/device.h
deleted file mode 100644
index 71deacc111..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC2460/device.h
+++ /dev/null
@@ -1,40 +0,0 @@
-// The 'features' section in 'target.json' is now used to create the device's hardware preprocessor switches.
-// Check the 'features' section of the target description in 'targets.json' for more details.
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2015 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-#ifndef MBED_DEVICE_H
-#define MBED_DEVICE_H
-
-
-
-
-
-
-
-
-
-
-
-#define DEVICE_ID_LENGTH 32
-#define DEVICE_MAC_OFFSET 20
-
-
-
-
-
-#include "objects.h"
-
-#endif
diff --git a/targets/TARGET_NXP/TARGET_LPC2460/device/LPC24xx.h b/targets/TARGET_NXP/TARGET_LPC2460/device/LPC24xx.h
deleted file mode 100644
index e73f0b17ff..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC2460/device/LPC24xx.h
+++ /dev/null
@@ -1,972 +0,0 @@
-/* mbed Microcontroller Library - LPC24xx CMSIS-like structs
- * Copyright (C) 2009-2015 ARM Limited. All rights reserved.
- *
- * An LPC24xx header file, based on LPC23xx.h
- */
-
-#ifndef __LPC24xx_H
-#define __LPC24xx_H
-
-#ifdef __cplusplus
- extern "C" {
-#endif
-
-/*
- * ==========================================================================
- * ---------- Interrupt Number Definition -----------------------------------
- * ==========================================================================
- */
-
-typedef enum IRQn
-{
-/****** LPC23xx Specific Interrupt Numbers *******************************************************/
- WDT_IRQn = 0, /*!< Watchdog Timer Interrupt */
-
- TIMER0_IRQn = 4, /*!< Timer0 Interrupt */
- TIMER1_IRQn = 5, /*!< Timer1 Interrupt */
- UART0_IRQn = 6, /*!< UART0 Interrupt */
- UART1_IRQn = 7, /*!< UART1 Interrupt */
- PWM0_IRQn = 8, /*!< PWM0 Interrupt */
- PWM1_IRQn = 8, /*!< PWM1 Interrupt */
- I2C0_IRQn = 9, /*!< I2C0 Interrupt */
- SPI_IRQn = 10, /*!< SPI Interrupt */
- SSP0_IRQn = 10, /*!< SSP0 Interrupt */
- SSP1_IRQn = 11, /*!< SSP1 Interrupt */
- PLL0_IRQn = 12, /*!< PLL0 Lock (Main PLL) Interrupt */
- RTC_IRQn = 13, /*!< Real Time Clock Interrupt */
- EINT0_IRQn = 14, /*!< External Interrupt 0 Interrupt */
- EINT1_IRQn = 15, /*!< External Interrupt 1 Interrupt */
- EINT2_IRQn = 16, /*!< External Interrupt 2 Interrupt */
- EINT3_IRQn = 17, /*!< External Interrupt 3 Interrupt */
- ADC_IRQn = 18, /*!< A/D Converter Interrupt */
- I2C1_IRQn = 19, /*!< I2C1 Interrupt */
- BOD_IRQn = 20, /*!< Brown-Out Detect Interrupt */
- ENET_IRQn = 21, /*!< Ethernet Interrupt */
- USB_IRQn = 22, /*!< USB Interrupt */
- CAN_IRQn = 23, /*!< CAN Interrupt */
- SDMMC_IRQn = 24, /*!< SD/MMC Interrupt */
- DMA_IRQn = 25, /*!< General Purpose DMA Interrupt */
- TIMER2_IRQn = 26, /*!< Timer2 Interrupt */
- TIMER3_IRQn = 27, /*!< Timer3 Interrupt */
- UART2_IRQn = 28, /*!< UART2 Interrupt */
- UART3_IRQn = 29, /*!< UART3 Interrupt */
- I2C2_IRQn = 30, /*!< I2C2 Interrupt */
- I2S_IRQn = 31, /*!< I2S Interrupt */
-} IRQn_Type;
-
-/*
- * ==========================================================================
- * ----------- Processor and Core Peripheral Section ------------------------
- * ==========================================================================
- */
-
-/* Configuration of the ARM7 Processor and Core Peripherals */
-#define __MPU_PRESENT 0 /*!< MPU present or not */
-#define __NVIC_PRIO_BITS 4 /*!< Number of Bits used for Priority Levels */
-#define __Vendor_SysTickConfig 0 /*!< Set to 1 if different SysTick Config is used */
-
-
-#include
-#include "system_LPC24xx.h" /* System Header */
-
-
-/******************************************************************************/
-/* Device Specific Peripheral registers structures */
-/******************************************************************************/
-#if defined ( __CC_ARM )
- #pragma anon_unions
-#endif
-
-/*------------- Vector Interupt Controler (VIC) ------------------------------*/
-typedef struct
-{
- __I uint32_t IRQStatus;
- __I uint32_t FIQStatus;
- __I uint32_t RawIntr;
- __IO uint32_t IntSelect;
- __IO uint32_t IntEnable;
- __O uint32_t IntEnClr;
- __IO uint32_t SoftInt;
- __O uint32_t SoftIntClr;
- __IO uint32_t Protection;
- __IO uint32_t SWPriorityMask;
- __IO uint32_t RESERVED0[54];
- __IO uint32_t VectAddr[32];
- __IO uint32_t RESERVED1[32];
- __IO uint32_t VectPriority[32];
- __IO uint32_t RESERVED2[800];
- __IO uint32_t Address;
-} LPC_VIC_TypeDef;
-
-/*------------- System Control (SC) ------------------------------------------*/
-typedef struct
-{
- __IO uint32_t MAMCR;
- __IO uint32_t MAMTIM;
- uint32_t RESERVED0[14];
- __IO uint32_t MEMMAP;
- uint32_t RESERVED1[15];
- __IO uint32_t PLL0CON; /* Clocking and Power Control */
- __IO uint32_t PLL0CFG;
- __I uint32_t PLL0STAT;
- __O uint32_t PLL0FEED;
- uint32_t RESERVED2[12];
- __IO uint32_t PCON;
- __IO uint32_t PCONP;
- uint32_t RESERVED3[15];
- __IO uint32_t CCLKCFG;
- __IO uint32_t USBCLKCFG;
- __IO uint32_t CLKSRCSEL;
- uint32_t RESERVED4[12];
- __IO uint32_t EXTINT; /* External Interrupts */
- __IO uint32_t INTWAKE;
- __IO uint32_t EXTMODE;
- __IO uint32_t EXTPOLAR;
- uint32_t RESERVED6[12];
- __IO uint32_t RSID; /* Reset */
- __IO uint32_t CSPR;
- __IO uint32_t AHBCFG1;
- __IO uint32_t AHBCFG2;
- uint32_t RESERVED7[4];
- __IO uint32_t SCS; /* Syscon Miscellaneous Registers */
- __IO uint32_t IRCTRIM; /* Clock Dividers */
- __IO uint32_t PCLKSEL0;
- __IO uint32_t PCLKSEL1;
- uint32_t RESERVED8[4];
- __IO uint32_t USBIntSt; /* USB Device/OTG Interrupt Register */
- uint32_t RESERVED9;
-// __IO uint32_t CLKOUTCFG; /* Clock Output Configuration */
- } LPC_SC_TypeDef;
-
-/*------------- Pin Connect Block (PINCON) -----------------------------------*/
-typedef struct
-{
- __IO uint32_t PINSEL0;
- __IO uint32_t PINSEL1;
- __IO uint32_t PINSEL2;
- __IO uint32_t PINSEL3;
- __IO uint32_t PINSEL4;
- __IO uint32_t PINSEL5;
- __IO uint32_t PINSEL6;
- __IO uint32_t PINSEL7;
- __IO uint32_t PINSEL8;
- __IO uint32_t PINSEL9;
- __IO uint32_t PINSEL10;
- uint32_t RESERVED0[5];
- __IO uint32_t PINMODE0;
- __IO uint32_t PINMODE1;
- __IO uint32_t PINMODE2;
- __IO uint32_t PINMODE3;
- __IO uint32_t PINMODE4;
- __IO uint32_t PINMODE5;
- __IO uint32_t PINMODE6;
- __IO uint32_t PINMODE7;
- __IO uint32_t PINMODE8;
- __IO uint32_t PINMODE9;
- __IO uint32_t PINMODE_OD0;
- __IO uint32_t PINMODE_OD1;
- __IO uint32_t PINMODE_OD2;
- __IO uint32_t PINMODE_OD3;
- __IO uint32_t PINMODE_OD4;
-} LPC_PINCON_TypeDef;
-
-#define PCTIM0 1
-#define PCTIM1 2
-#define PCUART0 3
-#define PCUART1 4
-#define PCPWM1 6
-#define PCI2C0 7
-#define PCSPI 8
-#define PCRTC 9
-#define PCSSP1 10
-#define PCEMC 11
-#define PCADC 12
-#define PCAN1 13
-#define PCAN2 14
-#define PCI2C1 19
-#define PCSSP0 21
-#define PCTIM2 22
-#define PCTIM3 23
-#define PCUART2 24
-#define PCUART3 25
-#define PCI2C2 26
-#define PCI2S 27
-#define PCSDC 28
-#define PCGPDMA 29
-#define PCENET 30
-#define PCUSB 31
-
-/*------------- General Purpose Input/Output (GPIO) --------------------------*/
-typedef struct
-{
- __IO uint32_t FIODIR;
- uint32_t RESERVED0[3];
- __IO uint32_t FIOMASK;
- __IO uint32_t FIOPIN;
- __IO uint32_t FIOSET;
- __O uint32_t FIOCLR;
-} LPC_GPIO_TypeDef;
-
-typedef struct
-{
- __I uint32_t IntStatus;
- __I uint32_t IO0IntStatR;
- __I uint32_t IO0IntStatF;
- __O uint32_t IO0IntClr;
- __IO uint32_t IO0IntEnR;
- __IO uint32_t IO0IntEnF;
- uint32_t RESERVED0[3];
- __I uint32_t IO2IntStatR;
- __I uint32_t IO2IntStatF;
- __O uint32_t IO2IntClr;
- __IO uint32_t IO2IntEnR;
- __IO uint32_t IO2IntEnF;
-} LPC_GPIOINT_TypeDef;
-
-/*------------- Timer (TIM) --------------------------------------------------*/
-typedef struct
-{
- __IO uint32_t IR;
- __IO uint32_t TCR;
- __IO uint32_t TC;
- __IO uint32_t PR;
- __IO uint32_t PC;
- __IO uint32_t MCR;
- __IO uint32_t MR0;
- __IO uint32_t MR1;
- __IO uint32_t MR2;
- __IO uint32_t MR3;
- __IO uint32_t CCR;
- __I uint32_t CR0;
- __I uint32_t CR1;
- uint32_t RESERVED0[2];
- __IO uint32_t EMR;
- uint32_t RESERVED1[12];
- __IO uint32_t CTCR;
-} LPC_TIM_TypeDef;
-
-/*------------- Pulse-Width Modulation (PWM) ---------------------------------*/
-typedef struct
-{
- __IO uint32_t IR;
- __IO uint32_t TCR;
- __IO uint32_t TC;
- __IO uint32_t PR;
- __IO uint32_t PC;
- __IO uint32_t MCR;
- __IO uint32_t MR0;
- __IO uint32_t MR1;
- __IO uint32_t MR2;
- __IO uint32_t MR3;
- __IO uint32_t CCR;
- __I uint32_t CR0;
- __I uint32_t CR1;
- __I uint32_t CR2;
- __I uint32_t CR3;
- uint32_t RESERVED0;
- __IO uint32_t MR4;
- __IO uint32_t MR5;
- __IO uint32_t MR6;
- __IO uint32_t PCR;
- __IO uint32_t LER;
- uint32_t RESERVED1[7];
- __IO uint32_t CTCR;
-} LPC_PWM_TypeDef;
-
-/*------------- Universal Asynchronous Receiver Transmitter (UART) -----------*/
-typedef struct
-{
- union {
- __I uint8_t RBR;
- __O uint8_t THR;
- __IO uint8_t DLL;
- uint32_t RESERVED0;
- };
- union {
- __IO uint8_t DLM;
- __IO uint32_t IER;
- };
- union {
- __I uint32_t IIR;
- __O uint8_t FCR;
- };
- __IO uint8_t LCR;
- uint8_t RESERVED1[7];
- __IO uint8_t LSR;
- uint8_t RESERVED2[7];
- __IO uint8_t SCR;
- uint8_t RESERVED3[3];
- __IO uint32_t ACR;
- __IO uint8_t ICR;
- uint8_t RESERVED4[3];
- __IO uint8_t FDR;
- uint8_t RESERVED5[7];
- __IO uint8_t TER;
- uint8_t RESERVED6[27];
- __IO uint8_t RS485CTRL;
- uint8_t RESERVED7[3];
- __IO uint8_t ADRMATCH;
-} LPC_UART_TypeDef;
-
-typedef struct
-{
- union {
- __I uint8_t RBR;
- __O uint8_t THR;
- __IO uint8_t DLL;
- uint32_t RESERVED0;
- };
- union {
- __IO uint8_t DLM;
- __IO uint32_t IER;
- };
- union {
- __I uint32_t IIR;
- __O uint8_t FCR;
- };
- __IO uint8_t LCR;
- uint8_t RESERVED1[3];
- __IO uint8_t MCR;
- uint8_t RESERVED2[3];
- __IO uint8_t LSR;
- uint8_t RESERVED3[3];
- __IO uint8_t MSR;
- uint8_t RESERVED4[3];
- __IO uint8_t SCR;
- uint8_t RESERVED5[3];
- __IO uint32_t ACR;
- uint32_t RESERVED6;
- __IO uint32_t FDR;
- uint32_t RESERVED7;
- __IO uint8_t TER;
- uint8_t RESERVED8[27];
- __IO uint8_t RS485CTRL;
- uint8_t RESERVED9[3];
- __IO uint8_t ADRMATCH;
- uint8_t RESERVED10[3];
- __IO uint8_t RS485DLY;
-} LPC_UART1_TypeDef;
-
-/*------------- Serial Peripheral Interface (SPI) ----------------------------*/
-typedef struct
-{
- __IO uint32_t SPCR;
- __I uint32_t SPSR;
- __IO uint32_t SPDR;
- __IO uint32_t SPCCR;
- uint32_t RESERVED0[3];
- __IO uint32_t SPINT;
-} LPC_SPI_TypeDef;
-
-/*------------- Synchronous Serial Communication (SSP) -----------------------*/
-typedef struct
-{
- __IO uint32_t CR0;
- __IO uint32_t CR1;
- __IO uint32_t DR;
- __I uint32_t SR;
- __IO uint32_t CPSR;
- __IO uint32_t IMSC;
- __IO uint32_t RIS;
- __IO uint32_t MIS;
- __IO uint32_t ICR;
- __IO uint32_t DMACR;
-} LPC_SSP_TypeDef;
-
-/*------------- Inter-Integrated Circuit (I2C) -------------------------------*/
-typedef struct
-{
- __IO uint32_t I2CONSET;
- __I uint32_t I2STAT;
- __IO uint32_t I2DAT;
- __IO uint32_t I2ADR0;
- __IO uint32_t I2SCLH;
- __IO uint32_t I2SCLL;
- __O uint32_t I2CONCLR;
- __IO uint32_t MMCTRL;
- __IO uint32_t I2ADR1;
- __IO uint32_t I2ADR2;
- __IO uint32_t I2ADR3;
- __I uint32_t I2DATA_BUFFER;
- __IO uint32_t I2MASK0;
- __IO uint32_t I2MASK1;
- __IO uint32_t I2MASK2;
- __IO uint32_t I2MASK3;
-} LPC_I2C_TypeDef;
-
-/*------------- Inter IC Sound (I2S) -----------------------------------------*/
-typedef struct
-{
- __IO uint32_t I2SDAO;
- __I uint32_t I2SDAI;
- __O uint32_t I2STXFIFO;
- __I uint32_t I2SRXFIFO;
- __I uint32_t I2SSTATE;
- __IO uint32_t I2SDMA1;
- __IO uint32_t I2SDMA2;
- __IO uint32_t I2SIRQ;
- __IO uint32_t I2STXRATE;
- __IO uint32_t I2SRXRATE;
- __IO uint32_t I2STXBITRATE;
- __IO uint32_t I2SRXBITRATE;
- __IO uint32_t I2STXMODE;
- __IO uint32_t I2SRXMODE;
-} LPC_I2S_TypeDef;
-
-/*------------- Real-Time Clock (RTC) ----------------------------------------*/
-typedef struct
-{
- __IO uint8_t ILR;
- uint8_t RESERVED0[3];
- __IO uint8_t CTC;
- uint8_t RESERVED1[3];
- __IO uint8_t CCR;
- uint8_t RESERVED2[3];
- __IO uint8_t CIIR;
- uint8_t RESERVED3[3];
- __IO uint8_t AMR;
- uint8_t RESERVED4[3];
- __I uint32_t CTIME0;
- __I uint32_t CTIME1;
- __I uint32_t CTIME2;
- __IO uint8_t SEC;
- uint8_t RESERVED5[3];
- __IO uint8_t MIN;
- uint8_t RESERVED6[3];
- __IO uint8_t HOUR;
- uint8_t RESERVED7[3];
- __IO uint8_t DOM;
- uint8_t RESERVED8[3];
- __IO uint8_t DOW;
- uint8_t RESERVED9[3];
- __IO uint16_t DOY;
- uint16_t RESERVED10;
- __IO uint8_t MONTH;
- uint8_t RESERVED11[3];
- __IO uint16_t YEAR;
- uint16_t RESERVED12;
- __IO uint32_t CALIBRATION;
- __IO uint32_t GPREG0;
- __IO uint32_t GPREG1;
- __IO uint32_t GPREG2;
- __IO uint32_t GPREG3;
- __IO uint32_t GPREG4;
- __IO uint8_t WAKEUPDIS;
- uint8_t RESERVED13[3];
- __IO uint8_t PWRCTRL;
- uint8_t RESERVED14[3];
- __IO uint8_t ALSEC;
- uint8_t RESERVED15[3];
- __IO uint8_t ALMIN;
- uint8_t RESERVED16[3];
- __IO uint8_t ALHOUR;
- uint8_t RESERVED17[3];
- __IO uint8_t ALDOM;
- uint8_t RESERVED18[3];
- __IO uint8_t ALDOW;
- uint8_t RESERVED19[3];
- __IO uint16_t ALDOY;
- uint16_t RESERVED20;
- __IO uint8_t ALMON;
- uint8_t RESERVED21[3];
- __IO uint16_t ALYEAR;
- uint16_t RESERVED22;
-} LPC_RTC_TypeDef;
-
-/*------------- Watchdog Timer (WDT) -----------------------------------------*/
-typedef struct
-{
- __IO uint8_t WDMOD;
- uint8_t RESERVED0[3];
- __IO uint32_t WDTC;
- __O uint8_t WDFEED;
- uint8_t RESERVED1[3];
- __I uint32_t WDTV;
- __IO uint32_t WDCLKSEL;
-} LPC_WDT_TypeDef;
-
-/*------------- Analog-to-Digital Converter (ADC) ----------------------------*/
-typedef struct
-{
- __IO uint32_t ADCR;
- __IO uint32_t ADGDR;
- uint32_t RESERVED0;
- __IO uint32_t ADINTEN;
- __I uint32_t ADDR0;
- __I uint32_t ADDR1;
- __I uint32_t ADDR2;
- __I uint32_t ADDR3;
- __I uint32_t ADDR4;
- __I uint32_t ADDR5;
- __I uint32_t ADDR6;
- __I uint32_t ADDR7;
- __I uint32_t ADSTAT;
- __IO uint32_t ADTRM;
-} LPC_ADC_TypeDef;
-
-/*------------- Digital-to-Analog Converter (DAC) ----------------------------*/
-typedef struct
-{
- __IO uint32_t DACR;
- __IO uint32_t DACCTRL;
- __IO uint16_t DACCNTVAL;
-} LPC_DAC_TypeDef;
-
-/*------------- Multimedia Card Interface (MCI) ------------------------------*/
-typedef struct
-{
- __IO uint32_t MCIPower; /* Power control */
- __IO uint32_t MCIClock; /* Clock control */
- __IO uint32_t MCIArgument;
- __IO uint32_t MMCCommand;
- __I uint32_t MCIRespCmd;
- __I uint32_t MCIResponse0;
- __I uint32_t MCIResponse1;
- __I uint32_t MCIResponse2;
- __I uint32_t MCIResponse3;
- __IO uint32_t MCIDataTimer;
- __IO uint32_t MCIDataLength;
- __IO uint32_t MCIDataCtrl;
- __I uint32_t MCIDataCnt;
- __I uint32_t MCIStatus;
- __O uint32_t MCIClear;
- __IO uint32_t MCIMask0;
- uint32_t RESERVED1[2];
- __I uint32_t MCIFifoCnt;
- uint32_t RESERVED2[13];
- __IO uint32_t MCIFIFO[16];
-} LPC_MCI_TypeDef;
-
-/*------------- Controller Area Network (CAN) --------------------------------*/
-typedef struct
-{
- __IO uint32_t mask[512]; /* ID Masks */
-} LPC_CANAF_RAM_TypeDef;
-
-typedef struct /* Acceptance Filter Registers */
-{
- __IO uint32_t AFMR;
- __IO uint32_t SFF_sa;
- __IO uint32_t SFF_GRP_sa;
- __IO uint32_t EFF_sa;
- __IO uint32_t EFF_GRP_sa;
- __IO uint32_t ENDofTable;
- __I uint32_t LUTerrAd;
- __I uint32_t LUTerr;
- __IO uint32_t FCANIE;
- __IO uint32_t FCANIC0;
- __IO uint32_t FCANIC1;
-} LPC_CANAF_TypeDef;
-
-typedef struct /* Central Registers */
-{
- __I uint32_t CANTxSR;
- __I uint32_t CANRxSR;
- __I uint32_t CANMSR;
-} LPC_CANCR_TypeDef;
-
-typedef struct /* Controller Registers */
-{
- __IO uint32_t MOD;
- __O uint32_t CMR;
- __IO uint32_t GSR;
- __I uint32_t ICR;
- __IO uint32_t IER;
- __IO uint32_t BTR;
- __IO uint32_t EWL;
- __I uint32_t SR;
- __IO uint32_t RFS;
- __IO uint32_t RID;
- __IO uint32_t RDA;
- __IO uint32_t RDB;
- __IO uint32_t TFI1;
- __IO uint32_t TID1;
- __IO uint32_t TDA1;
- __IO uint32_t TDB1;
- __IO uint32_t TFI2;
- __IO uint32_t TID2;
- __IO uint32_t TDA2;
- __IO uint32_t TDB2;
- __IO uint32_t TFI3;
- __IO uint32_t TID3;
- __IO uint32_t TDA3;
- __IO uint32_t TDB3;
-} LPC_CAN_TypeDef;
-
-/*------------- General Purpose Direct Memory Access (GPDMA) -----------------*/
-typedef struct /* Common Registers */
-{
- __I uint32_t DMACIntStat;
- __I uint32_t DMACIntTCStat;
- __O uint32_t DMACIntTCClear;
- __I uint32_t DMACIntErrStat;
- __O uint32_t DMACIntErrClr;
- __I uint32_t DMACRawIntTCStat;
- __I uint32_t DMACRawIntErrStat;
- __I uint32_t DMACEnbldChns;
- __IO uint32_t DMACSoftBReq;
- __IO uint32_t DMACSoftSReq;
- __IO uint32_t DMACSoftLBReq;
- __IO uint32_t DMACSoftLSReq;
- __IO uint32_t DMACConfig;
- __IO uint32_t DMACSync;
-} LPC_GPDMA_TypeDef;
-
-typedef struct /* Channel Registers */
-{
- __IO uint32_t DMACCSrcAddr;
- __IO uint32_t DMACCDestAddr;
- __IO uint32_t DMACCLLI;
- __IO uint32_t DMACCControl;
- __IO uint32_t DMACCConfig;
-} LPC_GPDMACH_TypeDef;
-
-/*------------- Universal Serial Bus (USB) -----------------------------------*/
-typedef struct
-{
- __I uint32_t HcRevision; /* USB Host Registers */
- __IO uint32_t HcControl;
- __IO uint32_t HcCommandStatus;
- __IO uint32_t HcInterruptStatus;
- __IO uint32_t HcInterruptEnable;
- __IO uint32_t HcInterruptDisable;
- __IO uint32_t HcHCCA;
- __I uint32_t HcPeriodCurrentED;
- __IO uint32_t HcControlHeadED;
- __IO uint32_t HcControlCurrentED;
- __IO uint32_t HcBulkHeadED;
- __IO uint32_t HcBulkCurrentED;
- __I uint32_t HcDoneHead;
- __IO uint32_t HcFmInterval;
- __I uint32_t HcFmRemaining;
- __I uint32_t HcFmNumber;
- __IO uint32_t HcPeriodicStart;
- __IO uint32_t HcLSTreshold;
- __IO uint32_t HcRhDescriptorA;
- __IO uint32_t HcRhDescriptorB;
- __IO uint32_t HcRhStatus;
- __IO uint32_t HcRhPortStatus1;
- __IO uint32_t HcRhPortStatus2;
- uint32_t RESERVED0[40];
- __I uint32_t Module_ID;
-
- __I uint32_t OTGIntSt; /* USB On-The-Go Registers */
- __IO uint32_t OTGIntEn;
- __O uint32_t OTGIntSet;
- __O uint32_t OTGIntClr;
- __IO uint32_t OTGStCtrl;
- __IO uint32_t OTGTmr;
- uint32_t RESERVED1[58];
-
- __I uint32_t USBDevIntSt; /* USB Device Interrupt Registers */
- __IO uint32_t USBDevIntEn;
- __O uint32_t USBDevIntClr;
- __O uint32_t USBDevIntSet;
-
- __O uint32_t USBCmdCode; /* USB Device SIE Command Registers */
- __I uint32_t USBCmdData;
-
- __I uint32_t USBRxData; /* USB Device Transfer Registers */
- __O uint32_t USBTxData;
- __I uint32_t USBRxPLen;
- __O uint32_t USBTxPLen;
- __IO uint32_t USBCtrl;
- __O uint32_t USBDevIntPri;
-
- __I uint32_t USBEpIntSt; /* USB Device Endpoint Interrupt Regs */
- __IO uint32_t USBEpIntEn;
- __O uint32_t USBEpIntClr;
- __O uint32_t USBEpIntSet;
- __O uint32_t USBEpIntPri;
-
- __IO uint32_t USBReEp; /* USB Device Endpoint Realization Reg*/
- __O uint32_t USBEpInd;
- __IO uint32_t USBMaxPSize;
-
- __I uint32_t USBDMARSt; /* USB Device DMA Registers */
- __O uint32_t USBDMARClr;
- __O uint32_t USBDMARSet;
- uint32_t RESERVED2[9];
- __IO uint32_t USBUDCAH;
- __I uint32_t USBEpDMASt;
- __O uint32_t USBEpDMAEn;
- __O uint32_t USBEpDMADis;
- __I uint32_t USBDMAIntSt;
- __IO uint32_t USBDMAIntEn;
- uint32_t RESERVED3[2];
- __I uint32_t USBEoTIntSt;
- __O uint32_t USBEoTIntClr;
- __O uint32_t USBEoTIntSet;
- __I uint32_t USBNDDRIntSt;
- __O uint32_t USBNDDRIntClr;
- __O uint32_t USBNDDRIntSet;
- __I uint32_t USBSysErrIntSt;
- __O uint32_t USBSysErrIntClr;
- __O uint32_t USBSysErrIntSet;
- uint32_t RESERVED4[15];
-
- __I uint32_t I2C_RX; /* USB OTG I2C Registers */
- __O uint32_t I2C_WO;
- __I uint32_t I2C_STS;
- __IO uint32_t I2C_CTL;
- __IO uint32_t I2C_CLKHI;
- __O uint32_t I2C_CLKLO;
- uint32_t RESERVED5[823];
-
- union {
- __IO uint32_t USBClkCtrl; /* USB Clock Control Registers */
- __IO uint32_t OTGClkCtrl;
- };
- union {
- __I uint32_t USBClkSt;
- __I uint32_t OTGClkSt;
- };
-} LPC_USB_TypeDef;
-
-/*------------- Ethernet Media Access Controller (EMAC) ----------------------*/
-typedef struct
-{
- __IO uint32_t MAC1; /* MAC Registers */
- __IO uint32_t MAC2;
- __IO uint32_t IPGT;
- __IO uint32_t IPGR;
- __IO uint32_t CLRT;
- __IO uint32_t MAXF;
- __IO uint32_t SUPP;
- __IO uint32_t TEST;
- __IO uint32_t MCFG;
- __IO uint32_t MCMD;
- __IO uint32_t MADR;
- __O uint32_t MWTD;
- __I uint32_t MRDD;
- __I uint32_t MIND;
- uint32_t RESERVED0[2];
- __IO uint32_t SA0;
- __IO uint32_t SA1;
- __IO uint32_t SA2;
- uint32_t RESERVED1[45];
- __IO uint32_t Command; /* Control Registers */
- __I uint32_t Status;
- __IO uint32_t RxDescriptor;
- __IO uint32_t RxStatus;
- __IO uint32_t RxDescriptorNumber;
- __I uint32_t RxProduceIndex;
- __IO uint32_t RxConsumeIndex;
- __IO uint32_t TxDescriptor;
- __IO uint32_t TxStatus;
- __IO uint32_t TxDescriptorNumber;
- __IO uint32_t TxProduceIndex;
- __I uint32_t TxConsumeIndex;
- uint32_t RESERVED2[10];
- __I uint32_t TSV0;
- __I uint32_t TSV1;
- __I uint32_t RSV;
- uint32_t RESERVED3[3];
- __IO uint32_t FlowControlCounter;
- __I uint32_t FlowControlStatus;
- uint32_t RESERVED4[34];
- __IO uint32_t RxFilterCtrl; /* Rx Filter Registers */
- __IO uint32_t RxFilterWoLStatus;
- __IO uint32_t RxFilterWoLClear;
- uint32_t RESERVED5;
- __IO uint32_t HashFilterL;
- __IO uint32_t HashFilterH;
- uint32_t RESERVED6[882];
- __I uint32_t IntStatus; /* Module Control Registers */
- __IO uint32_t IntEnable;
- __O uint32_t IntClear;
- __O uint32_t IntSet;
- uint32_t RESERVED7;
- __IO uint32_t PowerDown;
- uint32_t RESERVED8;
- __IO uint32_t Module_ID;
-} LPC_EMAC_TypeDef;
-
-/*-------------------- External Memory Controller (EMC) ----------------------*/
-typedef struct
-{
- __IO uint32_t EMCControl;
- __I uint32_t EMCStatus;
- __IO uint32_t EMCConfig;
- uint32_t RESERVED1[5];
- __IO uint32_t EMCDynamicControl;
- __IO uint32_t EMCDynamicRefresh;
- __IO uint32_t EMCDynamicReadConfig;
- uint32_t RESERVED2;
- __IO uint32_t EMCDynamicRP;
- __IO uint32_t EMCDynamicRAS;
- __IO uint32_t EMCDynamicSREX;
- __IO uint32_t EMCDynamicAPR;
- __IO uint32_t EMCDynamicDAL;
- __IO uint32_t EMCDynamicWR;
- __IO uint32_t EMCDynamicRC;
- __IO uint32_t EMCDynamicRFC;
- __IO uint32_t EMCDynamicXSR;
- __IO uint32_t EMCDynamicRRD;
- __IO uint32_t EMCDynamicMRD;
- uint32_t RESERVED3[9];
- __IO uint32_t EMCStaticExtendedWait;
- uint32_t RESERVED4[31];
- __IO uint32_t EMCDynamicConfig0;
- __IO uint32_t EMCDynamicRasCas0;
- uint32_t RESERVED5[6];
- __IO uint32_t EMCDynamicConfig1;
- __IO uint32_t EMCDynamicRasCas1;
- uint32_t RESERVED6[6];
- __IO uint32_t EMCDynamicConfic2;
- __IO uint32_t EMCDynamicRasCas2;
- uint32_t RESERVED7[6];
- __IO uint32_t EMCDynamicConfig3;
- __IO uint32_t EMCDynamicRasCas3;
- uint32_t RESERVED8[38];
- __IO uint32_t EMCStaticConfig0;
- __IO uint32_t EMCStaticWaitWen0;
- __IO uint32_t EMCStaticWaitOen0;
- __IO uint32_t EMCStaticWaitRd0;
- __IO uint32_t EMCStaticWaitPage0;
- __IO uint32_t EMCStaticWaitWr0;
- __IO uint32_t EMCStaticWaitTurn0;
- uint32_t RESERVED9;
- __IO uint32_t EMCStaticConfig1;
- __IO uint32_t EMCStaticWaitWen1;
- __IO uint32_t EMCStaticWaitOen1;
- __IO uint32_t EMCStaticWaitRd1;
- __IO uint32_t EMCStaticWaitPage1;
- __IO uint32_t EMCStaticWaitWr1;
- __IO uint32_t EMCStaticWaitTurn1;
- uint32_t RESERVED10;
- __IO uint32_t EMCStaticConfig2;
- __IO uint32_t EMCStaticWaitWen2;
- __IO uint32_t EMCStaticWaitOen2;
- __IO uint32_t EMCStaticWaitRd2;
- __IO uint32_t EMCStaticWaitPage2;
- __IO uint32_t EMCStaticWaitWr2;
- __IO uint32_t EMCStaticWaitTurn2;
- uint32_t RESERVED11;
- __IO uint32_t EMCStaticConfig3;
- __IO uint32_t EMCStaticWaitWen3;
- __IO uint32_t EMCStaticWaitOen3;
- __IO uint32_t EMCStaticWaitRd3;
- __IO uint32_t EMCStaticWaitPage3;
- __IO uint32_t EMCStaticWaitWr3;
- __IO uint32_t EMCStaticWaitTurn3;
-} LPC_EMC_TypeDef;
-#if defined ( __CC_ARM )
- #pragma no_anon_unions
-#endif
-
-/******************************************************************************/
-/* Peripheral memory map */
-/******************************************************************************/
-/* Base addresses */
-
-/* AHB Peripheral # 0 */
-
-/*
-#define FLASH_BASE (0x00000000UL)
-#define RAM_BASE (0x10000000UL)
-#define GPIO_BASE (0x2009C000UL)
-#define APB0_BASE (0x40000000UL)
-#define APB1_BASE (0x40080000UL)
-#define AHB_BASE (0x50000000UL)
-#define CM3_BASE (0xE0000000UL)
-*/
-
-// TODO - #define VIC_BASE_ADDR 0xFFFFF000
-
-#define LPC_WDT_BASE (0xE0000000)
-#define LPC_TIM0_BASE (0xE0004000)
-#define LPC_TIM1_BASE (0xE0008000)
-#define LPC_UART0_BASE (0xE000C000)
-#define LPC_UART1_BASE (0xE0010000)
-#define LPC_PWM1_BASE (0xE0018000)
-#define LPC_I2C0_BASE (0xE001C000)
-#define LPC_SPI_BASE (0xE0020000)
-#define LPC_RTC_BASE (0xE0024000)
-#define LPC_GPIOINT_BASE (0xE0028080)
-#define LPC_PINCON_BASE (0xE002C000)
-#define LPC_SSP1_BASE (0xE0030000)
-#define LPC_ADC_BASE (0xE0034000)
-#define LPC_CANAF_RAM_BASE (0xE0038000)
-#define LPC_CANAF_BASE (0xE003C000)
-#define LPC_CANCR_BASE (0xE0040000)
-#define LPC_CAN1_BASE (0xE0044000)
-#define LPC_CAN2_BASE (0xE0048000)
-#define LPC_I2C1_BASE (0xE005C000)
-#define LPC_SSP0_BASE (0xE0068000)
-#define LPC_DAC_BASE (0xE006C000)
-#define LPC_TIM2_BASE (0xE0070000)
-#define LPC_TIM3_BASE (0xE0074000)
-#define LPC_UART2_BASE (0xE0078000)
-#define LPC_UART3_BASE (0xE007C000)
-#define LPC_I2C2_BASE (0xE0080000)
-#define LPC_I2S_BASE (0xE0088000)
-#define LPC_MCI_BASE (0xE008C000)
-#define LPC_SC_BASE (0xE01FC000)
-#define LPC_EMAC_BASE (0xFFE00000)
-#define LPC_GPDMA_BASE (0xFFE04000)
-#define LPC_GPDMACH0_BASE (0xFFE04100)
-#define LPC_GPDMACH1_BASE (0xFFE04120)
-#define LPC_EMC_BASE (0xFFE08000)
-#define LPC_USB_BASE (0xFFE0C000)
-#define LPC_VIC_BASE (0xFFFFF000)
-
-/* GPIOs */
-#define LPC_GPIO0_BASE (0x3FFFC000)
-#define LPC_GPIO1_BASE (0x3FFFC020)
-#define LPC_GPIO2_BASE (0x3FFFC040)
-#define LPC_GPIO3_BASE (0x3FFFC060)
-#define LPC_GPIO4_BASE (0x3FFFC080)
-
-
-/******************************************************************************/
-/* Peripheral declaration */
-/******************************************************************************/
-#define LPC_SC (( LPC_SC_TypeDef *) LPC_SC_BASE)
-#define LPC_GPIO0 (( LPC_GPIO_TypeDef *) LPC_GPIO0_BASE)
-#define LPC_GPIO1 (( LPC_GPIO_TypeDef *) LPC_GPIO1_BASE)
-#define LPC_GPIO2 (( LPC_GPIO_TypeDef *) LPC_GPIO2_BASE)
-#define LPC_GPIO3 (( LPC_GPIO_TypeDef *) LPC_GPIO3_BASE)
-#define LPC_GPIO4 (( LPC_GPIO_TypeDef *) LPC_GPIO4_BASE)
-#define LPC_WDT (( LPC_WDT_TypeDef *) LPC_WDT_BASE)
-#define LPC_TIM0 (( LPC_TIM_TypeDef *) LPC_TIM0_BASE)
-#define LPC_TIM1 (( LPC_TIM_TypeDef *) LPC_TIM1_BASE)
-#define LPC_TIM2 (( LPC_TIM_TypeDef *) LPC_TIM2_BASE)
-#define LPC_TIM3 (( LPC_TIM_TypeDef *) LPC_TIM3_BASE)
-#define LPC_UART0 (( LPC_UART_TypeDef *) LPC_UART0_BASE)
-#define LPC_UART1 (( LPC_UART1_TypeDef *) LPC_UART1_BASE)
-#define LPC_UART2 (( LPC_UART_TypeDef *) LPC_UART2_BASE)
-#define LPC_UART3 (( LPC_UART_TypeDef *) LPC_UART3_BASE)
-#define LPC_PWM1 (( LPC_PWM_TypeDef *) LPC_PWM1_BASE)
-#define LPC_I2C0 (( LPC_I2C_TypeDef *) LPC_I2C0_BASE)
-#define LPC_I2C1 (( LPC_I2C_TypeDef *) LPC_I2C1_BASE)
-#define LPC_I2C2 (( LPC_I2C_TypeDef *) LPC_I2C2_BASE)
-#define LPC_I2S (( LPC_I2S_TypeDef *) LPC_I2S_BASE)
-#define LPC_SPI (( LPC_SPI_TypeDef *) LPC_SPI_BASE)
-#define LPC_RTC (( LPC_RTC_TypeDef *) LPC_RTC_BASE)
-#define LPC_GPIOINT (( LPC_GPIOINT_TypeDef *) LPC_GPIOINT_BASE)
-#define LPC_PINCON (( LPC_PINCON_TypeDef *) LPC_PINCON_BASE)
-#define LPC_SSP0 (( LPC_SSP_TypeDef *) LPC_SSP0_BASE)
-#define LPC_SSP1 (( LPC_SSP_TypeDef *) LPC_SSP1_BASE)
-#define LPC_ADC (( LPC_ADC_TypeDef *) LPC_ADC_BASE)
-#define LPC_DAC (( LPC_DAC_TypeDef *) LPC_DAC_BASE)
-#define LPC_CANAF_RAM ((LPC_CANAF_RAM_TypeDef *) LPC_CANAF_RAM_BASE)
-#define LPC_CANAF (( LPC_CANAF_TypeDef *) LPC_CANAF_BASE)
-#define LPC_CANCR (( LPC_CANCR_TypeDef *) LPC_CANCR_BASE)
-#define LPC_CAN1 (( LPC_CAN_TypeDef *) LPC_CAN1_BASE)
-#define LPC_CAN2 (( LPC_CAN_TypeDef *) LPC_CAN2_BASE)
-#define LPC_MCI (( LPC_MCI_TypeDef *) LPC_MCI_BASE)
-#define LPC_EMAC (( LPC_EMAC_TypeDef *) LPC_EMAC_BASE)
-#define LPC_GPDMA (( LPC_GPDMA_TypeDef *) LPC_GPDMA_BASE)
-#define LPC_GPDMACH0 (( LPC_GPDMACH_TypeDef *) LPC_GPDMACH0_BASE)
-#define LPC_GPDMACH1 (( LPC_GPDMACH_TypeDef *) LPC_GPDMACH1_BASE)
-#define LPC_USB (( LPC_USB_TypeDef *) LPC_USB_BASE)
-#define LPC_VIC (( LPC_VIC_TypeDef *) LPC_VIC_BASE)
-#define LPC_EMC (( LPC_EMC_TypeDef *) LPC_EMC_BASE)
-
-#ifdef __cplusplus
- }
-#endif
-
-#endif // __LPC24xx_H
-
diff --git a/targets/TARGET_NXP/TARGET_LPC2460/device/TOOLCHAIN_GCC_ARM/LPC2460.ld b/targets/TARGET_NXP/TARGET_LPC2460/device/TOOLCHAIN_GCC_ARM/LPC2460.ld
deleted file mode 100644
index db36b39dcc..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC2460/device/TOOLCHAIN_GCC_ARM/LPC2460.ld
+++ /dev/null
@@ -1,210 +0,0 @@
-OUTPUT_FORMAT("elf32-littlearm", "elf32-bigarm", "elf32-littlearm")
-OUTPUT_ARCH(arm)
-ENTRY(vectors)
-
-/* Memory Definitions: */
-MEMORY
-{
- Flash (rx) : ORIGIN = 0xA0001000, LENGTH = 512k
- Ram (rwx) : ORIGIN = 0x40000040, LENGTH = 64k - 0x40
- UsbRam (rw) : ORIGIN = 0x7FD00000, LENGTH = 8k
- EthRam (rw) : ORIGIN = 0x7FE00000, LENGTH = 16k
- CanRam (rw) : ORIGIN = 0xE0038000, LENGTH = 2k
- BatRam (rw) : ORIGIN = 0xE0084000, LENGTH = 2k
-}
-
-/* Stack sizes: */
-UND_Stack_Size = 64;
-SVC_Stack_Size = 64;
-ABT_Stack_Size = 64;
-FIQ_Stack_Size = 64;
-IRQ_Stack_Size = 64;
-User_Stack_Size = 4096;
-Stack_Size_Total = UND_Stack_Size + SVC_Stack_Size + ABT_Stack_Size + FIQ_Stack_Size + IRQ_Stack_Size + User_Stack_Size;
-
-/* Stack tops for each mode: */
-__und_stack_top__ = __stacks_top__;
-__abt_stack_top__ = __und_stack_top__ - UND_Stack_Size ;
-__fiq_stack_top__ = __abt_stack_top__ - ABT_Stack_Size ;
-__irq_stack_top__ = __fiq_stack_top__ - FIQ_Stack_Size ;
-__svc_stack_top__ = __irq_stack_top__ - IRQ_Stack_Size ;
-__usr_stack_top__ = __svc_stack_top__ - User_Stack_Size ;
-
-/* C-accessible symbols for memory address ranges: */
-__FLASH_segment_start__ = ORIGIN( Flash );
-__FLASH_segment_end__ = ORIGIN( Flash ) + LENGTH( Flash );
-__SRAM_segment_start__ = ORIGIN( Ram );
-__SRAM_segment_end__ = ORIGIN( Ram ) + LENGTH( Ram );
-
-/* Stacks (full descending) at top of RAM, grows downward:
- *
- * __stack_min__ is used by the malloc implementation to ensure heap never collides
- * with stack (assuming stack never grows beyond Stack_Size_Total in length) */
-__stacks_top__ = __SRAM_segment_end__;
-__stacks_min__ = __SRAM_segment_end__ - Stack_Size_Total;
-
-SECTIONS
-{
- /* first section is .text which is used for code */
- __text_start__ = . ;
- .text : {
- __privileged_code_start__ = . ;
- KEEP( *( .vectors ) )
- *( .privileged_code )
-
- __privileged_code_end__ = .;
-
- *( .text .text.* .gnu.linkonce.t.* )
- *( .plt )
- *( .gnu.warning )
- *( .glue_7t ) *( .glue_7 ) *( .vfp11_veneer )
-
- *( .rodata .rodata.* .gnu.linkonce.r.* )
-
- *(.ARM.extab* .gnu.linkonce.armextab.*)
- *(.gcc_except_table)
- *(.eh_frame_hdr)
- *(.eh_frame)
-
- . = ALIGN( 4 ) ;
- KEEP( *( .init ) )
- . = ALIGN( 4 ) ;
- __preinit_array_start = . ;
- KEEP( *( .preinit_array ) )
- __preinit_array_end = . ;
- . = ALIGN( 4 ) ;
- __init_array_start = . ;
- KEEP( *( SORT( .init_array.* ) ) )
- KEEP( *( .init_array ) )
- __init_array_end = . ;
-
- . = ALIGN( 4 ) ;
- KEEP( *crtbegin.o( .ctors ) )
- KEEP( *( EXCLUDE_FILE( *crtend.o ) .ctors ) )
- KEEP( *( SORT( .ctors.* ) ) )
- KEEP( *crtend.o( .ctors ) )
-
- . = ALIGN( 4 ) ;
- KEEP( *( .fini ) )
- . = ALIGN( 4 ) ;
- __fini_array_start = . ;
- KEEP( *( .fini_array ) )
- KEEP( *( SORT( .fini_array.* ) ) )
- __fini_array_end = . ;
-
- KEEP( *crtbegin.o( .dtors ) )
- KEEP( *( EXCLUDE_FILE( *crtend.o ) .dtors ) )
- KEEP( *( SORT( .dtors.* ) ) )
- KEEP( *crtend.o( .dtors ) )
-
- } >Flash
-
- __exidx_start = . ;
- .ARM.exidx : {
- *( .ARM.exidx* .gnu.linkonce.armexidx.* )
- } >Flash
- __exidx_end = . ;
-
- .text.align : { . = ALIGN( 8 ) ; } >Flash /* Alignment schenanigans */
- __text_end__ = . ;
-
- /* .bss section -- used for uninitialized data */
- /* Located at the start of RAM */
- .bss (NOLOAD) : {
- __bss_start__ = . ;
- *crt0.o( .ram_vectors )
-
- __user_bss_start__ = . ;
- *( .user_bss )
- __user_bss_end__ = . ;
-
- *( .shbss )
- *( .bss .bss.* .gnu.linkonce.b.* )
- *( COMMON )
- *( .ram.b )
- . = ALIGN( 8 ) ;
-
- __bss_end__ = . ;
- } >Ram AT>Flash
-
- /* .data section -- used for initialized data */
- .data : {
- __data_start__ = . ;
- KEEP( *( .jcr ) )
- *( .got.plt ) *( .got )
- *( .shdata )
- *( .data .data.* .gnu.linkonce.d.* )
- *( .ram )
- . = ALIGN( 8 ) ;
- __data_end__ = . ;
- } >Ram AT>Flash
-
- __data_init_start__ = LOADADDR( .data ) ;
-
- /* Heap starts here and grows up in memory */
- . = ALIGN( 8 ) ;
- __heap_start__ = . ;
- end = . ;
- __end__ = . ;
-
- .stab 0 (NOLOAD) : { *(.stab) }
- .stabstr 0 (NOLOAD) : { *(.stabstr) }
- /* DWARF debug sections. */
- /* Symbols in the DWARF debugging sections are relative to the */
- /* beginning of the section so we begin them at 0. */
- /* DWARF 1 */
- .debug 0 : { *(.debug) }
- .line 0 : { *(.line) }
- /* GNU DWARF 1 extensions */
- .debug_srcinfo 0 : { *(.debug_srcinfo) }
- .debug_sfnames 0 : { *(.debug_sfnames) }
- /* DWARF 1.1 and DWARF 2 */
- .debug_aranges 0 : { *(.debug_aranges) }
- .debug_pubnames 0 : { *(.debug_pubnames) }
- /* DWARF 2 */
- .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) }
- .debug_abbrev 0 : { *(.debug_abbrev) }
- .debug_line 0 : { *(.debug_line) }
- .debug_frame 0 : { *(.debug_frame) }
- .debug_str 0 : { *(.debug_str) }
- .debug_loc 0 : { *(.debug_loc) }
- .debug_macinfo 0 : { *(.debug_macinfo) }
- /* SGI/MIPS DWARF 2 extensions */
- .debug_weaknames 0 : { *(.debug_weaknames) }
- .debug_funcnames 0 : { *(.debug_funcnames) }
- .debug_typenames 0 : { *(.debug_typenames) }
- .debug_varnames 0 : { *(.debug_varnames) }
- /* DWARF 3 */
- .debug_pubtypes 0 : { *(.debug_pubtypes) }
- .debug_ranges 0 : { *(.debug_ranges) }
-
- .note.gnu.arm.ident 0 : { KEEP( *( .note.gnu.arm.ident ) ) }
- .ARM.attributes 0 : {
- KEEP( *( .ARM.attributes ) )
- KEEP( *( .gnu.attributes ) )
- }
- /DISCARD/ : { *( .note.GNU-stack ) }
-
- /* C data can be defined as being in special purpose RAMs using
- * __attribute__ ((section ("ethram"))) for example. */
- .usbram (NOLOAD):
- {
- *( .usbram )
- *( .usbram.* )
- } > UsbRam
- .ethram (NOLOAD):
- {
- *( .ethram )
- *( .ethram.* )
- } > EthRam
- .canram (NOLOAD):
- {
- *( .canram )
- *( .canram.* )
- } > CanRam
- .batram (NOLOAD):
- {
- *( .batram )
- *( .batram.* )
- } > BatRam
-}
diff --git a/targets/TARGET_NXP/TARGET_LPC2460/device/TOOLCHAIN_GCC_ARM/vector_functions.S b/targets/TARGET_NXP/TARGET_LPC2460/device/TOOLCHAIN_GCC_ARM/vector_functions.S
deleted file mode 100644
index 8afac4c300..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC2460/device/TOOLCHAIN_GCC_ARM/vector_functions.S
+++ /dev/null
@@ -1,195 +0,0 @@
-/* .include "vector_defns.h" */
-
-
-
-.section .privileged_code, "ax"
-.arm
-
-
-.weak __mbed_fiq
-.weak __mbed_undef
-.weak __mbed_prefetch_abort
-.weak __mbed_data_abort
-.weak __mbed_irq
-.weak __mbed_swi
-.weak __mbed_dcc_irq
-.weak __mbed_reset
-.global __mbed_init_realmonitor
-.weak SVC_Handler
-.weak IRQ_Handler
-/* .global __mbed_init */
-
-
-
-
-__mbed_fiq:
- B __mbed_fiq
-__mbed_undef:
- LDR PC, =0x7fffffa0
-__mbed_prefetch_abort:
- LDR PC, =0x7fffffb0
-__mbed_data_abort:
- LDR PC, =0x7fffffc0
-__mbed_irq:
-/*
- If RTOS is enabled then goto RTOS IRQ handler
-*/
- PUSH {R0}
- LDR R0, =IRQ_Handler
- CMP R0, #0
- POP {R0}
- BNE IRQ_Handler
-/*
- else use CMSIS IRQ handler
-*/
- MSR CPSR_c, #0x1F|0x80|0x40
-
- STMDB sp!, {r0-r3,r12,lr}
-
- MOV r0, #0xFFFFFF00
- LDR r0, [r0]
-
- MOV lr, pc
- BX r0
-
- MOV r0, #0xFFFFFF00
- STR r0, [r0]
-
- LDMFD sp!,{r0-r3,r12,lr}
-
- MSR CPSR_c, #0x12|0x80|0x40
-
- SUBS pc, lr, #4
-
-__mbed_swi:
-/*
- If RTOS is enabled then goto RTOS SVC handler
-*/
- PUSH {R0}
- LDR R0, =SVC_Handler
- CMP R0, #0
- POP {R0}
- BNE SVC_Handler
-/*
- else use CMSIS SVC handler
-*/
- STMFD sp!, {a4, r4, ip, lr}
-
- LDR r4, =0x40000040
-
- LDR a4, =0x00940000
- LDR PC, =0x7ffff820
-
-__mbed_dcc_irq:
- LDMFD sp!,{r0-r3,r12,lr}
-
- MSR CPSR_c, #0x12|0x80|0x40
-
- SUB lr, lr, #4
- STMFD sp!, {ip,lr}
-
- LDR LR, =0xfffff000
- STR LR, [LR, #0xf00]
-
- LDR PC, =0x7fffffe0
-/*
- __mbed_reset is called after reset
- we setup the stacks and realmonitor, then call Reset_Handler like on M3
-*/
-
-.section .text, "ax"
-.arm
-.global Reset_handler
-Reset_Handler:
- .extern __libc_init_array
- .extern SystemInit
- .weak software_init_hook
- LDR R0, =SystemInit
- MOV LR, PC
- BX R0
-
-/* if (software_init_hook) // give control to the RTOS
- software_init_hook(); // this will also call __libc_init_array
-*/
- LDR R0, =software_init_hook
- CMP R0, #0
- BEQ nortos
- ORR R0,R0,#1 /* set thumb address */
- BX R0
-/* else */
-nortos:
- LDR R0, =__libc_init_array
- MOV LR, PC
- BX R0
-
- MSR CPSR_c, #0x1F /* enable irq */
-
- LDR R0, =main
- BX R0
-
-__mbed_reset:
- LDR R0, =( __SRAM_segment_end__ )
-
- MSR CPSR_c, #0x1B|0x80|0x40
- MOV SP, R0
- SUB R0, R0, #0x00000040
-
- MSR CPSR_c, #0x17|0x80|0x40
- MOV SP, R0
- SUB R0, R0, #0x00000040
-
- MSR CPSR_c, #0x11|0x80|0x40
- MOV SP, R0
- SUB R0, R0, #0x00000040
-
- MSR CPSR_c, #0x12|0x80|0x40
- MOV SP, R0
- SUB R0, R0, #0x00000040
-
- MSR CPSR_c, #0x13|0x80|0x40
- MOV SP, R0
- SUB R0, R0, #0x00000040
-
-/*
- MSR CPSR_c, #0x10|0x80|0x40
- MOV SP, R0
-*/
- MSR CPSR_c, #0x1F|0x80|0x40
- MOV SP, R0
-
- MSR CPSR_c, #0x13|0x80|0x40 /* execute in Supervisor mode */
-
-/* Relocate .data section (Copy from ROM to RAM) */
- LDR R1, =__text_end__ /* _etext */
- LDR R2, =__data_start__ /* _data */
- LDR R3, =__data_end__ /* _edata */
- CMP R2, R3
- BEQ DataIsEmpty
-LoopRel: CMP R2, R3
- LDRLO R0, [R1], #4
- STRLO R0, [R2], #4
- BLO LoopRel
-DataIsEmpty:
-
-/* Clear .bss section (Zero init) */
- MOV R0, #0
- LDR R1, =__bss_start__
- LDR R2, =__bss_end__
- CMP R1,R2
- BEQ BSSIsEmpty
-LoopZI: CMP R1, R2
- STRLO R0, [R1], #4
- BLO LoopZI
-BSSIsEmpty:
-
-
-/* Init realmonitor */
-/*
- LDR R0, =__mbed_init_realmonitor
- MOV LR, PC
- BX R0
-*/
-
-/* Go to Reset_Handler */
- LDR R0, =Reset_Handler
- BX R0
diff --git a/targets/TARGET_NXP/TARGET_LPC2460/device/TOOLCHAIN_GCC_ARM/vector_table.S b/targets/TARGET_NXP/TARGET_LPC2460/device/TOOLCHAIN_GCC_ARM/vector_table.S
deleted file mode 100644
index d797c3794d..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC2460/device/TOOLCHAIN_GCC_ARM/vector_table.S
+++ /dev/null
@@ -1,45 +0,0 @@
-# 1 "vector_table.s"
-# 1 ""
-# 1 ""
-# 1 "vector_table.s"
-;
-
-
-
-
-# 1 "vector_defns.h" 1
-# 7 "vector_table.s" 2
-
-;
-
-
-
-
-
-
-
- .section .vectors, "ax"
- .arm
-
-
- .global __main
- .global __mbed_reset
- .global __mbed_undef
- .global __mbed_swi
- .global __mbed_prefetch_abort
- .global __mbed_data_abort
- .global __mbed_irq
- .global __mbed_fiq
-
-;
-
-
-_start:
- LDR PC, =__mbed_reset
- LDR PC, =__mbed_undef
- LDR PC, =__mbed_swi
- LDR PC, =__mbed_prefetch_abort
- LDR PC, =__mbed_data_abort
- NOP ;
- LDR PC, =__mbed_irq
- LDR PC, =__mbed_fiq
diff --git a/targets/TARGET_NXP/TARGET_LPC2460/device/cmsis.h b/targets/TARGET_NXP/TARGET_LPC2460/device/cmsis.h
deleted file mode 100644
index ae57701416..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC2460/device/cmsis.h
+++ /dev/null
@@ -1,13 +0,0 @@
-/* mbed Microcontroller Library - CMSIS
- * Copyright (C) 2009-2015 ARM Limited. All rights reserved.
- *
- * A generic CMSIS include header, pulling in LPC2368 specifics
- */
-
-#ifndef MBED_CMSIS_H
-#define MBED_CMSIS_H
-
-#include "LPC24xx.h"
-#include "cmsis_nvic.h"
-
-#endif
diff --git a/targets/TARGET_NXP/TARGET_LPC2460/device/cmsis_nvic.c b/targets/TARGET_NXP/TARGET_LPC2460/device/cmsis_nvic.c
deleted file mode 100644
index b7f02e2fa7..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC2460/device/cmsis_nvic.c
+++ /dev/null
@@ -1,40 +0,0 @@
-/* mbed Microcontroller Library
- * CMSIS-style functionality to support dynamic vectors
- *******************************************************************************
- * Copyright (c) 2011-2015 ARM Limited. All rights reserved.
- * All rights reserved.
- *
- * 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 of ARM Limited 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 HOLDER 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.
- *******************************************************************************
- */
-#include "cmsis_nvic.h"
-
-void NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) {
- LPC_VIC->VectAddr[(int)IRQn] = vector;
-}
-
-uint32_t NVIC_GetVector(IRQn_Type IRQn) {
- return LPC_VIC->VectAddr[(int)IRQn];
-}
-
diff --git a/targets/TARGET_NXP/TARGET_LPC2460/device/cmsis_nvic.h b/targets/TARGET_NXP/TARGET_LPC2460/device/cmsis_nvic.h
deleted file mode 100644
index d22cf0e4c7..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC2460/device/cmsis_nvic.h
+++ /dev/null
@@ -1,51 +0,0 @@
-/* mbed Microcontroller Library
- * CMSIS-style functionality to support dynamic vectors
- *******************************************************************************
- * Copyright (c) 2011-2015 ARM Limited. All rights reserved.
- * All rights reserved.
- *
- * 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 of ARM Limited 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 HOLDER 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 MBED_CMSIS_NVIC_H
-#define MBED_CMSIS_NVIC_H
-
-#define NVIC_NUM_VECTORS 32
-#define NVIC_USER_IRQ_OFFSET 0
-
-#include "cmsis.h"
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-void NVIC_SetVector(IRQn_Type IRQn, uint32_t vector);
-uint32_t NVIC_GetVector(IRQn_Type IRQn);
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif
diff --git a/targets/TARGET_NXP/TARGET_LPC2460/device/core_arm7.c b/targets/TARGET_NXP/TARGET_LPC2460/device/core_arm7.c
deleted file mode 100644
index 6eba5565d3..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC2460/device/core_arm7.c
+++ /dev/null
@@ -1,44 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (C) 2008-2015 ARM Limited. All rights reserved.
- *
- * ARM7 version of CMSIS-like functionality - not advised for use outside mbed!
- * based on core_cm3.h, V1.20
- */
-
-#include
-
-
-/* define compiler specific symbols */
-#if defined ( __CC_ARM )
- #define __ASM __asm /*!< asm keyword for armcc */
- #define __INLINE __inline /*!< inline keyword for armcc */
-
-#elif defined ( __ICCARM__ )
- #define __ASM __asm /*!< asm keyword for iarcc */
- #define __INLINE inline /*!< inline keyword for iarcc. Only avaiable in High optimization mode! */
-
-#elif defined ( __GNUC__ )
- #define __ASM __asm /*!< asm keyword for gcc */
- #define __INLINE inline /*!< inline keyword for gcc */
-
-#elif defined ( __TASKING__ )
- #define __ASM __asm /*!< asm keyword for TASKING Compiler */
- #define __INLINE inline /*!< inline keyword for TASKING Compiler */
-
-#endif
-
-#if defined ( __CC_ARM )
-/**
- * @brief Return the Main Stack Pointer (return current ARM7 stack)
- *
- * @param none
- * @return uint32_t Main Stack Pointer
- *
- * Return the current value of the MSP (main stack pointer)
- * Cortex processor register
- */
-uint32_t __get_MSP(void)
-{
- return __current_sp();
-}
-#endif
diff --git a/targets/TARGET_NXP/TARGET_LPC2460/device/core_arm7.h b/targets/TARGET_NXP/TARGET_LPC2460/device/core_arm7.h
deleted file mode 100644
index 5879cc19ad..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC2460/device/core_arm7.h
+++ /dev/null
@@ -1,343 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (C) 2008-2015 ARM Limited. All rights reserved.
- *
- * ARM7 version of CMSIS-like functionality - not advised for use outside mbed!
- * based on core_cm3.h, V1.20
- */
-
-#ifndef __ARM7_CORE_H__
-#define __ARM7_CORE_H__
-
-#include "vector_defns.h"
-#ifdef __cplusplus
-extern "C" {
-#endif
-//#include "cmsis_nvic.h"
-
-#define __CM3_CMSIS_VERSION_MAIN (0x01) /*!< [31:16] CMSIS HAL main version */
-#define __CM3_CMSIS_VERSION_SUB (0x20) /*!< [15:0] CMSIS HAL sub version */
-#define __CM3_CMSIS_VERSION ((__CM3_CMSIS_VERSION_MAIN << 16) | __CM3_CMSIS_VERSION_SUB) /*!< CMSIS HAL version number */
-
-#define __CORTEX_M (0x00) /*!< Cortex core */
-
-/**
- * Lint configuration \n
- * ----------------------- \n
- *
- * The following Lint messages will be suppressed and not shown: \n
- * \n
- * --- Error 10: --- \n
- * register uint32_t __regBasePri __asm("basepri"); \n
- * Error 10: Expecting ';' \n
- * \n
- * --- Error 530: --- \n
- * return(__regBasePri); \n
- * Warning 530: Symbol '__regBasePri' (line 264) not initialized \n
- * \n
- * --- Error 550: --- \n
- * __regBasePri = (basePri & 0x1ff); \n
- * } \n
- * Warning 550: Symbol '__regBasePri' (line 271) not accessed \n
- * \n
- * --- Error 754: --- \n
- * uint32_t RESERVED0[24]; \n
- * Info 754: local structure member '' (line 109, file ./cm3_core.h) not referenced \n
- * \n
- * --- Error 750: --- \n
- * #define __CM3_CORE_H__ \n
- * Info 750: local macro '__CM3_CORE_H__' (line 43, file./cm3_core.h) not referenced \n
- * \n
- * --- Error 528: --- \n
- * static __INLINE void NVIC_DisableIRQ(uint32_t IRQn) \n
- * Warning 528: Symbol 'NVIC_DisableIRQ(unsigned int)' (line 419, file ./cm3_core.h) not referenced \n
- * \n
- * --- Error 751: --- \n
- * } InterruptType_Type; \n
- * Info 751: local typedef 'InterruptType_Type' (line 170, file ./cm3_core.h) not referenced \n
- * \n
- * \n
- * Note: To re-enable a Message, insert a space before 'lint' * \n
- *
- */
-
-/*lint -save */
-/*lint -e10 */
-/*lint -e530 */
-/*lint -e550 */
-/*lint -e754 */
-/*lint -e750 */
-/*lint -e528 */
-/*lint -e751 */
-
-#include /* Include standard types */
-
-#if defined ( __CC_ARM )
-/**
- * @brief Return the Main Stack Pointer (current ARM7 stack)
- *
- * @param none
- * @return uint32_t Main Stack Pointer
- *
- * Return the current value of the MSP (main stack pointer)
- * Cortex processor register
- */
-extern uint32_t __get_MSP(void);
-#endif
-
-
-#if defined (__ICCARM__)
- #include /* IAR Intrinsics */
-#endif
-
-
-#ifndef __NVIC_PRIO_BITS
- #define __NVIC_PRIO_BITS 4 /*!< standard definition for NVIC Priority Bits */
-#endif
-
-typedef struct
-{
- uint32_t IRQStatus;
- uint32_t FIQStatus;
- uint32_t RawIntr;
- uint32_t IntSelect;
- uint32_t IntEnable;
- uint32_t IntEnClr;
- uint32_t SoftInt;
- uint32_t SoftIntClr;
- uint32_t Protection;
- uint32_t SWPriorityMask;
- uint32_t RESERVED0[54];
- uint32_t VectAddr[32];
- uint32_t RESERVED1[32];
- uint32_t VectPriority[32];
- uint32_t RESERVED2[800];
- uint32_t Address;
-} NVIC_TypeDef;
-
-#define NVIC_BASE (0xFFFFF000)
-#define NVIC (( NVIC_TypeDef *) NVIC_BASE)
-
-
-
-/**
- * IO definitions
- *
- * define access restrictions to peripheral registers
- */
-
-#ifdef __cplusplus
-#define __I volatile /*!< defines 'read only' permissions */
-#else
-#define __I volatile const /*!< defines 'read only' permissions */
-#endif
-#define __O volatile /*!< defines 'write only' permissions */
-#define __IO volatile /*!< defines 'read / write' permissions */
-
-
-
-
-
-#if defined ( __CC_ARM )
- #define __ASM __asm /*!< asm keyword for ARM Compiler */
- #define __INLINE __inline /*!< inline keyword for ARM Compiler */
-
-#elif defined ( __ICCARM__ )
- #define __ASM __asm /*!< asm keyword for IAR Compiler */
- #define __INLINE inline /*!< inline keyword for IAR Compiler. Only avaiable in High optimization mode! */
-
-#elif defined ( __GNUC__ )
- #define __ASM __asm /*!< asm keyword for GNU Compiler */
- #define __INLINE inline /*!< inline keyword for GNU Compiler */
-
-#elif defined ( __TASKING__ )
- #define __ASM __asm /*!< asm keyword for TASKING Compiler */
- #define __INLINE inline /*!< inline keyword for TASKING Compiler */
-
-#endif
-
-
-/* ################### Compiler specific Intrinsics ########################### */
-
-#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/
-/* ARM armcc specific functions */
-
-#define __enable_fault_irq __enable_fiq
-#define __disable_fault_irq __disable_fiq
-
-#define __NOP __nop
-//#define __WFI __wfi
-//#define __WFE __wfe
-//#define __SEV __sev
-//#define __ISB() __isb(0)
-//#define __DSB() __dsb(0)
-//#define __DMB() __dmb(0)
-//#define __REV __rev
-//#define __RBIT __rbit
-#define __LDREXB(ptr) ((unsigned char ) __ldrex(ptr))
-#define __LDREXH(ptr) ((unsigned short) __ldrex(ptr))
-#define __LDREXW(ptr) ((unsigned int ) __ldrex(ptr))
-#define __STREXB(value, ptr) __strex(value, ptr)
-#define __STREXH(value, ptr) __strex(value, ptr)
-#define __STREXW(value, ptr) __strex(value, ptr)
-
-#define __disable_irq() unsigned tmp_IntEnable = LPC_VIC->IntEnable; \
- LPC_VIC->IntEnClr = 0xffffffff
-
-#define __enable_irq() LPC_VIC->IntEnable = tmp_IntEnable
-
-#elif (defined (__ICCARM__)) /*------------------ ICC Compiler -------------------*/
-
-#define __enable_irq __enable_interrupt /*!< global Interrupt enable */
-#define __disable_irq __disable_interrupt /*!< global Interrupt disable */
-#define __NOP __no_operation() /*!< no operation intrinsic in IAR Compiler */
-
-#elif (defined (__GNUC__)) /*------------------ GNU Compiler ---------------------*/
-
-static __INLINE void __enable_irq() {
- unsigned long temp;
- __asm__ __volatile__("mrs %0, cpsr\n"
- "bic %0, %0, #0x80\n"
- "msr cpsr_c, %0"
- : "=r" (temp)
- :
- : "memory");
-}
-
-static __INLINE uint32_t __disable_irq() {
- unsigned long old,temp;
- __asm__ __volatile__("mrs %0, cpsr\n"
- "orr %1, %0, #0xc0\n"
- "msr cpsr_c, %1"
- : "=r" (old), "=r" (temp)
- :
- : "memory");
- return (old & 0x80) == 0;
-}
-
-static __INLINE void __NOP() { __ASM volatile ("nop"); }
-
-/** \brief Get Control Bits of Status Register
-
- This function returns the content of the Control Bits from the Program Status Register.
-
- \return Control Bits value
- */
-__attribute__( ( always_inline ) ) static inline uint32_t __get_CONTROL(void)
-{
- uint32_t result;
-
- __asm__ __volatile__ ("MRS %0, CPSR \n"
- "AND %0,%0,#31" : "=r" (result) );
- return(result);
-}
-#define MODE_USER 0x10
-#define MODE_FIQ 0x11
-#define MODE_IRQ 0x12
-#define MODE_SUPERVISOR 0x13
-#define MODE_ABORT 0x17
-#define MODE_UNDEFINED 0x1B
-#define MODE_SYSTEM 0x1F
-
-
-#elif (defined (__TASKING__)) /*------------------ TASKING Compiler ---------------------*/
-/* TASKING carm specific functions */
-
-/*
- * The CMSIS functions have been implemented as intrinsics in the compiler.
- * Please use "carm -?i" to get an up to date list of all instrinsics,
- * Including the CMSIS ones.
- */
-
-#endif
-
-
-/**
- * @brief Enable Interrupt in NVIC Interrupt Controller
- *
- * @param IRQn_Type IRQn specifies the interrupt number
- * @return none
- *
- * Enable a device specific interupt in the NVIC interrupt controller.
- * The interrupt number cannot be a negative value.
- */
-static __INLINE void NVIC_EnableIRQ(uint32_t IRQn)
-{
- NVIC->IntEnable = 1 << (uint32_t)IRQn;
-}
-
-
-/**
- * @brief Disable the interrupt line for external interrupt specified
- *
- * @param IRQn_Type IRQn is the positive number of the external interrupt
- * @return none
- *
- * Disable a device specific interupt in the NVIC interrupt controller.
- * The interrupt number cannot be a negative value.
- */
-static __INLINE void NVIC_DisableIRQ(uint32_t IRQn)
-{
- NVIC->IntEnClr = 1 << (uint32_t)IRQn;
-}
-
-/**
- * @brief Pend Interrupt in NVIC Interrupt Controller
- *
- * @param IRQn_Type IRQn specifies the interrupt number
- * @return none
- *
- * Force software a device specific interupt in the NVIC interrupt controller.
- * The interrupt number cannot be a negative value.
- */
-static __INLINE void NVIC_PendIRQ(uint32_t IRQn)
-{
- NVIC->SoftInt = 1 << (uint32_t)IRQn;
-}
-
-
-/**
- * @brief Unpend the interrupt in NVIC Interrupt Controller
- *
- * @param IRQn_Type IRQn is the positive number of the external interrupt
- * @return none
- *
- * Clear software device specific interupt in the NVIC interrupt controller.
- * The interrupt number cannot be a negative value.
- */
-static __INLINE void NVIC_UnpendIRQ(uint32_t IRQn)
-{
- NVIC->SoftIntClr = 1 << (uint32_t)IRQn;
-}
-
-/**
- * @brief Is IRQ pending
- *
- * @param IRQn_Type IRQn is the positive number of the external interrupt
- * @return 0 if IRQ is not pending
- * 1 if IRQ is pending
- *
- * Returns software device specific interupt in the NVIC interrupt controller.
- * The interrupt number cannot be a negative value.
- */
-static __INLINE uint32_t NVIC_Pending(uint32_t IRQn)
-{
- return (NVIC->SoftInt & (1 << (uint32_t)IRQn)) != 0;
-}
-
-static __INLINE uint32_t __get_IPSR(void)
-{
- unsigned i;
-
- for(i = 0; i < 32; i ++)
- if(NVIC->Address == NVIC->VectAddr[i])
- return i;
- return 1; // 1 is an invalid entry in the interrupt table on LPC2460
-}
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif /* __ARM7_CORE_H__ */
-
-/*lint -restore */
diff --git a/targets/TARGET_NXP/TARGET_LPC2460/device/system_LPC24xx.c b/targets/TARGET_NXP/TARGET_LPC2460/device/system_LPC24xx.c
deleted file mode 100644
index f1698c2658..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC2460/device/system_LPC24xx.c
+++ /dev/null
@@ -1,164 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (C) 2008-2015 ARM Limited. All rights reserved.
- *
- * ARM7 version of CMSIS-like functionality - not advised for use outside mbed!
- */
-
-#include
-#include "LPC24xx.h"
-
-#define CLOCK_SETUP 1
-#define SCS_Val ((1<<4) | (1 << 5))
-#define CLKSRCSEL_Val 0x00000001
-
-#define PLL0_SETUP 1
-#define PLL0CFG_Val 0x0000000B
-#define CCLKCFG_Val 0x00000003
-#define USBCLKCFG_Val 0x00000005
-#define PCLKSEL0_Val 0x00000000
-#define PCLKSEL1_Val 0x00000000
-#define PCONP_Val (1 << PCEMC)
-#define CLKOUTCFG_Val 0x00000000
-#define MAMCR_Val 0x00000002
-#define MAMTIM_Val 0x00000004
-
-/*----------------------------------------------------------------------------
- DEFINES
- *----------------------------------------------------------------------------*/
-
-#define XTAL (12000000UL) /* Oscillator frequency */
-#define OSC_CLK ( XTAL) /* Main oscillator frequency */
-#define RTC_CLK ( 32000UL) /* RTC oscillator frequency */
-#define IRC_OSC ( 4000000UL) /* Internal RC oscillator frequency */
-
-/* F_cco0 = (2 * M * F_in) / N */
-#define __M (((PLL0CFG_Val ) & 0x7FFF) + 1)
-#define __N (((PLL0CFG_Val >> 16) & 0x00FF) + 1)
-#define __FCCO(__F_IN) ((2 * __M * __F_IN) / __N)
-#define __CCLK_DIV (((CCLKCFG_Val ) & 0x00FF) + 1)
-
-/* Determine core clock frequency according to settings */
- #if (PLL0_SETUP)
- #if ((CLKSRCSEL_Val & 0x03) == 1)
- #define __CORE_CLK (__FCCO(OSC_CLK) / __CCLK_DIV)
- #elif ((CLKSRCSEL_Val & 0x03) == 2)
- #define __CORE_CLK (__FCCO(RTC_CLK) / __CCLK_DIV)
- #else
- #define __CORE_CLK (__FCCO(IRC_OSC) / __CCLK_DIV)
- #endif
- #endif
-
-
-/*----------------------------------------------------------------------------
- Clock Variable definitions
- *----------------------------------------------------------------------------*/
-uint32_t SystemCoreClock = __CORE_CLK;/*!< System Clock Frequency (Core Clock)*/
-
-/*----------------------------------------------------------------------------
- Clock functions
- *----------------------------------------------------------------------------*/
-void SystemCoreClockUpdate (void) /* Get Core Clock Frequency */
-{
- /* Determine clock frequency according to clock register values */
- if (((LPC_SC->PLL0STAT >> 24) & 3) == 3) { /* If PLL0 enabled and connected */
- switch (LPC_SC->CLKSRCSEL & 0x03) {
- case 0: /* Int. RC oscillator => PLL0 */
- case 3: /* Reserved, default to Int. RC */
- SystemCoreClock = (IRC_OSC *
- (((2 * ((LPC_SC->PLL0STAT & 0x7FFF) + 1))) /
- (((LPC_SC->PLL0STAT >> 16) & 0xFF) + 1)) /
- ((LPC_SC->CCLKCFG & 0xFF)+ 1));
- break;
- case 1: /* Main oscillator => PLL0 */
- SystemCoreClock = (OSC_CLK *
- (((2 * ((LPC_SC->PLL0STAT & 0x7FFF) + 1))) /
- (((LPC_SC->PLL0STAT >> 16) & 0xFF) + 1)) /
- ((LPC_SC->CCLKCFG & 0xFF)+ 1));
- break;
- case 2: /* RTC oscillator => PLL0 */
- SystemCoreClock = (RTC_CLK *
- (((2 * ((LPC_SC->PLL0STAT & 0x7FFF) + 1))) /
- (((LPC_SC->PLL0STAT >> 16) & 0xFF) + 1)) /
- ((LPC_SC->CCLKCFG & 0xFF)+ 1));
- break;
- }
- } else {
- switch (LPC_SC->CLKSRCSEL & 0x03) {
- case 0: /* Int. RC oscillator => PLL0 */
- case 3: /* Reserved, default to Int. RC */
- SystemCoreClock = IRC_OSC / ((LPC_SC->CCLKCFG & 0xFF)+ 1);
- break;
- case 1: /* Main oscillator => PLL0 */
- SystemCoreClock = OSC_CLK / ((LPC_SC->CCLKCFG & 0xFF)+ 1);
- break;
- case 2: /* RTC oscillator => PLL0 */
- SystemCoreClock = RTC_CLK / ((LPC_SC->CCLKCFG & 0xFF)+ 1);
- break;
- }
- }
-}
-
-void vectorRemap()
-{
- #define ARM_VECTOR_REBASE (0x40000000)
- extern unsigned long __privileged_code_start__; /* Startup code address from linker */
- int i;
-
- /* Copy ARM vector table into internal RAM */
- for (i = 0; i <= 56; i+=2)
- {
- *(unsigned short *)(ARM_VECTOR_REBASE + i) = *(unsigned short *)((unsigned long)(&__privileged_code_start__) + i);
- }
-
-// *(unsigned long *)(ARM_VECTOR_REBASE) = (unsigned long)armUnexpReset;
- /* Remap the interrupt vectors to RAM */
- LPC_SC->MEMMAP = 2;
-}
-
-/**
- * Initialize the system
- *
- * @param none
- * @return none
- *
- * @brief Setup the microcontroller system.
- * Initialize the System and update the SystemFrequency variable.
- */
-void SystemInit (void)
-{
- LPC_WDT->WDMOD = 0; /* Disable internal watchdog */
-#if (CLOCK_SETUP) /* Clock Setup */
- LPC_SC->SCS = SCS_Val;
- if (SCS_Val & (1 << 5)) { /* If Main Oscillator is enabled */
- while ((LPC_SC->SCS & (1 << 6)) == 0); /* Wait for Oscillator to be ready */
- }
-
- LPC_SC->CCLKCFG = CCLKCFG_Val; /* Setup Clock Divider */
-
-#if (PLL0_SETUP)
- LPC_SC->CLKSRCSEL = CLKSRCSEL_Val; /* Select Clock Source for PLL0 */
- LPC_SC->PLL0CFG = PLL0CFG_Val;
- LPC_SC->PLL0CON = 0x01; /* PLL0 Enable */
- LPC_SC->PLL0FEED = 0xAA;
- LPC_SC->PLL0FEED = 0x55;
- while (!(LPC_SC->PLL0STAT & (1 << 26))); /* Wait for PLOCK0 */
-
- LPC_SC->PLL0CON = 0x03; /* PLL0 Enable & Connect */
- LPC_SC->PLL0FEED = 0xAA;
- LPC_SC->PLL0FEED = 0x55;
-#endif
-
- LPC_SC->USBCLKCFG = USBCLKCFG_Val; /* Setup USB Clock Divider */
-#endif
-
- LPC_SC->PCLKSEL0 = PCLKSEL0_Val; /* Peripheral Clock Selection */
- LPC_SC->PCLKSEL1 = PCLKSEL1_Val;
-
- LPC_SC->PCONP = PCONP_Val; /* Power Control for Peripherals */
-
- // Setup MAM
- LPC_SC->MAMTIM = MAMTIM_Val;
- LPC_SC->MAMCR = MAMCR_Val;
- vectorRemap();
-}
-
diff --git a/targets/TARGET_NXP/TARGET_LPC2460/device/system_LPC24xx.h b/targets/TARGET_NXP/TARGET_LPC2460/device/system_LPC24xx.h
deleted file mode 100644
index 4e566818fa..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC2460/device/system_LPC24xx.h
+++ /dev/null
@@ -1,44 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (C) 2008-2015 ARM Limited. All rights reserved.
- *
- * ARM7 version of CMSIS-like functionality - not advised for use outside mbed!
- * based on cmsis system_LPC17xx.h
- */
-
-#ifndef __SYSTEM_LPC24xx_H
-#define __SYSTEM_LPC24xx_H
-
-#ifdef __cplusplus
- extern "C" {
-#endif
-
-extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
-
-/**
- * Initialize the system
- *
- * @param none
- * @return none
- *
- * @brief Setup the microcontroller system.
- * Initialize the System and update the SystemCoreClock variable.
- */
-extern void SystemInit (void);
-
-/**
- * Update SystemCoreClock variable
- *
- * @param none
- * @return none
- *
- * @brief Updates the SystemCoreClock with current core Clock
- * retrieved from cpu registers.
- */
-extern void SystemCoreClockUpdate (void);
-
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif
diff --git a/targets/TARGET_NXP/TARGET_LPC2460/device/vector_defns.h b/targets/TARGET_NXP/TARGET_LPC2460/device/vector_defns.h
deleted file mode 100644
index 00b6f869b3..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC2460/device/vector_defns.h
+++ /dev/null
@@ -1,77 +0,0 @@
-/* mbed Microcontroller Library - Vectors
- * Copyright (c) 2006-2015 ARM Limited. All rights reserved.
- */
-
-#ifndef MBED_VECTOR_DEFNS_H
-#define MBED_VECTOR_DEFNS_H
-
-// Assember Macros
-#ifdef __ARMCC_VERSION
-#define EXPORT(x) EXPORT x
-#define WEAK_EXPORT(x) EXPORT x [WEAK]
-#define IMPORT(x) IMPORT x
-#define LABEL(x) x
-#else
-#define EXPORT(x) .global x
-#define WEAK_EXPORT(x) .weak x
-#define IMPORT(x) .global x
-#define LABEL(x) x:
-#endif
-
-// RealMonitor
-// Requires RAM (0x40000040-0x4000011F) to be allocated by the linker
-
-// RealMonitor entry points
-#define rm_init_entry 0x7fffff91
-#define rm_undef_handler 0x7fffffa0
-#define rm_prefetchabort_handler 0x7fffffb0
-#define rm_dataabort_handler 0x7fffffc0
-#define rm_irqhandler2 0x7fffffe0
-//#define rm_RunningToStopped 0x7ffff808 // ARM - MBED64
-#define rm_RunningToStopped 0x7ffff820 // ARM - PHAT40
-
-// Unofficial RealMonitor entry points and variables
-#define RM_MSG_SWI 0x00940000
-#define StateP 0x40000040
-
-// VIC register addresses
-#define VIC_Base 0xfffff000
-#define VICAddress_Offset 0xf00
-#define VICVectAddr0_Offset 0x100
-#define VICVectAddr2_Offset 0x108
-#define VICVectAddr3_Offset 0x10c
-#define VICVectAddr31_Offset 0x17c
-#define VICIntEnClr_Offset 0x014
-#define VICIntEnClr (*(volatile unsigned long *)(VIC_Base + 0x014))
-#define VICVectAddr2 (*(volatile unsigned long *)(VIC_Base + 0x108))
-#define VICVectAddr3 (*(volatile unsigned long *)(VIC_Base + 0x10C))
-
-// ARM Mode bits and Interrupt flags in PSRs
-#define Mode_USR 0x10
-#define Mode_FIQ 0x11
-#define Mode_IRQ 0x12
-#define Mode_SVC 0x13
-#define Mode_ABT 0x17
-#define Mode_UND 0x1B
-#define Mode_SYS 0x1F
-#define I_Bit 0x80 // when I bit is set, IRQ is disabled
-#define F_Bit 0x40 // when F bit is set, FIQ is disabled
-
-// MCU RAM
-#define LPC2460_RAM_ADDRESS 0x40000000 // RAM Base
-#define LPC2460_RAM_SIZE 0x10000 // 64KB
-
-// ISR Stack Allocation
-#define UND_stack_size 0x00000040
-#define SVC_stack_size 0x00000040
-#define ABT_stack_size 0x00000040
-#define FIQ_stack_size 0x00000000
-#define IRQ_stack_size 0x00000040
-
-#define ISR_stack_size (UND_stack_size + SVC_stack_size + ABT_stack_size + FIQ_stack_size + IRQ_stack_size)
-
-// Full Descending Stack, so top-most stack points to just above the top of RAM
-#define LPC2460_STACK_TOP (LPC2460_RAM_ADDRESS + LPC2460_RAM_SIZE)
-#define USR_STACK_TOP (LPC2460_STACK_TOP - ISR_stack_size)
-
-#endif
diff --git a/targets/TARGET_NXP/TARGET_LPC2460/device/vector_realmonitor.c b/targets/TARGET_NXP/TARGET_LPC2460/device/vector_realmonitor.c
deleted file mode 100644
index cb84e74c08..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC2460/device/vector_realmonitor.c
+++ /dev/null
@@ -1,22 +0,0 @@
-/* mbed Microcontroller Library - RealMonitor
- * Copyright (c) 2006-2015 ARM Limited. All rights reserved.
- */
-#include "vector_defns.h"
-
-extern void __mbed_dcc_irq(void);
-
-/* Function: __mbed_init_realmonitor
- * Setup the RealMonitor DCC Interrupt Handlers
- */
-void __mbed_init_realmonitor(void) __attribute__((weak));
-void __mbed_init_realmonitor() {
- // Disable all interrupts
- VICIntEnClr = 0xffffffff;
-
- // Set DCC interrupt vector addresses
- VICVectAddr2 = (unsigned)&__mbed_dcc_irq;
- VICVectAddr3 = (unsigned)&__mbed_dcc_irq;
-
- // Initialise RealMonitor
- ((void (*)(void))rm_init_entry)();
-}
diff --git a/targets/TARGET_NXP/TARGET_LPC2460/ethernet_api.c b/targets/TARGET_NXP/TARGET_LPC2460/ethernet_api.c
deleted file mode 100644
index 793874c11b..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC2460/ethernet_api.c
+++ /dev/null
@@ -1,935 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2015 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-#include
-
-#include "ethernet_api.h"
-#include "cmsis.h"
-#include "mbed_interface.h"
-#include "mbed_toolchain.h"
-#include "mbed_error.h"
-
-#define NEW_LOGIC 0
-#define NEW_ETH_BUFFER 0
-
-#if NEW_ETH_BUFFER
-
-#define NUM_RX_FRAG 4 // Number of Rx Fragments (== packets)
-#define NUM_TX_FRAG 3 // Number of Tx Fragments (== packets)
-
-#define ETH_MAX_FLEN 1536 // Maximum Ethernet Frame Size
-#define ETH_FRAG_SIZE ETH_MAX_FLEN // Packet Fragment size (same as packet length)
-
-#else
-
-// Memfree calculation:
-// (16 * 1024) - ((2 * 4 * NUM_RX) + (2 * 4 * NUM_RX) + (0x300 * NUM_RX) +
-// (2 * 4 * NUM_TX) + (1 * 4 * NUM_TX) + (0x300 * NUM_TX)) = 8556
-/* EMAC Memory Buffer configuration for 16K Ethernet RAM. */
-#define NUM_RX_FRAG 4 /* Num.of RX Fragments 4*1536= 6.0kB */
-#define NUM_TX_FRAG 3 /* Num.of TX Fragments 3*1536= 4.6kB */
-//#define ETH_FRAG_SIZE 1536 /* Packet Fragment size 1536 Bytes */
-
-//#define ETH_MAX_FLEN 1536 /* Max. Ethernet Frame Size */
-#define ETH_FRAG_SIZE 0x300 /* Packet Fragment size 1536/2 Bytes */
-#define ETH_MAX_FLEN 0x300 /* Max. Ethernet Frame Size */
-
-const int ethernet_MTU_SIZE = 0x300;
-
-#endif
-
-#define ETHERNET_ADDR_SIZE 6
-
-PACKED struct RX_DESC_TypeDef { /* RX Descriptor struct */
- unsigned int Packet;
- unsigned int Ctrl;
-};
-typedef struct RX_DESC_TypeDef RX_DESC_TypeDef;
-
-PACKED struct RX_STAT_TypeDef { /* RX Status struct */
- unsigned int Info;
- unsigned int HashCRC;
-};
-typedef struct RX_STAT_TypeDef RX_STAT_TypeDef;
-
-PACKED struct TX_DESC_TypeDef { /* TX Descriptor struct */
- unsigned int Packet;
- unsigned int Ctrl;
-};
-typedef struct TX_DESC_TypeDef TX_DESC_TypeDef;
-
-PACKED struct TX_STAT_TypeDef { /* TX Status struct */
- unsigned int Info;
-};
-typedef struct TX_STAT_TypeDef TX_STAT_TypeDef;
-
-/* MAC Configuration Register 1 */
-#define MAC1_REC_EN 0x00000001 /* Receive Enable */
-#define MAC1_PASS_ALL 0x00000002 /* Pass All Receive Frames */
-#define MAC1_RX_FLOWC 0x00000004 /* RX Flow Control */
-#define MAC1_TX_FLOWC 0x00000008 /* TX Flow Control */
-#define MAC1_LOOPB 0x00000010 /* Loop Back Mode */
-#define MAC1_RES_TX 0x00000100 /* Reset TX Logic */
-#define MAC1_RES_MCS_TX 0x00000200 /* Reset MAC TX Control Sublayer */
-#define MAC1_RES_RX 0x00000400 /* Reset RX Logic */
-#define MAC1_RES_MCS_RX 0x00000800 /* Reset MAC RX Control Sublayer */
-#define MAC1_SIM_RES 0x00004000 /* Simulation Reset */
-#define MAC1_SOFT_RES 0x00008000 /* Soft Reset MAC */
-
-/* MAC Configuration Register 2 */
-#define MAC2_FULL_DUP 0x00000001 /* Full Duplex Mode */
-#define MAC2_FRM_LEN_CHK 0x00000002 /* Frame Length Checking */
-#define MAC2_HUGE_FRM_EN 0x00000004 /* Huge Frame Enable */
-#define MAC2_DLY_CRC 0x00000008 /* Delayed CRC Mode */
-#define MAC2_CRC_EN 0x00000010 /* Append CRC to every Frame */
-#define MAC2_PAD_EN 0x00000020 /* Pad all Short Frames */
-#define MAC2_VLAN_PAD_EN 0x00000040 /* VLAN Pad Enable */
-#define MAC2_ADET_PAD_EN 0x00000080 /* Auto Detect Pad Enable */
-#define MAC2_PPREAM_ENF 0x00000100 /* Pure Preamble Enforcement */
-#define MAC2_LPREAM_ENF 0x00000200 /* Long Preamble Enforcement */
-#define MAC2_NO_BACKOFF 0x00001000 /* No Backoff Algorithm */
-#define MAC2_BACK_PRESSURE 0x00002000 /* Backoff Presurre / No Backoff */
-#define MAC2_EXCESS_DEF 0x00004000 /* Excess Defer */
-
-/* Back-to-Back Inter-Packet-Gap Register */
-#define IPGT_FULL_DUP 0x00000015 /* Recommended value for Full Duplex */
-#define IPGT_HALF_DUP 0x00000012 /* Recommended value for Half Duplex */
-
-/* Non Back-to-Back Inter-Packet-Gap Register */
-#define IPGR_DEF 0x00000012 /* Recommended value */
-
-/* Collision Window/Retry Register */
-#define CLRT_DEF 0x0000370F /* Default value */
-
-/* PHY Support Register */
-#define SUPP_SPEED 0x00000100 /* Reduced MII Logic Current Speed */
-//#define SUPP_RES_RMII 0x00000800 /* Reset Reduced MII Logic */
-#define SUPP_RES_RMII 0x00000000 /* Reset Reduced MII Logic */
-
-/* Test Register */
-#define TEST_SHCUT_PQUANTA 0x00000001 /* Shortcut Pause Quanta */
-#define TEST_TST_PAUSE 0x00000002 /* Test Pause */
-#define TEST_TST_BACKP 0x00000004 /* Test Back Pressure */
-
-/* MII Management Configuration Register */
-#define MCFG_SCAN_INC 0x00000001 /* Scan Increment PHY Address */
-#define MCFG_SUPP_PREAM 0x00000002 /* Suppress Preamble */
-#define MCFG_CLK_SEL 0x0000003C /* Clock Select Mask */
-#define MCFG_RES_MII 0x00008000 /* Reset MII Management Hardware */
-
-/* MII Management Command Register */
-#define MCMD_READ 0x00000001 /* MII Read */
-#define MCMD_SCAN 0x00000002 /* MII Scan continuously */
-
-#define MII_WR_TOUT 0x00050000 /* MII Write timeout count */
-#define MII_RD_TOUT 0x00050000 /* MII Read timeout count */
-
-/* MII Management Address Register */
-#define MADR_REG_ADR 0x0000001F /* MII Register Address Mask */
-#define MADR_PHY_ADR 0x00001F00 /* PHY Address Mask */
-
-/* MII Management Indicators Register */
-#define MIND_BUSY 0x00000001 /* MII is Busy */
-#define MIND_SCAN 0x00000002 /* MII Scanning in Progress */
-#define MIND_NOT_VAL 0x00000004 /* MII Read Data not valid */
-#define MIND_MII_LINK_FAIL 0x00000008 /* MII Link Failed */
-
-/* Command Register */
-#define CR_RX_EN 0x00000001 /* Enable Receive */
-#define CR_TX_EN 0x00000002 /* Enable Transmit */
-#define CR_REG_RES 0x00000008 /* Reset Host Registers */
-#define CR_TX_RES 0x00000010 /* Reset Transmit Datapath */
-#define CR_RX_RES 0x00000020 /* Reset Receive Datapath */
-#define CR_PASS_RUNT_FRM 0x00000040 /* Pass Runt Frames */
-#define CR_PASS_RX_FILT 0x00000080 /* Pass RX Filter */
-#define CR_TX_FLOW_CTRL 0x00000100 /* TX Flow Control */
-#define CR_RMII 0x00000200 /* Reduced MII Interface */
-#define CR_FULL_DUP 0x00000400 /* Full Duplex */
-
-/* Status Register */
-#define SR_RX_EN 0x00000001 /* Enable Receive */
-#define SR_TX_EN 0x00000002 /* Enable Transmit */
-
-/* Transmit Status Vector 0 Register */
-#define TSV0_CRC_ERR 0x00000001 /* CRC error */
-#define TSV0_LEN_CHKERR 0x00000002 /* Length Check Error */
-#define TSV0_LEN_OUTRNG 0x00000004 /* Length Out of Range */
-#define TSV0_DONE 0x00000008 /* Tramsmission Completed */
-#define TSV0_MCAST 0x00000010 /* Multicast Destination */
-#define TSV0_BCAST 0x00000020 /* Broadcast Destination */
-#define TSV0_PKT_DEFER 0x00000040 /* Packet Deferred */
-#define TSV0_EXC_DEFER 0x00000080 /* Excessive Packet Deferral */
-#define TSV0_EXC_COLL 0x00000100 /* Excessive Collision */
-#define TSV0_LATE_COLL 0x00000200 /* Late Collision Occured */
-#define TSV0_GIANT 0x00000400 /* Giant Frame */
-#define TSV0_UNDERRUN 0x00000800 /* Buffer Underrun */
-#define TSV0_BYTES 0x0FFFF000 /* Total Bytes Transferred */
-#define TSV0_CTRL_FRAME 0x10000000 /* Control Frame */
-#define TSV0_PAUSE 0x20000000 /* Pause Frame */
-#define TSV0_BACK_PRESS 0x40000000 /* Backpressure Method Applied */
-#define TSV0_VLAN 0x80000000 /* VLAN Frame */
-
-/* Transmit Status Vector 1 Register */
-#define TSV1_BYTE_CNT 0x0000FFFF /* Transmit Byte Count */
-#define TSV1_COLL_CNT 0x000F0000 /* Transmit Collision Count */
-
-/* Receive Status Vector Register */
-#define RSV_BYTE_CNT 0x0000FFFF /* Receive Byte Count */
-#define RSV_PKT_IGNORED 0x00010000 /* Packet Previously Ignored */
-#define RSV_RXDV_SEEN 0x00020000 /* RXDV Event Previously Seen */
-#define RSV_CARR_SEEN 0x00040000 /* Carrier Event Previously Seen */
-#define RSV_REC_CODEV 0x00080000 /* Receive Code Violation */
-#define RSV_CRC_ERR 0x00100000 /* CRC Error */
-#define RSV_LEN_CHKERR 0x00200000 /* Length Check Error */
-#define RSV_LEN_OUTRNG 0x00400000 /* Length Out of Range */
-#define RSV_REC_OK 0x00800000 /* Frame Received OK */
-#define RSV_MCAST 0x01000000 /* Multicast Frame */
-#define RSV_BCAST 0x02000000 /* Broadcast Frame */
-#define RSV_DRIB_NIBB 0x04000000 /* Dribble Nibble */
-#define RSV_CTRL_FRAME 0x08000000 /* Control Frame */
-#define RSV_PAUSE 0x10000000 /* Pause Frame */
-#define RSV_UNSUPP_OPC 0x20000000 /* Unsupported Opcode */
-#define RSV_VLAN 0x40000000 /* VLAN Frame */
-
-/* Flow Control Counter Register */
-#define FCC_MIRR_CNT 0x0000FFFF /* Mirror Counter */
-#define FCC_PAUSE_TIM 0xFFFF0000 /* Pause Timer */
-
-/* Flow Control Status Register */
-#define FCS_MIRR_CNT 0x0000FFFF /* Mirror Counter Current */
-
-/* Receive Filter Control Register */
-#define RFC_UCAST_EN 0x00000001 /* Accept Unicast Frames Enable */
-#define RFC_BCAST_EN 0x00000002 /* Accept Broadcast Frames Enable */
-#define RFC_MCAST_EN 0x00000004 /* Accept Multicast Frames Enable */
-#define RFC_UCAST_HASH_EN 0x00000008 /* Accept Unicast Hash Filter Frames */
-#define RFC_MCAST_HASH_EN 0x00000010 /* Accept Multicast Hash Filter Fram.*/
-#define RFC_PERFECT_EN 0x00000020 /* Accept Perfect Match Enable */
-#define RFC_MAGP_WOL_EN 0x00001000 /* Magic Packet Filter WoL Enable */
-#define RFC_PFILT_WOL_EN 0x00002000 /* Perfect Filter WoL Enable */
-
-/* Receive Filter WoL Status/Clear Registers */
-#define WOL_UCAST 0x00000001 /* Unicast Frame caused WoL */
-#define WOL_BCAST 0x00000002 /* Broadcast Frame caused WoL */
-#define WOL_MCAST 0x00000004 /* Multicast Frame caused WoL */
-#define WOL_UCAST_HASH 0x00000008 /* Unicast Hash Filter Frame WoL */
-#define WOL_MCAST_HASH 0x00000010 /* Multicast Hash Filter Frame WoL */
-#define WOL_PERFECT 0x00000020 /* Perfect Filter WoL */
-#define WOL_RX_FILTER 0x00000080 /* RX Filter caused WoL */
-#define WOL_MAG_PACKET 0x00000100 /* Magic Packet Filter caused WoL */
-
-/* Interrupt Status/Enable/Clear/Set Registers */
-#define INT_RX_OVERRUN 0x00000001 /* Overrun Error in RX Queue */
-#define INT_RX_ERR 0x00000002 /* Receive Error */
-#define INT_RX_FIN 0x00000004 /* RX Finished Process Descriptors */
-#define INT_RX_DONE 0x00000008 /* Receive Done */
-#define INT_TX_UNDERRUN 0x00000010 /* Transmit Underrun */
-#define INT_TX_ERR 0x00000020 /* Transmit Error */
-#define INT_TX_FIN 0x00000040 /* TX Finished Process Descriptors */
-#define INT_TX_DONE 0x00000080 /* Transmit Done */
-#define INT_SOFT_INT 0x00001000 /* Software Triggered Interrupt */
-#define INT_WAKEUP 0x00002000 /* Wakeup Event Interrupt */
-
-/* Power Down Register */
-#define PD_POWER_DOWN 0x80000000 /* Power Down MAC */
-
-/* RX Descriptor Control Word */
-#define RCTRL_SIZE 0x000007FF /* Buffer size mask */
-#define RCTRL_INT 0x80000000 /* Generate RxDone Interrupt */
-
-/* RX Status Hash CRC Word */
-#define RHASH_SA 0x000001FF /* Hash CRC for Source Address */
-#define RHASH_DA 0x001FF000 /* Hash CRC for Destination Address */
-
-/* RX Status Information Word */
-#define RINFO_SIZE 0x000007FF /* Data size in bytes */
-#define RINFO_CTRL_FRAME 0x00040000 /* Control Frame */
-#define RINFO_VLAN 0x00080000 /* VLAN Frame */
-#define RINFO_FAIL_FILT 0x00100000 /* RX Filter Failed */
-#define RINFO_MCAST 0x00200000 /* Multicast Frame */
-#define RINFO_BCAST 0x00400000 /* Broadcast Frame */
-#define RINFO_CRC_ERR 0x00800000 /* CRC Error in Frame */
-#define RINFO_SYM_ERR 0x01000000 /* Symbol Error from PHY */
-#define RINFO_LEN_ERR 0x02000000 /* Length Error */
-#define RINFO_RANGE_ERR 0x04000000 /* Range Error (exceeded max. size) */
-#define RINFO_ALIGN_ERR 0x08000000 /* Alignment Error */
-#define RINFO_OVERRUN 0x10000000 /* Receive overrun */
-#define RINFO_NO_DESCR 0x20000000 /* No new Descriptor available */
-#define RINFO_LAST_FLAG 0x40000000 /* Last Fragment in Frame */
-#define RINFO_ERR 0x80000000 /* Error Occured (OR of all errors) */
-
-//#define RINFO_ERR_MASK (RINFO_FAIL_FILT | RINFO_CRC_ERR | RINFO_SYM_ERR | RINFO_LEN_ERR | RINFO_ALIGN_ERR | RINFO_OVERRUN)
-#define RINFO_ERR_MASK (RINFO_FAIL_FILT | RINFO_SYM_ERR | \
- RINFO_LEN_ERR | RINFO_ALIGN_ERR | RINFO_OVERRUN)
-
-
-/* TX Descriptor Control Word */
-#define TCTRL_SIZE 0x000007FF /* Size of data buffer in bytes */
-#define TCTRL_OVERRIDE 0x04000000 /* Override Default MAC Registers */
-#define TCTRL_HUGE 0x08000000 /* Enable Huge Frame */
-#define TCTRL_PAD 0x10000000 /* Pad short Frames to 64 bytes */
-#define TCTRL_CRC 0x20000000 /* Append a hardware CRC to Frame */
-#define TCTRL_LAST 0x40000000 /* Last Descriptor for TX Frame */
-#define TCTRL_INT 0x80000000 /* Generate TxDone Interrupt */
-
-/* TX Status Information Word */
-#define TINFO_COL_CNT 0x01E00000 /* Collision Count */
-#define TINFO_DEFER 0x02000000 /* Packet Deferred (not an error) */
-#define TINFO_EXCESS_DEF 0x04000000 /* Excessive Deferral */
-#define TINFO_EXCESS_COL 0x08000000 /* Excessive Collision */
-#define TINFO_LATE_COL 0x10000000 /* Late Collision Occured */
-#define TINFO_UNDERRUN 0x20000000 /* Transmit Underrun */
-#define TINFO_NO_DESCR 0x40000000 /* No new Descriptor available */
-#define TINFO_ERR 0x80000000 /* Error Occured (OR of all errors) */
-
-/* ENET Device Revision ID */
-#define OLD_EMAC_MODULE_ID 0x39022000 /* Rev. ID for first rev '-' */
-
-/* DP83848C PHY Registers */
-#define PHY_REG_BMCR 0x00 /* Basic Mode Control Register */
-#define PHY_REG_BMSR 0x01 /* Basic Mode Status Register */
-#define PHY_REG_IDR1 0x02 /* PHY Identifier 1 */
-#define PHY_REG_IDR2 0x03 /* PHY Identifier 2 */
-#define PHY_REG_ANAR 0x04 /* Auto-Negotiation Advertisement */
-#define PHY_REG_ANLPAR 0x05 /* Auto-Neg. Link Partner Abitily */
-#define PHY_REG_ANER 0x06 /* Auto-Neg. Expansion Register */
-#define PHY_REG_ANNPTR 0x07 /* Auto-Neg. Next Page TX */
-
-/* PHY Extended Registers */
-#define PHY_REG_STS 0x10 /* Status Register */
-#define PHY_REG_MICR 0x11 /* MII Interrupt Control Register */
-#define PHY_REG_MISR 0x12 /* MII Interrupt Status Register */
-#define PHY_REG_FCSCR 0x14 /* False Carrier Sense Counter */
-#define PHY_REG_RECR 0x15 /* Receive Error Counter */
-#define PHY_REG_PCSR 0x16 /* PCS Sublayer Config. and Status */
-#define PHY_REG_RBR 0x17 /* RMII and Bypass Register */
-#define PHY_REG_LEDCR 0x18 /* LED Direct Control Register */
-#define PHY_REG_PHYCR 0x19 /* PHY Control Register */
-#define PHY_REG_10BTSCR 0x1A /* 10Base-T Status/Control Register */
-#define PHY_REG_CDCTRL1 0x1B /* CD Test Control and BIST Extens. */
-#define PHY_REG_EDCR 0x1D /* Energy Detect Control Register */
-
-#define PHY_REG_SCSR 0x1F /* PHY Special Control/Status Register */
-
-#define PHY_FULLD_100M 0x2100 /* Full Duplex 100Mbit */
-#define PHY_HALFD_100M 0x2000 /* Half Duplex 100Mbit */
-#define PHY_FULLD_10M 0x0100 /* Full Duplex 10Mbit */
-#define PHY_HALFD_10M 0x0000 /* Half Duplex 10MBit */
-#define PHY_AUTO_NEG 0x3000 /* Select Auto Negotiation */
-
-#define DP83848C_DEF_ADR 0x0100 /* Default PHY device address */
-#define DP83848C_ID 0x20005C90 /* PHY Identifier - DP83848C */
-
-#define LAN8720_ID 0x0007C0F0 /* PHY Identifier - LAN8720 */
-
-#define PHY_STS_LINK 0x0001 /* PHY Status Link Mask */
-#define PHY_STS_SPEED 0x0002 /* PHY Status Speed Mask */
-#define PHY_STS_DUPLEX 0x0004 /* PHY Status Duplex Mask */
-
-#define PHY_BMCR_RESET 0x8000 /* PHY Reset */
-
-#define PHY_BMSR_LINK 0x0004 /* PHY BMSR Link valid */
-
-#define PHY_SCSR_100MBIT 0x0008 /* Speed: 1=100 MBit, 0=10Mbit */
-#define PHY_SCSR_DUPLEX 0x0010 /* PHY Duplex Mask */
-
-
-static int phy_read(unsigned int PhyReg);
-static int phy_write(unsigned int PhyReg, unsigned short Data);
-
-static void txdscr_init(void);
-static void rxdscr_init(void);
-
-#if defined (__ICCARM__)
-# define AHBSRAM1
-#elif defined(TOOLCHAIN_GCC_CR)
-# define AHBSRAM1 __attribute__((section(".data.$RamPeriph32")))
-#else
-# define AHBSRAM1 __attribute__((section("AHBSRAM1"),aligned))
-#endif
-
-AHBSRAM1 volatile uint8_t rxbuf[NUM_RX_FRAG][ETH_FRAG_SIZE];
-AHBSRAM1 volatile uint8_t txbuf[NUM_TX_FRAG][ETH_FRAG_SIZE];
-AHBSRAM1 volatile RX_DESC_TypeDef rxdesc[NUM_RX_FRAG];
-AHBSRAM1 volatile RX_STAT_TypeDef rxstat[NUM_RX_FRAG];
-AHBSRAM1 volatile TX_DESC_TypeDef txdesc[NUM_TX_FRAG];
-AHBSRAM1 volatile TX_STAT_TypeDef txstat[NUM_TX_FRAG];
-
-
-#if NEW_LOGIC
-static int rx_consume_offset = -1;
-static int tx_produce_offset = -1;
-#else
-static int send_doff = 0;
-static int send_idx = -1;
-static int send_size = 0;
-
-static int receive_soff = 0;
-static int receive_idx = -1;
-#endif
-
-static uint32_t phy_id = 0;
-
-static inline int rinc(int idx, int mod) {
- ++idx;
- idx %= mod;
- return idx;
-}
-
-//extern unsigned int SystemFrequency;
-static inline unsigned int clockselect() {
- if(SystemCoreClock < 10000000) {
- return 1;
- } else if(SystemCoreClock < 15000000) {
- return 2;
- } else if(SystemCoreClock < 20000000) {
- return 3;
- } else if(SystemCoreClock < 25000000) {
- return 4;
- } else if(SystemCoreClock < 35000000) {
- return 5;
- } else if(SystemCoreClock < 50000000) {
- return 6;
- } else if(SystemCoreClock < 70000000) {
- return 7;
- } else if(SystemCoreClock < 80000000) {
- return 8;
- } else if(SystemCoreClock < 90000000) {
- return 9;
- } else if(SystemCoreClock < 100000000) {
- return 10;
- } else if(SystemCoreClock < 120000000) {
- return 11;
- } else if(SystemCoreClock < 130000000) {
- return 12;
- } else if(SystemCoreClock < 140000000) {
- return 13;
- } else if(SystemCoreClock < 150000000) {
- return 15;
- } else if(SystemCoreClock < 160000000) {
- return 16;
- } else {
- return 0;
- }
-}
-
-#ifndef min
-#define min(x, y) (((x)<(y))?(x):(y))
-#endif
-
-/*----------------------------------------------------------------------------
- Ethernet Device initialize
- *----------------------------------------------------------------------------*/
-int ethernet_init() {
- int regv, tout;
- char mac[ETHERNET_ADDR_SIZE];
- unsigned int clock = clockselect();
-
- LPC_SC->PCONP |= 0x40000000; /* Power Up the EMAC controller. */
-
- LPC_PINCON->PINSEL2 = 0x50150105; /* Enable P1 Ethernet Pins. */
- LPC_PINCON->PINSEL3 = (LPC_PINCON->PINSEL3 & ~0x0000000F) | 0x00000005;
-
- /* Reset all EMAC internal modules. */
- LPC_EMAC->MAC1 = MAC1_RES_TX | MAC1_RES_MCS_TX | MAC1_RES_RX |
- MAC1_RES_MCS_RX | MAC1_SIM_RES | MAC1_SOFT_RES;
- LPC_EMAC->Command = CR_REG_RES | CR_TX_RES | CR_RX_RES | CR_PASS_RUNT_FRM;
-
- for(tout = 100; tout; tout--) __NOP(); /* A short delay after reset. */
-
- LPC_EMAC->MAC1 = MAC1_PASS_ALL; /* Initialize MAC control registers. */
- LPC_EMAC->MAC2 = MAC2_CRC_EN | MAC2_PAD_EN;
- LPC_EMAC->MAXF = ETH_MAX_FLEN;
- LPC_EMAC->CLRT = CLRT_DEF;
- LPC_EMAC->IPGR = IPGR_DEF;
-
- LPC_EMAC->Command = CR_RMII | CR_PASS_RUNT_FRM; /* Enable Reduced MII interface. */
-
- LPC_EMAC->MCFG = (clock << 0x2) & MCFG_CLK_SEL; /* Set clock */
- LPC_EMAC->MCFG |= MCFG_RES_MII; /* and reset */
-
- for(tout = 100; tout; tout--) __NOP(); /* A short delay */
-
- LPC_EMAC->MCFG = (clock << 0x2) & MCFG_CLK_SEL;
- LPC_EMAC->MCMD = 0;
-
- LPC_EMAC->SUPP = SUPP_RES_RMII; /* Reset Reduced MII Logic. */
-
- for (tout = 100; tout; tout--) __NOP(); /* A short delay */
-
- LPC_EMAC->SUPP = 0;
-
- phy_write(PHY_REG_BMCR, PHY_BMCR_RESET); /* perform PHY reset */
- for(tout = 0x20000; ; tout--) { /* Wait for hardware reset to end. */
- regv = phy_read(PHY_REG_BMCR);
- if(regv < 0 || tout == 0) {
- return -1; /* Error */
- }
- if(!(regv & PHY_BMCR_RESET)) {
- break; /* Reset complete. */
- }
- }
-
- phy_id = (phy_read(PHY_REG_IDR1) << 16);
- phy_id |= (phy_read(PHY_REG_IDR2) & 0XFFF0);
-
- if (phy_id != DP83848C_ID && phy_id != LAN8720_ID) {
- error("Unknown Ethernet PHY (%x)", (unsigned int)phy_id);
- }
-
- ethernet_set_link(-1, 0);
-
- /* Set the Ethernet MAC Address registers */
- ethernet_address(mac);
- LPC_EMAC->SA0 = ((uint32_t)mac[5] << 8) | (uint32_t)mac[4];
- LPC_EMAC->SA1 = ((uint32_t)mac[3] << 8) | (uint32_t)mac[2];
- LPC_EMAC->SA2 = ((uint32_t)mac[1] << 8) | (uint32_t)mac[0];
-
- txdscr_init(); /* initialize DMA TX Descriptor */
- rxdscr_init(); /* initialize DMA RX Descriptor */
-
- LPC_EMAC->RxFilterCtrl = RFC_UCAST_EN | RFC_MCAST_EN | RFC_BCAST_EN | RFC_PERFECT_EN;
- /* Receive Broadcast, Perfect Match Packets */
-
- LPC_EMAC->IntEnable = INT_RX_DONE | INT_TX_DONE; /* Enable EMAC interrupts. */
- LPC_EMAC->IntClear = 0xFFFF; /* Reset all interrupts */
-
-
- LPC_EMAC->Command |= (CR_RX_EN | CR_TX_EN); /* Enable receive and transmit mode of MAC Ethernet core */
- LPC_EMAC->MAC1 |= MAC1_REC_EN;
-
-#if NEW_LOGIC
- rx_consume_offset = -1;
- tx_produce_offset = -1;
-#else
- send_doff = 0;
- send_idx = -1;
- send_size = 0;
-
- receive_soff = 0;
- receive_idx = -1;
-#endif
-
- return 0;
-}
-
-/*----------------------------------------------------------------------------
- Ethernet Device Uninitialize
- *----------------------------------------------------------------------------*/
-void ethernet_free() {
- LPC_EMAC->IntEnable &= ~(INT_RX_DONE | INT_TX_DONE);
- LPC_EMAC->IntClear = 0xFFFF;
-
- LPC_SC->PCONP &= ~0x40000000; /* Power down the EMAC controller. */
-
- LPC_PINCON->PINSEL2 &= ~0x50150105; /* Disable P1 ethernet pins. */
- LPC_PINCON->PINSEL3 = (LPC_PINCON->PINSEL3 & ~0x0000000F) | 0x00000000;
-}
-
-// if(TxProduceIndex == TxConsumeIndex) buffer array is empty
-// if(TxProduceIndex == TxConsumeIndex - 1) buffer is full, should not fill
-// TxProduceIndex - The buffer that will/is being fileld by driver, s/w increment
-// TxConsumeIndex - The buffer that will/is beign sent by hardware
-
-int ethernet_write(const char *data, int slen) {
-
-#if NEW_LOGIC
-
- if(tx_produce_offset < 0) { // mark as active if not already
- tx_produce_offset = 0;
- }
-
- int index = LPC_EMAC->TxProduceIndex;
-
- int remaining = ETH_MAX_FLEN - tx_produce_offset - 4; // bytes written plus checksum
- int requested = slen;
- int ncopy = min(remaining, requested);
-
- void *pdst = (void *)(txdesc[index].Packet + tx_produce_offset);
- void *psrc = (void *)(data);
-
- if(ncopy > 0 ){
- if(data != NULL) {
- memcpy(pdst, psrc, ncopy);
- } else {
- memset(pdst, 0, ncopy);
- }
- }
-
- tx_produce_offset += ncopy;
-
- return ncopy;
-
-#else
- void *pdst, *psrc;
- const int dlen = ETH_FRAG_SIZE;
- int copy = 0;
- int soff = 0;
-
- if(send_idx == -1) {
- send_idx = LPC_EMAC->TxProduceIndex;
- }
-
- if(slen + send_doff > ethernet_MTU_SIZE) {
- return -1;
- }
-
- do {
- copy = min(slen - soff, dlen - send_doff);
- pdst = (void *)(txdesc[send_idx].Packet + send_doff);
- psrc = (void *)(data + soff);
- if(send_doff + copy > ETH_FRAG_SIZE) {
- txdesc[send_idx].Ctrl = (send_doff-1) | (TCTRL_INT);
- send_idx = rinc(send_idx, NUM_TX_FRAG);
- send_doff = 0;
- }
-
- if(data != NULL) {
- memcpy(pdst, psrc, copy);
- } else {
- memset(pdst, 0, copy);
- }
-
- soff += copy;
- send_doff += copy;
- send_size += copy;
- } while(soff != slen);
-
- return soff;
-#endif
-}
-
-int ethernet_send() {
-
-#if NEW_LOGIC
- if(tx_produce_offset < 0) { // no buffer active
- return -1;
- }
-
- // ensure there is a link
- if(!ethernet_link()) {
- return -2;
- }
-
- // we have been writing in to a buffer, so finalise it
- int size = tx_produce_offset;
- int index = LPC_EMAC->TxProduceIndex;
- txdesc[index].Ctrl = (tx_produce_offset-1) | (TCTRL_INT | TCTRL_LAST);
-
- // Increment ProduceIndex to allow it to be sent
- // We can only do this if the next slot is free
- int next = rinc(index, NUM_TX_FRAG);
- while(next == LPC_EMAC->TxConsumeIndex) {
- for(int i=0; i<1000; i++) { __NOP(); }
- }
-
- LPC_EMAC->TxProduceIndex = next;
- tx_produce_offset = -1;
- return size;
-
-#else
- int s = send_size;
- txdesc[send_idx].Ctrl = (send_doff-1) | (TCTRL_INT | TCTRL_LAST);
- send_idx = rinc(send_idx, NUM_TX_FRAG);
- LPC_EMAC->TxProduceIndex = send_idx;
- send_doff = 0;
- send_idx = -1;
- send_size = 0;
- return s;
-#endif
-}
-
-// RxConsmeIndex - The index of buffer the driver will/is reading from. Driver should inc once read
-// RxProduceIndex - The index of buffer that will/is being filled by MAC. H/w will inc once rxd
-//
-// if(RxConsumeIndex == RxProduceIndex) buffer array is empty
-// if(RxConsumeIndex == RxProduceIndex + 1) buffer array is full
-
-// Recevies an arrived ethernet packet.
-// Receiving an ethernet packet will drop the last received ethernet packet
-// and make a new ethernet packet ready to read.
-// Returns size of packet, else 0 if nothing to receive
-
-// We read from RxConsumeIndex from position rx_consume_offset
-// if rx_consume_offset < 0, then we have not recieved the RxConsumeIndex packet for reading
-// rx_consume_offset = -1 // no frame
-// rx_consume_offset = 0 // start of frame
-// Assumption: A fragment should alway be a whole frame
-
-int ethernet_receive() {
-#if NEW_LOGIC
-
- // if we are currently reading a valid RxConsume buffer, increment to the next one
- if(rx_consume_offset >= 0) {
- LPC_EMAC->RxConsumeIndex = rinc(LPC_EMAC->RxConsumeIndex, NUM_RX_FRAG);
- }
-
- // if the buffer is empty, mark it as no valid buffer
- if(LPC_EMAC->RxConsumeIndex == LPC_EMAC->RxProduceIndex) {
- rx_consume_offset = -1;
- return 0;
- }
-
- uint32_t info = rxstat[LPC_EMAC->RxConsumeIndex].Info;
- rx_consume_offset = 0;
-
- // check if it is not marked as last or for errors
- if(!(info & RINFO_LAST_FLAG) || (info & RINFO_ERR_MASK)) {
- return -1;
- }
-
- int size = (info & RINFO_SIZE) + 1;
- return size - 4; // don't include checksum bytes
-
-#else
- if(receive_idx == -1) {
- receive_idx = LPC_EMAC->RxConsumeIndex;
- } else {
- while(!(rxstat[receive_idx].Info & RINFO_LAST_FLAG) && ((uint32_t)receive_idx != LPC_EMAC->RxProduceIndex)) {
- receive_idx = rinc(receive_idx, NUM_RX_FRAG);
- }
- unsigned int info = rxstat[receive_idx].Info;
- int slen = (info & RINFO_SIZE) + 1;
-
- if(slen > ethernet_MTU_SIZE || (info & RINFO_ERR_MASK)) {
- /* Invalid frame, ignore it and free buffer. */
- receive_idx = rinc(receive_idx, NUM_RX_FRAG);
- }
- receive_idx = rinc(receive_idx, NUM_RX_FRAG);
- receive_soff = 0;
-
- LPC_EMAC->RxConsumeIndex = receive_idx;
- }
-
- if((uint32_t)receive_idx == LPC_EMAC->RxProduceIndex) {
- receive_idx = -1;
- return 0;
- }
-
- return (rxstat[receive_idx].Info & RINFO_SIZE) - 3;
-#endif
-}
-
-// Read from an recevied ethernet packet.
-// After receive returnd a number bigger than 0 it is
-// possible to read bytes from this packet.
-// Read will write up to size bytes into data.
-// It is possible to use read multible times.
-// Each time read will start reading after the last read byte before.
-
-int ethernet_read(char *data, int dlen) {
-#if NEW_LOGIC
- // Check we have a valid buffer to read
- if(rx_consume_offset < 0) {
- return 0;
- }
-
- // Assume 1 fragment block
- uint32_t info = rxstat[LPC_EMAC->RxConsumeIndex].Info;
- int size = (info & RINFO_SIZE) + 1 - 4; // exclude checksum
-
- int remaining = size - rx_consume_offset;
- int requested = dlen;
- int ncopy = min(remaining, requested);
-
- void *psrc = (void *)(rxdesc[LPC_EMAC->RxConsumeIndex].Packet + rx_consume_offset);
- void *pdst = (void *)(data);
-
- if(data != NULL && ncopy > 0) {
- memcpy(pdst, psrc, ncopy);
- }
-
- rx_consume_offset += ncopy;
-
- return ncopy;
-#else
- int slen;
- int copy = 0;
- unsigned int more;
- unsigned int info;
- void *pdst, *psrc;
- int doff = 0;
-
- if((uint32_t)receive_idx == LPC_EMAC->RxProduceIndex || receive_idx == -1) {
- return 0;
- }
-
- do {
- info = rxstat[receive_idx].Info;
- more = !(info & RINFO_LAST_FLAG);
- slen = (info & RINFO_SIZE) + 1;
-
- if(slen > ethernet_MTU_SIZE || (info & RINFO_ERR_MASK)) {
- /* Invalid frame, ignore it and free buffer. */
- receive_idx = rinc(receive_idx, NUM_RX_FRAG);
- } else {
-
- copy = min(slen - receive_soff, dlen - doff);
- psrc = (void *)(rxdesc[receive_idx].Packet + receive_soff);
- pdst = (void *)(data + doff);
-
- if(data != NULL) {
- /* check if Buffer available */
- memcpy(pdst, psrc, copy);
- }
-
- receive_soff += copy;
- doff += copy;
-
- if((more && (receive_soff == slen))) {
- receive_idx = rinc(receive_idx, NUM_RX_FRAG);
- receive_soff = 0;
- }
- }
- } while(more && !(doff == dlen) && !receive_soff);
-
- return doff;
-#endif
-}
-
-int ethernet_link(void) {
- if (phy_id == DP83848C_ID) {
- return (phy_read(PHY_REG_STS) & PHY_STS_LINK);
- }
- else { // LAN8720_ID
- return (phy_read(PHY_REG_BMSR) & PHY_BMSR_LINK);
- }
-}
-
-static int phy_write(unsigned int PhyReg, unsigned short Data) {
- unsigned int timeOut;
-
- LPC_EMAC->MADR = DP83848C_DEF_ADR | PhyReg;
- LPC_EMAC->MWTD = Data;
-
- for(timeOut = 0; timeOut < MII_WR_TOUT; timeOut++) { /* Wait until operation completed */
- if((LPC_EMAC->MIND & MIND_BUSY) == 0) {
- return 0;
- }
- }
-
- return -1;
-}
-
-static int phy_read(unsigned int PhyReg) {
- unsigned int timeOut;
-
- LPC_EMAC->MADR = DP83848C_DEF_ADR | PhyReg;
- LPC_EMAC->MCMD = MCMD_READ;
-
- for(timeOut = 0; timeOut < MII_RD_TOUT; timeOut++) { /* Wait until operation completed */
- if((LPC_EMAC->MIND & MIND_BUSY) == 0) {
- LPC_EMAC->MCMD = 0;
- return LPC_EMAC->MRDD; /* Return a 16-bit value. */
- }
- }
-
- return -1;
-}
-
-
-static void txdscr_init() {
- int i;
-
- for(i = 0; i < NUM_TX_FRAG; i++) {
- txdesc[i].Packet = (uint32_t)&txbuf[i];
- txdesc[i].Ctrl = 0;
- txstat[i].Info = 0;
- }
-
- LPC_EMAC->TxDescriptor = (uint32_t)txdesc; /* Set EMAC Transmit Descriptor Registers. */
- LPC_EMAC->TxStatus = (uint32_t)txstat;
- LPC_EMAC->TxDescriptorNumber = NUM_TX_FRAG-1;
-
- LPC_EMAC->TxProduceIndex = 0; /* Tx Descriptors Point to 0 */
-}
-
-static void rxdscr_init() {
- int i;
-
- for(i = 0; i < NUM_RX_FRAG; i++) {
- rxdesc[i].Packet = (uint32_t)&rxbuf[i];
- rxdesc[i].Ctrl = RCTRL_INT | (ETH_FRAG_SIZE-1);
- rxstat[i].Info = 0;
- rxstat[i].HashCRC = 0;
- }
-
- LPC_EMAC->RxDescriptor = (uint32_t)rxdesc; /* Set EMAC Receive Descriptor Registers. */
- LPC_EMAC->RxStatus = (uint32_t)rxstat;
- LPC_EMAC->RxDescriptorNumber = NUM_RX_FRAG-1;
-
- LPC_EMAC->RxConsumeIndex = 0; /* Rx Descriptors Point to 0 */
-}
-
-void ethernet_address(char *mac) {
- mbed_mac_address(mac);
-}
-
-void ethernet_set_link(int speed, int duplex) {
- unsigned short phy_data;
- int tout;
-
- if((speed < 0) || (speed > 1)) {
- phy_data = PHY_AUTO_NEG;
- } else {
- phy_data = (((unsigned short) speed << 13) |
- ((unsigned short) duplex << 8));
- }
-
- phy_write(PHY_REG_BMCR, phy_data);
-
- for(tout = 100; tout; tout--) { __NOP(); } /* A short delay */
-
- switch(phy_id) {
- case DP83848C_ID:
- phy_data = phy_read(PHY_REG_STS);
-
- if(phy_data & PHY_STS_DUPLEX) {
- LPC_EMAC->MAC2 |= MAC2_FULL_DUP;
- LPC_EMAC->Command |= CR_FULL_DUP;
- LPC_EMAC->IPGT = IPGT_FULL_DUP;
- } else {
- LPC_EMAC->MAC2 &= ~MAC2_FULL_DUP;
- LPC_EMAC->Command &= ~CR_FULL_DUP;
- LPC_EMAC->IPGT = IPGT_HALF_DUP;
- }
-
- if(phy_data & PHY_STS_SPEED) {
- LPC_EMAC->SUPP &= ~SUPP_SPEED;
- } else {
- LPC_EMAC->SUPP |= SUPP_SPEED;
- }
- break;
-
- case LAN8720_ID:
- phy_data = phy_read(PHY_REG_SCSR);
-
- if (phy_data & PHY_SCSR_DUPLEX) {
- LPC_EMAC->MAC2 |= MAC2_FULL_DUP;
- LPC_EMAC->Command |= CR_FULL_DUP;
- LPC_EMAC->IPGT = IPGT_FULL_DUP;
- } else {
- LPC_EMAC->Command &= ~CR_FULL_DUP;
- LPC_EMAC->IPGT = IPGT_HALF_DUP;
- }
-
- if(phy_data & PHY_SCSR_100MBIT) {
- LPC_EMAC->SUPP |= SUPP_SPEED;
- } else {
- LPC_EMAC->SUPP &= ~SUPP_SPEED;
- }
- break;
- }
-}
diff --git a/targets/TARGET_NXP/TARGET_LPC2460/gpio_api.c b/targets/TARGET_NXP/TARGET_LPC2460/gpio_api.c
deleted file mode 100644
index 425274fbba..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC2460/gpio_api.c
+++ /dev/null
@@ -1,57 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2015 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-#include "mbed_assert.h"
-#include "gpio_api.h"
-#include "pinmap.h"
-
-uint32_t gpio_set(PinName pin) {
- LPC_SC->SCS |= 1; // High speed GPIO is enabled on ports 0 and 1
-
- pin_function(pin, 0);
-
- return (1 << ((int)pin & 0x1F));
-}
-
-void gpio_init(gpio_t *obj, PinName pin) {
- if (pin == (PinName)NC)
- return;
- obj->pin = pin;
- if (pin == (PinName)NC)
- return;
-
- obj->mask = gpio_set(pin);
-
- LPC_GPIO_TypeDef *port_reg = (LPC_GPIO_TypeDef *) ((int)pin & ~0x1F);
-
- obj->reg_set = &port_reg->FIOSET;
- obj->reg_mask = &port_reg->FIOMASK;
- obj->reg_clr = &port_reg->FIOCLR;
- obj->reg_in = &port_reg->FIOPIN;
- obj->reg_dir = &port_reg->FIODIR;
-}
-
-void gpio_mode(gpio_t *obj, PinMode mode) {
- pin_mode(obj->pin, mode);
-}
-
-void gpio_dir(gpio_t *obj, PinDirection direction) {
- if (obj->pin == (PinName)NC)
- return;
- switch (direction) {
- case PIN_INPUT : *obj->reg_dir &= ~obj->mask; break;
- case PIN_OUTPUT: *obj->reg_dir |= obj->mask; break;
- }
-}
diff --git a/targets/TARGET_NXP/TARGET_LPC2460/gpio_irq_api.c b/targets/TARGET_NXP/TARGET_LPC2460/gpio_irq_api.c
deleted file mode 100644
index 9b4f3ae62e..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC2460/gpio_irq_api.c
+++ /dev/null
@@ -1,154 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2015 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-#include "gpio_irq_api.h"
-#include "mbed_error.h"
-#include
-#include "cmsis.h"
-
-#define CHANNEL_NUM 48
-
-static uint32_t channel_ids[CHANNEL_NUM] = {0};
-static gpio_irq_handler irq_handler;
-
-static void handle_interrupt_in(void) {
- // Read in all current interrupt registers. We do this once as the
- // GPIO interrupt registers are on the APB bus, and this is slow.
- uint32_t rise0 = LPC_GPIOINT->IO0IntStatR;
- uint32_t fall0 = LPC_GPIOINT->IO0IntStatF;
- uint32_t rise2 = LPC_GPIOINT->IO2IntStatR;
- uint32_t fall2 = LPC_GPIOINT->IO2IntStatF;
- uint32_t mask0 = 0;
- uint32_t mask2 = 0;
- int i;
-
- // P0.0-0.31
- for (i = 0; i < 32; i++) {
- uint32_t pmask = (1 << i);
- if (rise0 & pmask) {
- mask0 |= pmask;
- if (channel_ids[i] != 0)
- irq_handler(channel_ids[i], IRQ_RISE);
- }
- if (fall0 & pmask) {
- mask0 |= pmask;
- if (channel_ids[i] != 0)
- irq_handler(channel_ids[i], IRQ_FALL);
- }
- }
-
- // P2.0-2.15
- for (i = 0; i < 16; i++) {
- uint32_t pmask = (1 << i);
- int channel_index = i + 32;
- if (rise2 & pmask) {
- mask2 |= pmask;
- if (channel_ids[channel_index] != 0)
- irq_handler(channel_ids[channel_index], IRQ_RISE);
- }
- if (fall2 & pmask) {
- mask2 |= pmask;
- if (channel_ids[channel_index] != 0)
- irq_handler(channel_ids[channel_index], IRQ_FALL);
- }
- }
-
- // Clear the interrupts we just handled
- LPC_GPIOINT->IO0IntClr = mask0;
- LPC_GPIOINT->IO2IntClr = mask2;
-}
-
-int gpio_irq_init(gpio_irq_t *obj, PinName pin, gpio_irq_handler handler, uint32_t id) {
- if (pin == NC) return -1;
-
- irq_handler = handler;
-
- obj->port = (int)pin & ~0x1F;
- obj->pin = (int)pin & 0x1F;
-
- // Interrupts available only on GPIO0 and GPIO2
- if (obj->port != LPC_GPIO0_BASE && obj->port != LPC_GPIO2_BASE) {
- error("pins on this port cannot generate interrupts");
- }
-
- // put us in the interrupt table
- int index = (obj->port == LPC_GPIO0_BASE) ? obj->pin : obj->pin + 32;
- channel_ids[index] = id;
- obj->ch = index;
-
- NVIC_SetVector(EINT3_IRQn, (uint32_t)handle_interrupt_in);
- NVIC_EnableIRQ(EINT3_IRQn);
-
- return 0;
-}
-
-void gpio_irq_free(gpio_irq_t *obj) {
- channel_ids[obj->ch] = 0;
-}
-
-void gpio_irq_set(gpio_irq_t *obj, gpio_irq_event event, uint32_t enable) {
- // ensure nothing is pending
- switch (obj->port) {
- case LPC_GPIO0_BASE: LPC_GPIOINT->IO0IntClr = 1 << obj->pin; break;
- case LPC_GPIO2_BASE: LPC_GPIOINT->IO2IntClr = 1 << obj->pin; break;
- }
-
- // enable the pin interrupt
- if (event == IRQ_RISE) {
- switch (obj->port) {
- case LPC_GPIO0_BASE:
- if (enable) {
- LPC_GPIOINT->IO0IntEnR |= 1 << obj->pin;
- } else {
- LPC_GPIOINT->IO0IntEnR &= ~(1 << obj->pin);
- }
- break;
- case LPC_GPIO2_BASE:
- if (enable) {
- LPC_GPIOINT->IO2IntEnR |= 1 << obj->pin;
- } else {
- LPC_GPIOINT->IO2IntEnR &= ~(1 << obj->pin);
- }
- break;
- }
- } else {
- switch (obj->port) {
- case LPC_GPIO0_BASE:
- if (enable) {
- LPC_GPIOINT->IO0IntEnF |= 1 << obj->pin;
- } else {
- LPC_GPIOINT->IO0IntEnF &= ~(1 << obj->pin);
- }
- break;
-
- case LPC_GPIO2_BASE:
- if (enable) {
- LPC_GPIOINT->IO2IntEnF |= 1 << obj->pin;
- } else {
- LPC_GPIOINT->IO2IntEnF &= ~(1 << obj->pin);
- }
- break;
- }
- }
-}
-
-void gpio_irq_enable(gpio_irq_t *obj) {
- NVIC_EnableIRQ(EINT3_IRQn);
-}
-
-void gpio_irq_disable(gpio_irq_t *obj) {
- NVIC_DisableIRQ(EINT3_IRQn);
-}
-
diff --git a/targets/TARGET_NXP/TARGET_LPC2460/gpio_object.h b/targets/TARGET_NXP/TARGET_LPC2460/gpio_object.h
deleted file mode 100644
index 21b99e5e31..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC2460/gpio_object.h
+++ /dev/null
@@ -1,59 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2015 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-#ifndef MBED_GPIO_OBJECT_H
-#define MBED_GPIO_OBJECT_H
-
-#include "mbed_assert.h"
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-typedef struct {
- PinName pin;
- uint32_t mask;
-
- __IO uint32_t *reg_dir;
- __IO uint32_t *reg_mask;
- __IO uint32_t *reg_set;
- __IO uint32_t *reg_clr;
- __I uint32_t *reg_in;
-} gpio_t;
-
-static inline void gpio_write(gpio_t *obj, int value) {
- MBED_ASSERT(obj->pin != (PinName)NC);
- *obj->reg_mask &= ~obj->mask;
- if (value)
- *obj->reg_set = obj->mask;
- else
- *obj->reg_clr = obj->mask;
-}
-
-static inline int gpio_read(gpio_t *obj) {
- MBED_ASSERT(obj->pin != (PinName)NC);
- *obj->reg_mask &= ~obj->mask;
- return ((*obj->reg_in & obj->mask) ? 1 : 0);
-}
-
-static inline int gpio_is_connected(const gpio_t *obj) {
- return obj->pin != (PinName)NC;
-}
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif
diff --git a/targets/TARGET_NXP/TARGET_LPC2460/i2c_api.c b/targets/TARGET_NXP/TARGET_LPC2460/i2c_api.c
deleted file mode 100644
index e497eea83a..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC2460/i2c_api.c
+++ /dev/null
@@ -1,405 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2015 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-#include "i2c_api.h"
-#include "cmsis.h"
-#include "pinmap.h"
-
-static const PinMap PinMap_I2C_SDA[] = {
- {P0_0 , I2C_1, 3},
- {P0_10, I2C_2, 2},
- {P0_19, I2C_1, 3},
- {P0_27, I2C_0, 1},
- {P2_14, I2C_1, 3},
- {P2_30, I2C_2, 3},
- {P4_20, I2C_2, 2},
- {NC , NC , 0}
-};
-
-static const PinMap PinMap_I2C_SCL[] = {
- {P0_1 , I2C_1, 3},
- {P0_11, I2C_2, 2},
- {P0_20, I2C_1, 3},
- {P0_28, I2C_0, 1},
- {P2_15, I2C_1, 3},
- {P2_31, I2C_2, 3},
- {P4_21, I2C_2, 2},
- {NC , NC, 0}
-};
-
-#define I2C_CONSET(x) (x->i2c->I2CONSET)
-#define I2C_CONCLR(x) (x->i2c->I2CONCLR)
-#define I2C_STAT(x) (x->i2c->I2STAT)
-#define I2C_DAT(x) (x->i2c->I2DAT)
-#define I2C_SCLL(x, val) (x->i2c->I2SCLL = val)
-#define I2C_SCLH(x, val) (x->i2c->I2SCLH = val)
-
-static const uint32_t I2C_addr_offset[2][4] = {
- {0x0C, 0x20, 0x24, 0x28},
- {0x30, 0x34, 0x38, 0x3C}
-};
-
-static inline void i2c_conclr(i2c_t *obj, int start, int stop, int interrupt, int acknowledge) {
- I2C_CONCLR(obj) = (start << 5)
- | (stop << 4)
- | (interrupt << 3)
- | (acknowledge << 2);
-}
-
-static inline void i2c_conset(i2c_t *obj, int start, int stop, int interrupt, int acknowledge) {
- I2C_CONSET(obj) = (start << 5)
- | (stop << 4)
- | (interrupt << 3)
- | (acknowledge << 2);
-}
-
-// Clear the Serial Interrupt (SI)
-static inline void i2c_clear_SI(i2c_t *obj) {
- i2c_conclr(obj, 0, 0, 1, 0);
-}
-
-static inline int i2c_status(i2c_t *obj) {
- return I2C_STAT(obj);
-}
-
-// Wait until the Serial Interrupt (SI) is set
-static int i2c_wait_SI(i2c_t *obj) {
- int timeout = 0;
- while (!(I2C_CONSET(obj) & (1 << 3))) {
- timeout++;
- if (timeout > 100000) return -1;
- }
- return 0;
-}
-
-static inline void i2c_interface_enable(i2c_t *obj) {
- I2C_CONSET(obj) = 0x40;
-}
-
-static inline void i2c_power_enable(i2c_t *obj) {
- switch ((int)obj->i2c) {
- case I2C_0: LPC_SC->PCONP |= 1 << PCI2C0; break;
- case I2C_1: LPC_SC->PCONP |= 1 << PCI2C1; break;
- case I2C_2: LPC_SC->PCONP |= 1 << PCI2C2; break;
- }
-}
-
-void i2c_init(i2c_t *obj, PinName sda, PinName scl) {
- // determine the SPI to use
- I2CName i2c_sda = (I2CName)pinmap_peripheral(sda, PinMap_I2C_SDA);
- I2CName i2c_scl = (I2CName)pinmap_peripheral(scl, PinMap_I2C_SCL);
- obj->i2c = (LPC_I2C_TypeDef *)pinmap_merge(i2c_sda, i2c_scl);
- MBED_ASSERT((int)obj->i2c != NC);
-
- // enable power
- i2c_power_enable(obj);
-
- // set default frequency at 100k
- i2c_frequency(obj, 100000);
- i2c_conclr(obj, 1, 1, 1, 1);
- i2c_interface_enable(obj);
-
- pinmap_pinout(sda, PinMap_I2C_SDA);
- pinmap_pinout(scl, PinMap_I2C_SCL);
-}
-
-inline int i2c_start(i2c_t *obj) {
- int status = 0;
- int isInterrupted = I2C_CONSET(obj) & (1 << 3);
-
- // 8.1 Before master mode can be entered, I2CON must be initialised to:
- // - I2EN STA STO SI AA - -
- // - 1 0 0 x x - -
- // if AA = 0, it can't enter slave mode
- i2c_conclr(obj, 1, 1, 0, 1);
-
- // The master mode may now be entered by setting the STA bit
- // this will generate a start condition when the bus becomes free
- i2c_conset(obj, 1, 0, 0, 1);
- // Clearing SI bit when it wasn't set on entry can jump past state
- // 0x10 or 0x08 and erroneously send uninitialized slave address.
- if (isInterrupted)
- i2c_clear_SI(obj);
-
- i2c_wait_SI(obj);
- status = i2c_status(obj);
-
- // Clear start bit now that it's transmitted
- i2c_conclr(obj, 1, 0, 0, 0);
- return status;
-}
-
-inline int i2c_stop(i2c_t *obj) {
- int timeout = 0;
-
- // write the stop bit
- i2c_conset(obj, 0, 1, 0, 0);
- i2c_clear_SI(obj);
-
- // wait for STO bit to reset
- while (I2C_CONSET(obj) & (1 << 4)) {
- timeout ++;
- if (timeout > 100000) return 1;
- }
-
- return 0;
-}
-
-static inline int i2c_do_write(i2c_t *obj, int value, uint8_t addr) {
- // write the data
- I2C_DAT(obj) = value;
-
- // clear SI to init a send
- i2c_clear_SI(obj);
-
- // wait and return status
- i2c_wait_SI(obj);
- return i2c_status(obj);
-}
-
-static inline int i2c_do_read(i2c_t *obj, int last) {
- // we are in state 0x40 (SLA+R tx'd) or 0x50 (data rx'd and ack)
- if (last) {
- i2c_conclr(obj, 0, 0, 0, 1); // send a NOT ACK
- } else {
- i2c_conset(obj, 0, 0, 0, 1); // send a ACK
- }
-
- // accept byte
- i2c_clear_SI(obj);
-
- // wait for it to arrive
- i2c_wait_SI(obj);
-
- // return the data
- return (I2C_DAT(obj) & 0xFF);
-}
-
-void i2c_frequency(i2c_t *obj, int hz) {
- // [TODO] set pclk to /4
- uint32_t PCLK = SystemCoreClock / 4;
-
- uint32_t pulse = PCLK / (hz * 2);
-
- // I2C Rate
- I2C_SCLL(obj, pulse);
- I2C_SCLH(obj, pulse);
-}
-
-// The I2C does a read or a write as a whole operation
-// There are two types of error conditions it can encounter
-// 1) it can not obtain the bus
-// 2) it gets error responses at part of the transmission
-//
-// We tackle them as follows:
-// 1) we retry until we get the bus. we could have a "timeout" if we can not get it
-// which basically turns it in to a 2)
-// 2) on error, we use the standard error mechanisms to report/debug
-//
-// Therefore an I2C transaction should always complete. If it doesn't it is usually
-// because something is setup wrong (e.g. wiring), and we don't need to programatically
-// check for that
-int i2c_read(i2c_t *obj, int address, char *data, int length, int stop) {
- int count, status;
-
- status = i2c_start(obj);
-
- if ((status != 0x10) && (status != 0x08)) {
- i2c_stop(obj);
- return I2C_ERROR_BUS_BUSY;
- }
-
- status = i2c_do_write(obj, (address | 0x01), 1);
- if (status != 0x40) {
- i2c_stop(obj);
- return I2C_ERROR_NO_SLAVE;
- }
-
- // Read in all except last byte
- for (count = 0; count < (length - 1); count++) {
- int value = i2c_do_read(obj, 0);
- status = i2c_status(obj);
- if (status != 0x50) {
- i2c_stop(obj);
- return count;
- }
- data[count] = (char) value;
- }
-
- // read in last byte
- int value = i2c_do_read(obj, 1);
- status = i2c_status(obj);
- if (status != 0x58) {
- i2c_stop(obj);
- return length - 1;
- }
-
- data[count] = (char) value;
-
- // If not repeated start, send stop.
- if (stop) {
- i2c_stop(obj);
- }
-
- return length;
-}
-
-int i2c_write(i2c_t *obj, int address, const char *data, int length, int stop) {
- int i, status;
-
- status = i2c_start(obj);
-
- if ((status != 0x10) && (status != 0x08)) {
- i2c_stop(obj);
- return I2C_ERROR_BUS_BUSY;
- }
-
- status = i2c_do_write(obj, (address & 0xFE), 1);
- if (status != 0x18) {
- i2c_stop(obj);
- return I2C_ERROR_NO_SLAVE;
- }
-
- for (i=0; i= 0) && (idx <= 3)) {
- addr = ((uint32_t)obj->i2c) + I2C_addr_offset[0][idx];
- *((uint32_t *) addr) = address & 0xFF;
- }
-}
diff --git a/targets/TARGET_NXP/TARGET_LPC2460/objects.h b/targets/TARGET_NXP/TARGET_LPC2460/objects.h
deleted file mode 100644
index 157e44a357..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC2460/objects.h
+++ /dev/null
@@ -1,78 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2015 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-#ifndef MBED_OBJECTS_H
-#define MBED_OBJECTS_H
-
-#include "cmsis.h"
-#include "PortNames.h"
-#include "PeripheralNames.h"
-#include "PinNames.h"
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-struct gpio_irq_s {
- uint32_t port;
- uint32_t pin;
- uint32_t ch;
-};
-
-struct port_s {
- __IO uint32_t *reg_dir;
- __IO uint32_t *reg_out;
- __I uint32_t *reg_in;
- PortName port;
- uint32_t mask;
-};
-
-struct pwmout_s {
- __IO uint32_t *MR;
- PWMName pwm;
-};
-
-struct serial_s {
- LPC_UART_TypeDef *uart;
- int index;
-};
-
-struct analogin_s {
- ADCName adc;
-};
-
-struct dac_s {
- DACName dac;
-};
-
-struct can_s {
- LPC_CAN_TypeDef *dev;
-};
-
-struct i2c_s {
- LPC_I2C_TypeDef *i2c;
-};
-
-struct spi_s {
- LPC_SSP_TypeDef *spi;
-};
-
-#include "gpio_object.h"
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif
diff --git a/targets/TARGET_NXP/TARGET_LPC2460/pinmap.c b/targets/TARGET_NXP/TARGET_LPC2460/pinmap.c
deleted file mode 100644
index 2327928978..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC2460/pinmap.c
+++ /dev/null
@@ -1,46 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2015 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-#include "mbed_assert.h"
-#include "pinmap.h"
-#include "mbed_error.h"
-
-void pin_function(PinName pin, int function) {
- MBED_ASSERT(pin != (PinName)NC);
-
- uint32_t pin_number = (uint32_t)pin - (uint32_t)P0_0;
- int index = pin_number >> 4;
- int offset = (pin_number & 0xF) << 1;
-
- PINCONARRAY->PINSEL[index] &= ~(0x3 << offset);
- PINCONARRAY->PINSEL[index] |= function << offset;
-}
-
-void pin_mode(PinName pin, PinMode mode) {
- MBED_ASSERT((pin != (PinName)NC) && (mode != OpenDrain));
-
- uint32_t pin_number = (uint32_t)pin - (uint32_t)P0_0;
- int index = pin_number >> 5;
- int offset = pin_number & 0x1F;
- uint32_t drain = ((uint32_t) mode & (uint32_t) OpenDrain) >> 2;
-
- if (!drain) {
- index = pin_number >> 4;
- offset = (pin_number & 0xF) << 1;
-
- PINCONARRAY->PINMODE[index] &= ~(0x3 << offset);
- PINCONARRAY->PINMODE[index] |= (uint32_t)mode << offset;
- }
-}
diff --git a/targets/TARGET_NXP/TARGET_LPC2460/port_api.c b/targets/TARGET_NXP/TARGET_LPC2460/port_api.c
deleted file mode 100644
index da9aa4f5ca..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC2460/port_api.c
+++ /dev/null
@@ -1,71 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2015 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-#include "port_api.h"
-#include "pinmap.h"
-#include "gpio_api.h"
-
-PinName port_pin(PortName port, int pin_n) {
- return (PinName)(LPC_GPIO0_BASE + ((port << PORT_SHIFT) | pin_n));
-}
-
-void port_init(port_t *obj, PortName port, int mask, PinDirection dir) {
- obj->port = port;
- obj->mask = mask;
-
- LPC_GPIO_TypeDef *port_reg = (LPC_GPIO_TypeDef *)(LPC_GPIO0_BASE + ((int)port * 0x20));
-
- // Do not use masking, because it prevents the use of the unmasked pins
- // port_reg->FIOMASK = ~mask;
-
- obj->reg_out = &port_reg->FIOPIN;
- obj->reg_in = &port_reg->FIOPIN;
- obj->reg_dir = &port_reg->FIODIR;
-
- uint32_t i;
- // The function is set per pin: reuse gpio logic
- for (i=0; i<32; i++) {
- if (obj->mask & (1<port, i));
- }
- }
-
- port_dir(obj, dir);
-}
-
-void port_mode(port_t *obj, PinMode mode) {
- uint32_t i;
- // The mode is set per pin: reuse pinmap logic
- for (i=0; i<32; i++) {
- if (obj->mask & (1<port, i), mode);
- }
- }
-}
-
-void port_dir(port_t *obj, PinDirection dir) {
- switch (dir) {
- case PIN_INPUT : *obj->reg_dir &= ~obj->mask; break;
- case PIN_OUTPUT: *obj->reg_dir |= obj->mask; break;
- }
-}
-
-void port_write(port_t *obj, int value) {
- *obj->reg_out = (*obj->reg_in & ~obj->mask) | (value & obj->mask);
-}
-
-int port_read(port_t *obj) {
- return (*obj->reg_in & obj->mask);
-}
diff --git a/targets/TARGET_NXP/TARGET_LPC2460/pwmout_api.c b/targets/TARGET_NXP/TARGET_LPC2460/pwmout_api.c
deleted file mode 100644
index 0ce7138f58..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC2460/pwmout_api.c
+++ /dev/null
@@ -1,175 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2015 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-#include "mbed_assert.h"
-#include "pwmout_api.h"
-#include "cmsis.h"
-#include "pinmap.h"
-
-#define TCR_CNT_EN 0x00000001
-#define TCR_RESET 0x00000002
-
-// PORT ID, PWM ID, Pin function
-static const PinMap PinMap_PWM[] = {
- {P1_18, PWM_1, 2},
- {P1_20, PWM_2, 2},
- {P1_21, PWM_3, 2},
- {P1_23, PWM_4, 2},
- {P1_24, PWM_5, 2},
- {P1_26, PWM_6, 2},
- {P2_0 , PWM_1, 1},
- {P2_1 , PWM_2, 1},
- {P2_2 , PWM_3, 1},
- {P2_3 , PWM_4, 1},
- {P2_4 , PWM_5, 1},
- {P2_5 , PWM_6, 1},
- {P3_24, PWM_1, 3},
- {P3_25, PWM_2, 3},
- {P3_26, PWM_3, 3},
- {P3_27, PWM_4, 3},
- {P3_28, PWM_5, 3},
- {P3_29, PWM_6, 3},
- {NC, NC, 0}
-};
-
-__IO uint32_t *PWM_MATCH[] = {
- &(LPC_PWM1->MR0),
- &(LPC_PWM1->MR1),
- &(LPC_PWM1->MR2),
- &(LPC_PWM1->MR3),
- &(LPC_PWM1->MR4),
- &(LPC_PWM1->MR5),
- &(LPC_PWM1->MR6)
-};
-
-#define TCR_PWM_EN 0x00000008
-
-static unsigned int pwm_clock_mhz;
-
-void pwmout_init(pwmout_t* obj, PinName pin) {
- // determine the channel
- PWMName pwm = (PWMName)pinmap_peripheral(pin, PinMap_PWM);
- MBED_ASSERT(pwm != (PWMName)NC);
-
- obj->pwm = pwm;
- obj->MR = PWM_MATCH[pwm];
-
- // ensure the power is on
- LPC_SC->PCONP |= 1 << 6;
-
- // ensure clock to /4
- LPC_SC->PCLKSEL0 &= ~(0x3 << 12); // pclk = /4
- LPC_PWM1->PR = 0; // no pre-scale
-
- // ensure single PWM mode
- LPC_PWM1->MCR = 1 << 1; // reset TC on match 0
-
- // enable the specific PWM output
- LPC_PWM1->PCR |= 1 << (8 + pwm);
-
- pwm_clock_mhz = SystemCoreClock / 4000000;
-
- // default to 20ms: standard for servos, and fine for e.g. brightness control
- pwmout_period_ms(obj, 20);
- pwmout_write (obj, 0);
-
- // Wire pinout
- pinmap_pinout(pin, PinMap_PWM);
-}
-
-void pwmout_free(pwmout_t* obj) {
- // [TODO]
-}
-
-void pwmout_write(pwmout_t* obj, float value) {
- if (value < 0.0f) {
- value = 0.0;
- } else if (value > 1.0f) {
- value = 1.0;
- }
-
- // set channel match to percentage
- uint32_t v = (uint32_t)((float)(LPC_PWM1->MR0) * value);
-
- // workaround for PWM1[1] - Never make it equal MR0, else we get 1 cycle dropout
- if (v == LPC_PWM1->MR0) {
- v++;
- }
-
- *obj->MR = v;
-
- // accept on next period start
- LPC_PWM1->LER |= 1 << obj->pwm;
-}
-
-float pwmout_read(pwmout_t* obj) {
- float v = (float)(*obj->MR) / (float)(LPC_PWM1->MR0);
- return (v > 1.0f) ? (1.0f) : (v);
-}
-
-void pwmout_period(pwmout_t* obj, float seconds) {
- pwmout_period_us(obj, seconds * 1000000.0f);
-}
-
-void pwmout_period_ms(pwmout_t* obj, int ms) {
- pwmout_period_us(obj, ms * 1000);
-}
-
-// Set the PWM period, keeping the duty cycle the same.
-void pwmout_period_us(pwmout_t* obj, int us) {
- // calculate number of ticks
- uint32_t ticks = pwm_clock_mhz * us;
-
- // set reset
- LPC_PWM1->TCR = TCR_RESET;
-
- // set the global match register
- LPC_PWM1->MR0 = ticks;
-
- // Scale the pulse width to preserve the duty ratio
- if (LPC_PWM1->MR0 > 0) {
- *obj->MR = (*obj->MR * ticks) / LPC_PWM1->MR0;
- }
-
- // set the channel latch to update value at next period start
- LPC_PWM1->LER |= 1 << 0;
-
- // enable counter and pwm, clear reset
- LPC_PWM1->TCR = TCR_CNT_EN | TCR_PWM_EN;
-}
-
-void pwmout_pulsewidth(pwmout_t* obj, float seconds) {
- pwmout_pulsewidth_us(obj, seconds * 1000000.0f);
-}
-
-void pwmout_pulsewidth_ms(pwmout_t* obj, int ms) {
- pwmout_pulsewidth_us(obj, ms * 1000);
-}
-
-void pwmout_pulsewidth_us(pwmout_t* obj, int us) {
- // calculate number of ticks
- uint32_t v = pwm_clock_mhz * us;
-
- // workaround for PWM1[1] - Never make it equal MR0, else we get 1 cycle dropout
- if (v == LPC_PWM1->MR0) {
- v++;
- }
-
- // set the match register value
- *obj->MR = v;
-
- // set the channel latch to update value at next period start
- LPC_PWM1->LER |= 1 << obj->pwm;
-}
diff --git a/targets/TARGET_NXP/TARGET_LPC2460/rtc_api.c b/targets/TARGET_NXP/TARGET_LPC2460/rtc_api.c
deleted file mode 100644
index 526c6f3ad4..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC2460/rtc_api.c
+++ /dev/null
@@ -1,117 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2015 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-#include "rtc_api.h"
-
-// ensure rtc is running (unchanged if already running)
-
-/* Setup the RTC based on a time structure, ensuring RTC is enabled
- *
- * Can be clocked by a 32.768KHz oscillator or prescale divider based on the APB clock
- * - We want to use the 32khz clock, allowing for sleep mode
- *
- * Most registers are not changed by a Reset
- * - We must initialize these registers between power-on and setting the RTC into operation
-
- * Clock Control Register
- * RTC_CCR[0] : Enable - 0 = Disabled, 1 = Enabled
- * RTC_CCR[1] : Reset - 0 = Normal, 1 = Reset
- * RTC_CCR[4] : Clock Source - 0 = Prescaler, 1 = 32k Xtal
- *
- * The RTC may already be running, so we should set it up
- * without impacting if it is the case
- */
-void rtc_init(void) {
- LPC_SC->PCONP |= (1 << PCRTC); // Ensure power is on
- LPC_RTC->CCR = 0x00;
-
- // clock source on 2368 is special test mode on 1768!
- LPC_RTC->CCR |= 1 << 4; // Ensure clock source is 32KHz Xtal
-
- LPC_RTC->CCR |= 1 << 0; // Ensure the RTC is enabled
-}
-
-void rtc_free(void) {
- // [TODO]
-}
-
-/*
- * Little check routine to see if the RTC has been enabled
- *
- * Clock Control Register
- * RTC_CCR[0] : 0 = Disabled, 1 = Enabled
- *
- */
-
-int rtc_isenabled(void) {
- return(((LPC_RTC->CCR) & 0x01) != 0);
-}
-
-/*
- * RTC Registers
- * RTC_SEC Seconds 0-59
- * RTC_MIN Minutes 0-59
- * RTC_HOUR Hour 0-23
- * RTC_DOM Day of Month 1-28..31
- * RTC_DOW Day of Week 0-6
- * RTC_DOY Day of Year 1-365
- * RTC_MONTH Month 1-12
- * RTC_YEAR Year 0-4095
- *
- * struct tm
- * tm_sec seconds after the minute 0-61
- * tm_min minutes after the hour 0-59
- * tm_hour hours since midnight 0-23
- * tm_mday day of the month 1-31
- * tm_mon months since January 0-11
- * tm_year years since 1900
- * tm_wday days since Sunday 0-6
- * tm_yday days since January 1 0-365
- * tm_isdst Daylight Saving Time flag
- */
-time_t rtc_read(void) {
- // Setup a tm structure based on the RTC
- struct tm timeinfo;
- timeinfo.tm_sec = LPC_RTC->SEC;
- timeinfo.tm_min = LPC_RTC->MIN;
- timeinfo.tm_hour = LPC_RTC->HOUR;
- timeinfo.tm_mday = LPC_RTC->DOM;
- timeinfo.tm_mon = LPC_RTC->MONTH - 1;
- timeinfo.tm_year = LPC_RTC->YEAR - 1900;
-
- // Convert to timestamp
- time_t t = mktime(&timeinfo);
-
- return t;
-}
-
-void rtc_write(time_t t) {
- // Convert the time in to a tm
- struct tm *timeinfo = localtime(&t);
-
- // Pause clock, and clear counter register (clears us count)
- LPC_RTC->CCR |= 2;
-
- // Set the RTC
- LPC_RTC->SEC = timeinfo->tm_sec;
- LPC_RTC->MIN = timeinfo->tm_min;
- LPC_RTC->HOUR = timeinfo->tm_hour;
- LPC_RTC->DOM = timeinfo->tm_mday;
- LPC_RTC->MONTH = timeinfo->tm_mon + 1;
- LPC_RTC->YEAR = timeinfo->tm_year + 1900;
-
- // Restart clock
- LPC_RTC->CCR &= ~((uint32_t)2);
-}
diff --git a/targets/TARGET_NXP/TARGET_LPC2460/serial_api.c b/targets/TARGET_NXP/TARGET_LPC2460/serial_api.c
deleted file mode 100644
index 9a92bb04ba..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC2460/serial_api.c
+++ /dev/null
@@ -1,338 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2015 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-// math.h required for floating point operations for baud rate calculation
-#include "mbed_assert.h"
-#include
-#include
-#include
-
-#include "serial_api.h"
-#include "cmsis.h"
-#include "pinmap.h"
-
-/******************************************************************************
- * INITIALIZATION
- ******************************************************************************/
-#define UART_NUM 4
-
-static const PinMap PinMap_UART_TX[] = {
- {P0_0, UART_3, 2},
- {P0_2, UART_0, 1},
- {P0_10, UART_2, 1},
- {P0_15, UART_1, 1},
- {P0_25, UART_3, 3},
- {P2_0 , UART_1, 2},
- {P2_8 , UART_2, 2},
- {P4_28, UART_3, 3},
- {NC , NC , 0}
-};
-
-static const PinMap PinMap_UART_RX[] = {
- {P0_1 , UART_3, 2},
- {P0_3 , UART_0, 1},
- {P0_11, UART_2, 1},
- {P0_16, UART_1, 1},
- {P0_26, UART_3, 3},
- {P2_1 , UART_1, 2},
- {P2_9 , UART_2, 2},
- {P4_29, UART_3, 3},
- {NC , NC , 0}
-};
-
-static uint32_t serial_irq_ids[UART_NUM] = {0};
-static uart_irq_handler irq_handler;
-
-int stdio_uart_inited = 0;
-serial_t stdio_uart;
-
-void serial_init(serial_t *obj, PinName tx, PinName rx) {
- int is_stdio_uart = 0;
-
- // determine the UART to use
- UARTName uart_tx = (UARTName)pinmap_peripheral(tx, PinMap_UART_TX);
- UARTName uart_rx = (UARTName)pinmap_peripheral(rx, PinMap_UART_RX);
- UARTName uart = (UARTName)pinmap_merge(uart_tx, uart_rx);
- MBED_ASSERT((int)uart != NC);
-
- obj->uart = (LPC_UART_TypeDef *)uart;
- // enable power
- switch (uart) {
- case UART_0: LPC_SC->PCONP |= 1 << 3; break;
- case UART_1: LPC_SC->PCONP |= 1 << 4; break;
- case UART_2: LPC_SC->PCONP |= 1 << 24; break;
- case UART_3: LPC_SC->PCONP |= 1 << 25; break;
- }
-
- // enable fifos and default rx trigger level
- obj->uart->FCR = 1 << 0 // FIFO Enable - 0 = Disables, 1 = Enabled
- | 0 << 1 // Rx Fifo Reset
- | 0 << 2 // Tx Fifo Reset
- | 0 << 6; // Rx irq trigger level - 0 = 1 char, 1 = 4 chars, 2 = 8 chars, 3 = 14 chars
-
- // disable irqs
- obj->uart->IER = 0 << 0 // Rx Data available irq enable
- | 0 << 1 // Tx Fifo empty irq enable
- | 0 << 2; // Rx Line Status irq enable
-
- // set default baud rate and format
- serial_baud (obj, 9600);
- serial_format(obj, 8, ParityNone, 1);
-
- // pinout the chosen uart
- pinmap_pinout(tx, PinMap_UART_TX);
- pinmap_pinout(rx, PinMap_UART_RX);
-
- // set rx/tx pins in PullUp mode
- if (tx != NC) {
- pin_mode(tx, PullUp);
- }
- if (rx != NC) {
- pin_mode(rx, PullUp);
- }
-
- switch (uart) {
- case UART_0: obj->index = 0; break;
- case UART_1: obj->index = 1; break;
- case UART_2: obj->index = 2; break;
- case UART_3: obj->index = 3; break;
- }
-
- is_stdio_uart = (uart == STDIO_UART) ? (1) : (0);
-
- if (is_stdio_uart) {
- stdio_uart_inited = 1;
- memcpy(&stdio_uart, obj, sizeof(serial_t));
- }
-}
-
-void serial_free(serial_t *obj) {
- serial_irq_ids[obj->index] = 0;
-}
-
-// serial_baud
-// set the baud rate, taking in to account the current SystemFrequency
-void serial_baud(serial_t *obj, int baudrate) {
- MBED_ASSERT((int)obj->uart <= UART_3);
- // The LPC2300 and LPC1700 have a divider and a fractional divider to control the
- // baud rate. The formula is:
- //
- // Baudrate = (1 / PCLK) * 16 * DL * (1 + DivAddVal / MulVal)
- // where:
- // 1 < MulVal <= 15
- // 0 <= DivAddVal < 14
- // DivAddVal < MulVal
- //
- // set pclk to /1
- switch ((int)obj->uart) {
- case UART_0: LPC_SC->PCLKSEL0 &= ~(0x3 << 6); LPC_SC->PCLKSEL0 |= (0x1 << 6); break;
- case UART_1: LPC_SC->PCLKSEL0 &= ~(0x3 << 8); LPC_SC->PCLKSEL0 |= (0x1 << 8); break;
- case UART_2: LPC_SC->PCLKSEL1 &= ~(0x3 << 16); LPC_SC->PCLKSEL1 |= (0x1 << 16); break;
- case UART_3: LPC_SC->PCLKSEL1 &= ~(0x3 << 18); LPC_SC->PCLKSEL1 |= (0x1 << 18); break;
- default: break;
- }
-
- uint32_t PCLK = SystemCoreClock;
-
- // First we check to see if the basic divide with no DivAddVal/MulVal
- // ratio gives us an integer result. If it does, we set DivAddVal = 0,
- // MulVal = 1. Otherwise, we search the valid ratio value range to find
- // the closest match. This could be more elegant, using search methods
- // and/or lookup tables, but the brute force method is not that much
- // slower, and is more maintainable.
- uint16_t DL = PCLK / (16 * baudrate);
-
- uint8_t DivAddVal = 0;
- uint8_t MulVal = 1;
- int hit = 0;
- uint16_t dlv;
- uint8_t mv, dav;
- if ((PCLK % (16 * baudrate)) != 0) { // Checking for zero remainder
- int err_best = baudrate, b;
- for (mv = 1; mv < 16 && !hit; mv++)
- {
- for (dav = 0; dav < mv; dav++)
- {
- // baudrate = PCLK / (16 * dlv * (1 + (DivAdd / Mul))
- // solving for dlv, we get dlv = mul * PCLK / (16 * baudrate * (divadd + mul))
- // mul has 4 bits, PCLK has 27 so we have 1 bit headroom which can be used for rounding
- // for many values of mul and PCLK we have 2 or more bits of headroom which can be used to improve precision
- // note: X / 32 doesn't round correctly. Instead, we use ((X / 16) + 1) / 2 for correct rounding
-
- if ((mv * PCLK * 2) & 0x80000000) // 1 bit headroom
- dlv = ((((2 * mv * PCLK) / (baudrate * (dav + mv))) / 16) + 1) / 2;
- else // 2 bits headroom, use more precision
- dlv = ((((4 * mv * PCLK) / (baudrate * (dav + mv))) / 32) + 1) / 2;
-
- // datasheet says if DLL==DLM==0, then 1 is used instead since divide by zero is ungood
- if (dlv == 0)
- dlv = 1;
-
- // datasheet says if dav > 0 then DL must be >= 2
- if ((dav > 0) && (dlv < 2))
- dlv = 2;
-
- // integer rearrangement of the baudrate equation (with rounding)
- b = ((PCLK * mv / (dlv * (dav + mv) * 8)) + 1) / 2;
-
- // check to see how we went
- b = abs(b - baudrate);
- if (b < err_best)
- {
- err_best = b;
-
- DL = dlv;
- MulVal = mv;
- DivAddVal = dav;
-
- if (b == baudrate)
- {
- hit = 1;
- break;
- }
- }
- }
- }
- }
-
- // set LCR[DLAB] to enable writing to divider registers
- obj->uart->LCR |= (1 << 7);
-
- // set divider values
- obj->uart->DLM = (DL >> 8) & 0xFF;
- obj->uart->DLL = (DL >> 0) & 0xFF;
- obj->uart->FDR = (uint32_t) DivAddVal << 0
- | (uint32_t) MulVal << 4;
-
- // clear LCR[DLAB]
- obj->uart->LCR &= ~(1 << 7);
-}
-
-void serial_format(serial_t *obj, int data_bits, SerialParity parity, int stop_bits) {
- MBED_ASSERT((stop_bits == 1) || (stop_bits == 2)); // 0: 1 stop bits, 1: 2 stop bits
- MBED_ASSERT((data_bits > 4) && (data_bits < 9)); // 0: 5 data bits ... 3: 8 data bits
- MBED_ASSERT((parity == ParityNone) || (parity == ParityOdd) || (parity == ParityEven) ||
- (parity == ParityForced1) || (parity == ParityForced0));
-
- stop_bits -= 1;
- data_bits -= 5;
-
- int parity_enable = 0, parity_select = 0;
- switch (parity) {
- case ParityNone: parity_enable = 0; parity_select = 0; break;
- case ParityOdd : parity_enable = 1; parity_select = 0; break;
- case ParityEven: parity_enable = 1; parity_select = 1; break;
- case ParityForced1: parity_enable = 1; parity_select = 2; break;
- case ParityForced0: parity_enable = 1; parity_select = 3; break;
- default:
- break;
- }
-
- obj->uart->LCR = data_bits << 0
- | stop_bits << 2
- | parity_enable << 3
- | parity_select << 4;
-}
-
-/******************************************************************************
- * INTERRUPTS HANDLING
- ******************************************************************************/
-static inline void uart_irq(uint32_t iir, uint32_t index) {
- // [Chapter 14] LPC17xx UART0/2/3: UARTn Interrupt Handling
- SerialIrq irq_type;
- switch (iir) {
- case 1: irq_type = TxIrq; break;
- case 2: irq_type = RxIrq; break;
- default: return;
- }
-
- if (serial_irq_ids[index] != 0){
- irq_handler(serial_irq_ids[index], irq_type);
- }
-}
-
-void uart0_irq() {uart_irq((LPC_UART0->IIR >> 1) & 0x7, 0);}
-void uart1_irq() {uart_irq((LPC_UART1->IIR >> 1) & 0x7, 1);}
-void uart2_irq() {uart_irq((LPC_UART2->IIR >> 1) & 0x7, 2);}
-void uart3_irq() {uart_irq((LPC_UART3->IIR >> 1) & 0x7, 3);}
-
-void serial_irq_handler(serial_t *obj, uart_irq_handler handler, uint32_t id) {
- irq_handler = handler;
- serial_irq_ids[obj->index] = id;
-}
-
-void serial_irq_set(serial_t *obj, SerialIrq irq, uint32_t enable) {
- IRQn_Type irq_n = (IRQn_Type)0;
- uint32_t vector = 0;
- switch ((int)obj->uart) {
- case UART_0: irq_n=UART0_IRQn; vector = (uint32_t)&uart0_irq; break;
- case UART_1: irq_n=UART1_IRQn; vector = (uint32_t)&uart1_irq; break;
- case UART_2: irq_n=UART2_IRQn; vector = (uint32_t)&uart2_irq; break;
- case UART_3: irq_n=UART3_IRQn; vector = (uint32_t)&uart3_irq; break;
- }
-
- if (enable) {
- obj->uart->IER |= 1 << irq;
- NVIC_SetVector(irq_n, vector);
- NVIC_EnableIRQ(irq_n);
- } else { // disable
- int all_disabled = 0;
- SerialIrq other_irq = (irq == RxIrq) ? (TxIrq) : (RxIrq);
- obj->uart->IER &= ~(1 << irq);
- all_disabled = (obj->uart->IER & (1 << other_irq)) == 0;
- if (all_disabled)
- NVIC_DisableIRQ(irq_n);
- }
-}
-
-/******************************************************************************
- * READ/WRITE
- ******************************************************************************/
-int serial_getc(serial_t *obj) {
- while (!serial_readable(obj));
- return obj->uart->RBR;
-}
-
-void serial_putc(serial_t *obj, int c) {
- while (!serial_writable(obj));
- obj->uart->THR = c;
-}
-
-int serial_readable(serial_t *obj) {
- return obj->uart->LSR & 0x01;
-}
-
-int serial_writable(serial_t *obj) {
- return obj->uart->LSR & 0x20;
-}
-
-void serial_clear(serial_t *obj) {
- obj->uart->FCR = 1 << 1 // rx FIFO reset
- | 1 << 2 // tx FIFO reset
- | 0 << 6; // interrupt depth
-}
-
-void serial_pinout_tx(PinName tx) {
- pinmap_pinout(tx, PinMap_UART_TX);
-}
-
-void serial_break_set(serial_t *obj) {
- obj->uart->LCR |= (1 << 6);
-}
-
-void serial_break_clear(serial_t *obj) {
- obj->uart->LCR &= ~(1 << 6);
-}
-
diff --git a/targets/TARGET_NXP/TARGET_LPC2460/spi_api.c b/targets/TARGET_NXP/TARGET_LPC2460/spi_api.c
deleted file mode 100644
index a7de67dfcb..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC2460/spi_api.c
+++ /dev/null
@@ -1,219 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2015 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-#include "mbed_assert.h"
-#include
-
-#include "spi_api.h"
-#include "cmsis.h"
-#include "pinmap.h"
-#include "mbed_error.h"
-
-static const PinMap PinMap_SPI_SCLK[] = {
- {P0_7 , SPI_1, 2},
- {P0_15, SPI_0, 2},
- {P1_20, SPI_0, 3},
- {P1_31, SPI_1, 2},
- {NC , NC , 0}
-};
-
-static const PinMap PinMap_SPI_MOSI[] = {
- {P0_9 , SPI_1, 2},
- {P0_13, SPI_1, 2},
- {P0_18, SPI_0, 2},
- {P1_24, SPI_0, 3},
- {NC , NC , 0}
-};
-
-static const PinMap PinMap_SPI_MISO[] = {
- {P0_8 , SPI_1, 2},
- {P0_12, SPI_1, 2},
- {P0_17, SPI_0, 2},
- {P1_23, SPI_0, 3},
- {NC , NC , 0}
-};
-
-static const PinMap PinMap_SPI_SSEL[] = {
- {P0_6 , SPI_1, 2},
- {P0_14, SPI_1, 3},
- {P0_16, SPI_0, 2},
- {P1_21, SPI_0, 3},
- {NC , NC , 0}
-};
-
-static inline int ssp_disable(spi_t *obj);
-static inline int ssp_enable(spi_t *obj);
-
-void spi_init(spi_t *obj, PinName mosi, PinName miso, PinName sclk, PinName ssel) {
- // determine the SPI to use
- SPIName spi_mosi = (SPIName)pinmap_peripheral(mosi, PinMap_SPI_MOSI);
- SPIName spi_miso = (SPIName)pinmap_peripheral(miso, PinMap_SPI_MISO);
- SPIName spi_sclk = (SPIName)pinmap_peripheral(sclk, PinMap_SPI_SCLK);
- SPIName spi_ssel = (SPIName)pinmap_peripheral(ssel, PinMap_SPI_SSEL);
- SPIName spi_data = (SPIName)pinmap_merge(spi_mosi, spi_miso);
- SPIName spi_cntl = (SPIName)pinmap_merge(spi_sclk, spi_ssel);
- obj->spi = (LPC_SSP_TypeDef*)pinmap_merge(spi_data, spi_cntl);
- MBED_ASSERT((int)obj->spi != NC);
-
- // enable power and clocking
- switch ((int)obj->spi) {
- case SPI_0: LPC_SC->PCONP |= 1 << PCSSP0; break;
- case SPI_1: LPC_SC->PCONP |= 1 << PCSSP1; break;
- }
-
- // set default format and frequency
- if (ssel == NC) {
- spi_format(obj, 8, 0, 0); // 8 bits, mode 0, master
- } else {
- spi_format(obj, 8, 0, 1); // 8 bits, mode 0, slave
- }
- spi_frequency(obj, 1000000);
-
- // enable the ssp channel
- ssp_enable(obj);
-
- // pin out the spi pins
- pinmap_pinout(mosi, PinMap_SPI_MOSI);
- pinmap_pinout(miso, PinMap_SPI_MISO);
- pinmap_pinout(sclk, PinMap_SPI_SCLK);
- if (ssel != NC) {
- pinmap_pinout(ssel, PinMap_SPI_SSEL);
- }
-}
-
-void spi_free(spi_t *obj) {}
-
-void spi_format(spi_t *obj, int bits, int mode, int slave) {
- MBED_ASSERT(((bits >= 4) && (bits <= 16)) && ((mode >= 0) && (mode <= 3)));
- ssp_disable(obj);
-
- int polarity = (mode & 0x2) ? 1 : 0;
- int phase = (mode & 0x1) ? 1 : 0;
-
- // set it up
- int DSS = bits - 1; // DSS (data select size)
- int SPO = (polarity) ? 1 : 0; // SPO - clock out polarity
- int SPH = (phase) ? 1 : 0; // SPH - clock out phase
-
- int FRF = 0; // FRF (frame format) = SPI
- uint32_t tmp = obj->spi->CR0;
- tmp &= ~(0xFFFF);
- tmp |= DSS << 0
- | FRF << 4
- | SPO << 6
- | SPH << 7;
- obj->spi->CR0 = tmp;
-
- tmp = obj->spi->CR1;
- tmp &= ~(0xD);
- tmp |= 0 << 0 // LBM - loop back mode - off
- | ((slave) ? 1 : 0) << 2 // MS - master slave mode, 1 = slave
- | 0 << 3; // SOD - slave output disable - na
- obj->spi->CR1 = tmp;
-
- ssp_enable(obj);
-}
-
-void spi_frequency(spi_t *obj, int hz) {
- ssp_disable(obj);
-
- // setup the spi clock diveder to /1
- switch ((int)obj->spi) {
- case SPI_0:
- LPC_SC->PCLKSEL1 &= ~(3 << 10);
- LPC_SC->PCLKSEL1 |= (1 << 10);
- break;
- case SPI_1:
- LPC_SC->PCLKSEL0 &= ~(3 << 20);
- LPC_SC->PCLKSEL0 |= (1 << 20);
- break;
- }
-
- uint32_t PCLK = SystemCoreClock;
-
- int prescaler;
-
- for (prescaler = 2; prescaler <= 254; prescaler += 2) {
- int prescale_hz = PCLK / prescaler;
-
- // calculate the divider
- int divider = floor(((float)prescale_hz / (float)hz) + 0.5f);
-
- // check we can support the divider
- if (divider < 256) {
- // prescaler
- obj->spi->CPSR = prescaler;
-
- // divider
- obj->spi->CR0 &= ~(0xFFFF << 8);
- obj->spi->CR0 |= (divider - 1) << 8;
- ssp_enable(obj);
- return;
- }
- }
- error("Couldn't setup requested SPI frequency");
-}
-
-static inline int ssp_disable(spi_t *obj) {
- return obj->spi->CR1 &= ~(1 << 1);
-}
-
-static inline int ssp_enable(spi_t *obj) {
- return obj->spi->CR1 |= (1 << 1);
-}
-
-static inline int ssp_readable(spi_t *obj) {
- return obj->spi->SR & (1 << 2);
-}
-
-static inline int ssp_writeable(spi_t *obj) {
- return obj->spi->SR & (1 << 1);
-}
-
-static inline void ssp_write(spi_t *obj, int value) {
- while (!ssp_writeable(obj));
- obj->spi->DR = value;
-}
-
-static inline int ssp_read(spi_t *obj) {
- while (!ssp_readable(obj));
- return obj->spi->DR;
-}
-
-static inline int ssp_busy(spi_t *obj) {
- return (obj->spi->SR & (1 << 4)) ? (1) : (0);
-}
-
-int spi_master_write(spi_t *obj, int value) {
- ssp_write(obj, value);
- return ssp_read(obj);
-}
-
-int spi_slave_receive(spi_t *obj) {
- return (ssp_readable(obj) && !ssp_busy(obj)) ? (1) : (0);
-}
-
-int spi_slave_read(spi_t *obj) {
- return obj->spi->DR;
-}
-
-void spi_slave_write(spi_t *obj, int value) {
- while (ssp_writeable(obj) == 0) ;
- obj->spi->DR = value;
-}
-
-int spi_busy(spi_t *obj) {
- return ssp_busy(obj);
-}
diff --git a/targets/TARGET_NXP/TARGET_LPC2460/us_ticker.c b/targets/TARGET_NXP/TARGET_LPC2460/us_ticker.c
deleted file mode 100644
index 7fdccf35a4..0000000000
--- a/targets/TARGET_NXP/TARGET_LPC2460/us_ticker.c
+++ /dev/null
@@ -1,64 +0,0 @@
-/* mbed Microcontroller Library
- * Copyright (c) 2006-2015 ARM Limited
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- *
- * http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-#include
-#include "us_ticker_api.h"
-#include "PeripheralNames.h"
-
-#define US_TICKER_TIMER ((LPC_TIM_TypeDef *)LPC_TIM3_BASE)
-#define US_TICKER_TIMER_IRQn TIMER3_IRQn
-
-int us_ticker_inited = 0;
-
-void us_ticker_init(void) {
- if (us_ticker_inited) return;
- us_ticker_inited = 1;
-
- LPC_SC->PCONP |= 1 << PCTIM3; // Clock TIMER_3
-
- US_TICKER_TIMER->CTCR = 0x0; // timer mode
- uint32_t PCLK = SystemCoreClock / 4;
-
- US_TICKER_TIMER->TCR = 0x2; // reset
-
- uint32_t prescale = PCLK / 1000000; // default to 1MHz (1 us ticks)
- US_TICKER_TIMER->PR = prescale - 1;
- US_TICKER_TIMER->TCR = 1; // enable = 1, reset = 0
-
- NVIC_SetVector(US_TICKER_TIMER_IRQn, (uint32_t)us_ticker_irq_handler);
- NVIC_EnableIRQ(US_TICKER_TIMER_IRQn);
-}
-
-uint32_t us_ticker_read() {
- if (!us_ticker_inited)
- us_ticker_init();
-
- return US_TICKER_TIMER->TC;
-}
-
-void us_ticker_set_interrupt(timestamp_t timestamp) {
- // set match value
- US_TICKER_TIMER->MR0 = (uint32_t)timestamp;
- // enable match interrupt
- US_TICKER_TIMER->MCR |= 1;
-}
-
-void us_ticker_disable_interrupt(void) {
- US_TICKER_TIMER->MCR &= ~1;
-}
-
-void us_ticker_clear_interrupt(void) {
- US_TICKER_TIMER->IR = 1;
-}
diff --git a/targets/TARGET_NXP/mbed_rtx.h b/targets/TARGET_NXP/mbed_rtx.h
index bb28e4684a..f7f2d97539 100644
--- a/targets/TARGET_NXP/mbed_rtx.h
+++ b/targets/TARGET_NXP/mbed_rtx.h
@@ -110,41 +110,6 @@
#define OS_CLOCK 96000000
#endif
-#elif defined(TARGET_LPC2368)
-
-/* FIXME: INITIAL_SP is undefined for this target */
-#ifndef OS_TASKCNT
-#define OS_TASKCNT 14
-#endif
-#ifndef OS_MAINSTKSIZE
-#define OS_MAINSTKSIZE 256
-#endif
-#ifndef OS_CLOCK
-#define OS_CLOCK 96000000
-#endif
-#ifndef OS_SCHEDULERSTKSIZE
-#define OS_SCHEDULERSTKSIZE (136*2)
-#endif
-
-#elif defined(TARGET_LPC2460)
-
-extern unsigned char __usr_stack_top__[];
-#ifndef INITIAL_SP
-#define INITIAL_SP (__usr_stack_top__)
-#endif
-#ifndef OS_TASKCNT
-#define OS_TASKCNT 14
-#endif
-#ifndef OS_MAINSTKSIZE
-#define OS_MAINSTKSIZE 256
-#endif
-#ifndef OS_CLOCK
-#define OS_CLOCK 72000000
-#endif
-#ifndef OS_SCHEDULERSTKSIZE
-#define OS_SCHEDULERSTKSIZE (136*2)
-#endif
-
#elif defined(TARGET_LPC4088) || defined(TARGET_LPC4088_DM)
#ifndef INITIAL_SP
diff --git a/targets/targets.json b/targets/targets.json
index 9c1f298137..0f142be29d 100644
--- a/targets/targets.json
+++ b/targets/targets.json
@@ -266,20 +266,6 @@
"device_has": ["ANALOGIN", "ANALOGOUT", "CAN", "DEBUG_AWARENESS", "ERROR_PATTERN", "ETHERNET", "I2C", "I2CSLAVE", "INTERRUPTIN", "LOCALFILESYSTEM", "PORTIN", "PORTINOUT", "PORTOUT", "PWMOUT", "RTC", "SEMIHOST", "SERIAL", "SERIAL_FC", "SLEEP", "SPI", "SPISLAVE", "STDIO_MESSAGES", "FLASH"],
"device_name": "LPC1768"
},
- "LPC2368": {
- "inherits": ["LPCTarget"],
- "core": "ARM7TDMI-S",
- "extra_labels": ["NXP", "LPC23XX"],
- "supported_toolchains": ["GCC_ARM", "GCC_CR"],
- "device_has": ["ANALOGIN", "ANALOGOUT", "CAN", "ERROR_PATTERN", "ETHERNET", "I2C", "I2CSLAVE", "INTERRUPTIN", "LOCALFILESYSTEM", "PORTIN", "PORTINOUT", "PORTOUT", "PWMOUT", "RTC", "SEMIHOST", "SERIAL", "SPI", "SPISLAVE", "STDIO_MESSAGES"]
- },
- "LPC2460": {
- "inherits": ["LPCTarget"],
- "core": "ARM7TDMI-S",
- "extra_labels": ["NXP", "LPC2460"],
- "supported_toolchains": ["GCC_ARM"],
- "device_has": ["ANALOGIN", "ANALOGOUT", "CAN", "ERROR_PATTERN", "ETHERNET", "I2C", "I2CSLAVE", "INTERRUPTIN", "PORTIN", "PORTINOUT", "PORTOUT", "PWMOUT", "RTC", "SERIAL", "SPI", "SPISLAVE", "STDIO_MESSAGES"]
- },
"LPC810": {
"inherits": ["LPCTarget"],
"core": "Cortex-M0+",
diff --git a/tools/build_api.py b/tools/build_api.py
index c8a984a18b..ee0fb96eba 100644
--- a/tools/build_api.py
+++ b/tools/build_api.py
@@ -318,7 +318,7 @@ def prepare_toolchain(src_paths, build_dir, target, toolchain_name,
Positional arguments:
src_paths - the paths to source directories
- target - ['LPC1768', 'LPC11U24', 'LPC2368', etc.]
+ target - ['LPC1768', 'LPC11U24', etc.]
toolchain_name - ['ARM', 'uARM', 'GCC_ARM', 'GCC_CR']
Keyword arguments:
diff --git a/tools/build_travis.py b/tools/build_travis.py
index d389ae8e01..ba72bc64cb 100644
--- a/tools/build_travis.py
+++ b/tools/build_travis.py
@@ -28,8 +28,6 @@ import sys
build_list = (
{ "target": "LPC1768", "toolchains": "GCC_ARM", "libs": ["dsp", "rtos", "usb"] },
- { "target": "LPC2368", "toolchains": "GCC_ARM", "libs": [] },
- { "target": "LPC2460", "toolchains": "GCC_ARM", "libs": ["rtos", "usb"] },
{ "target": "LPC11U24", "toolchains": "GCC_ARM", "libs": ["dsp", "rtos"] },
{ "target": "OC_MBUINO", "toolchains": "GCC_ARM", "libs": [] },
diff --git a/tools/targets/__init__.py b/tools/targets/__init__.py
index 2225c34ac6..57f51a92a3 100644
--- a/tools/targets/__init__.py
+++ b/tools/targets/__init__.py
@@ -32,7 +32,6 @@ __all__ = ["target", "TARGETS", "TARGET_MAP", "TARGET_NAMES", "CORE_LABELS",
"CUMULATIVE_ATTRIBUTES", "get_resolution_order"]
CORE_LABELS = {
- "ARM7TDMI-S": ["ARM7", "LIKE_CORTEX_ARM7"],
"Cortex-M0" : ["M0", "CORTEX_M", "LIKE_CORTEX_M0"],
"Cortex-M0+": ["M0P", "CORTEX_M", "LIKE_CORTEX_M0"],
"Cortex-M1" : ["M1", "CORTEX_M", "LIKE_CORTEX_M1"],
diff --git a/tools/tests.py b/tools/tests.py
index 3ada1d6697..de409473a7 100644
--- a/tools/tests.py
+++ b/tools/tests.py
@@ -136,7 +136,7 @@ TESTS = [
"source_dir": join(TEST_DIR, "mbed", "file"),
"dependencies": [MBED_LIBRARIES, TEST_MBED_LIB],
"automated": True,
- "mcu": ["LPC1768", "LPC2368", "LPC11U24"]
+ "mcu": ["LPC1768", "LPC11U24"]
},
{
"id": "MBED_A3", "description": "C++ STL",
@@ -185,7 +185,7 @@ TESTS = [
"dependencies": [MBED_LIBRARIES, TEST_MBED_LIB],
"automated": True,
"peripherals": ["analog_loop"],
- "mcu": ["LPC1768", "LPC2368", "LPC2460", "KL25Z", "K64F", "K66F", "K22F", "LPC4088", "LPC1549",
+ "mcu": ["LPC1768", "KL25Z", "K64F", "K66F", "K22F", "LPC4088", "LPC1549",
"NUCLEO_F072RB", "NUCLEO_F091RC", "NUCLEO_F302R8", "NUCLEO_F303K8", "NUCLEO_F303RE", "NUCLEO_F207ZG",
"NUCLEO_F334R8", "NUCLEO_F303ZE", "NUCLEO_L053R8", "DISCO_L072CZ_LRWAN1", "NUCLEO_L073RZ", "NUCLEO_L152RE",
"NUCLEO_F410RB", "NUCLEO_F446RE", "NUCLEO_F446ZE", "NUCLEO_F429ZI",
@@ -523,7 +523,7 @@ TESTS = [
"source_dir": join(TEST_DIR, "mbed", "semihost"),
"dependencies": [MBED_LIBRARIES, TEST_MBED_LIB],
"automated": True,
- "mcu": ["LPC1768", "LPC2368", "LPC11U24"]
+ "mcu": ["LPC1768", "LPC11U24"]
},
{
"id": "MBED_23", "description": "Ticker Int us",
@@ -689,7 +689,7 @@ TESTS = [
"dependencies": [MBED_LIBRARIES, RTOS_LIBRARIES, TEST_MBED_LIB],
"automated": True,
#"host_test": "wait_us_auto",
- "mcu": ["LPC1768", "LPC1549", "LPC11U24", "LPC812", "LPC2460", "LPC824", "SSCI824",
+ "mcu": ["LPC1768", "LPC1549", "LPC11U24", "LPC812", "LPC824", "SSCI824",
"KL25Z", "KL05Z", "K22F", "K64F", "K66F", "KL43Z", "KL46Z", "HEXIWEAR",
"RZ_A1H", "VK_RZ_A1H", "DISCO_F407VG", "DISCO_F429ZI", "NUCLEO_F411RE", "NUCLEO_F412ZG", "DISCO_F469NI", "NUCLEO_F410RB", "NUCLEO_F429ZI",
"NUCLEO_F401RE", "NUCLEO_F334R8", "DISCO_F334C8", "NUCLEO_F302R8", "NUCLEO_F070RB", "NUCLEO_F207ZG",
@@ -704,7 +704,7 @@ TESTS = [
"source_dir": join(TEST_DIR, "rtos", "mbed", "mutex"),
"dependencies": [MBED_LIBRARIES, RTOS_LIBRARIES, TEST_MBED_LIB],
"automated": True,
- "mcu": ["LPC1768", "LPC1549", "LPC11U24", "LPC812", "LPC2460", "LPC824", "SSCI824",
+ "mcu": ["LPC1768", "LPC1549", "LPC11U24", "LPC812", "LPC824", "SSCI824",
"KL25Z", "KL05Z", "K22F", "K64F", "K66F", "KL43Z", "KL46Z", "HEXIWEAR",
"RZ_A1H", "VK_RZ_A1H", "DISCO_F407VG", "DISCO_F429ZI", "NUCLEO_F411RE", "NUCLEO_F412ZG", "DISCO_F469NI", "NUCLEO_F410RB", "NUCLEO_F429ZI",
"NUCLEO_F401RE", "NUCLEO_F334R8", "DISCO_F334C8", "NUCLEO_F302R8", "NUCLEO_F303ZE", "NUCLEO_F070RB", "NUCLEO_F207ZG",
@@ -720,7 +720,7 @@ TESTS = [
"source_dir": join(TEST_DIR, "rtos", "mbed", "semaphore"),
"dependencies": [MBED_LIBRARIES, RTOS_LIBRARIES, TEST_MBED_LIB],
"automated": True,
- "mcu": ["LPC1768", "LPC1549", "LPC11U24", "LPC812", "LPC2460", "LPC824", "SSCI824",
+ "mcu": ["LPC1768", "LPC1549", "LPC11U24", "LPC812", "LPC824", "SSCI824",
"KL25Z", "KL05Z", "K22F", "K64F", "K66F", "KL43Z", "KL46Z", "HEXIWEAR",
"RZ_A1H", "VK_RZ_A1H", "DISCO_F407VG", "DISCO_F429ZI", "NUCLEO_F411RE", "NUCLEO_F412ZG", "DISCO_F469NI", "NUCLEO_F410RB", "NUCLEO_F429ZI",
"NUCLEO_F401RE", "NUCLEO_F334R8", "DISCO_F334C8", "NUCLEO_F302R8", "NUCLEO_F303ZE", "NUCLEO_F070RB", "NUCLEO_F207ZG",
@@ -737,7 +737,7 @@ TESTS = [
"source_dir": join(TEST_DIR, "rtos", "mbed", "signals"),
"dependencies": [MBED_LIBRARIES, RTOS_LIBRARIES, TEST_MBED_LIB],
"automated": True,
- "mcu": ["LPC1768", "LPC1549", "LPC11U24", "LPC812", "LPC2460", "LPC824", "SSCI824",
+ "mcu": ["LPC1768", "LPC1549", "LPC11U24", "LPC812", "LPC824", "SSCI824",
"KL25Z", "KL05Z", "K22F", "K64F", "K66F", "KL43Z", "KL46Z", "HEXIWEAR",
"RZ_A1H", "VK_RZ_A1H", "DISCO_F407VG", "DISCO_F429ZI", "NUCLEO_F411RE", "NUCLEO_F412ZG", "DISCO_F469NI", "NUCLEO_F410RB", "NUCLEO_F429ZI",
"NUCLEO_F401RE", "NUCLEO_F334R8", "DISCO_F334C8", "NUCLEO_F302R8", "NUCLEO_F303ZE", "NUCLEO_F070RB", "NUCLEO_F207ZG",
@@ -754,7 +754,7 @@ TESTS = [
"source_dir": join(TEST_DIR, "rtos", "mbed", "queue"),
"dependencies": [MBED_LIBRARIES, RTOS_LIBRARIES, TEST_MBED_LIB],
"automated": True,
- "mcu": ["LPC1768", "LPC1549", "LPC11U24", "LPC812", "LPC2460", "LPC824", "SSCI824",
+ "mcu": ["LPC1768", "LPC1549", "LPC11U24", "LPC812", "LPC824", "SSCI824",
"KL25Z", "KL05Z", "K22F", "K64F", "K66F", "KL43Z", "KL46Z", "HEXIWEAR",
"RZ_A1H", "VK_RZ_A1H", "DISCO_F407VG", "DISCO_F429ZI", "NUCLEO_F411RE", "NUCLEO_F412ZG", "DISCO_F469NI", "NUCLEO_F410RB", "NUCLEO_F429ZI",
"NUCLEO_F401RE", "NUCLEO_F334R8", "DISCO_F334C8", "NUCLEO_F302R8", "NUCLEO_F303ZE", "NUCLEO_F070RB", "NUCLEO_F207ZG",
@@ -770,7 +770,7 @@ TESTS = [
"source_dir": join(TEST_DIR, "rtos", "mbed", "mail"),
"dependencies": [MBED_LIBRARIES, RTOS_LIBRARIES, TEST_MBED_LIB],
"automated": True,
- "mcu": ["LPC1768", "LPC1549", "LPC11U24", "LPC812", "LPC2460", "LPC824", "SSCI824",
+ "mcu": ["LPC1768", "LPC1549", "LPC11U24", "LPC812", "LPC824", "SSCI824",
"KL25Z", "KL05Z", "K22F", "K64F", "K66F", "KL43Z", "KL46Z", "HEXIWEAR",
"RZ_A1H", "VK_RZ_A1H", "DISCO_F407VG", "DISCO_F429ZI", "NUCLEO_F411RE", "NUCLEO_F412ZG", "DISCO_F469NI", "NUCLEO_F410RB", "NUCLEO_F429ZI",
"NUCLEO_F401RE", "NUCLEO_F334R8", "DISCO_F334C8", "NUCLEO_F302R8", "NUCLEO_F303ZE", "NUCLEO_F070RB", "NUCLEO_F207ZG",
@@ -787,7 +787,7 @@ TESTS = [
"dependencies": [MBED_LIBRARIES, RTOS_LIBRARIES, TEST_MBED_LIB],
"automated": True,
#"host_test": "wait_us_auto",
- "mcu": ["LPC1768", "LPC1549", "LPC11U24", "LPC812", "LPC2460", "LPC824", "SSCI824",
+ "mcu": ["LPC1768", "LPC1549", "LPC11U24", "LPC812", "LPC824", "SSCI824",
"KL25Z", "KL05Z", "K22F", "K64F", "K66F", "KL43Z", "KL46Z", "HEXIWEAR",
"RZ_A1H", "VK_RZ_A1H", "DISCO_F407VG", "DISCO_F429ZI", "NUCLEO_F411RE", "NUCLEO_F412ZG", "DISCO_F469NI", "NUCLEO_F410RB", "NUCLEO_F429ZI",
"NUCLEO_F401RE", "NUCLEO_F334R8", "DISCO_F334C8", "NUCLEO_F302R8", "NUCLEO_F303ZE", "NUCLEO_F070RB", "NUCLEO_F207ZG",
@@ -803,7 +803,7 @@ TESTS = [
"source_dir": join(TEST_DIR, "rtos", "mbed", "isr"),
"dependencies": [MBED_LIBRARIES, RTOS_LIBRARIES, TEST_MBED_LIB],
"automated": True,
- "mcu": ["LPC1768", "LPC1549", "LPC11U24", "LPC812", "LPC2460", "LPC824", "SSCI824",
+ "mcu": ["LPC1768", "LPC1549", "LPC11U24", "LPC812", "LPC824", "SSCI824",
"KL25Z", "KL05Z", "K22F", "K64F", "K66F", "KL43Z", "KL46Z", "HEXIWEAR",
"RZ_A1H", "VK_RZ_A1H", "DISCO_F407VG", "DISCO_F429ZI", "NUCLEO_F411RE", "NUCLEO_F412ZG", "DISCO_F469NI", "NUCLEO_F410RB", "NUCLEO_F429ZI",
"NUCLEO_F401RE", "NUCLEO_F334R8", "DISCO_F334C8", "NUCLEO_F302R8", "NUCLEO_F303ZE", "NUCLEO_F070RB", "NUCLEO_F207ZG",
@@ -948,7 +948,7 @@ TESTS = [
"source_dir": join(TEST_DIR, "utest", "semihost_fs"),
"dependencies": [MBED_LIBRARIES, TEST_MBED_LIB, CPPUTEST_LIBRARY],
"automated": False,
- "mcu": ["LPC1768", "LPC2368", "LPC11U24"]
+ "mcu": ["LPC1768", "LPC11U24"]
},
{
"id": "UT_3", "description": "General tests",
diff --git a/tools/toolchains/__init__.py b/tools/toolchains/__init__.py
index d63dc5f2ec..fc08727593 100644
--- a/tools/toolchains/__init__.py
+++ b/tools/toolchains/__init__.py
@@ -215,7 +215,7 @@ class Resources:
# standard labels for the "TARGET_" and "TOOLCHAIN_" specific directories, but
# had the knowledge of a list of these directories to be ignored.
LEGACY_IGNORE_DIRS = set([
- 'LPC11U24', 'LPC1768', 'LPC2368', 'LPC4088', 'LPC812', 'KL25Z',
+ 'LPC11U24', 'LPC1768', 'LPC4088', 'LPC812', 'KL25Z',
'ARM', 'uARM', 'IAR',
'GCC_ARM', 'GCC_CS', 'GCC_CR', 'GCC_CW', 'GCC_CW_EWL', 'GCC_CW_NEWLIB',
])