1
0
mirror of https://github.com/elua/elua.git synced 2025-01-08 20:56:17 +08:00

merged branch lpc24xx (r492:507) to trunk

This commit is contained in:
Bogdan Marinescu 2009-10-31 11:41:34 +00:00
parent f0a1e4011c
commit 8476b93446
15 changed files with 2427 additions and 4 deletions

View File

@ -56,7 +56,6 @@ toolchain_list = {
# Toolchain Aliases # Toolchain Aliases
toolchain_list['devkitarm'] = toolchain_list['arm-eabi-gcc'] toolchain_list['devkitarm'] = toolchain_list['arm-eabi-gcc']
# List of platform/CPU/toolchains combinations # List of platform/CPU/toolchains combinations
# The first toolchain in the toolchains list is the default one # The first toolchain in the toolchains list is the default one
# (the one that will be used if none is specified) # (the one that will be used if none is specified)
@ -69,7 +68,8 @@ platform_list = {
'lpc288x' : { 'cpus' : [ 'LPC2888' ], 'toolchains' : [ 'arm-gcc', 'codesourcery', 'devkitarm', 'arm-eabi-gcc' ] }, 'lpc288x' : { 'cpus' : [ 'LPC2888' ], 'toolchains' : [ 'arm-gcc', 'codesourcery', 'devkitarm', 'arm-eabi-gcc' ] },
'str7' : { 'cpus' : [ 'STR711FR2' ], 'toolchains' : [ 'arm-gcc', 'codesourcery', 'devkitarm', 'arm-eabi-gcc' ] }, 'str7' : { 'cpus' : [ 'STR711FR2' ], 'toolchains' : [ 'arm-gcc', 'codesourcery', 'devkitarm', 'arm-eabi-gcc' ] },
'stm32' : { 'cpus' : [ 'STM32F103ZE', 'STM32F103RE' ], 'toolchains' : [ 'arm-gcc', 'codesourcery', 'devkitarm', 'arm-eabi-gcc' ] }, 'stm32' : { 'cpus' : [ 'STM32F103ZE', 'STM32F103RE' ], 'toolchains' : [ 'arm-gcc', 'codesourcery', 'devkitarm', 'arm-eabi-gcc' ] },
'avr32' : { 'cpus' : [ 'AT32UC3A0512' ], 'toolchains' : [ 'avr32-gcc' ] } 'avr32' : { 'cpus' : [ 'AT32UC3A0512' ], 'toolchains' : [ 'avr32-gcc' ] },
'lpc24xx' : { 'cpus' : [ 'LPC2468' ], 'toolchains' : [ 'arm-gcc', 'codesourcery', 'devkitarm', 'arm-eabi-gcc' ] }
} }
# List of board/CPU combinations # List of board/CPU combinations
@ -86,7 +86,8 @@ board_list = { 'SAM7-EX256' : [ 'AT91SAM7X256', 'AT91SAM7X512' ],
'STM3210E-EVAL' : [ 'STM32F103ZE' ], 'STM3210E-EVAL' : [ 'STM32F103ZE' ],
'ATEVK1100' : [ 'AT32UC3A0512' ], 'ATEVK1100' : [ 'AT32UC3A0512' ],
'ET-STM32' : [ 'STM32F103RE' ], 'ET-STM32' : [ 'STM32F103RE' ],
'EAGLE-100' : [ 'LM3S6918' ] 'EAGLE-100' : [ 'LM3S6918' ],
'ELUA-PUC' : ['LPC2468' ]
} }
# ROMFS file list "groups" # ROMFS file list "groups"
@ -127,7 +128,8 @@ file_list = { 'SAM7-EX256' : [ 'bisect', 'hangman' , 'led', 'piano', 'hello', 'i
'STM3210E-EVAL' : [ 'bisect', 'hello', 'info' ], 'STM3210E-EVAL' : [ 'bisect', 'hello', 'info' ],
'ATEVK1100' : [ 'bisect', 'hangman', 'led', 'hello', 'info' ], 'ATEVK1100' : [ 'bisect', 'hangman', 'led', 'hello', 'info' ],
'ET-STM32' : [ 'hello', 'hangman', 'info', 'bisect','adcscope','adcpoll', 'dualpwm', 'pwmled' ], 'ET-STM32' : [ 'hello', 'hangman', 'info', 'bisect','adcscope','adcpoll', 'dualpwm', 'pwmled' ],
'EAGLE-100' : [ 'bisect', 'hangman', 'lhttpd', 'led', 'hello', 'info' ] 'EAGLE-100' : [ 'bisect', 'hangman', 'lhttpd', 'led', 'hello', 'info' ],
'ELUA-PUC' : [ 'bisect', 'hangman', 'led', 'hello', 'info' ]
} }
# Variants: board = <boardname> # Variants: board = <boardname>

View File

@ -19,6 +19,8 @@ elseif pd.board() == "ATEVK1100" then
invert = true invert = true
elseif pd.board() == "STR-E912" then elseif pd.board() == "STR-E912" then
ledpin = pio.P6_4 ledpin = pio.P6_4
elseif pd.board() == "ELUA-PUC" then
ledpin = pio.P1_20
else else
print( "\nError: Unknown board " .. pd.board() .. " !" ) print( "\nError: Unknown board " .. pd.board() .. " !" )
return return

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,39 @@
# Configuration file for the LPC24xx backend
cpumode = ARGUMENTS.get( 'cpumode', 'arm' ).lower()
specific_files = "startup.s irq.c target.c platform.c"
if cputype == 'LPC2468':
ldscript = "lpc2468.lds"
else:
print "Invalid CPU %s" % cputype
sys.exit( -1 )
# Check CPU mode
if cpumode == 'arm':
modeflag = ''
elif cpumode == 'thumb':
modeflag = '-mthumb'
else:
print "Invalid CPU mode %s", cpumode
sys.exit( -1 )
# Prepend with path
specific_files = " ".join( [ "src/platform/%s/%s" % ( platform, f ) for f in specific_files.split() ] )
ldscript = "src/platform/%s/%s" % ( platform, ldscript )
# Toolset data
tools[ 'lpc24xx' ] = {}
tools[ 'lpc24xx' ][ 'cccom' ] = "%s -mcpu=arm7tdmi %s %s $_CPPINCFLAGS -ffunction-sections -fdata-sections %s -Wall -c $SOURCE -o $TARGET" % ( toolset[ 'compile' ], modeflag, opt, cdefs )
tools[ 'lpc24xx' ][ 'linkcom' ] = "%s -nostartfiles -nostdlib %s -T %s -Wl,--gc-sections -Wl,-e,entry -Wl,--allow-multiple-definition -o $TARGET $SOURCES %s -lc -lgcc -lm" % ( toolset[ 'compile' ], modeflag, ldscript, local_libs )
tools[ 'lpc24xx' ][ 'ascom' ] = "%s -x assembler-with-cpp $_CPPINCFLAGS -mcpu=arm7tdmi %s %s -D__ASSEMBLY__ -Wall -c $SOURCE -o $TARGET" % ( toolset[ 'compile' ], modeflag, cdefs )
# Programming function for LPC24xx
def progfunc_lpx24xx( target, source, env ):
outname = output + ".elf"
os.system( "%s %s" % ( toolset[ 'size' ], outname ) )
print "Generating binary image..."
os.system( "%s -O ihex %s %s.hex" % ( toolset[ 'bin' ], outname, output ) )
tools[ 'lpc24xx' ][ 'progfunc' ] = progfunc_lpx24xx

108
src/platform/lpc24xx/irq.c Normal file
View File

@ -0,0 +1,108 @@
/*****************************************************************************
* irq.c: Interrupt handler C file for NXP LPC23xx/24xx Family Microprocessors
*
* Copyright(C) 2006, NXP Semiconductor
* All rights reserved.
*
* History
* 2006.07.13 ver 1.00 Prelimnary version, first Release
*
******************************************************************************/
#include "LPC23xx.h" /* LPC23XX/24xx Peripheral Registers */
#include "type.h"
#include "irq.h"
#if FIQ
#include "timer.h"
#endif
/******************************************************************************
** Function name: FIQ_Handler
**
** Descriptions: FIQ interrupt handler called in startup
** parameters:
**
** Returned value:
**
******************************************************************************/
// [TODO] make this GCC compatible if needed
#if FIQ
void FIQ_Handler( void ) __irq
{
//#if FIQ
if ( VICFIQStatus & (0x1<<4) && VICIntEnable & (0x1<<4) )
{
Timer0FIQHandler();
}
if ( VICFIQStatus & (0x1<<5) && VICIntEnable & (0x1<<5) )
{
Timer1FIQHandler();
}
return;
//#endif
}
#endif
/* Initialize the interrupt controller */
/******************************************************************************
** Function name: init_VIC
**
** Descriptions: Initialize VIC interrupt controller.
** parameters: None
** Returned value: None
**
******************************************************************************/
void init_VIC(void)
{
DWORD i = 0;
DWORD *vect_addr, *vect_prio;
/* initialize VIC*/
VICIntEnClr = 0xffffffff;
VICVectAddr = 0;
VICIntSelect = 0;
/* set all the vector and vector control register to 0 */
for ( i = 0; i < VIC_SIZE; i++ )
{
vect_addr = (DWORD *)(VIC_BASE_ADDR + VECT_ADDR_INDEX + i*4);
vect_prio = (DWORD *)(VIC_BASE_ADDR + VECT_PRIO_INDEX + i*4);
*vect_addr = 0x0;
*vect_prio = 0xF;
}
return;
}
/******************************************************************************
** Function name: install_irq
**
** Descriptions: Install interrupt handler
** parameters: Interrupt number, interrupt handler address,
** interrupt priority
** Returned value: true or false, return false if IntNum is out of range
**
******************************************************************************/
DWORD install_irq( DWORD IntNumber, void *HandlerAddr, DWORD Priority )
{
DWORD *vect_addr;
DWORD *vect_prio;
VICIntEnClr = 1 << IntNumber; /* Disable Interrupt */
if ( IntNumber >= VIC_SIZE )
{
return ( FALSE );
}
else
{
/* find first un-assigned VIC address for the handler */
vect_addr = (DWORD *)(VIC_BASE_ADDR + VECT_ADDR_INDEX + IntNumber*4);
vect_prio = (DWORD *)(VIC_BASE_ADDR + VECT_PRIO_INDEX + IntNumber*4);
*vect_addr = (DWORD)HandlerAddr; /* set interrupt vector */
*vect_prio = Priority;
VICIntEnable = 1 << IntNumber; /* Enable Interrupt */
return( TRUE );
}
}
/******************************************************************************
** End Of File
******************************************************************************/

View File

@ -0,0 +1,85 @@
/******************************************************************************
* irq.h: Interrupt related Header file for NXP LPC23xx/24xx Family
* Microprocessors
*
* Copyright(C) 2006, NXP Semiconductor
* All rights reserved.
*
* History
* 2006.09.01 ver 1.00 Prelimnary version, first Release
*
******************************************************************************/
#ifndef __IRQ_H
#define __IRQ_H
#define I_Bit 0x80
#define F_Bit 0x40
#define SYS32Mode 0x1F
#define IRQ32Mode 0x12
#define FIQ32Mode 0x11
/* Use FIQ, set below to 1, otherwise, it's 0 */
#define FIQ 0
#define HIGHEST_PRIORITY 0x01
#define LOWEST_PRIORITY 0x0F
#define WDT_INT 0
#define SWI_INT 1
#define ARM_CORE0_INT 2
#define ARM_CORE1_INT 3
#define TIMER0_INT 4
#define TIMER1_INT 5
#define UART0_INT 6
#define UART1_INT 7
#define PWM0_1_INT 8
#define I2C0_INT 9
#define SPI0_INT 10 /* SPI and SSP0 share VIC slot */
#define SSP0_INT 10
#define SSP1_INT 11
#define PLL_INT 12
#define RTC_INT 13
#define EINT0_INT 14
#define EINT1_INT 15
#define EINT2_INT 16
#define EINT3_INT 17
#define ADC0_INT 18
#define I2C1_INT 19
#define BOD_INT 20
#define EMAC_INT 21
#define USB_INT 22
#define CAN_INT 23
#define MCI_INT 24
#define GPDMA_INT 25
#define TIMER2_INT 26
#define TIMER3_INT 27
#define UART2_INT 28
#define UART3_INT 29
#define I2C2_INT 30
#define I2S_INT 31
#define VIC_SIZE 32
#define VECT_ADDR_INDEX 0x100
#define VECT_PRIO_INDEX 0x200
/* Be aware that, from compiler to compiler, nested interrupt will have to
be handled differently. More details can be found in Philips LPC2000
family app-note AN10381 */
/* unlike Keil CARM Compiler, in ARM's RealView compiler, don't save and
restore registers into the stack in RVD as the compiler does that for you.
See RVD ARM compiler Inline and embedded assemblers, "Rules for
using __asm and asm keywords. */
#define IENABLE __asm { MRS sysreg, SPSR; MSR CPSR_c, #SYS32Mode }
#define IDISABLE __asm { MSR CPSR_c, #(IRQ32Mode|I_Bit); MSR SPSR_cxsf, sysreg }
void init_VIC( void );
DWORD install_irq( DWORD IntNumber, void *HandlerAddr, DWORD Priority );
#endif /* end __IRQ_H */
/******************************************************************************
** End Of File
******************************************************************************/

View File

@ -0,0 +1,63 @@
OUTPUT_FORMAT("elf32-littlearm", "elf32-littlearm", "elf32-littlearm")
OUTPUT_ARCH(arm)
MEMORY
{
sram (W!RX) : ORIGIN = 0x40000000, LENGTH = 96k
flash (RX) : ORIGIN = 0x0, LENGTH = 512k
}
SECTIONS
{
.fixed :
{
. = ALIGN(4);
_sfixed = .;
PROVIDE(stext = .);
KEEP(*(.vectors))
*(.text .text.*)
*(.rodata .rodata.*)
*(.gnu.linkonce.t.*)
*(.glue_7)
*(.glue_7t)
*(.gcc_except_table)
*(.gnu.linkonce.r.*)
. = ALIGN(4);
_efixed = .;
PROVIDE(etext = .);
_fini = .;
*(.fini)
} >flash
.relocate : AT (_efixed)
{
. = ALIGN(4);
_srelocate = .;
*(.data .data.*)
*(.gnu.linkonce.d.*)
. = ALIGN(4);
_erelocate = .;
} >sram
.ARM.extab :
{
*(.ARM.extab*)
} >sram
__exidx_start = .;
.ARM.exidx :
{
*(.ARM.exidx*)
} >sram
__exidx_end = .;
.bss (NOLOAD) : {
_szero = .;
*(.bss .bss.*)
*(.gnu.linkonce.b.*)
*(COMMON)
_ezero = .;
} >sram
end = .;
}

View File

@ -0,0 +1,337 @@
// Platform-dependent functions
#include "platform.h"
#include "type.h"
#include "devman.h"
#include "genstd.h"
#include "stacks.h"
#include <reent.h>
#include <errno.h>
#include <string.h>
#include <ctype.h>
#include <stdio.h>
#include "utils.h"
#include "common.h"
#include "platform_conf.h"
// Platform includes
#include "LPC23xx.h" /* LPC23xx/24xx definitions */
#include "target.h"
#include "irq.h"
#include "uart.h"
// ****************************************************************************
// Platform initialization
static void platform_setup_timers();
// Power management definitions
enum
{
PCUART2 = 1ULL << 24,
PCUART3 = 1ULL << 25,
PCTIM2 = 1ULL << 22,
PCTIM3 = 1ULL << 23
};
// CPU initialization
static void platform_cpu_setup()
{
// Enable clock for UART2 and UART3
PCONP |= PCUART2 | PCUART3;
// Set clock for all the UARTs to the system clock (helps in baud generation)
PCLKSEL0 = ( PCLKSEL0 & 0xFFFFFC3F ) | 0x00000140;
PCLKSEL1 = ( PCLKSEL1 & 0xFFF0FFFF ) | 0x00050000;
// Enable clock for Timer 2 and Timer 3
PCONP |= PCTIM2 | PCTIM3;
// Setup GPIO0 and GPIO1 in fast mode
SCS |= 1;
}
int platform_init()
{
// Complete CPU initialization
platform_cpu_setup();
// Setup timers
platform_setup_timers();
// Initialize UART
platform_uart_setup( CON_UART_ID, CON_UART_SPEED, 8, PLATFORM_UART_PARITY_NONE, PLATFORM_UART_STOPBITS_1 );
// Common platform initialization code
cmn_platform_init();
return PLATFORM_OK;
}
// ****************************************************************************
// PIO section
static const u32 pio_fiodir[ NUM_PIO ] = { ( u32 )&FIO0DIR, ( u32 )&FIO1DIR, ( u32 )&FIO2DIR, ( u32 )&FIO3DIR, ( u32 )&FIO4DIR };
static const u32 pio_fiopin[ NUM_PIO ] = { ( u32 )&FIO0PIN, ( u32 )&FIO1PIN, ( u32 )&FIO2PIN, ( u32 )&FIO3PIN, ( u32 )&FIO4PIN };
static const u32 pio_fioset[ NUM_PIO ] = { ( u32 )&FIO0SET, ( u32 )&FIO1SET, ( u32 )&FIO2SET, ( u32 )&FIO3SET, ( u32 )&FIO4SET };
static const u32 pio_fioclr[ NUM_PIO ] = { ( u32 )&FIO0CLR, ( u32 )&FIO1CLR, ( u32 )&FIO2CLR, ( u32 )&FIO3CLR, ( u32 )&FIO4CLR };
// The platform I/O functions
pio_type platform_pio_op( unsigned port, pio_type pinmask, int op )
{
pio_type retval = 1;
PREG FIOxDIR = ( PREG )pio_fiodir[ port ];
PREG FIOxPIN = ( PREG )pio_fiopin[ port ];
PREG FIOxSET = ( PREG )pio_fioset[ port ];
PREG FIOxCLR = ( PREG )pio_fioclr[ port ];
switch( op )
{
case PLATFORM_IO_PORT_SET_VALUE:
*FIOxPIN = pinmask;
break;
case PLATFORM_IO_PIN_SET:
*FIOxSET = pinmask;
break;
case PLATFORM_IO_PIN_CLEAR:
*FIOxCLR = pinmask;
break;
case PLATFORM_IO_PORT_DIR_OUTPUT:
*FIOxDIR = 0xFFFFFFFF;
break;
case PLATFORM_IO_PIN_DIR_OUTPUT:
*FIOxDIR |= pinmask;
break;
case PLATFORM_IO_PORT_DIR_INPUT:
*FIOxDIR = 0;
break;
case PLATFORM_IO_PIN_DIR_INPUT:
*FIOxDIR &= ~pinmask;
break;
case PLATFORM_IO_PORT_GET_VALUE:
retval = *FIOxPIN;
break;
case PLATFORM_IO_PIN_GET:
retval =( *FIOxPIN & pinmask ) ? 1 : 0;
break;
default:
retval = 0;
break;
}
return retval;
}
// ****************************************************************************
// UART section
// UART0: Rx = P0.3, Tx = P0.2
// The other UARTs have assignable Rx/Tx pins and thus have to be configured
// by the user
static const u32 uart_lcr[ NUM_UART ] = { ( u32 )&U0LCR, ( u32 )&U1LCR, ( u32 )&U2LCR, ( u32 )&U3LCR };
static const u32 uart_dlm[ NUM_UART ] = { ( u32 )&U0DLM, ( u32 )&U1DLM, ( u32 )&U2DLM, ( u32 )&U3DLM };
static const u32 uart_dll[ NUM_UART ] = { ( u32 )&U0DLL, ( u32 )&U1DLL, ( u32 )&U2DLL, ( u32 )&U3DLL };
static const u32 uart_fcr[ NUM_UART ] = { ( u32 )&U0FCR, ( u32 )&U1FCR, ( u32 )&U2FCR, ( u32 )&U3FCR };
static const u32 uart_thr[ NUM_UART ] = { ( u32 )&U0THR, ( u32 )&U1THR, ( u32 )&U2THR, ( u32 )&U3THR };
static const u32 uart_lsr[ NUM_UART ] = { ( u32 )&U0LSR, ( u32 )&U1LSR, ( u32 )&U2LSR, ( u32 )&U3LSR };
static const u32 uart_rbr[ NUM_UART ] = { ( u32 )&U0RBR, ( u32 )&U1RBR, ( u32 )&U2RBR, ( u32 )&U3RBR };
u32 platform_uart_setup( unsigned id, u32 baud, int databits, int parity, int stopbits )
{
u32 temp;
PREG UxLCR = ( PREG )uart_lcr[ id ];
PREG UxDLM = ( PREG )uart_dlm[ id ];
PREG UxDLL = ( PREG )uart_dll[ id ];
PREG UxFCR = ( PREG )uart_fcr[ id ];
// Set data bits, parity, stop bit
temp = 0;
switch( databits )
{
case 5:
temp |= UART_DATABITS_5;
break;
case 6:
temp |= UART_DATABITS_6;
break;
case 7:
temp |= UART_DATABITS_7;
break;
case 8:
temp |= UART_DATABITS_8;
break;
}
if( stopbits == PLATFORM_UART_STOPBITS_2 )
temp |= UART_STOPBITS_2;
else
temp |= UART_STOPBITS_1;
if( parity != PLATFORM_UART_PARITY_NONE )
{
temp |= UART_PARITY_ENABLE;
if( parity == PLATFORM_UART_PARITY_ODD )
temp |= UART_PARITY_ODD;
else
temp |= UART_PARITY_EVEN;
}
*UxLCR = temp;
// Divisor computation
temp = ( Fpclk_UART >> 4 ) / baud;
// Set baud and divisors
*UxLCR |= UART_DLAB_ENABLE;
*UxDLM = temp >> 8;
*UxDLL = temp & 0xFF;
*UxLCR &= ~UART_DLAB_ENABLE;
// Enable and reset Tx and Rx FIFOs
*UxFCR = UART_FIFO_ENABLE | UART_RXFIFO_RESET | UART_TXFIFO_RESET;
// Setup PIOs for UART0. For the other ports, the user needs to specify what pin(s)
// are allocated for UART Rx/Tx.
if( id == 0 )
PINSEL0 = ( PINSEL0 & 0xFFFFFF0F ) | 0x00000050;
// Return the actual baud
return ( Fpclk_UART >> 4 ) / temp;
}
void platform_uart_send( unsigned id, u8 data )
{
PREG UxTHR = ( PREG )uart_thr[ id ];
PREG UxLSR = ( PREG )uart_lsr[ id ];
while( ( *UxLSR & LSR_THRE ) == 0 );
*UxTHR = data;
}
int platform_s_uart_recv( unsigned id, s32 timeout )
{
PREG UxLSR = ( PREG )uart_lsr[ id ];
PREG UxRBR = ( PREG )uart_rbr[ id ];
if( timeout == 0 )
{
// Return data only if already available
if( *UxLSR & LSR_RDR )
return *UxRBR;
else
return -1;
}
while( ( *UxLSR & LSR_RDR ) == 0 );
return *UxRBR;
}
// ****************************************************************************
// Timer section
static const u32 tmr_tcr[ NUM_TIMER ] = { ( u32 )&T0TCR, ( u32 )&T1TCR, ( u32 )&T2TCR, ( u32 )&T3TCR };
static const u32 tmr_tc[ NUM_TIMER ] = { ( u32 )&T0TC, ( u32 )&T1TC, ( u32 )&T2TC, ( u32 )&T3TC };
static const u32 tmr_pr[ NUM_TIMER ] = { ( u32 )&T0PR, ( u32 )&T1PR, ( u32 )&T2PR, ( u32 )&T3PR };
static const u32 tmr_pc[ NUM_TIMER ] = { ( u32 )&T0PC, ( u32 )&T1PC, ( u32 )&T2PC, ( u32 )&T3PC };
// Timer register definitions
enum
{
TMR_ENABLE = 1,
TMR_RESET = 2
};
// Helper function: get timer clock
static u32 platform_timer_get_clock( unsigned id )
{
PREG TxPR = ( PREG )tmr_pr[ id ];
return Fpclk / ( *TxPR + 1 );
}
// Helper function: set timer clock
static u32 platform_timer_set_clock( unsigned id, unsigned clock )
{
u32 div = Fpclk / clock, prevtc;
PREG TxPR = ( PREG )tmr_pr[ id ];
PREG TxPC = ( PREG )tmr_pc[ id ];
PREG TxTCR = ( PREG )tmr_tcr[ id ];
prevtc = *TxTCR;
*TxTCR = 0;
*TxPC = 0;
*TxPR = div - 1;
*TxTCR = prevtc;
return Fpclk / div;
}
// Helper function: setup timers
static void platform_setup_timers()
{
unsigned i;
PREG TxTCR;
// Set base frequency to 1MHz, as we can't use a better resolution anyway
for( i = 0; i < NUM_TIMER; i ++ )
{
TxTCR = ( PREG )tmr_tcr[ i ];
*TxTCR = 0;
platform_timer_set_clock( i, 1000000 );
}
}
void platform_s_timer_delay( unsigned id, u32 delay_us )
{
PREG TxTCR = ( PREG )tmr_tcr[ id ];
PREG TxTC = ( PREG )tmr_tc[ id ];
u32 last;
last = ( ( u64 )delay_us * platform_timer_get_clock( id ) ) / 1000000;
*TxTCR = TMR_ENABLE | TMR_RESET;
*TxTCR = TMR_ENABLE;
while( *TxTC < last );
}
u32 platform_s_timer_op( unsigned id, int op, u32 data )
{
u32 res = 0;
PREG TxTCR = ( PREG )tmr_tcr[ id ];
PREG TxTC = ( PREG )tmr_tc[ id ];
switch( op )
{
case PLATFORM_TIMER_OP_START:
*TxTCR = TMR_ENABLE | TMR_RESET;
*TxTCR = TMR_ENABLE;
break;
case PLATFORM_TIMER_OP_READ:
res = *TxTC;
break;
case PLATFORM_TIMER_OP_GET_MAX_DELAY:
res = platform_timer_get_diff_us( id, 0, 0xFFFFFFFF );
break;
case PLATFORM_TIMER_OP_GET_MIN_DELAY:
res = platform_timer_get_diff_us( id, 0, 1 );
break;
case PLATFORM_TIMER_OP_SET_CLOCK:
res = platform_timer_set_clock( id, data );
break;
case PLATFORM_TIMER_OP_GET_CLOCK:
res = platform_timer_get_clock( id );
break;
}
return res;
}

View File

@ -0,0 +1,82 @@
// eLua platform configuration
#ifndef __PLATFORM_CONF_H__
#define __PLATFORM_CONF_H__
#include "auxmods.h"
#include "stacks.h"
#include "target.h"
// *****************************************************************************
// Define here what components you want for this platform
#define BUILD_XMODEM
#define BUILD_SHELL
#define BUILD_ROMFS
#define BUILD_TERM
#define BUILD_CON_GENERIC
// *****************************************************************************
// UART/Timer IDs configuration data (used in main.c)
#define CON_UART_ID 0
#define CON_UART_SPEED 115200
#define CON_TIMER_ID 0
#define TERM_LINES 25
#define TERM_COLS 80
// *****************************************************************************
// Auxiliary libraries that will be compiled for this platform
#define LUA_PLATFORM_LIBS_ROM\
_ROM( AUXLIB_PIO, luaopen_pio, pio_map )\
_ROM( AUXLIB_TMR, luaopen_tmr, tmr_map )\
_ROM( AUXLIB_UART, luaopen_uart, uart_map )\
_ROM( AUXLIB_PIO, luaopen_pio, pio_map )\
_ROM( AUXLIB_PD, luaopen_pd, pd_map )\
_ROM( AUXLIB_TERM, luaopen_term, term_map )\
_ROM( AUXLIB_PACK, luaopen_pack, pack_map )\
_ROM( AUXLIB_BIT, luaopen_bit, bit_map )\
_ROM( LUA_MATHLIBNAME, luaopen_math, math_map )
// *****************************************************************************
// Configuration data
// Virtual timers (0 if not used)
#define VTMR_NUM_TIMERS 0
#define VTMR_FREQ_HZ 4
// Number of resources (0 if not available/not implemented)
#define NUM_PIO 5
#define NUM_SPI 0
#define NUM_UART 4
#define NUM_PWM 0
#define NUM_ADC 0
#define NUM_CAN 0
#define NUM_TIMER 4
// Enable RX buffering on UART
// [TODO] make this happen
//#define BUF_ENABLE_UART
//#define CON_BUF_SIZE BUF_SIZE_128
// CPU frequency (needed by the CPU module, 0 if not used)
#define CPU_FREQUENCY Fcclk
// PIO prefix ('0' for P0, P1, ... or 'A' for PA, PB, ...)
#define PIO_PREFIX '0'
// Pins per port configuration:
// #define PIO_PINS_PER_PORT (n) if each port has the same number of pins, or
// #define PIO_PIN_ARRAY { n1, n2, ... } to define pins per port in an array
// Use #define PIO_PINS_PER_PORT 0 if this isn't needed
#define PIO_PINS_PER_PORT 31
// Allocator data: define your free memory zones here in two arrays
// (start address and end address)
#define SRAM_ORIGIN 0x40000000
#define SRAM_SIZE 0x10000 // [TODO]: make this 96k?
#define MEM_START_ADDRESS { ( void* )end }
#define MEM_END_ADDRESS { ( void* )( SRAM_ORIGIN + SRAM_SIZE - STACK_SIZE_TOTAL - 1 ) }
#endif // #ifndef __PLATFORM_CONF_H__

View File

@ -0,0 +1,11 @@
// Stack size definitions
#ifndef __STACKS_H__
#define __STACKS_H__
#define STACK_SIZE_USR 8192
#define STACK_SIZE_IRQ 64
#define STACK_SIZE_TOTAL ( STACK_SIZE_USR + STACK_SIZE_IRQ )
#endif

View File

@ -0,0 +1,107 @@
#include "stacks.h"
//------------------------------------------------------------------------------
// Definitions
//------------------------------------------------------------------------------
#define ARM_MODE_ABT 0x17
#define ARM_MODE_FIQ 0x11
#define ARM_MODE_IRQ 0x12
#define ARM_MODE_SVC 0x13
#define I_BIT 0x80
#define F_BIT 0x40
#define RAM_Base 0x40000000
#define RAM_Size 0x10000 // [TODO] make this 96k?
#define Top_Stack (RAM_Base + RAM_Size)
//------------------------------------------------------------------------------
// Startup routine
//------------------------------------------------------------------------------
.align 4
.arm
/* Exception vectors
*******************/
.section .vectors, "a"
resetVector:
ldr pc, =resetHandler /* Reset */
undefVector:
b undefVector /* Undefined instruction */
swiVector:
b swiVector /* Software interrupt */
prefetchAbortVector:
b prefetchAbortVector /* Prefetch abort */
dataAbortVector:
b dataAbortVector /* Data abort */
reservedVector:
b reservedVector /* Reserved for future use */
irqVector:
ldr pc, [pc, #-0x0120] /* Vector from VicVectAddr */
fiqVector:
b fiqVector /* Fast interrupt */
//------------------------------------------------------------------------------
/// Initializes the chip and branches to the main() function.
//------------------------------------------------------------------------------
.section .text
.global entry
.extern main
.extern TargetResetInit
entry:
resetHandler:
// [TODO] enable interrupts
/* Setup stacks for each mode */
ldr r0, =Top_Stack
msr CPSR_c, #ARM_MODE_IRQ|I_BIT|F_BIT
mov r13, r0
sub r0, r0, #STACK_SIZE_IRQ
# Set up Supervisor Mode and set Supervisor Mode Stack (leave interrupts enabled)
msr CPSR_c, #ARM_MODE_SVC|F_BIT|I_BIT
mov r13, r0
/* Perform low-level initialization of the chip using LowLevelInit() */
/* Initialize the relocate segment */
ldr r0, =_efixed
ldr r1, =_srelocate
ldr r2, =_erelocate
CopyROMtoRAM:
cmp r1, r2
ldrcc r3, [r0], #4
strcc r3, [r1], #4
bcc CopyROMtoRAM
/* Clear the zero segment */
ldr r0, =_szero
ldr r1, =_ezero
mov r2, #0
ZeroBSS:
cmp r0, r1
strcc r2, [r0], #4
bcc ZeroBSS
/* Call external initialization code */
bl TargetResetInit
/* Branch to main()
******************/
ldr r0, =main
mov lr, pc
bx r0
/* Loop indefinitely when program is finished */
forever:
b forever
.end

View File

@ -0,0 +1,196 @@
/*****************************************************************************
* target.c: Target C file for NXP LPC23xx/24xx Family Microprocessors
*
* Copyright(C) 2006, NXP Semiconductor
* All rights reserved.
*
* History
* 2006.07.13 ver 1.00 Prelimnary version, first Release
*
*****************************************************************************/
#include "LPC23xx.h"
#include "type.h"
#include "irq.h"
#include "target.h"
/******************************************************************************
** Function name: TargetInit
**
** Descriptions: Initialize the target board; it is called in a necessary
** place, change it as needed
**
** parameters: None
** Returned value: None
**
******************************************************************************/
void TargetInit(void)
{
/* Add your codes here */
return;
}
/******************************************************************************
** Function name: GPIOResetInit
**
** Descriptions: Initialize the target board before running the main()
** function; User may change it as needed, but may not
** deleted it.
**
** parameters: None
** Returned value: None
**
******************************************************************************/
void GPIOResetInit( void )
{
/* Reset all GPIO pins to default: primary function */
PINSEL0 = 0x00000000;
PINSEL1 = 0x00000000;
PINSEL2 = 0x00000000;
PINSEL3 = 0x00000000;
PINSEL4 = 0x00000000;
PINSEL5 = 0x00000000;
PINSEL6 = 0x00000000;
PINSEL7 = 0x00000000;
PINSEL8 = 0x00000000;
PINSEL9 = 0x00000000;
PINSEL10 = 0x00000000;
IODIR0 = 0x00000000;
IODIR1 = 0x00000000;
IOSET0 = 0x00000000;
IOSET1 = 0x00000000;
FIO0DIR = 0x00000000;
FIO1DIR = 0x00000000;
FIO2DIR = 0x00000000;
FIO3DIR = 0x00000000;
FIO4DIR = 0x00000000;
FIO0SET = 0x00000000;
FIO1SET = 0x00000000;
FIO2SET = 0x00000000;
FIO3SET = 0x00000000;
FIO4SET = 0x00000000;
return;
}
/******************************************************************************
** Function name: ConfigurePLL
**
** Descriptions: Configure PLL switching to main OSC instead of IRC
** at power up and wake up from power down.
** This routine is used in TargetResetInit() and those
** examples using power down and wake up such as
** USB suspend to resume, ethernet WOL, and power management
** example
** parameters: None
** Returned value: None
**
******************************************************************************/
void ConfigurePLL ( void )
{
DWORD MValue, NValue;
if ( PLLSTAT & (1 << 25) )
{
PLLCON = 1; /* Enable PLL, disconnected */
PLLFEED = 0xaa;
PLLFEED = 0x55;
}
PLLCON = 0; /* Disable PLL, disconnected */
PLLFEED = 0xaa;
PLLFEED = 0x55;
SCS |= 0x20; /* Enable main OSC */
while( !(SCS & 0x40) ); /* Wait until main OSC is usable */
CLKSRCSEL = 0x1; /* select main OSC, 12MHz, as the PLL clock source */
PLLCFG = PLL_MValue | (PLL_NValue << 16);
PLLFEED = 0xaa;
PLLFEED = 0x55;
PLLCON = 1; /* Enable PLL, disconnected */
PLLFEED = 0xaa;
PLLFEED = 0x55;
CCLKCFG = CCLKDivValue; /* Set clock divider */
#if USE_USB
USBCLKCFG = USBCLKDivValue; /* usbclk = 288 MHz/6 = 48 MHz */
#endif
while ( ((PLLSTAT & (1 << 26)) == 0) ); /* Check lock bit status */
MValue = PLLSTAT & 0x00007FFF;
NValue = (PLLSTAT & 0x00FF0000) >> 16;
while ((MValue != PLL_MValue) && ( NValue != PLL_NValue) );
PLLCON = 3; /* enable and connect */
PLLFEED = 0xaa;
PLLFEED = 0x55;
while ( ((PLLSTAT & (1 << 25)) == 0) ); /* Check connect bit status */
}
/******************************************************************************
** Function name: TargetResetInit
**
** Descriptions: Initialize the target board before running the main()
** function; User may change it as needed, but may not
** deleted it.
**
** parameters: None
** Returned value: None
**
******************************************************************************/
void TargetResetInit(void)
{
#ifdef __DEBUG_RAM
MEMMAP = 0x2; /* remap to internal RAM */
#endif
#ifdef __DEBUG_FLASH
MEMMAP = 0x1; /* remap to internal flash */
#endif
#if USE_USB
PCONP |= 0x80000000; /* Turn On USB PCLK */
#endif
/* Configure PLL, switch from IRC to Main OSC */
ConfigurePLL();
/* Set system timers for each component */
#if (Fpclk / (Fcclk / 4)) == 1
PCLKSEL0 = 0x00000000; /* PCLK is 1/4 CCLK */
PCLKSEL1 = 0x00000000;
#endif
#if (Fpclk / (Fcclk / 4)) == 2
PCLKSEL0 = 0xAAAAAAAA; /* PCLK is 1/2 CCLK */
PCLKSEL1 = 0xAAAAAAAA;
#endif
#if (Fpclk / (Fcclk / 4)) == 4
PCLKSEL0 = 0x55555555; /* PCLK is the same as CCLK */
PCLKSEL1 = 0x55555555;
#endif
/* Set memory accelerater module*/
MAMCR = 0;
#if Fcclk < 20000000
MAMTIM = 1;
#else
#if Fcclk < 40000000
MAMTIM = 2;
#else
MAMTIM = 3;
#endif
#endif
MAMCR = 2;
GPIOResetInit();
init_VIC();
}
/******************************************************************************
** End Of File
******************************************************************************/

View File

@ -0,0 +1,136 @@
/*****************************************************************************
* target.h: Header file for NXP LPC23xx/24xx Family Microprocessors
*
* Copyright(C) 2006, NXP Semiconductor
* All rights reserved.
*
* History
* 2006.09.20 ver 1.00 Prelimnary version, first Release
*
******************************************************************************/
#ifndef __TARGET_H
#define __TARGET_H
#ifdef __cplusplus
extern "C" {
#endif
/* Only choose one of them below, by default, it's Keil MCB2300 */
/*#define ENG_BOARD_LPC24XX 0
#define KEIL_BOARD_LPC23XX 1
#define EA_BOARD_LPC24XX 0
#define IAR_BOARD_LPC23XX 0*/
/* On EA and IAR boards, they use Micrel PHY.
on ENG and KEIL boards, they use National PHY */
/*#define NATIONAL_PHY 1
#define MICREL_PHY 2*/
/* If USB device is used, CCO will be 288Mhz( divided by 6) or 384Mhz( divided by 8)
to get precise USB clock 48Mhz. If USB is not used, you set any clock you want
but make sure the divider of the CCO should be an even number. If you want to
use USB, change "define USE_USB" from 0 to 1 */
#define USE_USB 0
/* PLL Setting Table Matrix */
/*
Main Osc. CCLKCFG Fcco Fcclk M N
12Mhz 29 300Mhz 10Mhz 24 1
12Mhz 35 360Mhz 10Mhz 14 0
12Mhz 27 336Mhz 12Mhz 13 0
12Mhz 17 360Mhz 20Mhz 14 0
12Mhz 13 336Mhz 24Mhz 13 0
12Mhz 11 300Mhz 25Mhz 24 1
12Mhz 9 300Mhz 30Mhz 24 1
12Mhz 11 360Mhz 30Mhz 14 0
12Mhz 9 320Mhz 32Mhz 39 2
12Mhz 9 350Mhz 35Mhz 174 11
12Mhz 7 312Mhz 39Mhz 12 0
12Mhz 7 360Mhz 45Mhz 14 0
12Mhz 5 300Mhz 50Mhz 24 1
12Mhz 5 312Mhz 52Mhz 12 0
12Mhz 5 336Mhz 56Mhz 13 0
12Mhz 3 300Mhz 75Mhz 24 1
12Mhz 3 312Mhz 78Mhz 12 0
12Mhz 3 320Mhz 80Mhz 39 2
12Mhz 3 336Mhz 84Mhz 13 0
*/
/* These are limited number of Fcco configuration for
USB communication as the CPU clock and USB clock shares
the same PLL. The USB clock needs to be multiple of
48Mhz. */
#if USE_USB /* 1 is USB, 0 is non-USB related */
/* Fcck = 48Mhz, Fosc = 288Mhz, and USB 48Mhz */
#define PLL_MValue 11
#define PLL_NValue 0
#define CCLKDivValue 5
#define USBCLKDivValue 5
/* System configuration: Fosc, Fcclk, Fcco, Fpclk must be defined */
/* PLL input Crystal frequence range 4KHz~20MHz. */
#define Fosc 12000000
/* System frequence,should be less than 80MHz. */
#define Fcclk 48000000
#define Fcco 288000000
#else // #if USE_USB
// [TODO]: use the PLL calculator XLS to increase frequency a bit
/* Fcck = 60Mhz, Fosc = 360Mhz, USB can't be divided into 48Mhz
in this case, so USBCLKDivValue is not needed. */
#if 0 // 60MHz
#define PLL_MValue 14
#define PLL_NValue 0
#define CCLKDivValue 5
#define Fcclk 60000000ULL
#else // 72MHz
#define PLL_MValue 14
#define PLL_NValue 0
#define CCLKDivValue 4
#define Fcclk 72000000ULL
#endif
/* System configuration: Fosc, Fcclk, Fcco, Fpclk must be defined */
/* PLL input Crystal frequence range 4KHz~20MHz. */
#define Fosc 12000000
/* System frequence,should be less than 72MHz. */
#define Fcco 360000000
#endif
/* APB clock frequence , must be 1/2/4 multiples of ( Fcclk/4 ). */
/* If USB is enabled, the minimum APB must be greater than 16Mhz */
#if USE_USB
#define Fpclk (Fcclk / 2)
#else
#define Fpclk (Fcclk / 4)
#endif
#define Fpclk_MHz (Fpclk / 1000000)
#define Fpclk_UART (Fcclk)
/******************************************************************************
** Function name: TargetInit
**
** Descriptions: Initialize the target board; it is called in a
** necessary place, change it as needed
**
** parameters: None
** Returned value: None
**
******************************************************************************/
extern void TargetInit(void);
extern void ConfigurePLL( void );
extern void TargetResetInit(void);
#ifdef __cplusplus
}
#endif
#endif /* end __TARGET_H */
/******************************************************************************
** End Of File
******************************************************************************/

View File

@ -0,0 +1,29 @@
#ifndef __TYPE_H__
#define __TYPE_H__
typedef unsigned char u8;
typedef signed char s8;
typedef unsigned short u16;
typedef signed short s16;
typedef unsigned long u32;
typedef signed long s32;
typedef unsigned long long u64;
typedef signed long long s64;
#ifndef FALSE
#define FALSE (0)
#endif
#ifndef TRUE
#define TRUE (1)
#endif
typedef unsigned char BYTE;
typedef unsigned short WORD;
typedef unsigned long DWORD;
typedef unsigned int BOOL;
typedef volatile unsigned long* PREG;
#endif

View File

@ -0,0 +1,59 @@
/*****************************************************************************
* uart.h: Header file for NXP LPC23xx Family Microprocessors
*
* Copyright(C) 2006, NXP Semiconductor
* All rights reserved.
*
* History
* 2006.09.01 ver 1.00 Prelimnary version, first Release
*
* Modified by BogdanM for eLua
******************************************************************************/
#ifndef __UART_H
#define __UART_H
#include "type.h"
#define IER_RBR 0x01
#define IER_THRE 0x02
#define IER_RLS 0x04
#define IIR_PEND 0x01
#define IIR_RLS 0x03
#define IIR_RDA 0x02
#define IIR_CTI 0x06
#define IIR_THRE 0x01
#define LSR_RDR 0x01
#define LSR_OE 0x02
#define LSR_PE 0x04
#define LSR_FE 0x08
#define LSR_BI 0x10
#define LSR_THRE 0x20
#define LSR_TEMT 0x40
#define LSR_RXFE 0x80
// UART setup constants
enum
{
UART_DATABITS_5 = 0,
UART_DATABITS_6 = 1,
UART_DATABITS_7 = 2,
UART_DATABITS_8 = 3,
UART_STOPBITS_1 = 0,
UART_STOPBITS_2 = 4,
UART_PARITY_ENABLE = 8,
UART_PARITY_ODD = 0,
UART_PARITY_EVEN = 1 << 4,
UART_DLAB_ENABLE = 1 << 7,
UART_FIFO_ENABLE = 1,
UART_RXFIFO_RESET = 2,
UART_TXFIFO_RESET = 4
};
#endif /* end __UART_H */
/*****************************************************************************
** End Of File
******************************************************************************/