Updates to LPC4330_M4 drivers

pull/400/head
jesusalvarez 2014-07-11 14:48:25 -04:00
parent 6d2c15e80d
commit 4e82296c05
26 changed files with 6825 additions and 1977 deletions

220
build.log Normal file

File diff suppressed because one or more lines are too long

View File

@ -0,0 +1,12 @@
FUNC void Setup (unsigned int region) {
region &= 0xFF000000;
_WDWORD(0x40043100, region); // Set the shadow pointer
_WDWORD(0xE000ED08, 0); // Set the vector table offset to 0
SP = _RDWORD(0); // Setup Stack Pointer
PC = _RDWORD(4); // Setup Program Counter
}
LOAD %L INCREMENTAL
Setup(0x14000000); // Get ready to execute image in QSPI

View File

@ -29,7 +29,8 @@
; * this code.
; */
__initial_sp EQU 0x10020000 ; Top of first RAM segment for LPC43XX
; __initial_sp EQU 0x10020000 ; Top of first RAM segment for LPC43XX (IRAM1)
__initial_sp EQU 0x10092000 ; Top of first RAM segment for LPC43XX (IRAM2)
PRESERVE8
THUMB
@ -121,19 +122,21 @@ __Vectors DCD __initial_sp ; 0 Top of Stack
AREA |.text|, CODE, READONLY
; Reset Handler
Reset_Handler PROC
EXPORT Reset_Handler [WEAK]
IMPORT SystemInit
IMPORT __main
IMPORT SystemInit
LDR R0, =SystemInit
BLX R0
LDR R0, =SystemInit
BLX R0
LDR R0, =__main
BX R0
ENDP
; Dummy Exception Handlers (infinite loops which can be modified)
; Dummy Exception Handlers (infinite loops which can be modified)
NMI_Handler PROC
EXPORT NMI_Handler [WEAK]

View File

@ -1,19 +1,281 @@
/*
* LPC43XX Dual core Blinky stand-alone Cortex-M4 LD script
*/
/* mbed - LPC4330_M4 linker script
* Based linker script generated by Code Red Technologies Red Suite 7.0
*/
GROUP(libgcc.a libc.a libstdc++.a libm.a libcr_newlib_nohost.a crti.o crtn.o crtbegin.o crtend.o)
MEMORY
{
/* Define each memory region */
RO_MEM (rx) : ORIGIN = 0x14000000, LENGTH = 0x40000 /* 256K */
RW_MEM (rwx) : ORIGIN = 0x10000000, LENGTH = 0x8000 /* 32k */
RW_MEM1 (rwx) : ORIGIN = 0x20004000, LENGTH = 0x4000 /* 16K */
SH_MEM (rwx) : ORIGIN = 0x20000000, LENGTH = 0x2000 /* 8k */
FAT12_MEM (rwx) : ORIGIN = 0x20002000, LENGTH = 0x2000 /* 8k */
RamLoc128 (rwx) : ORIGIN = 0x10000118, LENGTH = 0x1FEE8 /* 128K bytes */
RamLoc72 (rwx) : ORIGIN = 0x10080000, LENGTH = 0x12000 /* 72K bytes */
RamAHB32 (rwx) : ORIGIN = 0x20000000, LENGTH = 0x8000 /* 32K bytes */
RamAHB16 (rwx) : ORIGIN = 0x20008000, LENGTH = 0x4000 /* 16K bytes */
RamAHB_ETB16 (rwx) : ORIGIN = 0x2000c000, LENGTH = 0x4000 /* 16K bytes */
SPIFI (rx) : ORIGIN = 0x14000000, LENGTH = 0x400000 /* 4M bytes */
}
/* Define a symbol for the top of each memory region */
__top_RamLoc128 = 0x10000000 + 0x20000;
__top_RamLoc72 = 0x10080000 + 0x12000;
__top_RamAHB32 = 0x20000000 + 0x8000;
__top_RamAHB16 = 0x20008000 + 0x4000;
__top_RamAHB_ETB16 = 0x2000c000 + 0x4000;
__top_SPIFI = 0x14000000 + 0x400000;
__top_RW_MEM = 0x10000000 + 0x8000;
ENTRY(ResetISR)
INCLUDE "lpc43xx_dualcore_lib.ld"
INCLUDE "lpc43xx_dualcore.ld"
SECTIONS
{
/* MAIN TEXT SECTION */
.text : ALIGN(4)
{
FILL(0xff)
__vectors_start__ = ABSOLUTE(.) ;
KEEP(*(.isr_vector))
/* Global Section Table */
. = ALIGN(4) ;
__section_table_start = .;
__data_section_table = .;
LONG(LOADADDR(.data));
LONG( ADDR(.data));
LONG( SIZEOF(.data));
LONG(LOADADDR(.data_RAM2));
LONG( ADDR(.data_RAM2));
LONG( SIZEOF(.data_RAM2));
LONG(LOADADDR(.data_RAM3));
LONG( ADDR(.data_RAM3));
LONG( SIZEOF(.data_RAM3));
LONG(LOADADDR(.data_RAM4));
LONG( ADDR(.data_RAM4));
LONG( SIZEOF(.data_RAM4));
LONG(LOADADDR(.data_RAM5));
LONG( ADDR(.data_RAM5));
LONG( SIZEOF(.data_RAM5));
__data_section_table_end = .;
__bss_section_table = .;
LONG( ADDR(.bss));
LONG( SIZEOF(.bss));
LONG( ADDR(.bss_RAM2));
LONG( SIZEOF(.bss_RAM2));
LONG( ADDR(.bss_RAM3));
LONG( SIZEOF(.bss_RAM3));
LONG( ADDR(.bss_RAM4));
LONG( SIZEOF(.bss_RAM4));
LONG( ADDR(.bss_RAM5));
LONG( SIZEOF(.bss_RAM5));
__bss_section_table_end = .;
__section_table_end = . ;
/* End of Global Section Table */
*(.after_vectors*)
} >SPIFI
.text : ALIGN(4)
{
*(.text*)
*(.rodata .rodata.* .constdata .constdata.*)
. = ALIGN(4);
/* C++ constructors etc */
. = 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 = .;
KEEP(*(.fini));
. = ALIGN(4);
KEEP (*crtbegin.o(.ctors))
KEEP (*(EXCLUDE_FILE (*crtend.o) .ctors))
KEEP (*(SORT(.ctors.*)))
KEEP (*crtend.o(.ctors))
. = ALIGN(4);
KEEP (*crtbegin.o(.dtors))
KEEP (*(EXCLUDE_FILE (*crtend.o) .dtors))
KEEP (*(SORT(.dtors.*)))
KEEP (*crtend.o(.dtors))
/* End C++ */
} > SPIFI
/*
* for exception handling/unwind - some Newlib functions (in common
* with C++ and STDC++) use this.
*/
.ARM.extab : ALIGN(4)
{
*(.ARM.extab* .gnu.linkonce.armextab.*)
} > SPIFI
__exidx_start = .;
.ARM.exidx : ALIGN(4)
{
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
} > SPIFI
__exidx_end = .;
_etext = .;
/* DATA section for RamLoc72 */
.data_RAM2 : ALIGN(4)
{
FILL(0xff)
*(.ramfunc.$RAM2)
*(.ramfunc.$RamLoc72)
*(.data.$RAM2*)
*(.data.$RamLoc72*)
. = ALIGN(4) ;
} > RamLoc72 AT>SPIFI
/* DATA section for RamAHB32 */
.data_RAM3 : ALIGN(4)
{
FILL(0xff)
*(.ramfunc.$RAM3)
*(.ramfunc.$RamAHB32)
*(.data.$RAM3*)
*(.data.$RamAHB32*)
. = ALIGN(4) ;
} > RamAHB32 AT>SPIFI
/* DATA section for RamAHB16 */
.data_RAM4 : ALIGN(4)
{
FILL(0xff)
*(.ramfunc.$RAM4)
*(.ramfunc.$RamAHB16)
*(.data.$RAM4*)
*(.data.$RamAHB16*)
. = ALIGN(4) ;
} > RamAHB16 AT>SPIFI
/* DATA section for RamAHB_ETB16 */
.data_RAM5 : ALIGN(4)
{
FILL(0xff)
*(.ramfunc.$RAM5)
*(.ramfunc.$RamAHB_ETB16)
*(.data.$RAM5*)
*(.data.$RamAHB_ETB16*)
. = ALIGN(4) ;
} > RamAHB_ETB16 AT>SPIFI
/* MAIN DATA SECTION */
.uninit_RESERVED : ALIGN(4)
{
KEEP(*(.bss.$RESERVED*))
. = ALIGN(4) ;
_end_uninit_RESERVED = .;
} > RamLoc128
/* Main DATA section (RamLoc128) */
.data : ALIGN(4)
{
FILL(0xff)
_data = . ;
*(vtable)
*(.ramfunc*)
*(.data*)
. = ALIGN(4) ;
_edata = . ;
} > RamLoc128 AT>SPIFI
/* BSS section for RamLoc72 */
.bss_RAM2 : ALIGN(4)
{
*(.bss.$RAM2*)
*(.bss.$RamLoc72*)
. = ALIGN(4) ;
} > RamLoc72
/* BSS section for RamAHB32 */
.bss_RAM3 : ALIGN(4)
{
*(.bss.$RAM3*)
*(.bss.$RamAHB32*)
. = ALIGN(4) ;
} > RamAHB32
/* BSS section for RamAHB16 */
.bss_RAM4 : ALIGN(4)
{
*(.bss.$RAM4*)
*(.bss.$RamAHB16*)
. = ALIGN(4) ;
} > RamAHB16
/* BSS section for RamAHB_ETB16 */
.bss_RAM5 : ALIGN(4)
{
*(.bss.$RAM5*)
*(.bss.$RamAHB_ETB16*)
. = ALIGN(4) ;
} > RamAHB_ETB16
/* MAIN BSS SECTION */
.bss : ALIGN(4)
{
_bss = .;
*(.bss*)
*(COMMON)
. = ALIGN(4) ;
_ebss = .;
PROVIDE(end = .);
} > RamLoc128
/* NOINIT section for RamLoc72 */
.noinit_RAM2 (NOLOAD) : ALIGN(4)
{
*(.noinit.$RAM2*)
*(.noinit.$RamLoc72*)
. = ALIGN(4) ;
} > RamLoc72
/* NOINIT section for RamAHB32 */
.noinit_RAM3 (NOLOAD) : ALIGN(4)
{
*(.noinit.$RAM3*)
*(.noinit.$RamAHB32*)
. = ALIGN(4) ;
} > RamAHB32
/* NOINIT section for RamAHB16 */
.noinit_RAM4 (NOLOAD) : ALIGN(4)
{
*(.noinit.$RAM4*)
*(.noinit.$RamAHB16*)
. = ALIGN(4) ;
} > RamAHB16
/* NOINIT section for RamAHB_ETB16 */
.noinit_RAM5 (NOLOAD) : ALIGN(4)
{
*(.noinit.$RAM5*)
*(.noinit.$RamAHB_ETB16*)
. = ALIGN(4) ;
} > RamAHB_ETB16
/* DEFAULT NOINIT SECTION */
.noinit (NOLOAD): ALIGN(4)
{
_noinit = .;
*(.noinit*)
. = ALIGN(4) ;
_end_noinit = .;
} > RamLoc128
PROVIDE(_pvHeapStart = .);
PROVIDE(_vStackTop = __top_RamLoc128 - 0);
}

View File

@ -1,10 +1,10 @@
// *****************************************************************************
// +--+
// | ++----+
// +-++ |
// | |
// +-+--+ |
// | +--+--+
//*****************************************************************************
// +--+
// | ++----+
// +-++ |
// | |
// +-+--+ |
// | +--+--+
// +----+ Copyright (c) 2011-12 Code Red Technologies Ltd.
//
// LPC43xx Microcontroller Startup code for use with Red Suite
@ -12,62 +12,58 @@
// Version : 120430
//
// Software License Agreement
//
//
// The software is owned by Code Red Technologies and/or its suppliers, and is
// protected under applicable copyright laws. All rights are reserved. Any
// use in violation of the foregoing restrictions may subject the user to criminal
// sanctions under applicable laws, as well as to civil liability for the breach
// protected under applicable copyright laws. All rights are reserved. Any
// use in violation of the foregoing restrictions may subject the user to criminal
// sanctions under applicable laws, as well as to civil liability for the breach
// of the terms and conditions of this license.
//
//
// THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED
// OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF
// MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE.
// USE OF THIS SOFTWARE FOR COMMERCIAL DEVELOPMENT AND/OR EDUCATION IS SUBJECT
// TO A CURRENT END USER LICENSE AGREEMENT (COMMERCIAL OR EDUCATIONAL) WITH
// CODE RED TECHNOLOGIES LTD.
// CODE RED TECHNOLOGIES LTD.
//
// *****************************************************************************
#if defined(__cplusplus)
//*****************************************************************************
#if defined (__cplusplus)
#ifdef __REDLIB__
#error Redlib does not support C++
#else
// *****************************************************************************
//*****************************************************************************
//
// The entry point for the C++ library startup
//
// *****************************************************************************
//*****************************************************************************
extern "C" {
extern void __libc_init_array(void);
extern void __libc_init_array(void);
}
#endif
#endif
#define WEAK __attribute__ ((weak))
#define ALIAS(f) __attribute__ ((weak, alias(# f)))
#define ALIAS(f) __attribute__ ((weak, alias (#f)))
//#if defined (__USE_CMSIS)
// Code Red - if CMSIS is being used, then SystemInit() routine
// will be called by startup code rather than in application's main()
#if defined (__USE_CMSIS)
#include "LPC43xx.h"
//#endif
#if defined(OS_UCOS_III)
extern void OS_CPU_PendSVHandler(void);
extern void OS_CPU_SysTickHandler (void);
#endif
// *****************************************************************************
#if defined(__cplusplus)
//*****************************************************************************
#if defined (__cplusplus)
extern "C" {
#endif
// *****************************************************************************
//*****************************************************************************
//
// Forward declaration of the default handlers. These are aliased.
// When the application defines a handler (with the same name), this will
// When the application defines a handler (with the same name), this will
// automatically take precedence over these weak definitions
//
// *****************************************************************************
void ResetISR(void);
//*****************************************************************************
void ResetISR(void);
WEAK void NMI_Handler(void);
WEAK void HardFault_Handler(void);
WEAK void MemManage_Handler(void);
@ -79,18 +75,19 @@ WEAK void PendSV_Handler(void);
WEAK void SysTick_Handler(void);
WEAK void IntDefaultHandler(void);
// *****************************************************************************
//*****************************************************************************
//
// Forward declaration of the specific IRQ handlers. These are aliased
// to the IntDefaultHandler, which is a 'forever' loop. When the application
// defines a handler (with the same name), this will automatically take
// defines a handler (with the same name), this will automatically take
// precedence over these weak definitions
//
// *****************************************************************************
//*****************************************************************************
void DAC_IRQHandler(void) ALIAS(IntDefaultHandler);
void MX_CORE_IRQHandler(void) ALIAS(IntDefaultHandler);
void M0CORE_IRQHandler(void) ALIAS(IntDefaultHandler);
void DMA_IRQHandler(void) ALIAS(IntDefaultHandler);
void FLASHEEPROM_IRQHandler(void) ALIAS(IntDefaultHandler);
void EZH_IRQHandler(void) ALIAS(IntDefaultHandler);
void FLASH_EEPROM_IRQHandler(void) ALIAS(IntDefaultHandler);
void ETH_IRQHandler(void) ALIAS(IntDefaultHandler);
void SDIO_IRQHandler(void) ALIAS(IntDefaultHandler);
void LCD_IRQHandler(void) ALIAS(IntDefaultHandler);
@ -105,8 +102,8 @@ void TIMER3_IRQHandler(void) ALIAS(IntDefaultHandler);
void MCPWM_IRQHandler(void) ALIAS(IntDefaultHandler);
void ADC0_IRQHandler(void) ALIAS(IntDefaultHandler);
void I2C0_IRQHandler(void) ALIAS(IntDefaultHandler);
void I2C1_IRQHandler(void) ALIAS(IntDefaultHandler);
void SPI_IRQHandler (void) ALIAS(IntDefaultHandler);
void I2C1_IRQHandler(void) ALIAS(IntDefaultHandler);
void ADC1_IRQHandler(void) ALIAS(IntDefaultHandler);
void SSP0_IRQHandler(void) ALIAS(IntDefaultHandler);
void SSP1_IRQHandler(void) ALIAS(IntDefaultHandler);
@ -130,157 +127,130 @@ void GINT0_IRQHandler(void) ALIAS(IntDefaultHandler);
void GINT1_IRQHandler(void) ALIAS(IntDefaultHandler);
void EVRT_IRQHandler(void) ALIAS(IntDefaultHandler);
void CAN1_IRQHandler(void) ALIAS(IntDefaultHandler);
void VADC_IRQHandler(void) ALIAS(IntDefaultHandler);
void ATIMER_IRQHandler(void) ALIAS(IntDefaultHandler);
void RTC_IRQHandler(void) ALIAS(IntDefaultHandler);
void WDT_IRQHandler(void) ALIAS(IntDefaultHandler);
void M0s_IRQHandler(void) ALIAS(IntDefaultHandler);
void CAN0_IRQHandler(void) ALIAS(IntDefaultHandler);
void QEI_IRQHandler(void) ALIAS(IntDefaultHandler);
// *****************************************************************************
//*****************************************************************************
//
// The entry point for the application.
// __main() is the entry point for Redlib based applications
// main() is the entry point for Newlib based applications
//
// *****************************************************************************
#if defined(__REDLIB__)
//*****************************************************************************
#if defined (__REDLIB__)
extern void __main(void);
#endif
extern int main(void);
// *****************************************************************************
//*****************************************************************************
//
// External declaration for the pointer to the stack top from the Linker Script
//
// *****************************************************************************
//*****************************************************************************
extern void _vStackTop(void);
// *****************************************************************************
//
// Application can define Stack size (If not defined, default stack size will
// used
//
// *****************************************************************************
#ifndef STACK_SIZE
#define STACK_SIZE (0x200)
//*****************************************************************************
#if defined (__cplusplus)
} // extern "C"
#endif
// *****************************************************************************
//
// Application can define Heap size (If not defined, default Heap size will
// used
//
// *****************************************************************************
#ifndef HEAP_SIZE
#define HEAP_SIZE (0x4000)
#endif
unsigned int __vStack[STACK_SIZE / sizeof(unsigned int)] __attribute__((section("STACK,\"aw\",%nobits@")));
unsigned int __vHeap[HEAP_SIZE / sizeof(unsigned int)] __attribute__((section("HEAP,\"aw\",%nobits@")));
// *****************************************************************************
#if defined(__cplusplus)
} // extern "C"
#endif
// *****************************************************************************
//*****************************************************************************
//
// The vector table.
// This relies on the linker script to place at correct location in memory.
//
// *****************************************************************************
extern void(*const g_pfnVectors[]) (void);
//*****************************************************************************
extern void (* const g_pfnVectors[])(void);
__attribute__ ((section(".isr_vector")))
void(*const g_pfnVectors[]) (void) = {
// Core Level - CM4/CM3
&_vStackTop, // The initial stack pointer
ResetISR, // The reset handler
NMI_Handler, // The NMI handler
HardFault_Handler, // The hard fault handler
MemManage_Handler, // The MPU fault handler
BusFault_Handler, // The bus fault handler
UsageFault_Handler, // The usage fault handler
0, // Reserved
0, // Reserved
0, // Reserved
0, // Reserved
SVC_Handler, // SVCall handler
DebugMon_Handler, // Debug monitor handler
0, // Reserved
#if defined(OS_UCOS_III)
OS_CPU_PendSVHandler, // uCOS-III PendSV handler
OS_CPU_SysTickHandler, // uCOS-III SysTick handler
#else
PendSV_Handler, // The PendSV handler
SysTick_Handler, // The SysTick handler
#endif
void (* const g_pfnVectors[])(void) = {
// Core Level - CM4
&_vStackTop, // The initial stack pointer
ResetISR, // The reset handler
NMI_Handler, // The NMI handler
HardFault_Handler, // The hard fault handler
MemManage_Handler, // The MPU fault handler
BusFault_Handler, // The bus fault handler
UsageFault_Handler, // The usage fault handler
0, // Reserved
0, // Reserved
0, // Reserved
0, // Reserved
SVC_Handler, // SVCall handler
DebugMon_Handler, // Debug monitor handler
0, // Reserved
PendSV_Handler, // The PendSV handler
SysTick_Handler, // The SysTick handler
// Chip Level - LPC18xx/43xx
DAC_IRQHandler, // 16 D/A Converter
MX_CORE_IRQHandler, // 17 CortexM4/M0 (LPC43XX ONLY)
DMA_IRQHandler, // 18 General Purpose DMA
0, // 19 Reserved
FLASHEEPROM_IRQHandler, // 20 ORed flash Bank A, flash Bank B, EEPROM interrupts
ETH_IRQHandler, // 21 Ethernet
SDIO_IRQHandler, // 22 SD/MMC
LCD_IRQHandler, // 23 LCD
USB0_IRQHandler, // 24 USB0
USB1_IRQHandler, // 25 USB1
SCT_IRQHandler, // 26 State Configurable Timer
RIT_IRQHandler, // 27 Repetitive Interrupt Timer
TIMER0_IRQHandler, // 28 Timer0
TIMER1_IRQHandler, // 29 Timer 1
TIMER2_IRQHandler, // 30 Timer 2
TIMER3_IRQHandler, // 31 Timer 3
MCPWM_IRQHandler, // 32 Motor Control PWM
ADC0_IRQHandler, // 33 A/D Converter 0
I2C0_IRQHandler, // 34 I2C0
I2C1_IRQHandler, // 35 I2C1
SPI_IRQHandler, // 36 SPI (LPC43XX ONLY)
ADC1_IRQHandler, // 37 A/D Converter 1
SSP0_IRQHandler, // 38 SSP0
SSP1_IRQHandler, // 39 SSP1
UART0_IRQHandler, // 40 UART0
UART1_IRQHandler, // 41 UART1
UART2_IRQHandler, // 42 UART2
UART3_IRQHandler, // 43 USRT3
I2S0_IRQHandler, // 44 I2S0
I2S1_IRQHandler, // 45 I2S1
SPIFI_IRQHandler, // 46 SPI Flash Interface
SGPIO_IRQHandler, // 47 SGPIO (LPC43XX ONLY)
GPIO0_IRQHandler, // 48 GPIO0
GPIO1_IRQHandler, // 49 GPIO1
GPIO2_IRQHandler, // 50 GPIO2
GPIO3_IRQHandler, // 51 GPIO3
GPIO4_IRQHandler, // 52 GPIO4
GPIO5_IRQHandler, // 53 GPIO5
GPIO6_IRQHandler, // 54 GPIO6
GPIO7_IRQHandler, // 55 GPIO7
GINT0_IRQHandler, // 56 GINT0
GINT1_IRQHandler, // 57 GINT1
EVRT_IRQHandler, // 58 Event Router
CAN1_IRQHandler, // 59 C_CAN1
0, // 60 Reserved
0, // 61 Reserved
ATIMER_IRQHandler, // 62 ATIMER
RTC_IRQHandler, // 63 RTC
0, // 64 Reserved
WDT_IRQHandler, // 65 WDT
0, // 66 Reserved
CAN0_IRQHandler, // 67 C_CAN0
QEI_IRQHandler, // 68 QEI
};
// Chip Level - LPC43
DAC_IRQHandler, // 16
M0CORE_IRQHandler, // 17
DMA_IRQHandler, // 18
EZH_IRQHandler, // 19
FLASH_EEPROM_IRQHandler, // 20
ETH_IRQHandler, // 21
SDIO_IRQHandler, // 22
LCD_IRQHandler, // 23
USB0_IRQHandler, // 24
USB1_IRQHandler, // 25
SCT_IRQHandler, // 26
RIT_IRQHandler, // 27
TIMER0_IRQHandler, // 28
TIMER1_IRQHandler, // 29
TIMER2_IRQHandler, // 30
TIMER3_IRQHandler, // 31
MCPWM_IRQHandler, // 32
ADC0_IRQHandler, // 33
I2C0_IRQHandler, // 34
I2C1_IRQHandler, // 35
SPI_IRQHandler, // 36
ADC1_IRQHandler, // 37
SSP0_IRQHandler, // 38
SSP1_IRQHandler, // 39
UART0_IRQHandler, // 40
UART1_IRQHandler, // 41
UART2_IRQHandler, // 42
UART3_IRQHandler, // 43
I2S0_IRQHandler, // 44
I2S1_IRQHandler, // 45
SPIFI_IRQHandler, // 46
SGPIO_IRQHandler, // 47
GPIO0_IRQHandler, // 48
GPIO1_IRQHandler, // 49
GPIO2_IRQHandler, // 50
GPIO3_IRQHandler, // 51
GPIO4_IRQHandler, // 52
GPIO5_IRQHandler, // 53
GPIO6_IRQHandler, // 54
GPIO7_IRQHandler, // 55
GINT0_IRQHandler, // 56
GINT1_IRQHandler, // 57
EVRT_IRQHandler, // 58
CAN1_IRQHandler, // 59
0, // 60
VADC_IRQHandler, // 61
ATIMER_IRQHandler, // 62
RTC_IRQHandler, // 63
0, // 64
WDT_IRQHandler, // 65
M0s_IRQHandler, // 66
CAN0_IRQHandler, // 67
QEI_IRQHandler, // 68
};
// *****************************************************************************
//*****************************************************************************
// Functions to carry out the initialization of RW and BSS data sections. These
// are written as separate functions rather than being inlined within the
// ResetISR() function in order to cope with MCUs with multiple banks of
// memory.
// *****************************************************************************
//*****************************************************************************
__attribute__ ((section(".after_vectors")))
void data_init(unsigned int romstart, unsigned int start, unsigned int len) {
unsigned int *pulDest = (unsigned int *) start;
unsigned int *pulSrc = (unsigned int *) romstart;
unsigned int *pulDest = (unsigned int*) start;
unsigned int *pulSrc = (unsigned int*) romstart;
unsigned int loop;
for (loop = 0; loop < len; loop = loop + 4)
*pulDest++ = *pulSrc++;
@ -288,49 +258,94 @@ void data_init(unsigned int romstart, unsigned int start, unsigned int len) {
__attribute__ ((section(".after_vectors")))
void bss_init(unsigned int start, unsigned int len) {
unsigned int *pulDest = (unsigned int *) start;
unsigned int *pulDest = (unsigned int*) start;
unsigned int loop;
for (loop = 0; loop < len; loop = loop + 4)
*pulDest++ = 0;
}
// *****************************************************************************
//*****************************************************************************
// The following symbols are constructs generated by the linker, indicating
// the location of various points in the "Global Section Table". This table is
// created by the linker via the Code Red managed linker script mechanism. It
// contains the load address, execution address and length of each RW data
// section and the execution and length of each BSS (zero initialized) section.
// *****************************************************************************
//*****************************************************************************
extern unsigned int __data_section_table;
extern unsigned int __data_section_table_end;
extern unsigned int __bss_section_table;
extern unsigned int __bss_section_table_end;
// *****************************************************************************
//*****************************************************************************
// Reset entry point for your code.
// Sets up a simple runtime environment and initializes the C/C++
// library.
//
// *****************************************************************************
extern "C" void software_init_hook(void) __attribute__((weak));
//*****************************************************************************
void
ResetISR(void) {
//
// Copy the data sections from flash to SRAM.
//
// *************************************************************
// The following conditional block of code manually resets as
// much of the peripheral set of the LPC43 as possible. This is
// done because the LPC43 does not provide a means of triggering
// a full system reset under debugger control, which can cause
// problems in certain circumstances when debugging.
//
// You can prevent this code block being included if you require
// (for example when creating a final executable which you will
// not debug) by setting the define 'DONT_RESET_ON_RESTART'.
//
#ifndef DONT_RESET_ON_RESTART
// Disable interrupts
__asm volatile ("cpsid i");
// equivalent to CMSIS '__disable_irq()' function
unsigned int *RESET_CONTROL = (unsigned int *) 0x40053100;
// LPC_RGU->RESET_CTRL0 @ 0x40053100
// LPC_RGU->RESET_CTRL1 @ 0x40053104
// Note that we do not use the CMSIS register access mechanism,
// as there is no guarantee that the project has been configured
// to use CMSIS.
// Write to LPC_RGU->RESET_CTRL0
*(RESET_CONTROL+0) = 0x10DF0000;
// GPIO_RST|AES_RST|ETHERNET_RST|SDIO_RST|DMA_RST|
// USB1_RST|USB0_RST|LCD_RST
// Write to LPC_RGU->RESET_CTRL1
*(RESET_CONTROL+1) = 0x01DFF7FF;
// M0APP_RST|CAN0_RST|CAN1_RST|I2S_RST|SSP1_RST|SSP0_RST|
// I2C1_RST|I2C0_RST|UART3_RST|UART1_RST|UART1_RST|UART0_RST|
// DAC_RST|ADC1_RST|ADC0_RST|QEI_RST|MOTOCONPWM_RST|SCT_RST|
// RITIMER_RST|TIMER3_RST|TIMER2_RST|TIMER1_RST|TIMER0_RST
// Clear all pending interrupts in the NVIC
volatile unsigned int *NVIC_ICPR = (unsigned int *) 0xE000E280;
unsigned int irqpendloop;
for (irqpendloop = 0; irqpendloop < 8; irqpendloop++) {
*(NVIC_ICPR+irqpendloop)= 0xFFFFFFFF;
}
// Reenable interrupts
__asm volatile ("cpsie i");
// equivalent to CMSIS '__enable_irq()' function
#endif // ifndef DONT_RESET_ON_RESTART
// *************************************************************
//
// Copy the data sections from flash to SRAM.
//
unsigned int LoadAddr, ExeAddr, SectionLen;
unsigned int *SectionTableAddr;
/* Call SystemInit() for clocking/memory setup prior to scatter load */
SystemInit();
// Load base address of Global Section Table
SectionTableAddr = &__data_section_table;
// Copy the data sections from flash to SRAM.
// Copy the data sections from flash to SRAM.
while (SectionTableAddr < &__data_section_table_end) {
LoadAddr = *SectionTableAddr++;
ExeAddr = *SectionTableAddr++;
@ -345,107 +360,141 @@ ResetISR(void) {
bss_init(ExeAddr, SectionLen);
}
if (software_init_hook) // give control to the RTOS
software_init_hook(); // this will also call __libc_init_array
else {
#if defined(__cplusplus)
//
// Call C++ library initialisation
//
__libc_init_array();
#endif
#if defined (__VFP_FP__) && !defined (__SOFTFP__)
/*
* Code to enable the Cortex-M4 FPU only included
* if appropriate build options have been selected.
* Code taken from Section 7.1, Cortex-M4 TRM (DDI0439C)
*/
// CPACR is located at address 0xE000ED88
asm("LDR.W R0, =0xE000ED88");
// Read CPACR
asm("LDR R1, [R0]");
// Set bits 20-23 to enable CP10 and CP11 coprocessors
asm(" ORR R1, R1, #(0xF << 20)");
// Write back the modified value to the CPACR
asm("STR R1, [R0]");
#endif // (__VFP_FP__) && !(__SOFTFP__)
#if defined(__REDLIB__)
// Call the Redlib library, which in turn calls main()
__main();
#else
main();
#endif
}
// ******************************
// Check to see if we are running the code from a non-zero
// address (eg RAM, external flash), in which case we need
// to modify the VTOR register to tell the CPU that the
// vector table is located at a non-0x0 address.
// Note that we do not use the CMSIS register access mechanism,
// as there is no guarantee that the project has been configured
// to use CMSIS.
unsigned int * pSCB_VTOR = (unsigned int *) 0xE000ED08;
if ((unsigned int *)g_pfnVectors!=(unsigned int *) 0x00000000) {
// CMSIS : SCB->VTOR = <address of vector table>
*pSCB_VTOR = (unsigned int)g_pfnVectors;
}
#ifdef __USE_CMSIS
SystemInit();
#endif
#if defined (__cplusplus)
//
// main() shouldn't return, but if it does, we'll just enter an infinite loop
// Call C++ library initialisation
//
while (1) {}
__libc_init_array();
#endif
#if defined (__REDLIB__)
// Call the Redlib library, which in turn calls main()
__main() ;
#else
main();
#endif
//
// main() shouldn't return, but if it does, we'll just enter an infinite loop
//
while (1) {
;
}
}
// *****************************************************************************
//*****************************************************************************
// Default exception handlers. Override the ones here by defining your own
// handler routines in your application code.
// *****************************************************************************
//*****************************************************************************
__attribute__ ((section(".after_vectors")))
void NMI_Handler(void)
{
while (1) {}
while(1)
{
}
}
__attribute__ ((section(".after_vectors")))
void HardFault_Handler(void)
{
while (1) {}
while(1)
{
}
}
__attribute__ ((section(".after_vectors")))
void MemManage_Handler(void)
{
while (1) {}
while(1)
{
}
}
__attribute__ ((section(".after_vectors")))
void BusFault_Handler(void)
{
while (1) {}
while(1)
{
}
}
__attribute__ ((section(".after_vectors")))
void UsageFault_Handler(void)
{
while (1) {}
while(1)
{
}
}
__attribute__ ((section(".after_vectors")))
void SVC_Handler(void)
{
while (1) {}
while(1)
{
}
}
__attribute__ ((section(".after_vectors")))
void DebugMon_Handler(void)
{
while (1) {}
while(1)
{
}
}
__attribute__ ((section(".after_vectors")))
void PendSV_Handler(void)
{
while (1) {}
while(1)
{
}
}
__attribute__ ((section(".after_vectors")))
void SysTick_Handler(void)
{
while (1) {}
while(1)
{
}
}
// *****************************************************************************
//*****************************************************************************
//
// Processor ends up here if an unexpected interrupt occurs or a specific
// handler is not present in the application code.
//
// *****************************************************************************
//*****************************************************************************
__attribute__ ((section(".after_vectors")))
void IntDefaultHandler(void)
{
while (1) {}
while(1)
{
}
}
// *****************************************************************************
//
// Heap overflow check function required by REDLib_V2 library
//
// *****************************************************************************
extern unsigned int *_pvHeapStart;
unsigned int __check_heap_overflow (void * new_end_of_heap)
{
return (new_end_of_heap >= (void *)&__vHeap[HEAP_SIZE/sizeof(unsigned int)]);
}

View File

@ -35,8 +35,11 @@
#define COUNT_OF(a) (sizeof(a)/sizeof(a[0]))
/* Clock variables */
//uint32_t SystemCoreClock = CRYSTAL_MAIN_FREQ_IN; /*!< System Clock Frequency (Core Clock)*/
uint32_t SystemCoreClock = 204000000;
#if (CLOCK_SETUP)
uint32_t SystemCoreClock = MAX_CLOCK_FREQ;
#else
uint32_t SystemCoreClock = CRYSTAL_MAIN_FREQ_IN;
#endif
#if !defined(CORE_M0)
/* SCU pin definitions for pin muxing */
@ -45,32 +48,80 @@ typedef struct {
uint16_t mode; /* SCU pin mode and function */
} PINMUX_GRP_T;
/* Local functions */
static void SystemCoreClockUpdate(void);
static void SystemSetupClock(void);
static void SystemSetupPins(const PINMUX_GRP_T *mux, uint32_t n);
static void SystemSetupMemory(void);
static void WaitUs(uint32_t us);
/* Pins to initialize before clocks are configured */
static const PINMUX_GRP_T pre_clock_mux[] = {
/* SPIFI pins */
{SCU_REG(0x3, 3), (SCU_PINIO_FAST | 0x3)}, // P3_3 SPIFI CLK
{SCU_REG(0x3, 4), (SCU_PINIO_FAST | 0x3)}, // P3_4 SPIFI D3
{SCU_REG(0x3, 5), (SCU_PINIO_FAST | 0x3)}, // P3_5 SPIFI D2
{SCU_REG(0x3, 6), (SCU_PINIO_FAST | 0x3)}, // P3_6 SPIFI D1
{SCU_REG(0x3, 7), (SCU_PINIO_FAST | 0x3)}, // P3_7 SPIFI D0
{SCU_REG(0x3, 8), (SCU_PINIO_FAST | 0x3)} // P3_8 SPIFI CS/SSEL
{SCU_REG(0x3, 3), (SCU_PINIO_FAST | 0x3)}, /* P3_3 SPIFI CLK */
{SCU_REG(0x3, 4), (SCU_PINIO_FAST | 0x3)}, /* P3_4 SPIFI D3 */
{SCU_REG(0x3, 5), (SCU_PINIO_FAST | 0x3)}, /* P3_5 SPIFI D2 */
{SCU_REG(0x3, 6), (SCU_PINIO_FAST | 0x3)}, /* P3_6 SPIFI D1 */
{SCU_REG(0x3, 7), (SCU_PINIO_FAST | 0x3)}, /* P3_7 SPIFI D0 */
{SCU_REG(0x3, 8), (SCU_PINIO_FAST | 0x3)} /* P3_8 SPIFI CS/SSEL */
};
/* Pins to initialize after clocks are configured */
static const PINMUX_GRP_T post_clock_mux[] = {
/* Boot pins */
{SCU_REG(0x1, 1), (SCU_PINIO_FAST | 0x0)}, // P1_1 BOOT0
{SCU_REG(0x1, 2), (SCU_PINIO_FAST | 0x0)}, // P1_2 BOOT1
{SCU_REG(0x2, 8), (SCU_PINIO_FAST | 0x0)}, // P2_8 BOOT2
{SCU_REG(0x2, 9), (SCU_PINIO_FAST | 0x0)} // P2_9 BOOT3
{SCU_REG(0x1, 1), (SCU_PINIO_FAST | 0x0)}, /* P1_1 BOOT0 */
{SCU_REG(0x1, 2), (SCU_PINIO_FAST | 0x0)}, /* P1_2 BOOT1 */
{SCU_REG(0x2, 8), (SCU_PINIO_FAST | 0x0)}, /* P2_8 BOOT2 */
{SCU_REG(0x2, 9), (SCU_PINIO_FAST | 0x0)}, /* P2_9 BOOT3 */
/* Micromint Bambino 200/210 */
{SCU_REG(0x6, 11), (SCU_PINIO_FAST | 0x0)}, /* P6_11 LED1 */
{SCU_REG(0x2, 5), (SCU_PINIO_FAST | 0x0)}, /* P2_5 LED2 */
{SCU_REG(0x2, 7), (SCU_PINIO_FAST | 0x0)}, /* P2_7 BTN1 */
/* Micromint Bambino 210 */
{SCU_REG(0x6, 1), (SCU_PINIO_FAST | 0x0)}, /* P6_1 LED3 */
{SCU_REG(0x6, 2), (SCU_PINIO_FAST | 0x0)}, /* P6_2 LED4 */
};
#if (CLOCK_SETUP)
/* Structure for initial base clock states */
struct CLK_BASE_STATES {
CGU_BASE_CLK_T clk; /* Base clock */
CGU_CLKIN_T clkin; /* Base clock source */
uint8_t powerdn; /* Set to 1 if base clock is initially powered down */
};
/* Initial base clock states are mostly on */
static const struct CLK_BASE_STATES clock_states[] = {
{CLK_BASE_SAFE, CLKIN_IRC, 0},
{CLK_BASE_APB1, CLKIN_MAINPLL, 0},
{CLK_BASE_APB3, CLKIN_MAINPLL, 0},
{CLK_BASE_USB0, CLKIN_USBPLL, 1},
{CLK_BASE_PERIPH, CLKIN_MAINPLL, 0},
{CLK_BASE_SPI, CLKIN_MAINPLL, 0},
{CLK_BASE_PHY_TX, CLKIN_ENET_TX, 0},
#if defined(USE_RMII)
{CLK_BASE_PHY_RX, CLKIN_ENET_TX, 0},
#else
{CLK_BASE_PHY_RX, CLKIN_ENET_RX, 0},
#endif
{CLK_BASE_SDIO, CLKIN_MAINPLL, 0},
{CLK_BASE_SSP0, CLKIN_MAINPLL, 0},
{CLK_BASE_SSP1, CLKIN_MAINPLL, 0},
{CLK_BASE_UART0, CLKIN_MAINPLL, 0},
{CLK_BASE_UART1, CLKIN_MAINPLL, 0},
{CLK_BASE_UART2, CLKIN_MAINPLL, 0},
{CLK_BASE_UART3, CLKIN_MAINPLL, 0},
{CLK_BASE_OUT, CLKINPUT_PD, 0},
{CLK_BASE_APLL, CLKINPUT_PD, 0},
{CLK_BASE_CGU_OUT0, CLKINPUT_PD, 0},
{CLK_BASE_CGU_OUT1, CLKINPUT_PD, 0},
/* Clocks derived from dividers */
{CLK_BASE_LCD, CLKIN_IDIVC, 0},
{CLK_BASE_USB1, CLKIN_IDIVD, 1}
};
#endif /* defined(CLOCK_SETUP) */
/* Local functions */
static uint32_t SystemGetMainPLLHz(void);
static void SystemSetupClock(void);
static void SystemSetupPins(const PINMUX_GRP_T *mux, uint32_t n);
static void SystemSetupMemory(void);
static void WaitUs(uint32_t us);
#endif /* !defined(CORE_M0) */
/*
@ -79,33 +130,34 @@ static const PINMUX_GRP_T post_clock_mux[] = {
void SystemInit(void)
{
#if !defined(CORE_M0)
unsigned int *pSCB_VTOR = (unsigned int *) 0xE000ED08;
/* Initialize vector table in flash */
#if defined(__ARMCC_VERSION)
extern void *__Vectors;
*pSCB_VTOR = (unsigned int) &__Vectors;
SCB->VTOR = (unsigned int) &__Vectors;
#elif defined(__IAR_SYSTEMS_ICC__)
extern void *__vector_table;
*pSCB_VTOR = (unsigned int) &__vector_table;
SCB->VTOR = (unsigned int) &__vector_table;
#elif defined(TOOLCHAIN_GCC_ARM)
extern void *__isr_vector;
*pSCB_VTOR = (unsigned int) &__isr_vector;
SCB->VTOR = (unsigned int) &__isr_vector;
#else /* defined(__GNUC__) and others */
extern void *g_pfnVectors;
*pSCB_VTOR = (unsigned int) &g_pfnVectors;
SCB->VTOR = (unsigned int) &g_pfnVectors;
#endif
#if !defined(TOOLCHAIN_GCC)
#if defined(__FPU_PRESENT) && __FPU_PRESENT == 1
/* Initialize floating point */
fpuInit();
#endif
#endif
SystemSetupPins(pre_clock_mux, COUNT_OF(pre_clock_mux)); /* Configure pins */
SystemSetupClock(); /* Configure processor and peripheral clocks */
SystemSetupPins(post_clock_mux, COUNT_OF(post_clock_mux)); /* Configure pins */
SystemSetupMemory(); /* Configure external memory */
@ -119,44 +171,125 @@ void SystemInit(void)
*/
void SystemCoreClockUpdate(void)
{
uint32_t reg, div, rate;
/* Get main PLL rate */
rate = SystemGetMainPLLHz();
/* Get clock divider */
reg = LPC_CCU1->CLKCCU[CLK_MX_MXCORE].CFG;
if (((reg >> 5) & 0x7) == 0) {
div = 1;
}
else {
div = 2;
}
rate = rate / div;
SystemCoreClock = rate;
}
/* Returns the frequency of the main PLL */
uint32_t SystemGetMainPLLHz(void)
{
uint32_t PLLReg = LPC_CGU->PLL1_CTRL;
uint32_t freq = CRYSTAL_MAIN_FREQ_IN;
uint32_t msel, nsel, psel, direct, fbsel;
uint32_t m, n, p;
const uint8_t ptab[] = {1, 2, 4, 8};
msel = (PLLReg >> 16) & 0xFF;
nsel = (PLLReg >> 12) & 0x3;
psel = (PLLReg >> 8) & 0x3;
direct = (PLLReg >> 7) & 0x1;
fbsel = (PLLReg >> 6) & 0x1;
m = msel + 1;
n = nsel + 1;
p = ptab[psel];
if (direct || fbsel) {
return m * (freq / n);
}
return (m / (2 * p)) * (freq / n);
}
#if !defined(CORE_M0)
/*
* SystemSetupClock() - Set processor and peripheral clocks
*
* Clock Frequency Source
* CLK_BASE_MX 204 MHz CLKIN_MAINPLL (CLKIN_PLL1)
* CLK_BASE_SPIFI 102 MHz CLKIN_IDIVE
* CLK_BASE_USB0 480 MHz CLKIN_USBPLL (Disabled) (CLKIN_PLL0USB)
* CLK_BASE_USB1 60 MHz CLKIN_IDIVE (Disabled)
* 120 MHz CLKIN_IDIVD (Disabled)
*
* 12 MHz CLKIN_IDIVB
* 12 MHz CLKIN_IDIVC
*
*/
void SystemSetupClock(void)
{
#if (CLOCK_SETUP)
/* Switch main clock to Internal RC (IRC) */
LPC_CGU->BASE_CLK[CLK_BASE_MX] = ((1 << 11) | (CLKIN_IRC << 24));
uint32_t i;
/* Switch main clock to Internal RC (IRC) while setting up PLL1 */
LPC_CGU->BASE_CLK[CLK_BASE_MX] = (1 << 11) | (CLKIN_IRC << 24);
/* Enable the oscillator and wait 100 us */
LPC_CGU->XTAL_OSC_CTRL = 0;
WaitUs(100);
#if (SPIFI_INIT)
/* Switch IDIVA clock to IRC and connect to SPIFI clock */
LPC_CGU->IDIV_CTRL[CLK_IDIV_A] = ((1 << 11) | (CLKIN_IRC << 24));
LPC_CGU->BASE_CLK[CLK_BASE_SPIFI] = ((1 << 11) | (CLKIN_IDIVA << 24));
/* Setup SPIFI control register and no-opcode mode */
LPC_SPIFI->CTRL = (0x100 << 0) | (1 << 16) | (1 << 29) | (1 << 30);
LPC_SPIFI->IDATA = 0xA5;
/* Switch IDIVE clock to IRC and connect to SPIFI clock */
LPC_CGU->IDIV_CTRL[CLK_IDIV_E] = ((1 << 11) | (CLKIN_IRC << 24));
LPC_CGU->BASE_CLK[CLK_BASE_SPIFI] = ((1 << 11) | (CLKIN_IDIVE << 24));
#endif /* SPIFI_INIT */
/* Power down PLL1 */
LPC_CGU->PLL1_CTRL |= 1;
/* Configure PLL1 (MAINPLL) for main clock */
LPC_CGU->PLL1_CTRL |= 1; /* Power down PLL1 */
/* Change PLL1 to 108 Mhz (msel=9, 12 MHz*9=108 MHz) */
// LPC_CGU->PLL1_CTRL = (DIRECT << 7) | (PSEL << 8) | (1 << 11) | (P(NSEL-1) << 12) | ((MSEL-1) << 16) | (CLKIN_PLL1 << 24);
LPC_CGU->PLL1_CTRL = (1 << 7) | (0 << 8) | (1 << 11) | (0 << 12) | (8 << 16) | (CLKIN_PLL1 << 24);
LPC_CGU->PLL1_CTRL = (1 << 7) | (0 << 8) | (1 << 11) | (0 << 12) | (8 << 16)
| (CLKIN_MAINPLL << 24);
while (!(LPC_CGU->PLL1_STAT & 1)); /* Wait for PLL1 to lock */
WaitUs(100);
/* Change PLL1 to 204 Mhz (msel=17, 12 MHz*17=204 MHz) */
LPC_CGU->PLL1_CTRL = (1 << 7) | (0 << 8) | (1 << 11) | (0 << 12) | (16 << 16) | (CLKIN_PLL1 << 24);
LPC_CGU->PLL1_CTRL = (1 << 7) | (0 << 8) | (1 << 11) | (0 << 12) | (16 << 16)
| (CLKIN_MAINPLL << 24);
while (!(LPC_CGU->PLL1_STAT & 1)); /* Wait for PLL1 to lock */
/* Switch main clock to PLL1 */
LPC_CGU->BASE_CLK[CLK_BASE_MX] = ((1 << 11) | (CLKIN_PLL1 << 24));
SystemCoreClock = 204000000;
/* Connect main clock to PLL1 */
LPC_CGU->BASE_CLK[CLK_BASE_MX] = (1 << 11) | (CLKIN_MAINPLL << 24);
/* Set USB PLL dividers for 480 MHz (for USB0) */
LPC_CGU->PLL[CGU_USB_PLL].PLL_MDIV = 0x06167FFA;
LPC_CGU->PLL[CGU_USB_PLL].PLL_NP_DIV = 0x00302062;
LPC_CGU->PLL[CGU_USB_PLL].PLL_CTRL = 0x0000081D | (CLKIN_CRYSTAL << 24);
/* Set IDIVE clock to PLL1/2 = 102 MHz */
LPC_CGU->IDIV_CTRL[CLK_IDIV_E] = (1 << 2) | (1 << 11) | (CLKIN_MAINPLL << 24); /* PLL1/2 */
/* Set IDIVD clock to ((USBPLL/4) / 2) = 60 MHz (for USB1) */
LPC_CGU->IDIV_CTRL[CLK_IDIV_A] = (3 << 2) | (1 << 11) | (CLKIN_USBPLL << 24); /* USBPLL/4 */
LPC_CGU->IDIV_CTRL[CLK_IDIV_D] = (1 << 2) | (1 << 11) | (CLKIN_IDIVA << 24); /* IDIVA/2 */
/* Configure remaining integer dividers */
LPC_CGU->IDIV_CTRL[CLK_IDIV_B] = (0 << 2) | (1 << 11) | (CLKIN_IRC << 24); /* IRC */
LPC_CGU->IDIV_CTRL[CLK_IDIV_C] = (1 << 2) | (1 << 11) | (CLKIN_MAINPLL << 24); /* PLL1/2 */
/* Connect base clocks */
for (i = 0; i < COUNT_OF(clock_states); i++) {
LPC_CGU->BASE_CLK[clock_states[i].clk] =
( clock_states[i].powerdn << 0)
| (1 << 11) | (clock_states[i].clkin << 24);
}
#endif /* CLOCK_SETUP */
}
@ -165,7 +298,7 @@ void SystemSetupClock(void)
*/
void SystemSetupPins(const PINMUX_GRP_T *mux, uint32_t n)
{
uint16_t i;
uint32_t i;
for (i = 0; i < n; i++) {
*(mux[i].reg) = mux[i].mode;
@ -188,35 +321,36 @@ void SystemSetupMemory(void)
*/
void fpuInit(void)
{
// from ARM TRM manual:
// ; CPACR is located at address 0xE000ED88
// LDR.W R0, =0xE000ED88
// ; Read CPACR
// LDR R1, [R0]
// ; Set bits 20-23 to enable CP10 and CP11 coprocessors
// ORR R1, R1, #(0xF << 20)
// ; Write back the modified value to the CPACR
// STR R1, [R0]
/*
* from ARM TRM manual:
* ; CPACR is located at address 0xE000ED88
* LDR.W R0, =0xE000ED88
* ; Read CPACR
* LDR R1, [R0]
* ; Set bits 20-23 to enable CP10 and CP11 coprocessors
* ORR R1, R1, #(0xF << 20)
* ; Write back the modified value to the CPACR
* STR R1, [R0]
*/
volatile uint32_t *regCpacr = (uint32_t *) LPC_CPACR;
volatile uint32_t *regMvfr0 = (uint32_t *) SCB_MVFR0;
volatile uint32_t *regMvfr1 = (uint32_t *) SCB_MVFR1;
volatile uint32_t Cpacr;
volatile uint32_t Mvfr0;
volatile uint32_t Mvfr1;
char vfpPresent = 0;
volatile uint32_t *regCpacr = (uint32_t *) LPC_CPACR;
volatile uint32_t *regMvfr0 = (uint32_t *) SCB_MVFR0;
volatile uint32_t *regMvfr1 = (uint32_t *) SCB_MVFR1;
volatile uint32_t Cpacr;
volatile uint32_t Mvfr0;
volatile uint32_t Mvfr1;
char vfpPresent = 0;
Mvfr0 = *regMvfr0;
Mvfr1 = *regMvfr1;
Mvfr0 = *regMvfr0;
Mvfr1 = *regMvfr1;
vfpPresent = ((SCB_MVFR0_RESET == Mvfr0) && (SCB_MVFR1_RESET == Mvfr1));
if (vfpPresent) {
Cpacr = *regCpacr;
Cpacr |= (0xF << 20);
*regCpacr = Cpacr; // enable CP10 and CP11 for full access
}
vfpPresent = ((SCB_MVFR0_RESET == Mvfr0) && (SCB_MVFR1_RESET == Mvfr1));
if (vfpPresent) {
Cpacr = *regCpacr;
Cpacr |= (0xF << 20);
*regCpacr = Cpacr; /* enable CP10 and CP11 for full access */
}
}
#endif /* defined(__FPU_PRESENT) && __FPU_PRESENT == 1 */

View File

@ -81,6 +81,7 @@ extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) *
* Initialize the System and update the SystemCoreClock variable.
*/
extern void SystemInit (void);
extern void SystemCoreClockUpdate(void);
#ifdef __cplusplus
}

View File

@ -63,15 +63,22 @@ typedef enum {
} I2CName;
typedef enum {
PWM0_1 = 1,
PWM0_2,
PWM0_3,
PWM1_1,
PWM1_2,
PWM1_3,
PWM2_1,
PWM2_2,
PWM2_3
PWM_0,
PWM_1,
PWM_2,
PWM_3,
PWM_4,
PWM_5,
PWM_6,
PWM_7,
PWM_8,
PWM_9,
PWM_10,
PWM_11,
PWM_12,
PWM_13,
PWM_14,
PWM_15
} PWMName;
typedef enum {
@ -79,9 +86,47 @@ typedef enum {
CAN_1 = (int)LPC_C_CAN1_BASE
} CANName;
#define STDIO_UART_TX UART0_TX
#define STDIO_UART_RX UART0_RX
#define STDIO_UART UART_0
#define STDIO_UART_TX USBTX
#define STDIO_UART_RX USBRX
#define STDIO_UART UART_2
// Default peripherals
#define MBED_SPI0 SPI0_MOSI, SPI0_MISO, SPI0_SCK, SPI0_SSEL
#define MBED_SPI1 SPI1_MOSI, SPI1_MISO, SPI1_SCK, SPI1_SSEL
#define MBED_UART0 UART0_TX, UART0_RX
#define MBED_UART1 UART1_TX, UART1_RX
#define MBED_UART2 UART2_TX, UART2_RX
#define MBED_UART3 UART3_TX, UART3_RX
#define MBED_UARTUSB USBTX, USBRX
#define COM1 MBED_UART0
#define COM2 MBED_UART1
#define COM3 MBED_UART2
#define COM4 MBED_UART3
#define MBED_I2C0 I2C0_SDA, I2C0_SCL
#define MBED_I2C1 I2C1_SDA, I2C1_SCL
#define MBED_CAN0 p30, p29
#define MBED_ANALOGOUT0 DAC0
#define MBED_ANALOGIN0 ADC0
#define MBED_ANALOGIN1 ADC1
#define MBED_ANALOGIN2 ADC2
#define MBED_ANALOGIN3 ADC3
#define MBED_ANALOGIN4 ADC4
#define MBED_ANALOGIN5 ADC5
#define MBED_ANALOGIN6 ADC6
#define MBED_ANALOGIN7 ADC7
#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
}

View File

@ -435,7 +435,7 @@ typedef enum {
SFP_CLK1 = MBED_PIN(0x18, 1, 0, 0),
SFP_CLK2 = MBED_PIN(0x18, 2, 0, 0),
SFP_CLK3 = MBED_PIN(0x18, 3, 0, 0),
// Group 0x19 : USB1, I2C0, ADC0, ADC1
SFP_USB1 = MBED_PIN(0x19, 0, 0, 0),
SFP_I2C0 = MBED_PIN(0x19, 1, 0, 0),
@ -448,107 +448,245 @@ typedef enum {
SFP_INS0 = MBED_PIN(0x1C, 0, 0, 0), // Interrupt select for pin interrupts 0 to 3
SFP_INS1 = MBED_PIN(0x1C, 1, 0, 0), // Interrupt select for pin interrupts 4 to 7
#define MBED_ADC_NUM(MBED_PIN) ((MBED_PIN >> 5) & 0x0000000F)
#define MBED_ADC_CHAN(MBED_PIN) (MBED_PIN & 0x0000001F)
// Dedicated pin (no GPIO)
P_DED = MBED_PIN(0, 0, NO_GPIO, 0),
// Use pseudo-pin ID also for ADCs, although with special handling
SFP_ADC0_0 = MBED_PIN(0x19, 2, 0, 0), // ADC0_0
SFP_ADC0_1 = MBED_PIN(0x19, 2, 0, 1), // ADC0_1
SFP_ADC0_2 = MBED_PIN(0x19, 2, 0, 2), // ADC0_2
SFP_ADC0_3 = MBED_PIN(0x19, 2, 0, 3), // ADC0_3
SFP_ADC0_4 = MBED_PIN(0x19, 2, 0, 4), // ADC0_4
SFP_ADC0_5 = MBED_PIN(0x19, 2, 0, 5), // ADC0_5
SFP_ADC0_6 = MBED_PIN(0x19, 2, 0, 6), // ADC0_6
// Not connected
NC = (int)0xFFFFFFFF,
SFP_ADC1_0 = MBED_PIN(0x19, 3, 1, 0), // ADC1_0
SFP_ADC1_1 = MBED_PIN(0x19, 3, 1, 1), // ADC1_1
SFP_ADC1_2 = MBED_PIN(0x19, 3, 1, 2), // ADC1_2
SFP_ADC1_3 = MBED_PIN(0x19, 3, 1, 3), // ADC1_3
SFP_ADC1_4 = MBED_PIN(0x19, 3, 1, 4), // ADC1_4
SFP_ADC1_5 = MBED_PIN(0x19, 3, 1, 5), // ADC1_5
SFP_ADC1_6 = MBED_PIN(0x19, 3, 1, 6), // ADC1_6
SFP_ADC1_7 = MBED_PIN(0x19, 3, 1, 7), // ADC1_7
// ---------- Micromint Bambino 200/200E/210/210E (LQFP144) ----------
// Base headers - J8, J9, J10 on Bambino 210/210E
// n/p = not populated, n/a = not available
// 210E 210 200E 200
// ---- ---- ---- ----
p15 = P7_4, // J8-1 J8-1 S4-3 S4-3
p16 = P7_5, // J8-2 J8-2 S4-4 S4-4
p17 = P4_1, // J8-3 J8-3 S3-4 S3-4
p18 = P7_7, // J8-4 J8-4 S4-5 S4-5
p19 = P4_3, // J8-5* J8-5* S3-4 S3-3
p20 = P4_4, // J8-6* J8-6* S1-5 S1-5
p20b = PF_8, // J8-6** J8-6** S3-5 S3-5
// (*) if p20 is configured as DAC, ADC is not available for p19
// (**) requires JP2 mod
// ---------- Micromint Bambino 200 ----------
// LQFP144
// NOTE: Pins marked (*) only available on 200E
p5 = P1_2, // SPI0 mosi
p6 = P1_1, // SPI0 miso
p7 = P3_0, // SPI0 sck
p8 = P4_5,
p9 = P6_4, // Serial0 tx, I2C0 sda
p10 = P6_5, // Serial0 rx, I2C0 scl
p11 = P1_4, // SPI1 mosi (*)
p12 = P1_3, // SPI1 miso (*)
p13 = PF_4, // Serial1 tx, SPI1 sck (*)
p14 = P1_14, // Serial1 rx
p15 = P4_3, // ADC0
p16 = P4_1, // ADC1
p17 = P7_4, // ADC2
p18 = SFP_ADC0_0, // ADC3, DAC0
p19 = P7_5, // ADC4
p20 = P7_7, // ADC5
p21 = P4_0, // PWM0
p22 = P5_5, // PWM1
p23 = P5_7, // PWM2
p24 = P4_8, // PWM3
p25 = P4_9, // PWM4
p26 = P4_10, // PWM5
p27 = P2_4, // I2C1 scl, Serial2 rx
p28 = P2_3, // I2C1 sda, Serial2 tx
p29 = P3_2, // CAN0 td
p30 = P3_1, // CAN0 rx
p21 = P6_5, // J9-1 J9-1 S2-5 S2-5
p22 = P6_4, // J9-2 J9-2 S2=4 S2-4
p23 = P1_7, // J9-3 J9-3 S2-3 S2-3
p24 = P4_0, // J9-4 J9-4 S3-7 S3-7
p25 = P6_9, // J9-5 J9-5 S8-7 n/p
p26 = P5_5, // J9-6 J9-6 S3-8 S3-8
p27 = P5_7, // J9-7 J9-7 S3-9 S3-9
p28 = P7_6, // J9-8 J9-8 S4-6 S4-6
p29 = P6_12, // J10-1 J10-1 S10-3 n/p
p30 = P5_0, // J10-2 J10-2 S1-4 S1-4
p31 = P4_6, // J10-3 J10-3 S2-6 S2-6
p32 = P4_8, // J10-4 J10-4 S2-7 S2-7
p33 = P4_9, // J10-5 J10-5 S2-8 S2-8
p34 = P4_10, // J10-6 J10-6 S2-9 S2-9
p37 = P2_3, // J10-9 J10-9 S4-8 S4-8
p38 = P2_4, // J10-10 J10-10 S4-9 S4-9
// Extended headers - J11, J12, J13, J14 on Bambino 210E
// 210E 210 200E 200
// ---- ---- ---- ----
p47 = P6_3, // J11-1 n/p S7-5 n/p
p48 = P6_6, // J11-2 n/p S6-7 n/p
p49 = P6_7, // J11-3 n/p S6-8 n/p
p50 = P6_8, // J11-4 n/p S6-9 n/p
p53 = P2_2, // J11-7 n/p S7-7 n/p
p54 = P2_1, // J11-8 n/p S7-3 n/p
p55 = PF_10, // J12-1 n/p n/a n/a
p56 = PF_7, // J12-2 n/p n/a n/a
p57 = P2_6, // J12-3 n/p S8-6 n/p
p58 = P2_8, // J12-4 n/p S8-3 n/p
p59 = P6_10, // J12-5 n/p S7-8 n/p
p60 = P2_9, // J12-6 n/p S9-3 n/p
p61 = P7_3, // J13-1 n/p S7-9 n/p
p62 = P3_2, // J13-2 n/p S9-4 n/p
p63 = P7_2, // J13-3 n/p S4-7 S4-7
p64 = P3_1, // J13-4 n/p S9-5 n/p
p65 = P7_1, // J13-5 n/p S9-8 n/p
p66 = P7_0, // J13-6 n/p S9-9 n/p
p67 = P4_2, // J13-7 n/p S4-6 S4-6
p68 = P4_5, // J13-8 n/p S1-3 S1-3
p69 = P2_13, // J14-1 n/p S9-7 n/p
p70 = P2_12, // J14-2 n/p S9-6 n/p
p71 = P9_6, // J14-3 n/p S6-6 n/p
p72 = P9_5, // J14-4 n/p S7-4 n/p
p73 = P5_3, // J14-5 n/p S6-5 n/p
p74 = P1_8, // J14-6 n/p S6-4 n/p
p75 = P1_5, // J14-7 n/p S10-6 n/p
p76 = P1_4, // J14-8 n/p S10-7 n/p
p77 = P1_3, // J14-9 n/p S10-8 n/p
p78 = PF_4, // J14-10 n/p S10-9 n/p
// J16 - PMOD-SSP header (not populated, field installable)
p80 = P1_0, // J16-1 J16-1 S1-6 S1-6
p81 = P1_2, // J16-2 J16-2 S1-7 S1-7
p82 = P1_1, // J16-3 J16-3 S1-8 S1-8
p83 = P3_0, // J16-4 J16-4 S1-9 S1-9
// Arduino pins - J8, J9, J10
// 210E 210 200E 200
// ---- ---- ---- ----
D0 = p21, // J9-1 J9-1 S2-5 S2-5
D1 = p22, // J9-2 J9-2 S2-4 S2-4
D2 = p23, // J9-3 J9-3 S2-3 S2-3
D3 = p24, // J9-4 J9-4 S3-7 S3-7
D4 = p25, // J9-5 J9-5 S8-7 n/p
D5 = p26, // J9-6 J9-6 S3-8 S3-8
D6 = p27, // J9-7 J9-7 S3-9 S3-9
D7 = p28, // J9-8 J9-8 S4-6 S4-6
D8 = p29, // J10-1 J10-1 S10-1 n/p
D9 = p30, // J10-2 J10-2 S1-4 S1-4
D10 = p31, // J10-3 J10-3 S2-6 S2-6
D11 = p32, // J10-4 J10-4 S2-7 S2-7
D12 = p33, // J10-5 J10-5 S2-8 S2-8
D13 = p34, // J10-6 J10-6 S2-9 S2-9
D16 = p37, // J10-9 J10-9 S4-8 S4-8
D17 = p38, // J10-10 J10-10 S4-9 S4-9
A0 = p15, // J8-1 J8-1 S4-3 S4-3
A1 = p16, // J8-2 J8-2 S4-4 S4-4
A2 = p17, // J8-3 J8-3 S3-4 S3-4
A3 = p18, // J8-4 J8-4 S3-4 S3-4
A4 = p19, // J8-5* J8-5* S3-3 S3-3
A5 = p20, // J8-6* J8-6* S1-5 S1-5
A5b = p20b, // J8-6** J8-6** S3-5 S3-5
// (*) if A5 is configured as DAC, ADC is not available for A4
// (**) requires JP2 mod
// Extended Arduino pins - J11, J12, J13, J14
// 210E 210 200E 200
// ---- ---- ---- ----
D20 = p61, // J13-1 n/p S7-9 n/p
D21 = p62, // J13-2 n/p S9-4 n/p
D22 = p63, // J13-3 n/p S4-7 S4-7
D23 = p64, // J13-4 n/p S9-5 n/p
D24 = p65, // J13-5 n/p S9-8 n/p
D25 = p66, // J13-6 n/p S9-9 n/p
D26 = p67, // J13-7 n/p S3-7 S3-7
D27 = p68, // J13-8 n/p S1-3 S1-3
D30 = p69, // J14-1 n/p S9-7 n/p
D31 = p70, // J14-2 n/p S9-6 n/p
D32 = p71, // J14-3 n/p S6-6 n/p
D33 = p72, // J14-4 n/p S7-4 n/p
D34 = p73, // J14-5 n/p S6-5 n/p
D35 = p74, // J14-6 n/p S6-4 n/p
D36 = p75, // J14-7 n/p S10-6 n/p
D37 = p76, // J14-8 n/p S10-7 n/p
D38 = p77, // J14-9 n/p S10-8 n/p
D39 = p78, // J14-10 n/p S10-9 n/p
D40 = p47, // J11-1 n/p S7-5 n/p
D41 = p48, // J11-2 n/p S6-7 n/p
D42 = p49, // J11-3 n/p S6-8 n/p
D43 = p50, // J11-4 n/p S6-9 n/p
D46 = p53, // J11-7 n/p S7-7 n/p
D47 = p54, // J11-8 n/p S7-3 n/p
D52 = p57, // J12-3 n/p S8-6 n/p
D53 = p58, // J12-4 n/p S8-3 n/p
D54 = p59, // J12-5 n/p S7-8 n/p
D55 = p60, // J12-6 n/p S9-3 n/p
A6 = p55, // J12-1 n/p n/a n/a
A7 = p56, // J12-2 n/p n/a n/a
// User interfaces: LEDs, buttons
LED_YELLOW = P6_11,
LED_GREEN = P2_5,
LED_RED = LED_YELLOW,
LED_BLUE = LED_GREEN,
// 210E 210 200E 200
// ---- ---- ---- ----
LED1 = P6_11, // 210/210E/200e/200
LED2 = P2_5, // 210/210E/200e/200
LED3 = P6_1, // 210/210E only S6-3 n/p
LED4 = P6_2, // 210/210E only S7-6 n/p
LED1 = LED_YELLOW,
LED2 = LED_GREEN,
LED3 = LED_GREEN,
LED4 = LED_GREEN,
LED_YELLOW = LED1,
LED_GREEN = LED2,
LED_RED = LED3,
LED_BLUE = LED4,
BTN1 = P2_7,
// Serial pins
UART0_TX = P6_4,
UART0_RX = P6_5,
UART1_TX = P5_6,
UART1_RX = P1_14,
UART2_TX = P2_10,
UART2_RX = P2_11,
UART3_TX = P2_3,
UART3_RX = P2_4,
// Serial pins - UART, SPI, I2C
// 210E 210 200E 200
// ---- ---- ---- ----
UART0_TX = P6_4, // J9-2 J9-2 S2-4 S2-4
UART0_RX = P6_5, // J9-1 J9-1 S2-5 S2-5
UART1_TX = P5_6, // XBEE n/p S5-4/XBEE S5-4
UART1_RX = P1_14, // XBEE n/p S5-5/XBEE S5-5
UART2_TX = P2_10, // MBEDHDK MBEDHDK S10-4 n/p
UART2_RX = P2_11, // MBEDHDK MBEDHDK S10-5 n/p
UART3_TX = P2_3, // J10-9 n/p S4-8 S4-8
UART3_RX = P2_4, // J10-10 n/p S4-9 S4-9
COM1_TX = UART0_TX,
COM1_RX = UART0_RX,
COM2_TX = UART1_TX,
COM2_RX = UART1_RX,
COM3_TX = UART2_TX,
COM3_RX = UART2_RX,
COM4_TX = UART3_TX,
COM4_RX = UART3_RX,
// 210E 210 200E 200
// ---- ---- ---- ----
SPI0_SCK = P3_0, // J16-4 n/p S1-9 S1-9
SPI0_MISO = P1_1, // J16-3 n/p S1-8 S1-8
SPI0_MOSI = P1_2, // J16-2 n/p S1-7 S1-7
SPI0_SSEL = P1_0, // J16-1 n/p S1-6 S1-6
SPI1_SCK = PF_4, // J14-10 n/p S10-9 n/p
SPI1_MISO = P1_3, // J14-9 n/p S10-8 n/p
SPI1_MOSI = P1_4, // J14-8 n/p S10-7 n/p
SPI1_SSEL = P1_5, // J14-7 n/p S10-6 n/p
I2C0_SDA = P_DED, // J15-3 J15-3 S8-8 n/p
I2C0_SCL = P_DED, // J15-1 J15-1 S8-9 n/p
I2C1_SDA = P2_3, // J10-9 J10-9 S4-8 S4-8
I2C1_SCL = P2_4, // J10-10 J10-10 S4-9 S4-9
// Analog pins
P_ADC0_0 = P4_3,
P_ADC0_1 = P4_1,
P_ADC1_0 = SFP_ADC0_0,
P_ADC0_4 = P7_4,
P_ADC0_3 = P7_5,
P_ADC1_6 = P7_7,
P_ADC0 = P_ADC0_0,
P_ADC1 = P_ADC0_1,
P_ADC2 = P_ADC1_0,
P_ADC3 = P_ADC0_4,
P_ADC4 = P_ADC0_3,
P_ADC5 = P_ADC1_6,
P_DAC0 = P4_4,
ADC0 = P7_4, // J8-1 J8-1 S4-3 S4-3
ADC1 = P7_5, // J8-2 J8-2 S4-4 S4-4
ADC2 = P4_1, // J8-3 J8-3 S3-4 S3-4
ADC3 = P7_7, // J8-4 J8-4 S3-4 S3-4
ADC4 = P4_3, // J8-5* J8-5* S3-3 S3-3
ADC5 = PF_8, // J8-6** J8-6** S1-5 S1-5
ADC6 = PF_10, // J12-1 n/p n/a n/a
ADC7 = PF_7, // J12-2 n/p n/a n/a
DAC0 = P4_4, // J8-6* J8-6* S3-5 S3-5
// (*) if DAC0 is configured, ADC4 is not available
// (**) ADC5 requires JP2 mod
// USB pins
//P_USB0_TX = SFP_USB1,
//P_USB0_RX = SFP_USB1,
// 210E 210 200E 200
// ---- ---- ---- ----
USBTX = UART2_TX, // MBEDHDK MBEDHDK S10-4 n/p
USBRX = UART2_RX, // MBEDHDK MBEDHDK S10-5 n/p
USBTX = UART0_TX,
USBRX = UART0_RX,
// ---------- End of Micromint Bambino 200 ----------
// PWM pins
// 210E 210 200E 200
// ---- ---- ---- ----
PWM1 = P1_7, // J9-3 J9-3 S2-3 S2-3
PWM2 = P7_6, // J9-8 J9-8 S4-6 S4-6
PWM3 = P6_12, // J10-1 J10-1 S10-3 n/p
PWM4 = P4_6, // J10-3 J10-3 S2-6 S2-6
PWM5 = P7_5, // J8-2 J8-2 S4-4 S4-4
PWM6 = P4_1, // J8-3 J8-3 S3-4 S3-4
PWM7 = P7_7, // J8-4 J8-4 S4-5 S4-5
PWM8 = P2_8, // J12-4 n/p S8-3 n/p
PWM9 = P2_9, // J12-6 n/p S9-3 n/p
PWM10 = P7_1, // J13-5 n/p S9-8 n/p
PWM11 = P7_0, // J13-6 n/p S9-9 n/p
PWM12 = P1_5, // J14-7 n/p S10-6 n/p
// Not connected
NC = (int)0xFFFFFFFF
// ---------- End of Micromint Bambino ----------
} PinName;
typedef enum {

View File

@ -19,6 +19,8 @@
#include "analogin_api.h"
#include "cmsis.h"
#include "pinmap.h"
#include "error.h"
#include "gpio_api.h"
#define ANALOGIN_MEDIAN_FILTER 1
@ -26,68 +28,74 @@ static inline int div_round_up(int x, int y) {
return (x + (y - 1)) / y;
}
// ToDo: Add support for ADC1
static const PinMap PinMap_ADC[] = {
{P_ADC0, ADC0_0, 0x08},
{P_ADC1, ADC0_1, 0x07},
{P_ADC2, ADC0_2, 0x01},
{P_ADC3, ADC0_3, 0x08},
{P_ADC4, ADC0_4, 0x08},
{P_ADC5, ADC0_5, 0x08},
{NC , NC , 0 }
{P4_3, ADC0_0, 0},
{P4_1, ADC0_1, 0},
{PF_8, ADC0_2, 0},
{P7_5, ADC0_3, 0},
{P7_4, ADC0_4, 0},
{PF_10, ADC0_5, 0},
{PB_6, ADC0_6, 0},
{PC_3, ADC1_0, 0},
{PC_0, ADC1_1, 0},
{PF_9, ADC1_2, 0},
{PF_6, ADC1_3, 0},
{PF_5, ADC1_4, 0},
{PF_11, ADC1_5, 0},
{P7_7, ADC1_6, 0},
{PF_7, ADC1_7, 0},
{NC, NC, 0 }
};
void analogin_init(analogin_t *obj, PinName pin) {
uint8_t num, chan;
ADCName name;
obj->adc = (ADCName)pinmap_peripheral(pin, PinMap_ADC);
MBED_ASSERT(obj->adc != (ADCName)NC);
name = (ADCName)pinmap_peripheral(pin, PinMap_ADC);
MBED_ASSERT(obj->adc != (LPC_ADC_T *)NC);
// Configure the pin as GPIO input
if (pin < SFP_AIO0) {
pin_function(pin, (SCU_PINIO_PULLNONE | 0x0));
pin_mode(pin, PullNone);
num = (uint8_t)(obj->adc) / 8; // Heuristic?
chan = (uint8_t)(obj->adc) % 7;
} else {
num = MBED_ADC_NUM(pin);
chan = MBED_ADC_CHAN(pin);
}
// Set ADC register, number and channel
obj->num = (name >> ADC0_7) ? 1 : 0;
obj->ch = name % (ADC0_7 + 1);
obj->adc = (LPC_ADC_T *) (obj->num > 0) ? LPC_ADC1 : LPC_ADC0;
// Reset pin function to GPIO
gpio_set(pin);
// Select ADC on analog function select register in SCU
LPC_SCU->ENAIO[obj->num] |= (1 << obj->ch);
// Calculate minimum clock divider
// clkdiv = divider - 1
uint32_t PCLK = SystemCoreClock;
uint32_t PCLK = SystemCoreClock;
uint32_t adcRate = 400000;
uint32_t clkdiv = div_round_up(PCLK, adcRate) - 1;
// Set the generic software-controlled ADC settings
LPC_ADC0->CR = (0 << 0) // SEL: 0 = no channels selected
obj->adc->CR = (0 << 0) // SEL: 0 = no channels selected
| (clkdiv << 8) // CLKDIV:
| (0 << 16) // BURST: 0 = software control
| (1 << 21) // PDN: 1 = operational
| (0 << 24) // START: 0 = no start
| (0 << 27); // EDGE: not applicable
// Select ADC on analog function select register in SCU
LPC_SCU->ENAIO[num] |= 1UL << chan;
}
static inline uint32_t adc_read(analogin_t *obj) {
uint32_t temp;
uint8_t channel = obj->ch;
LPC_ADC_T *pADC = obj->adc;
// Select the appropriate channel and start conversion
LPC_ADC0->CR &= ~0xFF;
LPC_ADC0->CR |= 1 << (int)obj->adc;
LPC_ADC0->CR |= 1 << 24;
pADC->CR |= ADC_CR_CH_SEL(channel);
temp = pADC->CR & ~ADC_CR_START_MASK;
pADC->CR = temp | (ADC_CR_START_MODE_SEL(ADC_START_NOW));
// Repeatedly get the sample data until DONE bit
unsigned int data;
do {
data = LPC_ADC0->GDR;
} while ((data & ((unsigned int)1 << 31)) == 0);
// Wait for DONE bit and read data
while (!(pADC->STAT & ADC_CR_CH_SEL(channel)));
temp = pADC->DR[channel];
// Stop conversion
LPC_ADC0->CR &= ~(1 << 24);
return (data >> 6) & ADC_RANGE; // 10 bit
// Deselect channel and return result
pADC->CR &= ~ADC_CR_START_MASK;
pADC->CR &= ~ADC_CR_CH_SEL(channel);
return ADC_DR_RESULT(temp);
}
static inline void order(uint32_t *a, uint32_t *b) {

View File

@ -17,26 +17,30 @@
*/
#include "mbed_assert.h"
#include "analogout_api.h"
#include "cmsis.h"
#include "pinmap.h"
#include "error.h"
#include "gpio_api.h"
static const PinMap PinMap_DAC[] = {
{P_DAC0 , DAC_0, 0x0},
{NC , NC , 0}
{P4_4, DAC_0, 0},
{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);
// Configure the pin as GPIO input
pin_function(pin, (SCU_PINIO_PULLNONE | 0x0));
pin_mode(pin, PullNone);
// Reset pin function to GPIO
gpio_set(pin);
// Select DAC on analog function select register in SCU
LPC_SCU->ENAIO[2] |= 1; // Sets pin P4_4 as DAC
LPC_SCU->ENAIO[2] |= 1; // Sets pin as DAC
// Set Maximum update rate for DAC */
// Set bias=0 for maximum DAC update rate (1 MHz)
LPC_DAC->CR &= ~DAC_BIAS_EN;
// Enable DAC and DMA
LPC_DAC->CTRL |= DAC_DMA_ENA;
analogout_write_u16(obj, 0);
}
@ -44,16 +48,13 @@ void analogout_init(dac_t *obj, PinName pin) {
void analogout_free(dac_t *obj) {}
static inline void dac_write(int value) {
uint32_t tmp;
// Set the DAC output
tmp = LPC_DAC->CR & DAC_BIAS_EN;
tmp |= DAC_VALUE(value);
LPC_DAC->CR = tmp;
LPC_DAC->CR = DAC_SET(value);
}
static inline int dac_read() {
return (DAC_VALUE(LPC_DAC->CR));
return (DAC_GET(LPC_DAC->CR));
}
void analogout_write(dac_t *obj, float value) {

View File

@ -26,9 +26,10 @@
#define DEVICE_ANALOGOUT 1
#define DEVICE_SERIAL 1
//#define DEVICE_SERIAL_FC 1
#define DEVICE_I2C 0
#define DEVICE_I2CSLAVE 0
#define DEVICE_I2C 1
#define DEVICE_I2CSLAVE 1
#define DEVICE_SPI 1
#define DEVICE_SPISLAVE 1
@ -37,9 +38,9 @@
#define DEVICE_RTC 1
#define DEVICE_ETHERNET 0
#define DEVICE_ETHERNET 1
#define DEVICE_PWMOUT 0
#define DEVICE_PWMOUT 1
#define DEVICE_SEMIHOST 0
#define DEVICE_LOCALFILESYSTEM 0
@ -52,7 +53,7 @@
#define DEVICE_STDIO_MESSAGES 1
#define DEVICE_ERROR_RED 1
#define DEVICE_ERROR_PATTERN 1
#include "objects.h"

View File

@ -0,0 +1,435 @@
/* 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.
*
* Ported to NXP LPC43XX by Micromint USA <support@micromint.com>
*/
#include "ethernet_api.h"
#include <string.h>
#include "cmsis.h"
#include "mbed_interface.h"
#include "toolchain.h"
#include "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 */
#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];
#ifndef min
#define min(x, y) (((x)<(y))?(x):(y))
#endif
/*----------------------------------------------------------------------------
Ethernet Device initialize
*----------------------------------------------------------------------------*/
int ethernet_init() {
return 0;
}
/*----------------------------------------------------------------------------
Ethernet Device Uninitialize
*----------------------------------------------------------------------------*/
void ethernet_free() {
}
// 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) {
return -1;
}
int ethernet_send() {
return -1;
}
// 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() {
return -1;
}
// 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) {
return -1;
}
int ethernet_link(void) {
return -1;
}
void ethernet_address(char *mac) {
}
void ethernet_set_link(int speed, int duplex) {
}

View File

@ -28,13 +28,13 @@
* A future implementation may provide group interrupt support.
*/
#if !defined(CORE_M0)
#define CHANNEL_NUM 8
#define CHANNEL_MAX 8
#else
#define CHANNEL_NUM 1
#define CHANNEL_MAX 1
#endif
static uint32_t channel_ids[CHANNEL_NUM] = {0};
static uint32_t channel = 0;
static uint32_t channel_ids[CHANNEL_MAX] = {0};
static uint8_t channel = 0;
static gpio_irq_handler irq_handler;
static void handle_interrupt_in(void) {
@ -43,19 +43,21 @@ static void handle_interrupt_in(void) {
uint32_t pmask;
int i;
for (i = 0; i < CHANNEL_NUM; i++) {
for (i = 0; i < CHANNEL_MAX; i++) {
pmask = (1 << i);
if (rise & pmask) {
/* Rising edge interrupts */
if (channel_ids[i] != 0)
if (channel_ids[i] != 0) {
irq_handler(channel_ids[i], IRQ_RISE);
}
/* Clear rising edge detected */
LPC_GPIO_PIN_INT->RISE = pmask;
}
if (fall & pmask) {
/* Falling edge interrupts */
if (channel_ids[i] != 0)
if (channel_ids[i] != 0) {
irq_handler(channel_ids[i], IRQ_FALL);
}
/* Clear falling edge detected */
LPC_GPIO_PIN_INT->FALL = pmask;
}
@ -100,7 +102,7 @@ int gpio_irq_init(gpio_irq_t *obj, PinName pin, gpio_irq_handler handler, uint32
// Increment channel number
channel++;
channel %= CHANNEL_NUM;
channel %= CHANNEL_MAX;
return 0;
}

View File

@ -16,8 +16,6 @@
#ifndef MBED_GPIO_OBJECT_H
#define MBED_GPIO_OBJECT_H
#include "mbed_assert.h"
#ifdef __cplusplus
extern "C" {
#endif
@ -33,7 +31,6 @@ typedef struct {
} 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
@ -41,7 +38,6 @@ static inline void gpio_write(gpio_t *obj, int value) {
}
static inline int gpio_read(gpio_t *obj) {
MBED_ASSERT(obj->pin != (PinName)NC);
return ((*obj->reg_in & obj->mask) ? 1 : 0);
}

View File

@ -0,0 +1,391 @@
/* 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.
*
* Ported to NXP LPC43XX by Micromint USA <support@micromint.com>
*/
#include "i2c_api.h"
#include "cmsis.h"
#include "pinmap.h"
#include "error.h"
static const PinMap PinMap_I2C_SDA[] = {
{P_DED, I2C_0, 0},
{P2_3, I2C_1, 1},
{PE_13, I2C_1, 2},
{NC, NC, 0}
};
static const PinMap PinMap_I2C_SCL[] = {
{P_DED, I2C_0, 0},
{P2_4, I2C_1, 1},
{PE_14, I2C_1, 2},
{NC, NC, 0}
};
#define I2C_CONSET(x) (x->i2c->CONSET)
#define I2C_CONCLR(x) (x->i2c->CONCLR)
#define I2C_STAT(x) (x->i2c->STAT)
#define I2C_DAT(x) (x->i2c->DAT)
#define I2C_SCLL(x, val) (x->i2c->SCLL = val)
#define I2C_SCLH(x, val) (x->i2c->SCLH = 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;
}
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_T *)pinmap_merge(i2c_sda, i2c_scl);
if ((int)obj->i2c == NC) {
error("I2C pin mapping failed");
}
// set default frequency at 100k
i2c_frequency(obj, 100000);
i2c_conclr(obj, 1, 1, 1, 1);
i2c_interface_enable(obj);
// If pins are not dedicated, set SCU functions
if (sda != P_DED) {
pinmap_pinout(sda, PinMap_I2C_SDA);
}
if (scl != P_DED) {
pinmap_pinout(scl, PinMap_I2C_SCL);
}
}
inline int i2c_start(i2c_t *obj) {
int status = 0;
// 8.1 Before master mode can be entered, I2CON must be initialised to:
// - I2EN STA STO SI AA - -
// - 1 0 0 0 x - -
// if AA = 0, it can't enter slave mode
i2c_conclr(obj, 1, 1, 1, 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);
i2c_wait_SI(obj);
status = i2c_status(obj);
// Clear start bit now transmitted, and interrupt bit
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<length; i++) {
status = i2c_do_write(obj, data[i], 0);
if(status != 0x28) {
i2c_stop(obj);
return i;
}
}
// clearing the serial interrupt here might cause an unintended rewrite of the last byte
// see also issue report https://mbed.org/users/mbed_official/code/mbed/issues/1
// i2c_clear_SI(obj);
// If not repeated start, send stop.
if (stop) {
i2c_stop(obj);
}
return length;
}
void i2c_reset(i2c_t *obj) {
i2c_stop(obj);
}
int i2c_byte_read(i2c_t *obj, int last) {
return (i2c_do_read(obj, last) & 0xFF);
}
int i2c_byte_write(i2c_t *obj, int data) {
int ack;
int status = i2c_do_write(obj, (data & 0xFF), 0);
switch(status) {
case 0x18: case 0x28: // Master transmit ACKs
ack = 1;
break;
case 0x40: // Master receive address transmitted ACK
ack = 1;
break;
case 0xB8: // Slave transmit ACK
ack = 1;
break;
default:
ack = 0;
break;
}
return ack;
}
void i2c_slave_mode(i2c_t *obj, int enable_slave) {
if (enable_slave != 0) {
i2c_conclr(obj, 1, 1, 1, 0);
i2c_conset(obj, 0, 0, 0, 1);
} else {
i2c_conclr(obj, 1, 1, 1, 1);
}
}
int i2c_slave_receive(i2c_t *obj) {
int status;
int retval;
status = i2c_status(obj);
switch(status) {
case 0x60: retval = 3; break;
case 0x70: retval = 2; break;
case 0xA8: retval = 1; break;
default : retval = 0; break;
}
return(retval);
}
int i2c_slave_read(i2c_t *obj, char *data, int length) {
int count = 0;
int status;
do {
i2c_clear_SI(obj);
i2c_wait_SI(obj);
status = i2c_status(obj);
if((status == 0x80) || (status == 0x90)) {
data[count] = I2C_DAT(obj) & 0xFF;
}
count++;
} while (((status == 0x80) || (status == 0x90) ||
(status == 0x060) || (status == 0x70)) && (count < length));
if(status != 0xA0) {
i2c_stop(obj);
}
i2c_clear_SI(obj);
return count;
}
int i2c_slave_write(i2c_t *obj, const char *data, int length) {
int count = 0;
int status;
if(length <= 0) {
return(0);
}
do {
status = i2c_do_write(obj, data[count], 0);
count++;
} while ((count < length) && (status == 0xB8));
if ((status != 0xC0) && (status != 0xC8)) {
i2c_stop(obj);
}
i2c_clear_SI(obj);
return(count);
}
void i2c_slave_address(i2c_t *obj, int idx, uint32_t address, uint32_t mask) {
uint32_t addr;
if ((idx >= 0) && (idx <= 3)) {
addr = ((uint32_t)obj->i2c) + I2C_addr_offset[0][idx];
*((uint32_t *) addr) = address & 0xFF;
addr = ((uint32_t)obj->i2c) + I2C_addr_offset[1][idx];
*((uint32_t *) addr) = mask & 0xFE;
}
}

View File

@ -20,6 +20,7 @@
#include "PortNames.h"
#include "PeripheralNames.h"
#include "PinNames.h"
#include "gpio_object.h"
#ifdef __cplusplus
extern "C" {
@ -40,9 +41,8 @@ struct port_s {
};
struct pwmout_s {
__IO uint32_t *MR;
LPC_MCPWM_T *pwm;
uint32_t channel;
PWMName pwm;
uint8_t mr;
};
struct serial_s {
@ -51,7 +51,9 @@ struct serial_s {
};
struct analogin_s {
ADCName adc;
LPC_ADC_T *adc;
uint8_t num;
uint8_t ch;
};
struct dac_s {
@ -70,8 +72,6 @@ struct spi_s {
LPC_SSP_T *spi;
};
#include "gpio_object.h"
#ifdef __cplusplus
}
#endif

View File

@ -29,7 +29,7 @@ void pin_function(PinName pin, int function) {
}
void pin_mode(PinName pin, PinMode mode) {
MBED_ASSERT((pin != (PinName)NC) && (mode == OpenDrain));
MBED_ASSERT(pin != (PinName)NC); // && (mode != OpenDrain));
__IO uint32_t *reg = (__IO uint32_t*) MBED_SCU_REG(pin);
uint32_t tmp = *reg;

View File

@ -0,0 +1,266 @@
/* 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.
*
* Ported to NXP LPC43XX by Micromint USA <support@micromint.com>
*/
#include "mbed_assert.h"
#include "pwmout_api.h"
#include "cmsis.h"
#include "pinmap.h"
#include "error.h"
// PWM implementation for the LPC43xx using State Configurable Timer (SCT)
// * PWM_0 to PWM_15 on mbed use CTOUT_0 to CTOUT_15 outputs on LPC43xx
// * Event 0 is PWM period, events 1 to PWM_EVENT_MAX are PWM channels
// * Default is unified 32-bit timer, but could be configured to use
// a 16-bit timer so a timer is available for other SCT functions
// configuration options
#define PWM_FREQ_BASE 1000000 // Base frequency 1 MHz = 1000000
#define PWM_MODE 1 // 0 = 32-bit, 1 = 16-bit low, 2 = 16-bit high
// macros
#define PWM_SETCOUNT(x) (x - 1) // set count value
#define PWM_GETCOUNT(x) (x + 1) // get count value
#if (PWM_MODE == 0) // unified 32-bit counter, events 1 to 15
#define PWM_EVENT_MAX (CONFIG_SCT_nEV - 1) // Max PWM channels
#define PWM_CONFIG SCT_CONFIG_32BIT_COUNTER // default config
#define PWM_CTRL &LPC_SCT->CTRL_U // control register
#define PWM_HALT SCT_CTRL_HALT_L // halt counter
#define PWM_CLEAR SCT_CTRL_CLRCTR_L // clock clear
#define PWM_PRE(x) SCT_CTRL_PRE_L(x) // clock prescale
#define PWM_EVT_MASK (1 << 12) // event control mask
#define PWM_LIMIT &LPC_SCT->LIMIT_L // limit register
#define PWM_MATCH(x) &LPC_SCT->MATCH[x].U // match register
#define PWM_MR(x) &LPC_SCT->MATCHREL[x].U // 32-bit match reload register
#elif (PWM_MODE == 1) // 16-bit low counter, events 1 to 7
#define PWM_EVENT_MAX (CONFIG_SCT_nEV/2 - 1) // Max PWM channels
#define PWM_CONFIG SCT_CONFIG_16BIT_COUNTER // default config
#define PWM_CTRL &LPC_SCT->CTRL_L // control register
#define PWM_HALT SCT_CTRL_HALT_L // halt counter
#define PWM_CLEAR SCT_CTRL_CLRCTR_L // clock clear
#define PWM_PRE(x) SCT_CTRL_PRE_L(x) // clock prescale
#define PWM_EVT_MASK (1 << 12) // event control mask
#define PWM_LIMIT &LPC_SCT->LIMIT_L // limit register
#define PWM_MATCH(x) &LPC_SCT->MATCH[x].L // match register
#define PWM_MR(x) &LPC_SCT->MATCHREL[x].L // 16-bit match reload register
#elif (PWM_MODE == 2) // 16-bit high counter, events 1 to 7
// [TODO] use events 8 to 15 on mode 2
#define PWM_EVENT_MAX (CONFIG_SCT_nEV/2 - 1) // Max PWM channels
#define PWM_CONFIG SCT_CONFIG_16BIT_COUNTER // default config
#define PWM_CTRL &LPC_SCT->CTRL_H // control register
#define PWM_HALT SCT_CTRL_HALT_L // halt counter
#define PWM_CLEAR SCT_CTRL_CLRCTR_L // clock clear
#define PWM_PRE(x) SCT_CTRL_PRE_L(x) // clock prescale
#define PWM_EVT_MASK ((1 << 4) | (1 << 12)) // event control mask
#define PWM_LIMIT &LPC_SCT->LIMIT_H // limit register
#define PWM_MATCH(x) &LPC_SCT->MATCH[x].H // match register
#define PWM_MR(x) &LPC_SCT->MATCHREL[x].H // 16-bit match reload register
#else
#error "PWM mode not implemented"
#endif
#define PWM_MR0 PWM_MR(0) // MR register 0 is for period
static uint8_t event = 0;
// PORT ID, PWM ID, Pin function
static const PinMap PinMap_PWM[] = {
{P1_1, PWM_7, (SCU_PINIO_FAST | 1)},
{P1_2, PWM_6, (SCU_PINIO_FAST | 1)},
{P1_3, PWM_8, (SCU_PINIO_FAST | 1)},
{P1_4, PWM_9, (SCU_PINIO_FAST | 1)},
{P1_5, PWM_10, (SCU_PINIO_FAST | 1)},
{P1_7, PWM_13, (SCU_PINIO_FAST | 2)},
{P1_8, PWM_12, (SCU_PINIO_FAST | 2)},
{P1_9, PWM_11, (SCU_PINIO_FAST | 2)},
{P1_10, PWM_14, (SCU_PINIO_FAST | 2)},
{P1_11, PWM_15, (SCU_PINIO_FAST | 2)},
{P2_7, PWM_1, (SCU_PINIO_FAST | 1)},
{P2_8, PWM_0, (SCU_PINIO_FAST | 1)},
{P2_9, PWM_3, (SCU_PINIO_FAST | 1)},
{P2_10, PWM_2, (SCU_PINIO_FAST | 1)},
{P2_11, PWM_5, (SCU_PINIO_FAST | 1)},
{P2_12, PWM_4, (SCU_PINIO_FAST | 1)},
{P4_1, PWM_1, (SCU_PINIO_FAST | 1)},
{P4_2, PWM_0, (SCU_PINIO_FAST | 1)},
{P4_3, PWM_3, (SCU_PINIO_FAST | 1)},
{P4_4, PWM_2, (SCU_PINIO_FAST | 1)},
{P4_5, PWM_5, (SCU_PINIO_FAST | 1)},
{P4_6, PWM_4, (SCU_PINIO_FAST | 1)},
{P6_5, PWM_6, (SCU_PINIO_FAST | 1)},
{P6_12, PWM_7, (SCU_PINIO_FAST | 1)},
{P7_0, PWM_14, (SCU_PINIO_FAST | 1)},
{P7_1, PWM_15, (SCU_PINIO_FAST | 1)},
{P7_4, PWM_13, (SCU_PINIO_FAST | 1)},
{P7_5, PWM_12, (SCU_PINIO_FAST | 1)},
{P7_6, PWM_11, (SCU_PINIO_FAST | 1)},
{P7_7, PWM_8, (SCU_PINIO_FAST | 1)},
{PA_4, PWM_9, (SCU_PINIO_FAST | 1)},
{PB_0, PWM_10, (SCU_PINIO_FAST | 1)},
{PB_1, PWM_6, (SCU_PINIO_FAST | 5)},
{PB_2, PWM_7, (SCU_PINIO_FAST | 5)},
{PB_3, PWM_8, (SCU_PINIO_FAST | 5)},
{PD_0, PWM_15, (SCU_PINIO_FAST | 1)},
{PD_2, PWM_7, (SCU_PINIO_FAST | 1)},
{PD_3, PWM_6, (SCU_PINIO_FAST | 1)},
{PD_4, PWM_8, (SCU_PINIO_FAST | 1)},
{PD_5, PWM_9, (SCU_PINIO_FAST | 1)},
{PD_6, PWM_10, (SCU_PINIO_FAST | 1)},
{PD_9, PWM_13, (SCU_PINIO_FAST | 1)},
{PD_11, PWM_14, (SCU_PINIO_FAST | 6)},
{PD_12, PWM_10, (SCU_PINIO_FAST | 6)},
{PD_13, PWM_13, (SCU_PINIO_FAST | 6)},
{PD_14, PWM_11, (SCU_PINIO_FAST | 6)},
{PD_15, PWM_8, (SCU_PINIO_FAST | 6)},
{PD_16, PWM_12, (SCU_PINIO_FAST | 6)},
{PE_5, PWM_3, (SCU_PINIO_FAST | 1)},
{PE_6, PWM_2, (SCU_PINIO_FAST | 1)},
{PE_7, PWM_5, (SCU_PINIO_FAST | 1)},
{PE_8, PWM_4, (SCU_PINIO_FAST | 1)},
{PE_11, PWM_12, (SCU_PINIO_FAST | 1)},
{PE_12, PWM_11, (SCU_PINIO_FAST | 1)},
{PE_13, PWM_14, (SCU_PINIO_FAST | 1)},
{PE_15, PWM_0, (SCU_PINIO_FAST | 1)},
{PF_9, PWM_1, (SCU_PINIO_FAST | 2)},
{NC, NC, 0}
};
static unsigned int pwm_clock_mhz;
static void _pwmout_dev_init() {
uint32_t i;
// set SCT clock and config
LPC_CCU1->CLKCCU[CLK_MX_SCT].CFG = (1 << 0); // enable SCT clock in CCU1
LPC_SCT->CONFIG |= PWM_CONFIG; // set config options
*PWM_CTRL |= PWM_HALT; // set HALT bit to stop counter
// clear counter and set prescaler for desired freq
*PWM_CTRL |= PWM_CLEAR | PWM_PRE(SystemCoreClock / PWM_FREQ_BASE - 1);
pwm_clock_mhz = PWM_FREQ_BASE / 1000000;
// configure SCT events
for (i = 0; i < PWM_EVENT_MAX; i++) {
*PWM_MATCH(i) = 0; // match register
*PWM_MR(i) = 0; // match reload register
LPC_SCT->EVENT[i].STATE = 0xFFFFFFFF; // event happens in all states
LPC_SCT->EVENT[i].CTRL = (i << 0) | PWM_EVT_MASK; // match condition only
}
*PWM_LIMIT = (1 << 0) ; // set event 0 as limit
// initialize period to 20ms: standard for servos, and fine for e.g. brightness control
*PWM_MR0 = PWM_SETCOUNT((uint32_t)(((20 * PWM_FREQ_BASE) / 1000000) * 1000));
// initialize SCT outputs
for (i = 0; i < CONFIG_SCT_nOU; i++) {
LPC_SCT->OUT[i].SET = (1 << 0); // event 0 will set SCTOUT_xx
LPC_SCT->OUT[i].CLR = 0; // set clear event when duty cycle
}
LPC_SCT->OUTPUT = 0; // default outputs to clear
*PWM_CTRL &= ~PWM_HALT; // clear HALT bit to start counter
}
void pwmout_init(pwmout_t* obj, PinName pin) {
// determine the channel
PWMName pwm = (PWMName)pinmap_peripheral(pin, PinMap_PWM);
MBED_ASSERT((pwm != (PWMName)NC) && (event < PWM_EVENT_MAX));
// init SCT clock and outputs on first PWM init
if (event == 0) {
_pwmout_dev_init();
}
// init PWM object
event++;
obj->pwm = pwm; // pwm output
obj->mr = event; // index of match reload register
// initial duty cycle is 0
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 new pulse width
uint32_t us = (uint32_t)((float)PWM_GETCOUNT(*PWM_MR0) * value) * pwm_clock_mhz;
pwmout_pulsewidth_us(obj, us);
}
float pwmout_read(pwmout_t* obj) {
float v = (float)PWM_GETCOUNT(*PWM_MR(obj->mr)) / (float)PWM_GETCOUNT(*PWM_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;
uint32_t old_ticks = PWM_GETCOUNT(*PWM_MR0);
uint32_t i, v;
// set new period
*PWM_MR0 = PWM_SETCOUNT(ticks);
// Scale pulse widths to preserve the duty ratio
for (i = 1; i < PWM_EVENT_MAX; i++) {
v = PWM_GETCOUNT(*PWM_MR(i));
if (v > 1) {
v = (v * ticks) / old_ticks;
*PWM_MR(i) = PWM_SETCOUNT(v);
}
}
}
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;
//MBED_ASSERT(PWM_GETCOUNT(*PWM_MR0) >= v);
if (v > 0) {
// set new match register value and enable SCT output
*PWM_MR(obj->mr) = PWM_SETCOUNT(v);
LPC_SCT->OUT[obj->pwm].CLR = (1 << obj->mr); // on event will clear PWM_XX
} else {
// set match to zero and disable SCT output
*PWM_MR(obj->mr) = 0;
LPC_SCT->OUT[obj->pwm].CLR = 0;
}
}

View File

@ -24,34 +24,87 @@
#include "cmsis.h"
#include "pinmap.h"
#include "error.h"
#include "gpio_api.h"
/******************************************************************************
* INITIALIZATION
******************************************************************************/
#define UART_NUM 4
static const PinMap PinMap_UART_TX[] = {
{UART0_TX, UART_0, (SCU_PINIO_PULLDOWN | 2)},
{UART1_TX, UART_1, (SCU_PINIO_PULLDOWN | 4)},
{UART2_TX, UART_2, (SCU_PINIO_PULLDOWN | 2)},
{UART3_TX, UART_3, (SCU_PINIO_PULLDOWN | 2)},
{NC , NC , 0}
{P1_13, UART_1, (SCU_MODE_PULLDOWN | 1)},
{P1_15, UART_2, (SCU_MODE_PULLDOWN | 1)},
{P2_0, UART_0, (SCU_MODE_PULLDOWN | 1)},
{P2_3, UART_3, (SCU_MODE_PULLDOWN | 2)},
{P2_10, UART_2, (SCU_MODE_PULLDOWN | 2)},
{P3_4, UART_1, (SCU_MODE_PULLDOWN | 4)},
{P4_1, UART_3, (SCU_MODE_PULLDOWN | 6)},
{P5_6, UART_1, (SCU_MODE_PULLDOWN | 4)},
{P6_4, UART_0, (SCU_MODE_PULLDOWN | 2)},
{P7_1, UART_2, (SCU_MODE_PULLDOWN | 6)},
{P9_3, UART_3, (SCU_MODE_PULLDOWN | 7)},
{P9_5, UART_0, (SCU_MODE_PULLDOWN | 7)},
{PA_1, UART_2, (SCU_MODE_PULLDOWN | 3)},
{PC_13, UART_1, (SCU_MODE_PULLDOWN | 2)},
{PE_11, UART_1, (SCU_MODE_PULLDOWN | 2)},
{PF_2, UART_3, (SCU_MODE_PULLDOWN | 1)},
{PF_10, UART_0, (SCU_MODE_PULLDOWN | 1)},
{NC, NC, 0}
};
static const PinMap PinMap_UART_RX[] = {
{UART0_RX, UART_0, (SCU_PINIO_PULLDOWN | 2)},
{UART1_RX, UART_1, (SCU_PINIO_PULLDOWN | 1)},
{UART2_RX, UART_2, (SCU_PINIO_PULLDOWN | 2)},
{UART3_RX, UART_3, (SCU_PINIO_PULLDOWN | 2)},
{NC , NC , 0}
{P1_14, UART_1, (SCU_PINIO_PULLNONE | 1)},
{P1_16, UART_2, (SCU_PINIO_PULLNONE | 1)},
{P2_1, UART_0, (SCU_PINIO_PULLNONE | 1)},
{P2_4, UART_3, (SCU_PINIO_PULLNONE | 2)},
{P2_11, UART_2, (SCU_PINIO_PULLNONE | 2)},
{P3_5, UART_1, (SCU_PINIO_PULLNONE | 4)},
{P4_2, UART_3, (SCU_PINIO_PULLNONE | 6)},
{P5_7, UART_1, (SCU_PINIO_PULLNONE | 4)},
{P6_5, UART_0, (SCU_PINIO_PULLNONE | 2)},
{P7_2, UART_2, (SCU_PINIO_PULLNONE | 6)},
{P9_4, UART_3, (SCU_PINIO_PULLNONE | 7)},
{P9_6, UART_0, (SCU_PINIO_PULLNONE | 7)},
{PA_2, UART_2, (SCU_PINIO_PULLNONE | 3)},
{PC_14, UART_1, (SCU_PINIO_PULLNONE | 2)},
{PE_12, UART_1, (SCU_PINIO_PULLNONE | 2)},
{PF_3, UART_3, (SCU_PINIO_PULLNONE | 1)},
{PF_11, UART_0, (SCU_PINIO_PULLNONE | 1)},
{NC, NC, 0}
};
#define UART_NUM 4
#if (DEVICE_SERIAL_FC)
// RTS/CTS PinMap for flow control
static const PinMap PinMap_UART_RTS[] = {
{P1_9, UART_1, (SCU_PINIO_FAST | 1)},
{P5_2, UART_1, (SCU_PINIO_FAST | 4)},
{PC_3, UART_1, (SCU_PINIO_FAST | 2)},
{PE_5, UART_1, (SCU_PINIO_FAST | 2)},
{NC, NC, 0}
};
static const PinMap PinMap_UART_CTS[] = {
{P1_11, UART_1, (SCU_PINIO_FAST | 1)},
{P5_4, UART_1, (SCU_PINIO_FAST | 4),
{PC_2, UART_1, (SCU_PINIO_FAST | 2)},
{PE_7, UART_1, (SCU_PINIO_FAST | 2)},
{NC, NC, 0}
};
#endif
static uint32_t serial_irq_ids[UART_NUM] = {0};
static uart_irq_handler irq_handler;
int stdio_uart_inited = 0;
serial_t stdio_uart;
struct serial_global_data_s {
uint32_t serial_irq_id;
gpio_t sw_rts, sw_cts;
uint8_t count, rx_irq_set_flow, rx_irq_set_api;
};
static struct serial_global_data_s uart_data[UART_NUM];
void serial_init(serial_t *obj, PinName tx, PinName rx) {
int is_stdio_uart = 0;
@ -77,7 +130,8 @@ void serial_init(serial_t *obj, PinName tx, PinName rx) {
| 0 << 2; // Rx Line Status irq enable
// set default baud rate and format
serial_baud (obj, 9600);
is_stdio_uart = (uart == STDIO_UART) ? (1) : (0);
serial_baud (obj, is_stdio_uart ? 115200 : 9600);
serial_format(obj, 8, ParityNone, 1);
// pinout the chosen uart
@ -92,15 +146,11 @@ void serial_init(serial_t *obj, PinName tx, PinName rx) {
case UART_0: obj->index = 0; break;
case UART_1: obj->index = 1; break;
case UART_2: obj->index = 2; break;
#if (UART_NUM > 3)
case UART_3: obj->index = 3; break;
#endif
#if (UART_NUM > 4)
case UART_4: obj->index = 4; break;
#endif
}
is_stdio_uart = (uart == STDIO_UART) ? (1) : (0);
uart_data[obj->index].sw_rts.pin = NC;
uart_data[obj->index].sw_cts.pin = NC;
serial_set_flow_control(obj, FlowControlNone, NC, NC);
if (is_stdio_uart) {
stdio_uart_inited = 1;
@ -109,14 +159,14 @@ void serial_init(serial_t *obj, PinName tx, PinName rx) {
}
void serial_free(serial_t *obj) {
serial_irq_ids[obj->index] = 0;
uart_data[obj->index].serial_irq_id = 0;
}
// serial_baud
// set the baud rate, taking in to account the current SystemFrequency
void serial_baud(serial_t *obj, int baudrate) {
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
@ -192,12 +242,16 @@ void serial_baud(serial_t *obj, int baudrate) {
}
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));
// 0: 1 stop bits, 1: 2 stop bits
if (stop_bits != 1 && stop_bits != 2) {
error("Invalid stop bits specified");
}
stop_bits -= 1;
// 0: 5 data bits ... 3: 8 data bits
if (data_bits < 5 || data_bits > 8) {
error("Invalid number of bits (%d) in serial format, should be 5..8", data_bits);
}
data_bits -= 5;
int parity_enable, parity_select;
@ -208,7 +262,8 @@ void serial_format(serial_t *obj, int data_bits, SerialParity parity, int stop_b
case ParityForced1: parity_enable = 1; parity_select = 2; break;
case ParityForced0: parity_enable = 1; parity_select = 3; break;
default:
break;
error("Invalid serial parity setting");
return;
}
obj->uart->LCR = data_bits << 0
@ -220,7 +275,7 @@ void serial_format(serial_t *obj, int data_bits, SerialParity parity, int stop_b
/******************************************************************************
* INTERRUPTS HANDLING
******************************************************************************/
static inline void uart_irq(uint32_t iir, uint32_t index) {
static inline void uart_irq(uint32_t iir, uint32_t index, LPC_USART_T *puart) {
// [Chapter 14] LPC17xx UART0/2/3: UARTn Interrupt Handling
SerialIrq irq_type;
switch (iir) {
@ -228,27 +283,33 @@ static inline void uart_irq(uint32_t iir, uint32_t index) {
case 2: irq_type = RxIrq; break;
default: return;
}
if (serial_irq_ids[index] != 0)
irq_handler(serial_irq_ids[index], irq_type);
if ((RxIrq == irq_type) && (NC != uart_data[index].sw_rts.pin)) {
gpio_write(&uart_data[index].sw_rts, 1);
// Disable interrupt if it wasn't enabled by other part of the application
if (!uart_data[index].rx_irq_set_api)
puart->IER &= ~(1 << RxIrq);
}
if (uart_data[index].serial_irq_id != 0)
if ((irq_type != RxIrq) || (uart_data[index].rx_irq_set_api))
irq_handler(uart_data[index].serial_irq_id, irq_type);
}
void uart0_irq() {uart_irq((LPC_USART0->IIR >> 1) & 0x7, 0);}
void uart1_irq() {uart_irq((LPC_UART1->IIR >> 1) & 0x7, 1);}
void uart2_irq() {uart_irq((LPC_USART2->IIR >> 1) & 0x7, 2);}
void uart3_irq() {uart_irq((LPC_USART3->IIR >> 1) & 0x7, 3);}
void uart0_irq() {uart_irq((LPC_USART0->IIR >> 1) & 0x7, 0, (LPC_USART_T*)LPC_USART0);}
void uart1_irq() {uart_irq((LPC_UART1->IIR >> 1) & 0x7, 1, (LPC_USART_T*)LPC_UART1);}
void uart2_irq() {uart_irq((LPC_USART2->IIR >> 1) & 0x7, 2, (LPC_USART_T*)LPC_USART2);}
void uart3_irq() {uart_irq((LPC_USART3->IIR >> 1) & 0x7, 3, (LPC_USART_T*)LPC_USART3);}
void serial_irq_handler(serial_t *obj, uart_irq_handler handler, uint32_t id) {
irq_handler = handler;
serial_irq_ids[obj->index] = id;
uart_data[obj->index].serial_irq_id = id;
}
void serial_irq_set(serial_t *obj, SerialIrq irq, uint32_t enable) {
static void serial_irq_set_internal(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=USART0_IRQn; vector = (uint32_t)&uart0_irq; break;
case UART_1: irq_n=UART1_IRQn; vector = (uint32_t)&uart1_irq; break;
case UART_1: irq_n=UART1_IRQn; vector = (uint32_t)&uart1_irq; break;
case UART_2: irq_n=USART2_IRQn; vector = (uint32_t)&uart2_irq; break;
case UART_3: irq_n=USART3_IRQn; vector = (uint32_t)&uart3_irq; break;
}
@ -257,7 +318,7 @@ void serial_irq_set(serial_t *obj, SerialIrq irq, uint32_t enable) {
obj->uart->IER |= 1 << irq;
NVIC_SetVector(irq_n, vector);
NVIC_EnableIRQ(irq_n);
} else { // disable
} else if ((TxIrq == irq) || (uart_data[obj->index].rx_irq_set_api + uart_data[obj->index].rx_irq_set_flow == 0)) { // disable
int all_disabled = 0;
SerialIrq other_irq = (irq == RxIrq) ? (TxIrq) : (RxIrq);
obj->uart->IER &= ~(1 << irq);
@ -267,17 +328,36 @@ void serial_irq_set(serial_t *obj, SerialIrq irq, uint32_t enable) {
}
}
void serial_irq_set(serial_t *obj, SerialIrq irq, uint32_t enable) {
if (RxIrq == irq)
uart_data[obj->index].rx_irq_set_api = enable;
serial_irq_set_internal(obj, irq, enable);
}
#if (DEVICE_SERIAL_FC)
static void serial_flow_irq_set(serial_t *obj, uint32_t enable) {
uart_data[obj->index].rx_irq_set_flow = enable;
serial_irq_set_internal(obj, RxIrq, enable);
}
#endif
/******************************************************************************
* READ/WRITE
******************************************************************************/
int serial_getc(serial_t *obj) {
while (!serial_readable(obj));
return obj->uart->RBR;
int data = obj->uart->RBR;
if (NC != uart_data[obj->index].sw_rts.pin) {
gpio_write(&uart_data[obj->index].sw_rts, 0);
obj->uart->IER |= 1 << RxIrq;
}
return data;
}
void serial_putc(serial_t *obj, int c) {
while (!serial_writable(obj));
obj->uart->THR = c;
uart_data[obj->index].count++;
}
int serial_readable(serial_t *obj) {
@ -285,11 +365,21 @@ int serial_readable(serial_t *obj) {
}
int serial_writable(serial_t *obj) {
return obj->uart->LSR & 0x20;
int isWritable = 1;
if (NC != uart_data[obj->index].sw_cts.pin)
isWritable = (gpio_read(&uart_data[obj->index].sw_cts) == 0) && (obj->uart->LSR & 0x40); //If flow control: writable if CTS low + UART done
else {
if (obj->uart->LSR & 0x20)
uart_data[obj->index].count = 0;
else if (uart_data[obj->index].count >= 16)
isWritable = 0;
}
return isWritable;
}
void serial_clear(serial_t *obj) {
obj->uart->FCR = 1 << 1 // rx FIFO reset
obj->uart->FCR = 1 << 0 // FIFO Enable - 0 = Disables, 1 = Enabled
| 1 << 1 // rx FIFO reset
| 1 << 2 // tx FIFO reset
| 0 << 6; // interrupt depth
}
@ -306,3 +396,7 @@ void serial_break_clear(serial_t *obj) {
obj->uart->LCR &= ~(1 << 6);
}
void serial_set_flow_control(serial_t *obj, FlowControl type, PinName rxflow, PinName txflow) {
#if (DEVICE_SERIAL_FC)
#endif
}

View File

@ -24,27 +24,48 @@
#include "error.h"
static const PinMap PinMap_SPI_SCLK[] = {
{P3_0 , SPI_0, (SCU_PINIO_FAST | 2)},
{PF_4 , SPI_1, (SCU_PINIO_FAST | 2)},
{NC , NC , 0}
{P1_19, SPI_1, (SCU_PINIO_FAST | 1)},
{P3_0, SPI_0, (SCU_PINIO_FAST | 4)},
{P3_3, SPI_0, (SCU_PINIO_FAST | 2)},
{PF_0, SPI_0, (SCU_PINIO_FAST | 0)},
{PF_4, SPI_1, (SCU_PINIO_FAST | 0)},
{NC, NC, 0}
};
static const PinMap PinMap_SPI_MOSI[] = {
{P1_2 , SPI_0, (SCU_PINIO_FAST | 2)},
{P1_4 , SPI_1, (SCU_PINIO_FAST | 2)},
{NC , NC , 0}
{P0_1, SPI_1, (SCU_PINIO_FAST | 1)},
{P1_2, SPI_0, (SCU_PINIO_FAST | 5)},
{P1_4, SPI_1, (SCU_PINIO_FAST | 5)},
{P3_7, SPI_0, (SCU_PINIO_FAST | 5)},
{P3_8, SPI_0, (SCU_PINIO_FAST | 2)},
{P9_2, SPI_0, (SCU_PINIO_FAST | 7)},
{PF_3, SPI_0, (SCU_PINIO_FAST | 2)},
{PF_7, SPI_1, (SCU_PINIO_FAST | 2)},
{NC, NC, 0}
};
static const PinMap PinMap_SPI_MISO[] = {
{P1_1 , SPI_0, (SCU_PINIO_FAST | 2)},
{P1_3 , SPI_1, (SCU_PINIO_FAST | 2)},
{NC , NC , 0}
{P0_0, SPI_1, (SCU_PINIO_FAST | 1)},
{P1_1, SPI_0, (SCU_PINIO_FAST | 5)},
{P1_3, SPI_1, (SCU_PINIO_FAST | 5)},
{P3_6, SPI_0, (SCU_PINIO_FAST | 5)},
{P3_7, SPI_0, (SCU_PINIO_FAST | 2)},
{P9_1, SPI_0, (SCU_PINIO_FAST | 7)},
{PF_2, SPI_0, (SCU_PINIO_FAST | 2)},
{PF_6, SPI_1, (SCU_PINIO_FAST | 2)},
{NC, NC, 0}
};
static const PinMap PinMap_SPI_SSEL[] = {
{P1_0 , SPI_0, (SCU_PINIO_FAST | 2)},
{P1_5 , SPI_1, (SCU_PINIO_FAST | 2)},
{NC , NC , 0}
{P1_0, SPI_0, (SCU_PINIO_FAST | 5)},
{P1_5, SPI_1, (SCU_PINIO_FAST | 5)},
{P1_20, SPI_1, (SCU_PINIO_FAST | 2)},
{P3_6, SPI_0, (SCU_PINIO_FAST | 2)},
{P3_8, SPI_0, (SCU_PINIO_FAST | 5)},
{P9_0, SPI_0, (SCU_PINIO_FAST | 7)},
{PF_1, SPI_0, (SCU_PINIO_FAST | 2)},
{PF_5, SPI_1, (SCU_PINIO_FAST | 2)},
{NC, NC, 0}
};
static inline int ssp_disable(spi_t *obj);

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,83 @@
<?xml version="1.0" encoding="UTF-8"?>
<projectDescription>
<name>{{name}}</name>
<comment>This file was automagically generated by mbed.org. For more information, see http://mbed.org/handbook/Exporting-To-Code-Red</comment>
<projects>
</projects>
<buildSpec>
<buildCommand>
<name>org.eclipse.cdt.managedbuilder.core.genmakebuilder</name>
<triggers>clean,full,incremental,</triggers>
<arguments>
<dictionary>
<key>?name?</key>
<value></value>
</dictionary>
<dictionary>
<key>org.eclipse.cdt.make.core.append_environment</key>
<value>true</value>
</dictionary>
<dictionary>
<key>org.eclipse.cdt.make.core.autoBuildTarget</key>
<value>all</value>
</dictionary>
<dictionary>
<key>org.eclipse.cdt.make.core.buildArguments</key>
<value></value>
</dictionary>
<dictionary>
<key>org.eclipse.cdt.make.core.buildCommand</key>
<value>make</value>
</dictionary>
<dictionary>
<key>org.eclipse.cdt.make.core.buildLocation</key>
<value>${workspace_loc:/{{name}}/Debug}</value>
</dictionary>
<dictionary>
<key>org.eclipse.cdt.make.core.cleanBuildTarget</key>
<value>clean</value>
</dictionary>
<dictionary>
<key>org.eclipse.cdt.make.core.contents</key>
<value>org.eclipse.cdt.make.core.activeConfigSettings</value>
</dictionary>
<dictionary>
<key>org.eclipse.cdt.make.core.enableAutoBuild</key>
<value>false</value>
</dictionary>
<dictionary>
<key>org.eclipse.cdt.make.core.enableCleanBuild</key>
<value>true</value>
</dictionary>
<dictionary>
<key>org.eclipse.cdt.make.core.enableFullBuild</key>
<value>true</value>
</dictionary>
<dictionary>
<key>org.eclipse.cdt.make.core.fullBuildTarget</key>
<value>all</value>
</dictionary>
<dictionary>
<key>org.eclipse.cdt.make.core.stopOnError</key>
<value>true</value>
</dictionary>
<dictionary>
<key>org.eclipse.cdt.make.core.useDefaultBuildCmd</key>
<value>true</value>
</dictionary>
</arguments>
</buildCommand>
<buildCommand>
<name>org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder</name>
<triggers>full,incremental,</triggers>
<arguments>
</arguments>
</buildCommand>
</buildSpec>
<natures>
<nature>org.eclipse.cdt.core.cnature</nature>
<nature>org.eclipse.cdt.core.ccnature</nature>
<nature>org.eclipse.cdt.managedbuilder.core.managedBuildNature</nature>
<nature>org.eclipse.cdt.managedbuilder.core.ScannerConfigNature</nature>
</natures>
</projectDescription>

View File

@ -0,0 +1,205 @@
<?xml version="1.0" encoding="UTF-8" standalone="no" ?>
<ProjectOpt xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" xsi:noNamespaceSchemaLocation="project_opt.xsd">
<SchemaVersion>1.0</SchemaVersion>
<Header>### uVision Project, (C) Keil Software</Header>
<Extensions>
<cExt>*.c</cExt>
<aExt>*.s*; *.src; *.a*</aExt>
<oExt>*.obj</oExt>
<lExt>*.lib</lExt>
<tExt>*.txt; *.h; *.inc</tExt>
<pExt>*.plm</pExt>
<CppX>*.cpp</CppX>
</Extensions>
<DaveTm>
<dwLowDateTime>0</dwLowDateTime>
<dwHighDateTime>0</dwHighDateTime>
</DaveTm>
<Target>
<TargetName>mbed NXP LPC4330_M4</TargetName>
<ToolsetNumber>0x4</ToolsetNumber>
<ToolsetName>ARM-ADS</ToolsetName>
<TargetOption>
<CLKADS>12000000</CLKADS>
<OPTTT>
<gFlags>1</gFlags>
<BeepAtEnd>1</BeepAtEnd>
<RunSim>1</RunSim>
<RunTarget>0</RunTarget>
</OPTTT>
<OPTHX>
<HexSelection>1</HexSelection>
<FlashByte>65535</FlashByte>
<HexRangeLowAddress>0</HexRangeLowAddress>
<HexRangeHighAddress>0</HexRangeHighAddress>
<HexOffset>0</HexOffset>
</OPTHX>
<OPTLEX>
<PageWidth>79</PageWidth>
<PageLength>66</PageLength>
<TabStop>8</TabStop>
<ListingPath>.\build\</ListingPath>
</OPTLEX>
<ListingPage>
<CreateCListing>1</CreateCListing>
<CreateAListing>1</CreateAListing>
<CreateLListing>1</CreateLListing>
<CreateIListing>0</CreateIListing>
<AsmCond>1</AsmCond>
<AsmSymb>1</AsmSymb>
<AsmXref>0</AsmXref>
<CCond>1</CCond>
<CCode>0</CCode>
<CListInc>0</CListInc>
<CSymb>0</CSymb>
<LinkerCodeListing>0</LinkerCodeListing>
</ListingPage>
<OPTXL>
<LMap>1</LMap>
<LComments>1</LComments>
<LGenerateSymbols>1</LGenerateSymbols>
<LLibSym>1</LLibSym>
<LLines>1</LLines>
<LLocSym>1</LLocSym>
<LPubSym>1</LPubSym>
<LXref>0</LXref>
<LExpSel>0</LExpSel>
</OPTXL>
<OPTFL>
<tvExp>1</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<IsCurrentTarget>1</IsCurrentTarget>
</OPTFL>
<CpuCode>8</CpuCode>
<DllOpt>
<SimDllName>SARMCM3.DLL</SimDllName>
<SimDllArguments>-MPU</SimDllArguments>
<SimDlgDllName>DCM.DLL</SimDlgDllName>
<SimDlgDllArguments>-pCM4</SimDlgDllArguments>
<TargetDllName>SARMCM3.DLL</TargetDllName>
<TargetDllArguments>-MPU</TargetDllArguments>
<TargetDlgDllName>TCM.DLL</TargetDlgDllName>
<TargetDlgDllArguments>-pCM4</TargetDlgDllArguments>
</DllOpt>
<DebugOpt>
<uSim>0</uSim>
<uTrg>1</uTrg>
<sLdApp>1</sLdApp>
<sGomain>1</sGomain>
<sRbreak>1</sRbreak>
<sRwatch>1</sRwatch>
<sRmem>1</sRmem>
<sRfunc>1</sRfunc>
<sRbox>1</sRbox>
<tLdApp>1</tLdApp>
<tGomain>1</tGomain>
<tRbreak>1</tRbreak>
<tRwatch>1</tRwatch>
<tRmem>1</tRmem>
<tRfunc>0</tRfunc>
<tRbox>1</tRbox>
<tRtrace>0</tRtrace>
<sRunDeb>0</sRunDeb>
<sLrtime>0</sLrtime>
<nTsel>14</nTsel>
<sDll></sDll>
<sDllPa></sDllPa>
<sDlgDll></sDlgDll>
<sDlgPa></sDlgPa>
<sIfile></sIfile>
<tDll></tDll>
<tDllPa></tDllPa>
<tDlgDll></tDlgDll>
<tDlgPa></tDlgPa>
<tIfile>.\mbed\TARGET_LPC4330_M4\TOOLCHAIN_ARM_STD\LPC43xx_spifi.ini</tIfile>
<pMon>BIN\CMSIS_AGDI.dll</pMon>
</DebugOpt>
<TargetDriverDllRegistry>
<SetRegEntry>
<Number>0</Number>
<Key>DLGTARM</Key>
<Name>(1010=-1,-1,-1,-1,0)(1007=-1,-1,-1,-1,0)(1008=-1,-1,-1,-1,0)(1009=-1,-1,-1,-1,0)(1012=-1,-1,-1,-1,0)</Name>
</SetRegEntry>
<SetRegEntry>
<Number>0</Number>
<Key>ARMDBGFLAGS</Key>
<Name></Name>
</SetRegEntry>
<SetRegEntry>
<Number>0</Number>
<Key>DLGUARM</Key>
<Name></Name>
</SetRegEntry>
<SetRegEntry>
<Number>0</Number>
<Key>CMSIS_AGDI</Key>
<Name>-X"MBED CMSIS-DAP" -U16050201FD55783D5C667D3A -O910 -S10 -C0 -P00 -N00("ARM CoreSight JTAG-DP") -D00(4BA00477) -L00(0) -N01("ARM CoreSight JTAG-DP") -D01(0BA01477) -L01(0) -FO3 -FD10000000 -FC4000 -FN1 -FF0LPC18xx43xx_S25FL032 -FS014000000 -FL0400000</Name>
</SetRegEntry>
<SetRegEntry>
<Number>0</Number>
<Key>UL2CM3</Key>
<Name>UL2CM3(-O975 -S0 -C0)</Name>
</SetRegEntry>
</TargetDriverDllRegistry>
<Breakpoint/>
<DebugFlag>
<trace>0</trace>
<periodic>0</periodic>
<aLwin>1</aLwin>
<aCover>0</aCover>
<aSer1>0</aSer1>
<aSer2>0</aSer2>
<aPa>0</aPa>
<viewmode>1</viewmode>
<vrSel>0</vrSel>
<aSym>0</aSym>
<aTbox>0</aTbox>
<AscS1>0</AscS1>
<AscS2>0</AscS2>
<AscS3>0</AscS3>
<aSer3>0</aSer3>
<eProf>0</eProf>
<aLa>0</aLa>
<aPa1>0</aPa1>
<AscS4>0</AscS4>
<aSer4>0</aSer4>
<StkLoc>0</StkLoc>
<TrcWin>0</TrcWin>
<newCpu>0</newCpu>
<uProt>0</uProt>
</DebugFlag>
<LintExecutable></LintExecutable>
<LintConfigFile></LintConfigFile>
</TargetOption>
</Target>
<Group>
<GroupName>src</GroupName>
<tvExp>1</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<cbSel>0</cbSel>
<RteFlg>0</RteFlg>
<File>
<GroupNumber>1</GroupNumber>
<FileNumber>1</FileNumber>
<FileType>8</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<ColumnNumber>0</ColumnNumber>
<tvExpOptDlg>0</tvExpOptDlg>
<TopLine>1</TopLine>
<CurrentLine>10</CurrentLine>
<bDave2>0</bDave2>
<PathWithFileName>main.cpp</PathWithFileName>
<FilenameWithoutPath>main.cpp</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
</Group>
</ProjectOpt>

View File

@ -0,0 +1,431 @@
<?xml version="1.0" encoding="UTF-8" standalone="no" ?>
<Project xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" xsi:noNamespaceSchemaLocation="project_proj.xsd">
<SchemaVersion>1.1</SchemaVersion>
<Header>###This file was automagically generated by mbed.org. For more information, see http://mbed.org/handbook/Exporting-To-Uvision </Header>
<Targets>
<Target>
<TargetName>{{name}}_LPC4330_M4</TargetName>
<ToolsetNumber>0x4</ToolsetNumber>
<ToolsetName>ARM-ADS</ToolsetName>
<TargetOption>
<TargetCommonOption>
<Device>LPC4330</Device>
<Vendor>NXP (founded by Philips)</Vendor>
<Cpu>IRAM(0x10000000-0x1001FFFF) IRAM2(0x20000000-0x2000FFFF) CLOCK(12000000) CPUTYPE("Cortex-M4") FPU2</Cpu>
<FlashUtilSpec></FlashUtilSpec>
<StartupFile>"STARTUP\NXP\LPC43xx\startup_LPC43xx.s" ("NXP LPC43xx Startup Code")</StartupFile>
<FlashDriverDll>UL2CM3(-O975 -S0 -C0)</FlashDriverDll>
<DeviceId>6193</DeviceId>
<RegisterFile>LPC43xx.H</RegisterFile>
<MemoryEnv></MemoryEnv>
<Cmp></Cmp>
<Asm></Asm>
<Linker></Linker>
<OHString></OHString>
<InfinionOptionDll></InfinionOptionDll>
<SLE66CMisc></SLE66CMisc>
<SLE66AMisc></SLE66AMisc>
<SLE66LinkerMisc></SLE66LinkerMisc>
<SFDFile>SFD\NXP\LPC43xx\LPC43xx.SFR</SFDFile>
<bCustSvd>0</bCustSvd>
<UseEnv>0</UseEnv>
<BinPath></BinPath>
<IncludePath></IncludePath>
<LibPath></LibPath>
<RegisterFilePath>NXP\LPC43xx\</RegisterFilePath>
<DBRegisterFilePath>NXP\LPC43xx\</DBRegisterFilePath>
<TargetStatus>
<Error>0</Error>
<ExitCodeStop>0</ExitCodeStop>
<ButtonStop>0</ButtonStop>
<NotGenerated>0</NotGenerated>
<InvalidFlash>1</InvalidFlash>
</TargetStatus>
<OutputDirectory>.\build\</OutputDirectory>
<OutputName>{{name}}</OutputName>
<CreateExecutable>1</CreateExecutable>
<CreateLib>0</CreateLib>
<CreateHexFile>0</CreateHexFile>
<DebugInformation>1</DebugInformation>
<BrowseInformation>1</BrowseInformation>
<ListingPath>.\build\</ListingPath>
<HexFormatSelection>1</HexFormatSelection>
<Merge32K>0</Merge32K>
<CreateBatchFile>0</CreateBatchFile>
<BeforeCompile>
<RunUserProg1>0</RunUserProg1>
<RunUserProg2>0</RunUserProg2>
<UserProg1Name></UserProg1Name>
<UserProg2Name></UserProg2Name>
<UserProg1Dos16Mode>0</UserProg1Dos16Mode>
<UserProg2Dos16Mode>0</UserProg2Dos16Mode>
<nStopU1X>0</nStopU1X>
<nStopU2X>0</nStopU2X>
</BeforeCompile>
<BeforeMake>
<RunUserProg1>0</RunUserProg1>
<RunUserProg2>0</RunUserProg2>
<UserProg1Name></UserProg1Name>
<UserProg2Name></UserProg2Name>
<UserProg1Dos16Mode>0</UserProg1Dos16Mode>
<UserProg2Dos16Mode>0</UserProg2Dos16Mode>
</BeforeMake>
<AfterMake>
<RunUserProg1>1</RunUserProg1>
<RunUserProg2>1</RunUserProg2>
<UserProg1Name>$K\ARM\BIN\ELFDWT.EXE !L BASEADDRESS(0x14000000)</UserProg1Name>
<UserProg2Name>fromelf --bin -o "$L@L_LPC4330_M4.bin" "$L@L.axf"</UserProg2Name>
<UserProg1Dos16Mode>0</UserProg1Dos16Mode>
<UserProg2Dos16Mode>0</UserProg2Dos16Mode>
</AfterMake>
<SelectedForBatchBuild>0</SelectedForBatchBuild>
<SVCSIdString></SVCSIdString>
</TargetCommonOption>
<CommonProperty>
<UseCPPCompiler>0</UseCPPCompiler>
<RVCTCodeConst>0</RVCTCodeConst>
<RVCTZI>0</RVCTZI>
<RVCTOtherData>0</RVCTOtherData>
<ModuleSelection>0</ModuleSelection>
<IncludeInBuild>1</IncludeInBuild>
<AlwaysBuild>0</AlwaysBuild>
<GenerateAssemblyFile>0</GenerateAssemblyFile>
<AssembleAssemblyFile>0</AssembleAssemblyFile>
<PublicsOnly>0</PublicsOnly>
<StopOnExitCode>3</StopOnExitCode>
<CustomArgument></CustomArgument>
<IncludeLibraryModules></IncludeLibraryModules>
<ComprImg>1</ComprImg>
</CommonProperty>
<DllOption>
<SimDllName>SARMCM3.DLL</SimDllName>
<SimDllArguments>-MPU</SimDllArguments>
<SimDlgDll>DCM.DLL</SimDlgDll>
<SimDlgDllArguments>-pCM4</SimDlgDllArguments>
<TargetDllName>SARMCM3.DLL</TargetDllName>
<TargetDllArguments>-MPU</TargetDllArguments>
<TargetDlgDll>TCM.DLL</TargetDlgDll>
<TargetDlgDllArguments>-pCM4</TargetDlgDllArguments>
</DllOption>
<DebugOption>
<OPTHX>
<HexSelection>1</HexSelection>
<HexRangeLowAddress>0</HexRangeLowAddress>
<HexRangeHighAddress>0</HexRangeHighAddress>
<HexOffset>0</HexOffset>
<Oh166RecLen>16</Oh166RecLen>
</OPTHX>
<Simulator>
<UseSimulator>0</UseSimulator>
<LoadApplicationAtStartup>1</LoadApplicationAtStartup>
<RunToMain>1</RunToMain>
<RestoreBreakpoints>1</RestoreBreakpoints>
<RestoreWatchpoints>1</RestoreWatchpoints>
<RestoreMemoryDisplay>1</RestoreMemoryDisplay>
<RestoreFunctions>1</RestoreFunctions>
<RestoreToolbox>1</RestoreToolbox>
<LimitSpeedToRealTime>0</LimitSpeedToRealTime>
</Simulator>
<Target>
<UseTarget>1</UseTarget>
<LoadApplicationAtStartup>1</LoadApplicationAtStartup>
<RunToMain>1</RunToMain>
<RestoreBreakpoints>1</RestoreBreakpoints>
<RestoreWatchpoints>1</RestoreWatchpoints>
<RestoreMemoryDisplay>1</RestoreMemoryDisplay>
<RestoreFunctions>0</RestoreFunctions>
<RestoreToolbox>1</RestoreToolbox>
<RestoreTracepoints>0</RestoreTracepoints>
</Target>
<RunDebugAfterBuild>0</RunDebugAfterBuild>
<TargetSelection>14</TargetSelection>
<SimDlls>
<CpuDll></CpuDll>
<CpuDllArguments></CpuDllArguments>
<PeripheralDll></PeripheralDll>
<PeripheralDllArguments></PeripheralDllArguments>
<InitializationFile></InitializationFile>
</SimDlls>
<TargetDlls>
<CpuDll></CpuDll>
<CpuDllArguments></CpuDllArguments>
<PeripheralDll></PeripheralDll>
<PeripheralDllArguments></PeripheralDllArguments>
<InitializationFile>.\mbed\TARGET_LPC4330_M4\TOOLCHAIN_ARM_STD\LPC43xx_spifi.ini</InitializationFile>
<Driver>BIN\CMSIS_AGDI.dll</Driver>
</TargetDlls>
</DebugOption>
<Utilities>
<Flash1>
<UseTargetDll>1</UseTargetDll>
<UseExternalTool>0</UseExternalTool>
<RunIndependent>0</RunIndependent>
<UpdateFlashBeforeDebugging>1</UpdateFlashBeforeDebugging>
<Capability>1</Capability>
<DriverSelection>4096</DriverSelection>
</Flash1>
<bUseTDR>1</bUseTDR>
<Flash2>BIN\UL2CM3.DLL</Flash2>
<Flash3>"" ()</Flash3>
<Flash4></Flash4>
<pFcarmOut></pFcarmOut>
<pFcarmGrp></pFcarmGrp>
<pFcArmRoot></pFcArmRoot>
<FcArmLst>0</FcArmLst>
</Utilities>
<TargetArmAds>
<ArmAdsMisc>
<GenerateListings>0</GenerateListings>
<asHll>1</asHll>
<asAsm>1</asAsm>
<asMacX>1</asMacX>
<asSyms>1</asSyms>
<asFals>1</asFals>
<asDbgD>1</asDbgD>
<asForm>1</asForm>
<ldLst>0</ldLst>
<ldmm>1</ldmm>
<ldXref>1</ldXref>
<BigEnd>0</BigEnd>
<AdsALst>1</AdsALst>
<AdsACrf>1</AdsACrf>
<AdsANop>0</AdsANop>
<AdsANot>0</AdsANot>
<AdsLLst>1</AdsLLst>
<AdsLmap>1</AdsLmap>
<AdsLcgr>1</AdsLcgr>
<AdsLsym>1</AdsLsym>
<AdsLszi>1</AdsLszi>
<AdsLtoi>1</AdsLtoi>
<AdsLsun>1</AdsLsun>
<AdsLven>1</AdsLven>
<AdsLsxf>1</AdsLsxf>
<RvctClst>0</RvctClst>
<GenPPlst>0</GenPPlst>
<AdsCpuType>"Cortex-M4"</AdsCpuType>
<RvctDeviceName></RvctDeviceName>
<mOS>0</mOS>
<uocRom>0</uocRom>
<uocRam>0</uocRam>
<hadIROM>0</hadIROM>
<hadIRAM>1</hadIRAM>
<hadXRAM>0</hadXRAM>
<uocXRam>0</uocXRam>
<RvdsVP>2</RvdsVP>
<hadIRAM2>1</hadIRAM2>
<hadIROM2>0</hadIROM2>
<StupSel>8</StupSel>
<useUlib>0</useUlib>
<EndSel>0</EndSel>
<uLtcg>0</uLtcg>
<RoSelD>3</RoSelD>
<RwSelD>3</RwSelD>
<CodeSel>0</CodeSel>
<OptFeed>0</OptFeed>
<NoZi1>0</NoZi1>
<NoZi2>0</NoZi2>
<NoZi3>0</NoZi3>
<NoZi4>0</NoZi4>
<NoZi5>0</NoZi5>
<Ro1Chk>0</Ro1Chk>
<Ro2Chk>0</Ro2Chk>
<Ro3Chk>0</Ro3Chk>
<Ir1Chk>1</Ir1Chk>
<Ir2Chk>0</Ir2Chk>
<Ra1Chk>0</Ra1Chk>
<Ra2Chk>0</Ra2Chk>
<Ra3Chk>0</Ra3Chk>
<Im1Chk>1</Im1Chk>
<Im2Chk>0</Im2Chk>
<OnChipMemories>
<Ocm1>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm1>
<Ocm2>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm2>
<Ocm3>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm3>
<Ocm4>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm4>
<Ocm5>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm5>
<Ocm6>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm6>
<IRAM>
<Type>0</Type>
<StartAddress>0x10000000</StartAddress>
<Size>0x20000</Size>
</IRAM>
<IROM>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</IROM>
<XRAM>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</XRAM>
<OCR_RVCT1>
<Type>1</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT1>
<OCR_RVCT2>
<Type>1</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT2>
<OCR_RVCT3>
<Type>1</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT3>
<OCR_RVCT4>
<Type>1</Type>
<StartAddress>0x14000000</StartAddress>
<Size>0x400000</Size>
</OCR_RVCT4>
<OCR_RVCT5>
<Type>1</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT5>
<OCR_RVCT6>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT6>
<OCR_RVCT7>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT7>
<OCR_RVCT8>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT8>
<OCR_RVCT9>
<Type>0</Type>
<StartAddress>0x10000000</StartAddress>
<Size>0x20000</Size>
</OCR_RVCT9>
<OCR_RVCT10>
<Type>0</Type>
<StartAddress>0x20000000</StartAddress>
<Size>0x10000</Size>
</OCR_RVCT10>
</OnChipMemories>
<RvctStartVector></RvctStartVector>
</ArmAdsMisc>
<Cads>
<interw>1</interw>
<Optim>1</Optim>
<oTime>0</oTime>
<SplitLS>0</SplitLS>
<OneElfS>1</OneElfS>
<Strict>0</Strict>
<EnumInt>0</EnumInt>
<PlainCh>0</PlainCh>
<Ropi>0</Ropi>
<Rwpi>0</Rwpi>
<wLevel>2</wLevel>
<uThumb>0</uThumb>
<uSurpInc>1</uSurpInc>
<VariousControls>
<MiscControls>--gnu --no_rtti</MiscControls>
<Define>{% for s in symbols %} {{s}}, {% endfor %}</Define>
<Undefine></Undefine>
<IncludePath> {% for path in include_paths %} {{path}}; {% endfor %} </IncludePath>
</VariousControls>
</Cads>
<Aads>
<interw>1</interw>
<Ropi>0</Ropi>
<Rwpi>0</Rwpi>
<thumb>0</thumb>
<SplitLS>0</SplitLS>
<SwStkChk>0</SwStkChk>
<NoWarn>0</NoWarn>
<uSurpInc>1</uSurpInc>
<VariousControls>
<MiscControls></MiscControls>
<Define></Define>
<Undefine></Undefine>
<IncludePath></IncludePath>
</VariousControls>
</Aads>
<LDads>
<umfTarg>0</umfTarg>
<Ropi>0</Ropi>
<Rwpi>0</Rwpi>
<noStLib>0</noStLib>
<RepFail>1</RepFail>
<useFile>0</useFile>
<TextAddressRange>0x00000000</TextAddressRange>
<DataAddressRange>0x10000000</DataAddressRange>
<ScatterFile>{{scatter_file}}</ScatterFile>
<IncludeLibs></IncludeLibs>
<IncludeLibsPath></IncludeLibsPath>
<Misc>
{% for file in object_files %}
{{file}}
{% endfor %}
</Misc>
<LinkerInputFile></LinkerInputFile>
<DisabledWarnings></DisabledWarnings>
</LDads>
</TargetArmAds>
</TargetOption>
<Groups>
{% for group,files in source_files %}
<Group>
<GroupName>{{group}}</GroupName>
<Files>
{% for file in files %}
<File>
<FileName>{{file.name}}</FileName>
<FileType>{{file.type}}</FileType>
<FilePath>{{file.path}}</FilePath>
{%if file.type == "1" %}
<FileOption>
<FileArmAds>
<Cads>
<VariousControls>
<MiscControls>--c99</MiscControls>
</VariousControls>
</Cads>
</FileArmAds>
</FileOption>
{% endif %}
</File>
{% endfor %}
</Files>
</Group>
{% endfor %}
</Groups>
</Target>
</Targets>
</Project>