1
0
mirror of https://github.com/elua/elua.git synced 2025-01-25 01:02:54 +08:00

- factored out common code from all backends in src/common.c

- added virtual timers (on LM3S, AVR32 and AT91SAM7 for now)
- added interrupt handling code for AT91SAM7 and AVR32
- fixed two serious bugs that prevented the eLua image to run on both STR9 and LPC2888 (linker command file issues)
- fixed line endings (DOS->UNIX) in the STM32 library files
- fixed preprocessor errors (hopefully all of them) like #if ELUA_CPU == LM3S8962
- other minor or less than minor fixes :)
This commit is contained in:
Bogdan Marinescu 2009-01-07 20:17:18 +00:00
parent 450dc03989
commit 58da9ac870
67 changed files with 18158 additions and 18396 deletions

View File

@ -123,7 +123,7 @@ local_include = local_include + " -Isrc/modules -Isrc/platform/%s" % platform
local_libs = ''
# Application files
app_files = " src/main.c src/romfs.c src/xmodem.c src/shell.c src/term.c src/dlmalloc.c "
app_files = " src/main.c src/romfs.c src/xmodem.c src/shell.c src/term.c src/dlmalloc.c src/common.c "
# Newlib related files
newlib_files = " src/newlib/devman.c src/newlib/stubs.c src/newlib/genstd.c src/newlib/stdtcp.c"

15
inc/common.h Normal file
View File

@ -0,0 +1,15 @@
// Common platform functions
#ifndef __COMMON_H__
#define __COMMON_H__
// Virtual timers data
#define VTMR_FIRST_ID ( 32 )
#define VTMR_GET_ID( x ) ( ( x ) - VTMR_FIRST_ID )
#define TIMER_IS_VIRTUAL( x ) ( ( VTMR_NUM_TIMERS > 0 ) && ( ( x ) >= VTMR_FIRST_ID ) && ( ( x ) < VTMR_NUM_TIMERS + VTMR_FIRST_ID ) )
// Functions exported by the common platform layer
void cmn_platform_init();
void cmn_virtual_timer_cb();
#endif // #ifndef __COMMON_H__

View File

@ -117,6 +117,7 @@ int platform_uart_exists( unsigned id );
u32 platform_uart_setup( unsigned id, u32 baud, int databits, int parity, int stopbits );
void platform_uart_send( unsigned id, u8 data );
int platform_uart_recv( unsigned id, unsigned timer_id, int timeout );
int platform_s_uart_recv( unsigned id, unsigned timer_id, int timeout );
// *****************************************************************************
// Timer subsection
@ -141,10 +142,11 @@ enum
// The platform timer functions
int platform_timer_exists( unsigned id );
void platform_timer_delay( unsigned id, u32 delay_us );
void platform_s_timer_delay( unsigned id, u32 delay_us );
u32 platform_timer_op( unsigned id, int op, u32 data );
u32 platform_s_timer_op( unsigned id, int op, u32 data );
u32 platform_timer_get_diff_us( unsigned id, timer_data_type end, timer_data_type start );
// *****************************************************************************
// OLED DISP subsection

View File

@ -42,13 +42,12 @@
#define XMODEM_INCREMENT_AMMOUNT 512
#define XMODEM_BUFFER_SIZE 128
// xmodem control characters
#define SOH 0x01
#define STX 0x02
#define EOT 0x04
#define ACK 0x06
#define NAK 0x15
#define CAN 0x18
#define XMODEM_CAN 0x18
#define CTRLZ 0x1A
// xmodem timeout/retry parameters

250
src/common.c Normal file
View File

@ -0,0 +1,250 @@
// Common platform functions
#include "platform.h"
#include "platform_conf.h"
#include "type.h"
#include "genstd.h"
#include "common.h"
#include <stdio.h>
// *****************************************************************************
// std functions and platform initialization
static void uart_send( int fd, char c )
{
fd = fd;
platform_uart_send( CON_UART_ID, c );
}
static int uart_recv()
{
return platform_uart_recv( CON_UART_ID, 0, PLATFORM_UART_INFINITE_TIMEOUT );
}
void cmn_platform_init()
{
// Set the send/recv functions
std_set_send_func( uart_send );
std_set_get_func( uart_recv );
}
// ****************************************************************************
// PIO functions
int platform_pio_has_port( unsigned port )
{
return port < NUM_PIO;
}
const char* platform_pio_get_prefix( unsigned port )
{
static char c[ 3 ];
sprintf( c, "P%c", ( char )( port + PIO_PREFIX ) );
return c;
}
int platform_pio_has_pin( unsigned port, unsigned pin )
{
#if defined( PIO_PINS_PER_PORT )
return port < NUM_PIO && pin < PIO_PINS_PER_PORT;
#elif defined( PIO_PIN_ARRAY )
const u8 pio_port_pins[] = PIO_PIN_ARRAY;
return port < NUM_PIO && pin < pio_port_pins[ port ];
#else
#error "You must define either PIO_PINS_PER_PORT of PIO_PIN_ARRAY in platform_conf.h"
#endif
}
// ****************************************************************************
// UART functions
// The platform UART functions
int platform_uart_exists( unsigned id )
{
return id < NUM_UART;
}
int platform_uart_recv( unsigned id, unsigned timer_id, int timeout )
{
timer_data_type tmr_start, tmr_crt;
int res;
if( timeout == 0 )
return platform_s_uart_recv( id, timer_id, timeout );
else if( timeout == PLATFORM_UART_INFINITE_TIMEOUT )
return platform_s_uart_recv( id, timer_id, timeout );
else
{
// Receive char with the specified timeout
tmr_start = platform_timer_op( timer_id, PLATFORM_TIMER_OP_START, 0 );
while( 1 )
{
if( ( res = platform_s_uart_recv( id, timer_id, 0 ) ) >= 0 )
break;
tmr_crt = platform_timer_op( timer_id, PLATFORM_TIMER_OP_READ, 0 );
if( platform_timer_get_diff_us( timer_id, tmr_crt, tmr_start ) >= timeout )
break;
}
return res;
}
}
// ****************************************************************************
// Timers (and vtimers) functions
#if VTMR_NUM_TIMERS > 0
static volatile u32 vtmr_counters[ VTMR_NUM_TIMERS ];
static volatile s8 vtmr_reset_idx = -1;
// This should be called from the platform's timer interrupt at VTMR_FREQ_HZ
void cmn_virtual_timer_cb()
{
unsigned i;
for( i = 0; i < VTMR_NUM_TIMERS; i ++ )
vtmr_counters[ i ] ++;
if( vtmr_reset_idx != -1 )
{
vtmr_counters[ vtmr_reset_idx ] = 0;
vtmr_reset_idx = -1;
}
}
static void vtmr_reset_timer( unsigned vid )
{
unsigned id = VTMR_GET_ID( vid );
vtmr_reset_idx = ( s8 )id;
while( vtmr_reset_idx != -1 );
}
static void vtmr_delay( unsigned vid, u32 delay_us )
{
timer_data_type final;
unsigned id = VTMR_GET_ID( vid );
final = ( ( u64 )delay_us * VTMR_FREQ_HZ ) / 1000000;
vtmr_reset_timer( vid );
while( vtmr_counters[ id ] < final );
}
#else // #if VTMR_NUM_TIMERS > 0
void cmn_virtual_timer_cb()
{
}
#endif // #if VTMR_NUM_TIMERS > 0
int platform_timer_exists( unsigned id )
{
#if VTMR_NUM_TIMERS > 0
if( TIMER_IS_VIRTUAL( id ) )
return TIMER_IS_VIRTUAL( id );
else
#endif
return id < NUM_TIMER;
}
void platform_timer_delay( unsigned id, u32 delay_us )
{
#if VTMR_NUM_TIMERS > 0
if( TIMER_IS_VIRTUAL( id ) )
vtmr_delay( id, delay_us );
else
#endif
platform_s_timer_delay( id, delay_us );
}
u32 platform_timer_op( unsigned id, int op, u32 data )
{
u32 res = 0;
if( ( VTMR_NUM_TIMERS == 0 ) || ( !TIMER_IS_VIRTUAL( id ) ) )
return platform_s_timer_op( id, op, data );
#if VTMR_NUM_TIMERS > 0
switch( op )
{
case PLATFORM_TIMER_OP_START:
vtmr_reset_timer( id );
res = 0;
break;
case PLATFORM_TIMER_OP_READ:
res = vtmr_counters[ VTMR_GET_ID( id ) ];
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:
case PLATFORM_TIMER_OP_GET_CLOCK:
res = VTMR_FREQ_HZ;
break;
}
#endif
return res;
}
u32 platform_timer_get_diff_us( unsigned id, timer_data_type end, timer_data_type start )
{
timer_data_type temp;
u32 freq;
freq = platform_timer_op( id, PLATFORM_TIMER_OP_GET_CLOCK, 0 );
if( start < end )
{
temp = end;
end = start;
start = temp;
}
return ( ( u64 )( start - end ) * 1000000 ) / freq;
}
// ****************************************************************************
// SPI functions
int platform_spi_exists( unsigned id )
{
return id < NUM_SPI;
}
// ****************************************************************************
// PWM functions
int platform_pwm_exists( unsigned id )
{
return id < NUM_PWM;
}
// ****************************************************************************
// CPU functions
u32 platform_cpu_get_frequency()
{
return CPU_FREQUENCY;
}
// ****************************************************************************
// Allocator support
extern char end[];
void* platform_get_first_free_ram( unsigned id )
{
void* mstart[] = MEM_START_ADDRESS;
return id >= sizeof( mstart ) / sizeof( void* ) ? NULL : mstart[ id ];
}
void* platform_get_last_free_ram( unsigned id )
{
void* mend[] = MEM_END_ADDRESS;
return id >= sizeof( mend ) / sizeof( void* ) ? NULL : mend[ id ];
}

View File

@ -24,12 +24,12 @@ extern char etext[];
static void xmodem_send( u8 data )
{
platform_uart_send( XMODEM_UART_ID, data );
platform_uart_send( CON_UART_ID, data );
}
static int xmodem_recv( u32 timeout )
{
return platform_uart_recv( XMODEM_UART_ID, XMODEM_TIMER_ID, timeout );
return platform_uart_recv( CON_UART_ID, XMODEM_TIMER_ID, timeout );
}
#endif // #ifdef BUILD_XMODEM
@ -41,15 +41,15 @@ static int xmodem_recv( u32 timeout )
static void term_out( u8 data )
{
platform_uart_send( TERM_UART_ID, data );
platform_uart_send( CON_UART_ID, data );
}
static int term_in( int mode )
{
if( mode == TERM_INPUT_DONT_WAIT )
return platform_uart_recv( TERM_UART_ID, TERM_TIMER_ID, 0 );
return platform_uart_recv( CON_UART_ID, TERM_TIMER_ID, 0 );
else
return platform_uart_recv( TERM_UART_ID, TERM_TIMER_ID, PLATFORM_UART_INFINITE_TIMEOUT );
return platform_uart_recv( CON_UART_ID, TERM_TIMER_ID, PLATFORM_UART_INFINITE_TIMEOUT );
}
static int term_translate( u8 data )
@ -62,9 +62,9 @@ static int term_translate( u8 data )
{
// If we don't get a second char, we got a simple "ESC", so return KC_ESC
// If we get a second char it must be '[', the next one is relevant for us
if( platform_uart_recv( TERM_UART_ID, TERM_TIMER_ID, TERM_TIMEOUT ) == -1 )
if( platform_uart_recv( CON_UART_ID, TERM_TIMER_ID, TERM_TIMEOUT ) == -1 )
return KC_ESC;
if( ( c = platform_uart_recv( TERM_UART_ID, TERM_TIMER_ID, TERM_TIMEOUT ) ) == -1 )
if( ( c = platform_uart_recv( CON_UART_ID, TERM_TIMER_ID, TERM_TIMEOUT ) ) == -1 )
return KC_UNKNOWN;
switch( c )
{
@ -81,7 +81,7 @@ static int term_translate( u8 data )
else if( data == 0x0D )
{
// CR/LF sequence, read the second char (LF) if applicable
platform_uart_recv( TERM_UART_ID, TERM_TIMER_ID, TERM_TIMEOUT );
platform_uart_recv( CON_UART_ID, TERM_TIMER_ID, TERM_TIMEOUT );
return KC_ENTER;
}
else

View File

@ -5,6 +5,8 @@
#include "lauxlib.h"
#include "platform.h"
#include "auxmods.h"
#include "platform_conf.h"
#include "common.h"
// Helper function for the read/start functions
static int tmrh_timer_op( lua_State* L, int op )
@ -129,5 +131,9 @@ static const luaL_reg tmr_map[] =
LUALIB_API int luaopen_tmr( lua_State *L )
{
luaL_register( L, AUXLIB_TMR, tmr_map );
#if VTMR_NUM_TIMERS > 0
lua_pushnumber( L, VTMR_FIRST_ID );
lua_setfield( L, -2, "VIRT0" );
#endif
return 1;
}

View File

@ -307,7 +307,7 @@ int _link_r( struct _reent *r, const char *c1, const char *c2 )
}
#include <sys/time.h>
#ifdef AVR32
#ifdef FORAVR32
int _gettimeofday_r( struct _reent *r, struct timeval *tp, struct timezone *tzp )
#else
int _gettimeofday_r( struct _reent *r, struct timeval *tv, void *tz )
@ -394,7 +394,7 @@ DM_DEVICE* std_get_desc()
#endif // #if !defined( BUILD_CON_GENERIC ) && !defined( BUILD_CON_TCP )
#ifdef AVR32
#ifdef FORAVR32
void* memcpy( void *dst, const void* src, size_t len )
{
char *pdest = ( char* )dst;
@ -407,4 +407,5 @@ void* memcpy( void *dst, const void* src, size_t len )
}
return dst;
}
#endif // #if ELUA_PLATFORM == AVR32
#endif // #ifdef FORAVR32

View File

@ -0,0 +1,80 @@
/* ----------------------------------------------------------------------------
* ATMEL Microcontroller Software Support
* ----------------------------------------------------------------------------
* Copyright (c) 2008, Atmel Corporation
*
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* - Redistributions of source code must retain the above copyright notice,
* this list of conditions and the disclaimer below.
*
* Atmel's name may not be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* DISCLAIMER: THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
* DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
* ----------------------------------------------------------------------------
*/
//------------------------------------------------------------------------------
// Headers
//------------------------------------------------------------------------------
#include "aic.h"
#include <board.h>
//------------------------------------------------------------------------------
// Exported functions
//------------------------------------------------------------------------------
//------------------------------------------------------------------------------
/// Configures the interrupt associated with the given source, using the
/// specified mode and interrupt handler.
/// \param source Interrupt source to configure.
/// \param mode Triggering mode of the interrupt.
/// \param handler Interrupt handler function.
//------------------------------------------------------------------------------
void AIC_ConfigureIT(unsigned int source,
unsigned int mode,
void (*handler)( void ))
{
// Disable the interrupt first
AT91C_BASE_AIC->AIC_IDCR = 1 << source;
// Configure mode and handler
AT91C_BASE_AIC->AIC_SMR[source] = mode;
AT91C_BASE_AIC->AIC_SVR[source] = (unsigned int) handler;
// Clear interrupt
AT91C_BASE_AIC->AIC_ICCR = 1 << source;
}
//------------------------------------------------------------------------------
/// Enables interrupts coming from the given (unique) source.
/// \param source Interrupt source to enable.
//------------------------------------------------------------------------------
void AIC_EnableIT(unsigned int source)
{
AT91C_BASE_AIC->AIC_IECR = 1 << source;
}
//------------------------------------------------------------------------------
/// Disables interrupts coming from the given (unique) source.
/// \param source Interrupt source to enable.
//------------------------------------------------------------------------------
void AIC_DisableIT(unsigned int source)
{
AT91C_BASE_AIC->AIC_IDCR = 1 << source;
}

View File

@ -0,0 +1,74 @@
/* ----------------------------------------------------------------------------
* ATMEL Microcontroller Software Support
* ----------------------------------------------------------------------------
* Copyright (c) 2008, Atmel Corporation
*
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* - Redistributions of source code must retain the above copyright notice,
* this list of conditions and the disclaimer below.
*
* Atmel's name may not be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* DISCLAIMER: THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
* DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
* ----------------------------------------------------------------------------
*/
//------------------------------------------------------------------------------
/// \dir
/// !Purpose
///
/// Methods and definitions for configuring interrupts using the Advanced
/// Interrupt Controller (AIC).
///
/// !Usage
/// -# Configure an interrupt source using AIC_ConfigureIT
/// -# Enable or disable interrupt generation of a particular source with
/// AIC_EnableIT and AIC_DisableIT.
//------------------------------------------------------------------------------
#ifndef AIC_H
#define AIC_H
//------------------------------------------------------------------------------
// Headers
//------------------------------------------------------------------------------
#include <board.h>
//------------------------------------------------------------------------------
// Definitions
//------------------------------------------------------------------------------
#ifndef AT91C_AIC_SRCTYPE_INT_HIGH_LEVEL
/// Redefinition of missing constant.
#define AT91C_AIC_SRCTYPE_INT_HIGH_LEVEL AT91C_AIC_SRCTYPE_INT_LEVEL_SENSITIVE
#endif
//------------------------------------------------------------------------------
// Global functions
//------------------------------------------------------------------------------
extern void AIC_ConfigureIT(unsigned int source,
unsigned int mode,
void (*handler)( void ));
extern void AIC_EnableIT(unsigned int source);
extern void AIC_DisableIT(unsigned int source);
#endif //#ifndef AIC_H

View File

@ -133,7 +133,7 @@ resetHandler:
1:
ldr r4, =_sstack
mov sp, r4
ldr r0, =LowLevelInit
ldr r0, =LowLevelInit
mov lr, pc
bx r0

View File

@ -69,7 +69,6 @@
*/
void defaultSpuriousHandler( void )
{
while (1);
}
/*!

View File

@ -2,7 +2,7 @@
cpumode = ARGUMENTS.get( 'cpumode', 'thumb' ).lower()
specific_files = "board_cstartup.s board_lowlevel.c board_memories.c usart.c pmc.c pio.c platform.c tc.c pwmc.c"
specific_files = "board_cstartup.s board_lowlevel.c board_memories.c usart.c pmc.c pio.c platform.c tc.c pwmc.c aic.c"
if cputype == 'AT91SAM7X256':
ldscript = "flash256.lds"
cdefs = cdefs + " -Dat91sam7x256"

View File

@ -17,20 +17,9 @@
#include <ctype.h>
#include <stdio.h>
#include "utils.h"
// *****************************************************************************
// std functions
static void uart_send( int fd, char c )
{
fd = fd;
USART_Write( AT91C_BASE_US0, c, 0 );
}
static int uart_recv()
{
return USART_Read( AT91C_BASE_US0, 0 );
}
#include "common.h"
#include "aic.h"
#include "platform_conf.h"
// ****************************************************************************
// Platform initialization
@ -42,6 +31,16 @@ static const Pin platform_uart_pins[ 2 ][ 2 ] =
};
static const AT91S_TC* timer_base[] = { AT91C_BASE_TC0, AT91C_BASE_TC1, AT91C_BASE_TC2 };
#if VTMR_NUM_TIMERS > 0
static void ISR_Tc2()
{
cmn_virtual_timer_cb();
AT91C_BASE_TC2->TC_SR;
asm( "pop {r0}":: );
asm( "bx r0":: );
}
#endif
int platform_init()
{
int i;
@ -63,14 +62,14 @@ int platform_init()
PIO_Configure(platform_uart_pins[ 0 ], PIO_LISTSIZE(platform_uart_pins[ 0 ]));
// Configure the USART in the desired mode @115200 bauds
USART_Configure(AT91C_BASE_US0, mode, 115200, BOARD_MCK);
USART_Configure(AT91C_BASE_US0, mode, CON_UART_SPEED, BOARD_MCK);
// Enable receiver & transmitter
USART_SetTransmitterEnabled(AT91C_BASE_US0, 1);
USART_SetReceiverEnabled(AT91C_BASE_US0, 1);
// Configure the timers
AT91C_BASE_TCB->TCB_BMR = 7;
AT91C_BASE_TCB->TCB_BMR = 0x15;
for( i = 0; i < 3; i ++ )
TC_Configure( ( AT91S_TC* )timer_base[ i ], AT91C_TC_CLKS_TIMER_DIV5_CLOCK | AT91C_TC_WAVE );
@ -86,9 +85,18 @@ int platform_init()
PWMC_EnableChannelIt( i );
}
// Set the send/recv functions
std_set_send_func( uart_send );
std_set_get_func( uart_recv );
cmn_platform_init();
#if VTMR_NUM_TIMERS > 0
// Virtual timer initialization
TC_Configure( AT91C_BASE_TC2, AT91C_TC_CLKS_TIMER_DIV5_CLOCK | AT91C_TC_WAVE | AT91C_TC_WAVESEL_UP_AUTO );
AT91C_BASE_TC2->TC_RC = ( BOARD_MCK / 1024 ) / VTMR_FREQ_HZ;
AIC_DisableIT( AT91C_ID_TC2 );
AIC_ConfigureIT( AT91C_ID_TC2, 0, ISR_Tc2 );
AT91C_BASE_TC2->TC_IER = AT91C_TC_CPCS;
AIC_EnableIT( AT91C_ID_TC2 );
TC_Start( AT91C_BASE_TC2 );
#endif
return PLATFORM_OK;
}
@ -102,24 +110,6 @@ static Pin pio_port_desc[] =
{ 0, AT91C_BASE_PIOB, AT91C_ID_PIOB, PIO_INPUT, PIO_DEFAULT }
};
int platform_pio_has_port( unsigned port )
{
return port <= 1;
}
const char* platform_pio_get_prefix( unsigned port )
{
static char c[ 3 ];
sprintf( c, "P%c", ( char )( port + 'A' ) );
return c;
}
int platform_pio_has_pin( unsigned port, unsigned pin )
{
return port <= 1 && pin <= 30;
}
pio_type platform_pio_op( unsigned port, pio_type pinmask, int op )
{
Pin* pin;
@ -178,12 +168,6 @@ pio_type platform_pio_op( unsigned port, pio_type pinmask, int op )
// ****************************************************************************
// UART functions
// The platform UART functions
int platform_uart_exists( unsigned id )
{
return id <= 1;
}
u32 platform_uart_setup( unsigned id, u32 baud, int databits, int parity, int stopbits )
{
unsigned int mode;
@ -240,11 +224,9 @@ void platform_uart_send( unsigned id, u8 data )
USART_Write( base, data, 0 );
}
int platform_uart_recv( unsigned id, unsigned timer_id, int timeout )
int platform_s_uart_recv( unsigned id, unsigned timer_id, int timeout )
{
AT91S_USART* base = id == 0 ? AT91C_BASE_US0 : AT91C_BASE_US1;
timer_data_type tmr_start, tmr_crt;
int res;
if( timeout == 0 )
{
@ -254,30 +236,7 @@ int platform_uart_recv( unsigned id, unsigned timer_id, int timeout )
else
return -1;
}
else if( timeout == PLATFORM_UART_INFINITE_TIMEOUT )
{
// Wait for data
return USART_Read( base, 0 );
}
else
{
// Receive char with the specified timeout
tmr_start = platform_timer_op( timer_id, PLATFORM_TIMER_OP_START,0 );
while( 1 )
{
if( USART_IsDataAvailable( base ) )
{
res = USART_Read( base, 0 );
break;
}
else
res = -1;
tmr_crt = platform_timer_op( timer_id, PLATFORM_TIMER_OP_READ, 0 );
if( platform_timer_get_diff_us( timer_id, tmr_crt, tmr_start ) >= timeout )
break;
}
return res;
}
return USART_Read( base, 0 );
}
// ****************************************************************************
@ -308,12 +267,7 @@ static u32 platform_timer_set_clock( unsigned id, u32 clock )
return BOARD_MCK / clkdivs[ mini ];
}
int platform_timer_exists( unsigned id )
{
return id < 3;
}
void platform_timer_delay( unsigned id, u32 delay_us )
void platform_s_timer_delay( unsigned id, u32 delay_us )
{
AT91S_TC* base = ( AT91S_TC* )timer_base[ id ];
u32 freq;
@ -329,7 +283,7 @@ void platform_timer_delay( unsigned id, u32 delay_us )
while( base->TC_CV < final );
}
u32 platform_timer_op( unsigned id, int op, u32 data )
u32 platform_s_timer_op( unsigned id, int op, u32 data )
{
u32 res = 0;
AT91S_TC* base = ( AT91S_TC* )timer_base[ id ];
@ -366,29 +320,12 @@ u32 platform_timer_op( unsigned id, int op, u32 data )
return res;
}
u32 platform_timer_get_diff_us( unsigned id, timer_data_type end, timer_data_type start )
{
timer_data_type temp;
u32 freq;
freq = platform_timer_get_clock( id );
if( start < end )
{
temp = end;
end = start;
start = temp;
}
return ( ( u64 )( start - end ) * 1000000 ) / freq;
}
// ****************************************************************************
// PWMs
// PWM0, PWM1 -> they can modify CLKA and are statically assigned to CLKA
// PWM2, PWM3 -> they can modify CLKB and are statically assigned to CLKB
#define PLATFORM_NUM_PWMS 4
// PWM pins
static const Pin pwm_pins[] = { PIN_PWMC_PWM0, PIN_PWMC_PWM1, PIN_PWMC_PWM2, PIN_PWMC_PWM3 };
@ -422,11 +359,6 @@ static u32 platform_pwm_set_clock( unsigned id, u32 clock )
return platform_pwm_get_clock( id );
}
int platform_pwm_exists( unsigned id )
{
return id < PLATFORM_NUM_PWMS;
}
u32 platform_pwm_setup( unsigned id, u32 frequency, unsigned duty )
{
u32 pwmclk = platform_pwm_get_clock( id );
@ -471,32 +403,3 @@ u32 platform_pwm_op( unsigned id, int op, u32 data )
return res;
}
// ****************************************************************************
// CPU functions
u32 platform_cpu_get_frequency()
{
return BOARD_MCK;
}
// ****************************************************************************
// Allocator support
extern char end[];
void* platform_get_first_free_ram( unsigned id )
{
return id > 0 ? NULL : ( void* )end;
}
#define SRAM_ORIGIN 0x200000
#ifdef at91sam7x256
#define SRAM_SIZE 0x10000
#else
#define SRAM_SIZE 0x20000
#endif
void* platform_get_last_free_ram( unsigned id )
{
return id > 0 ? NULL : ( void* )( SRAM_ORIGIN + SRAM_SIZE - STACK_SIZE_TOTAL - 1 );
}

View File

@ -4,6 +4,8 @@
#define __PLATFORM_CONF_H__
#include "auxmods.h"
#include "board.h"
#include "stacks.h"
// *****************************************************************************
// Define here what components you want for this platform
@ -17,9 +19,9 @@
// *****************************************************************************
// UART/Timer IDs configuration data (used in main.c)
#define XMODEM_UART_ID 0
#define CON_UART_ID 0
#define CON_UART_SPEED 115200
#define XMODEM_TIMER_ID 0
#define TERM_UART_ID 0
#define TERM_TIMER_ID 0
#define TERM_LINES 25
#define TERM_COLS 80
@ -39,4 +41,44 @@
{ AUXLIB_BIT, luaopen_bit },\
{ LUA_MATHLIBNAME, luaopen_math }
// *****************************************************************************
// Configuration data
// Virtual timers (0 if not used)
#define VTMR_NUM_TIMERS 4
#define VTMR_FREQ_HZ 4
// Number of resources (0 if not available/not implemented)
#define NUM_PIO 2
#define NUM_SPI 0
#define NUM_UART 2
#if VTMR_NUM_TIMERS > 0
#define NUM_TIMER 3
#else
#define NUM_TIMER 2
#endif
#define NUM_PWM 4
// CPU frequency (needed by the CPU module, 0 if not used)
#define CPU_FREQUENCY BOARD_MCK
// PIO prefix ('0' for P0, P1, ... or 'A' for PA, PB, ...)
#define PIO_PREFIX 'A'
// 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 0x200000
#ifdef at91sam7x256
#define SRAM_SIZE 0x10000
#else
#define SRAM_SIZE 0x20000
#endif
#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

@ -4,7 +4,7 @@
#define __STACKS_H__
#define STACK_SIZE_USR 256
#define STACK_SIZE_IRQ 32
#define STACK_SIZE_IRQ 64
#define STACK_SIZE_TOTAL ( STACK_SIZE_USR + STACK_SIZE_IRQ )
#endif

View File

@ -2,7 +2,7 @@
specific_files = "crt0.s trampoline.s platform.c exception.s intc.c pm.c flashc.c pm_conf_clocks.c usart.c gpio.c tc.c"
ldscript = "at32uc3a0512.ld"
cdefs = cdefs + " -DAVR32"
cdefs = cdefs + " -DFORAVR32"
# Prepend with path
specific_files = " ".join( [ "src/platform/%s/%s" % ( platform, f ) for f in specific_files.split() ] )

View File

@ -12,6 +12,7 @@
#include <stdio.h>
#include "utils.h"
#include "platform_conf.h"
#include "common.h"
// Platform-specific includes
#include <avr32/io.h>
@ -22,26 +23,26 @@
#include "usart.h"
#include "gpio.h"
#include "tc.h"
// *****************************************************************************
// std functions
static void uart_send( int fd, char c )
{
fd = fd;
platform_uart_send( CON_UART_ID, c );
}
static int uart_recv()
{
return platform_uart_recv( CON_UART_ID, 0, PLATFORM_UART_INFINITE_TIMEOUT );
}
#include "intc.h"
// ****************************************************************************
// Platform initialization
extern int pm_configure_clocks( pm_freq_param_t *param );
#if VTMR_NUM_TIMERS > 0
#define VTMR_CH (2)
__attribute__((__interrupt__)) static void tmr_int_handler()
{
volatile avr32_tc_t *tc = &AVR32_TC;
tc_read_sr( tc, VTMR_CH );
cmn_virtual_timer_cb();
}
#endif
int platform_init()
{
pm_freq_param_t pm_freq_param =
@ -80,6 +81,7 @@ int platform_init()
unsigned i;
Disable_global_interrupt();
INTC_init_interrupts();
// Setup clocks
if( PM_FREQ_STATUS_FAIL == pm_configure_clocks( &pm_freq_param ) )
@ -99,9 +101,30 @@ int platform_init()
tc_init_waveform( tc, &tmropt );
}
// Set the send/recv functions
std_set_send_func( uart_send );
std_set_get_func( uart_recv );
// Setup timer interrupt for the virtual timers if needed
#if VTMR_NUM_TIMERS > 0
INTC_register_interrupt( &tmr_int_handler, AVR32_TC_IRQ2, AVR32_INTC_INT0 );
tmropt.channel = VTMR_CH;
tmropt.wavsel = TC_WAVEFORM_SEL_UP_MODE_RC_TRIGGER;
tc_init_waveform( tc, &tmropt );
tc_interrupt_t tmrint =
{
0, // External trigger interrupt.
0, // RB load interrupt.
0, // RA load interrupt.
1, // RC compare interrupt.
0, // RB compare interrupt.
0, // RA compare interrupt.
0, // Load overrun interrupt.
0 // Counter overflow interrupt.
};
tc_write_rc( tc, VTMR_CH, 32768 / VTMR_FREQ_HZ );
tc_configure_interrupts( tc, VTMR_CH, &tmrint );
Enable_global_interrupt();
tc_start( tc, VTMR_CH );
#endif
cmn_platform_init();
// All done
return PLATFORM_OK;
@ -132,7 +155,6 @@ on the hardware ports (PA, PB, PC).
*/
// Port data
#define NUM_PORTS 5
#define PA 0
#define PB 1
#define PC 2
@ -147,26 +169,6 @@ on the hardware ports (PA, PB, PC).
#define GPIO AVR32_GPIO
static const u8 pio_port_pins[ NUM_PORTS ] = { 31, 32, 6, 32, 8 };
int platform_pio_has_port( unsigned port )
{
return port < NUM_PORTS;
}
const char* platform_pio_get_prefix( unsigned port )
{
static char c[ 3 ];
sprintf( c, "P%c", ( char )( port + 'A' ) );
return c;
}
int platform_pio_has_pin( unsigned port, unsigned pin )
{
return port < NUM_PORTS && pin < pio_port_pins[ port ];
}
// Helper function: for a given port, return the address of a specific register (value, direction, pullup ...)
static volatile unsigned long* platform_pio_get_port_reg_addr( unsigned port, int regtype )
{
@ -311,9 +313,7 @@ pio_type platform_pio_op( unsigned port, pio_type pinmask, int op )
// ****************************************************************************
// UART functions
#define NUM_UARTS 4
static const u32 uart_base_addr[ NUM_UARTS ] = { AVR32_USART0_ADDRESS, AVR32_USART1_ADDRESS, AVR32_USART2_ADDRESS, AVR32_USART3_ADDRESS };
static const u32 uart_base_addr[ NUM_UART ] = { AVR32_USART0_ADDRESS, AVR32_USART1_ADDRESS, AVR32_USART2_ADDRESS, AVR32_USART3_ADDRESS };
static const gpio_map_t uart_pins =
{
// UART 0
@ -330,12 +330,6 @@ static const gpio_map_t uart_pins =
{ AVR32_USART3_TXD_0_0_PIN, AVR32_USART3_TXD_0_0_FUNCTION }
};
// The platform UART functions
int platform_uart_exists( unsigned id )
{
return id < NUM_UARTS;
}
u32 platform_uart_setup( unsigned id, u32 baud, int databits, int parity, int stopbits )
{
volatile avr32_usart_t *pusart = ( volatile avr32_usart_t* )uart_base_addr[ id ];
@ -376,7 +370,7 @@ void platform_uart_send( unsigned id, u8 data )
usart_putchar( pusart, data );
}
int platform_uart_recv( unsigned id, unsigned timer_id, int timeout )
int platform_s_uart_recv( unsigned id, unsigned timer_id, int timeout )
{
volatile avr32_usart_t *pusart = ( volatile avr32_usart_t* )uart_base_addr[ id ];
int temp;
@ -388,20 +382,13 @@ int platform_uart_recv( unsigned id, unsigned timer_id, int timeout )
else
return temp;
}
else if( timeout == PLATFORM_UART_INFINITE_TIMEOUT )
{
return usart_getchar( pusart );
}
else
{
return -1;
}
return usart_getchar( pusart );
}
// ****************************************************************************
// Timer functions
#define NUM_TIMERS 3
static const u16 clkdivs[] = { 0xFFFF, 2, 8, 32, 128 };
// Helper: get timer clock
@ -427,12 +414,7 @@ static u32 platform_timer_set_clock( unsigned id, u32 clock )
return mini == 0 ? 32768 : REQ_PBA_FREQ / clkdivs[ mini ];
}
int platform_timer_exists( unsigned id )
{
return id < NUM_TIMERS;
}
void platform_timer_delay( unsigned id, u32 delay_us )
void platform_s_timer_delay( unsigned id, u32 delay_us )
{
volatile avr32_tc_t *tc = &AVR32_TC;
u32 freq;
@ -450,7 +432,7 @@ void platform_timer_delay( unsigned id, u32 delay_us )
while( ( tc_read_tc( tc, id ) < final ) && !sr->covfs );
}
u32 platform_timer_op( unsigned id, int op, u32 data )
u32 platform_s_timer_op( unsigned id, int op, u32 data )
{
u32 res = 0;
volatile int i;
@ -487,42 +469,16 @@ u32 platform_timer_op( unsigned id, int op, u32 data )
return res;
}
u32 platform_timer_get_diff_us( unsigned id, timer_data_type end, timer_data_type start )
{
timer_data_type temp;
u32 freq;
freq = platform_timer_get_clock( id );
if( start < end )
{
temp = end;
end = start;
start = temp;
}
return ( ( u64 )( start - end ) * 1000000 ) / freq;
}
// ****************************************************************************
// CPU functions
u32 platform_cpu_get_frequency()
void platform_cpu_enable_interrupts()
{
return REQ_CPU_FREQ;
Enable_global_interrupt();
}
// ****************************************************************************
// Allocator support
extern char end[];
void* platform_get_first_free_ram( unsigned id )
void platform_cpu_disable_interrupts()
{
return id > 0 ? NULL : ( void* )end;
Disable_global_interrupt();
}
#define SRAM_ORIGIN 0x0
#define SRAM_SIZE 0x10000
void* platform_get_last_free_ram( unsigned id )
{
return id > 0 ? NULL : ( void* )( SRAM_ORIGIN + SRAM_SIZE - STACK_SIZE_TOTAL - 1 );
}

View File

@ -4,6 +4,8 @@
#define __PLATFORM_CONF_H__
#include "auxmods.h"
#include "board.h"
#include "stacks.h"
// *****************************************************************************
// Define here what components you want for this platform
@ -12,24 +14,18 @@
#define BUILD_SHELL
#define BUILD_ROMFS
#define BUILD_TERM
//#define BUILD_UIP
//#define BUILD_DNS
#define BUILD_CON_GENERIC
// *****************************************************************************
// UART/Timer IDs configuration data (used in main.c)
// [TODO] added CON_UART_xxxx below, add it to all backends, and probably remove
// XMODEM_UART_ID (although this isn't strictly required)
#define CON_UART_ID 0
#define CON_UART_SPEED 38400
#define XMODEM_UART_ID 0
#define XMODEM_TIMER_ID 0
#define TERM_UART_ID 0
#define TERM_TIMER_ID 0
#define TERM_LINES 25
#define TERM_COLS 80
#define TERM_TIMEOUT 100000
#define CON_UART_ID 0
#define CON_UART_SPEED 38400
#define XMODEM_TIMER_ID 0
#define TERM_TIMER_ID 0
#define TERM_LINES 25
#define TERM_COLS 80
#define TERM_TIMEOUT 100000
// *****************************************************************************
// Auxiliary libraries that will be compiled for this platform
@ -42,31 +38,42 @@
{ AUXLIB_TERM, luaopen_term },\
{ AUXLIB_PACK, luaopen_pack },\
{ AUXLIB_BIT, luaopen_bit },\
{ AUXLIB_CPU, luaopen_cpu },\
{ LUA_MATHLIBNAME, luaopen_math }
// *****************************************************************************
// Configuration data
// Static TCP/IP configuration
#define ELUA_CONF_IPADDR0 192
#define ELUA_CONF_IPADDR1 168
#define ELUA_CONF_IPADDR2 1
#define ELUA_CONF_IPADDR3 218
// Virtual timers (0 if not used)
#define VTMR_NUM_TIMERS 4
#define VTMR_FREQ_HZ 4
#define ELUA_CONF_NETMASK0 255
#define ELUA_CONF_NETMASK1 255
#define ELUA_CONF_NETMASK2 255
#define ELUA_CONF_NETMASK3 0
// Number of resources (0 if not available/not implemented)
#define NUM_PIO 5
#define NUM_SPI 0
#define NUM_UART 4
#if VTMR_NUM_TIMERS > 0
#define NUM_TIMER 2
#else
#define NUM_TIMER 3
#endif
#define NUM_PWM 0
#define ELUA_CONF_DEFGW0 192
#define ELUA_CONF_DEFGW1 168
#define ELUA_CONF_DEFGW2 1
#define ELUA_CONF_DEFGW3 1
// CPU frequency (needed by the CPU module, 0 if not used)
#define CPU_FREQUENCY REQ_CPU_FREQ
#define ELUA_CONF_DNS0 192
#define ELUA_CONF_DNS1 168
#define ELUA_CONF_DNS2 1
#define ELUA_CONF_DNS3 1
// PIO prefix ('0' for P0, P1, ... or 'A' for PA, PB, ...)
#define PIO_PREFIX 'A'
// 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_PIN_ARRAY { 31, 32, 6, 32, 8 }
// Allocator data: define your free memory zones here in two arrays
// (start address and end address)
#define MEM_START_ADDRESS { ( void* )end }
#define MEM_END_ADDRESS { ( void* )( 0x10000 - STACK_SIZE_TOTAL - 1 ) }
// *****************************************************************************
// CPU constants that should be exposed to the eLua "cpu" module

View File

@ -17,6 +17,6 @@ tools[ 'i386' ][ 'ascom' ] = "nasm -felf $SOURCE"
def progfunc_i386( target, source, env ):
outname = output + ".elf"
os.system( "i686-elf-size %s" % outname )
print "Visit http://elua.berlios.de for instructions on how to use your eLua ELF file"
print "Visit http://www.eluaproject.net for instructions on how to use your eLua ELF file"
tools[ 'i386' ][ 'progfunc' ] = progfunc_i386

View File

@ -83,11 +83,6 @@ int platform_init()
// ****************************************************************************
// "Dummy" UART functions
int platform_uart_exists( unsigned id )
{
return 0;
}
u32 platform_uart_setup( unsigned id, u32 baud, int databits, int parity, int stopbits )
{
return 0;
@ -97,22 +92,27 @@ void platform_uart_send( unsigned id, u8 data )
{
}
int platform_uart_recv( unsigned id, unsigned timer_id, int timeout )
int platform_s_uart_recv( unsigned id, unsigned timer_id, int timeout )
{
return -1;
}
// ****************************************************************************
// "Dummy" timer functions
void platform_s_timer_delay( unsigned id, u32 delay_us )
{
}
u32 platform_s_timer_op( unsigned id, int op, u32 data )
{
return 0;
}
// ****************************************************************************
// Allocator support
extern char end[];
void* platform_get_first_free_ram( unsigned id )
u32 platform_get_lastmem()
{
return id > 0 ? NULL : ( void* )end;
}
#define MY_STACK_SIZE ( 16 * 1024 )
void* platform_get_last_free_ram( unsigned id )
{
return id > 0 ? NULL : ( void* )( lastmem - MY_STACK_SIZE - 1 );
return lastmem;
}

View File

@ -4,6 +4,7 @@
#define __PLATFORM_CONF_H__
#include "auxmods.h"
#include "type.h"
// *****************************************************************************
// Define here what components you want for this platform
@ -19,4 +20,36 @@
{ AUXLIB_PD, luaopen_pd },\
{ LUA_MATHLIBNAME, luaopen_math }
#define CON_UART_ID 0
// *****************************************************************************
// Configuration data
// Virtual timers (0 if not used)
#define VTMR_NUM_TIMERS 0
// Number of resources (0 if not available/not implemented)
#define NUM_PIO 0
#define NUM_SPI 0
#define NUM_UART 0
#define NUM_TIMER 0
#define NUM_PWM 0
// CPU frequency (needed by the CPU module, 0 if not used)
#define CPU_FREQUENCY 0
// PIO prefix ('0' for P0, P1, ... or 'A' for PA, PB, ...)
#define PIO_PREFIX 'A'
// 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 0
// Allocator data: define your free memory zones here in two arrays
// (start address and end address)
u32 platform_get_lastmem();
#define MEM_START_ADDRESS { ( void* )end }
#define MEM_END_ADDRESS { ( void* )( platform_get_lastmem() - 16384 - 1 ) }
#endif // #ifndef __PLATFORM_CONF_H__

View File

@ -7,6 +7,11 @@ ldscript = "lm3s.ld"
specific_files = " ".join( [ "src/platform/%s/%s" % ( platform, f ) for f in specific_files.split() ] )
ldscript = "src/platform/%s/%s" % ( platform, ldscript )
if cputype == 'LM3S8962':
cdefs = cdefs + " -DFORLM3S8962"
else:
cdefs = cdefs + " -DFORLM3S6965"
cdefs = cdefs + " -Dgcc"
# Toolset data

View File

@ -13,6 +13,7 @@
#include "elua_uip.h"
#include "uip-conf.h"
#include "platform_conf.h"
#include "common.h"
// Platform specific includes
#include "hw_ints.h"
@ -38,22 +39,11 @@
#include "rit128x96x4.h"
// UIP sys tick data
// NOTE: when using virtual timers, SYSTICKHZ and VTMR_FREQ_HZ should have the
// same value, as they're served by the same timer (the systick)
#define SYSTICKHZ 4
#define SYSTICKMS (1000 / SYSTICKHZ)
// *****************************************************************************
// std function
static void uart_send( int fd, char c )
{
fd = fd;
UARTCharPut( UART0_BASE, c );
}
static int uart_recv()
{
return UARTCharGet( UART0_BASE );
}
// ****************************************************************************
// Platform initialization
@ -88,9 +78,18 @@ int platform_init()
// Setup ethernet (TCP/IP)
eth_init();
// Set the send/recv functions
std_set_send_func( uart_send );
std_set_get_func( uart_recv );
// Common platform initialization code
cmn_platform_init();
// Virtual timers
// If the ethernet controller is used the timer is already initialized, so skip this sequence
#if VTMR_NUM_TIMERS > 0 && !defined( BUILD_UIP )
// Configure SysTick for a periodic interrupt.
SysTickPeriodSet( SysCtlClockGet() / SYSTICKHZ );
SysTickEnable();
SysTickIntEnable();
IntMasterEnable();
#endif
// All done
return PLATFORM_OK;
@ -104,36 +103,13 @@ static const u32 pio_base[] = { GPIO_PORTA_BASE, GPIO_PORTB_BASE, GPIO_PORTC_BAS
GPIO_PORTE_BASE, GPIO_PORTF_BASE, GPIO_PORTG_BASE, GPIO_PORTH_BASE };
static const u32 pio_sysctl[] = { SYSCTL_PERIPH_GPIOA, SYSCTL_PERIPH_GPIOB, SYSCTL_PERIPH_GPIOC, SYSCTL_PERIPH_GPIOD,
SYSCTL_PERIPH_GPIOE, SYSCTL_PERIPH_GPIOF, SYSCTL_PERIPH_GPIOG, SYSCTL_PERIPH_GPIOH };
static const u8 pio_port_pins[] = { 8, 8, 8, 8, 4, 4, 2, 0 };
#define PIOS_COUNT 42
#define PIOS_PORT_COUNT 7
static void pios_init()
{
unsigned i;
for( i = 0; i < PIOS_PORT_COUNT; i ++ )
{
for( i = 0; i < NUM_PIO; i ++ )
SysCtlPeripheralEnable(pio_sysctl[ i ]);
}
}
int platform_pio_has_port( unsigned port )
{
return port < PIOS_PORT_COUNT;
}
const char* platform_pio_get_prefix( unsigned port )
{
static char c[ 3 ];
sprintf( c, "P%c", ( char )( port + 'A' ) );
return c;
}
int platform_pio_has_pin( unsigned port, unsigned pin )
{
return pin < pio_port_pins[ port ];
}
pio_type platform_pio_op( unsigned port, pio_type pinmask, int op )
@ -204,21 +180,13 @@ static const u8 spi_gpio_pins[] = { GPIO_PIN_2 | GPIO_PIN_3 | GPIO_PIN_4 | GPIO_
GPIO_PIN_0 | GPIO_PIN_1 | GPIO_PIN_2 | GPIO_PIN_3 };
// SSIxClk SSIxFss SSIxRx SSIxTx
static const u8 spi_gpio_clk_pin[] = { GPIO_PIN_2, GPIO_PIN_0 };
#define SPIS_COUNT 1
static void spis_init()
{
unsigned i;
for( i = 0; i < SPIS_COUNT; i ++ )
{
for( i = 0; i < NUM_SPI; i ++ )
SysCtlPeripheralEnable(spi_sysctl[ i ]);
}
}
int platform_spi_exists( unsigned id )
{
return id < SPIS_COUNT;
}
u32 platform_spi_setup( unsigned id, int mode, u32 clock, unsigned cpol, unsigned cpha, unsigned databits )
@ -260,12 +228,6 @@ void platform_spi_select( unsigned id, int is_select )
// UART
// Different configurations for LM3S8962 (2 UARTs) and LM3S6965 (3 UARTs)
#if ELUA_CPU == LM3S8962
#define UARTS_COUNT 2
#elif ELUA_CPU == LM3S6965
#define UARTS_COUNT 3
#endif
// All possible LM3S uarts defs
static const u32 uart_base[] = { UART0_BASE, UART1_BASE, UART2_BASE };
static const u32 uart_sysctl[] = { SYSCTL_PERIPH_UART0, SYSCTL_PERIPH_UART1, SYSCTL_PERIPH_UART2 };
@ -276,24 +238,17 @@ static void uarts_init()
{
unsigned i;
for( i = 0; i < UARTS_COUNT; i ++ )
{
for( i = 0; i < NUM_UART; i ++ )
SysCtlPeripheralEnable(uart_sysctl[ i ]);
}
// Special case for UART 0
// Configure the UART for 115,200, 8-N-1 operation.
GPIOPinTypeUART(GPIO_PORTA_BASE, GPIO_PIN_0 | GPIO_PIN_1);
UARTConfigSetExpClk(UART0_BASE, SysCtlClockGet(), 115200,
UARTConfigSetExpClk(UART0_BASE, SysCtlClockGet(), CON_UART_SPEED,
(UART_CONFIG_WLEN_8 | UART_CONFIG_STOP_ONE |
UART_CONFIG_PAR_NONE));
}
int platform_uart_exists( unsigned id )
{
return id < UARTS_COUNT;
}
u32 platform_uart_setup( unsigned id, u32 baud, int databits, int parity, int stopbits )
{
u32 config;
@ -331,35 +286,13 @@ void platform_uart_send( unsigned id, u8 data )
UARTCharPut( uart_base[ id ], data );
}
int platform_uart_recv( unsigned id, unsigned timer_id, int timeout )
int platform_s_uart_recv( unsigned id, unsigned timer_id, int timeout )
{
u32 base = uart_base[ id ];
timer_data_type tmr_start, tmr_crt;
int res;
if( timeout == 0 )
{
return UARTCharGetNonBlocking( base );
}
else if( timeout == PLATFORM_UART_INFINITE_TIMEOUT )
{
// Receive char blocking
return UARTCharGet( base );
}
else
{
// Receive char with the specified timeout
tmr_start = platform_timer_op( timer_id, PLATFORM_TIMER_OP_START, 0 );
while( 1 )
{
if( ( res = UARTCharGetNonBlocking( base ) ) >= 0 )
break;
tmr_crt = platform_timer_op( timer_id, PLATFORM_TIMER_OP_READ, 0 );
if( platform_timer_get_diff_us( timer_id, tmr_crt, tmr_start ) >= timeout )
break;
}
return res;
}
return UARTCharGet( base );
}
// ****************************************************************************
@ -369,26 +302,20 @@ int platform_uart_recv( unsigned id, unsigned timer_id, int timeout )
// All possible LM3S timers defs
static const u32 timer_base[] = { TIMER0_BASE, TIMER1_BASE, TIMER2_BASE, TIMER3_BASE };
static const u32 timer_sysctl[] = { SYSCTL_PERIPH_TIMER0, SYSCTL_PERIPH_TIMER1, SYSCTL_PERIPH_TIMER2, SYSCTL_PERIPH_TIMER3 };
#define TIMERS_COUNT 4
static void timers_init()
{
unsigned i;
for( i = 0; i < TIMERS_COUNT; i ++ )
for( i = 0; i < NUM_TIMER; i ++ )
{
SysCtlPeripheralEnable(timer_sysctl[ i ]);
SysCtlPeripheralEnable(timer_sysctl[ i ]);
TimerConfigure(timer_base[ i ], TIMER_CFG_32_BIT_PER);
TimerEnable(timer_base[ i ], TIMER_A);
}
}
int platform_timer_exists( unsigned id )
{
return id < TIMERS_COUNT;
}
void platform_timer_delay( unsigned id, u32 delay_us )
void platform_s_timer_delay( unsigned id, u32 delay_us )
{
timer_data_type final;
u32 base = timer_base[ id ];
@ -398,7 +325,7 @@ void platform_timer_delay( unsigned id, u32 delay_us )
while( TimerValueGet( base, TIMER_A ) > final );
}
u32 platform_timer_op( unsigned id, int op, u32 data )
u32 platform_s_timer_op( unsigned id, int op, u32 data )
{
u32 res = 0;
u32 base = timer_base[ id ];
@ -432,26 +359,10 @@ u32 platform_timer_op( unsigned id, int op, u32 data )
return res;
}
u32 platform_timer_get_diff_us( unsigned id, timer_data_type end, timer_data_type start )
{
timer_data_type temp;
id = id;
if( start < end )
{
temp = end;
end = start;
start = temp;
}
return ( ( u64 )( start - end ) * 1000000 ) / SysCtlClockGet();
}
// ****************************************************************************
// PWMs
// Same on LM3S8962 and LM3S6965
#define PLATFORM_NUM_PWMS 6
// SYSCTL div data and actual div factors
const static u32 pwm_div_ctl[] = { SYSCTL_PWMDIV_1, SYSCTL_PWMDIV_2, SYSCTL_PWMDIV_4, SYSCTL_PWMDIV_8, SYSCTL_PWMDIV_16, SYSCTL_PWMDIV_32, SYSCTL_PWMDIV_64 };
const static u8 pwm_div_data[] = { 1, 2, 4, 8, 16, 32, 64 };
@ -496,11 +407,6 @@ static u32 platform_pwm_set_clock( u32 clock )
return sysclk / pwm_div_data[ min_i ];
}
int platform_pwm_exists( unsigned id )
{
return id < PLATFORM_NUM_PWMS;
}
u32 platform_pwm_setup( unsigned id, u32 frequency, unsigned duty )
{
u32 pwmclk = platform_pwm_get_clock();
@ -560,11 +466,6 @@ void platform_cpu_disable_interrupts()
IntMasterDisable();
}
u32 platform_cpu_get_frequency()
{
return SysCtlClockGet();
}
// ****************************************************************************
// OLED Display specific functions
//
@ -720,6 +621,9 @@ u32 platform_eth_get_elapsed_time()
void SysTickIntHandler()
{
// Handle virtual timers
cmn_virtual_timer_cb();
// Indicate that a SysTick interrupt has occurred.
eth_timer_fired = 1;
@ -744,26 +648,10 @@ void EthernetIntHandler()
void SysTickIntHandler()
{
cmn_virtual_timer_cb();
}
void EthernetIntHandler()
{
}
#endif // #ifdef ELUA_UIP
// ****************************************************************************
// Allocator support
extern char end[];
void* platform_get_first_free_ram( unsigned id )
{
return id > 0 ? NULL : ( void* )end;
}
#define STACK_SIZE 256
#define SRAM_SIZE ( 64 * 1024 )
void* platform_get_last_free_ram( unsigned id )
{
return id > 0 ? NULL : ( void* )( SRAM_BASE + SRAM_SIZE - STACK_SIZE - 1 );
}

View File

@ -4,6 +4,10 @@
#define __PLATFORM_CONF_H__
#include "auxmods.h"
#include "hw_memmap.h"
#include "hw_types.h"
#include "stacks.h"
#include "sysctl.h"
// *****************************************************************************
// Define here what components you want for this platform
@ -21,9 +25,9 @@
// *****************************************************************************
// UART/Timer IDs configuration data (used in main.c)
#define XMODEM_UART_ID 0
#define CON_UART_ID 0
#define CON_UART_SPEED 115200
#define XMODEM_TIMER_ID 0
#define TERM_UART_ID 0
#define TERM_TIMER_ID 0
#define TERM_LINES 25
#define TERM_COLS 80
@ -51,25 +55,59 @@
// Configuration data
// Static TCP/IP configuration
#define ELUA_CONF_IPADDR0 192
#define ELUA_CONF_IPADDR1 168
#define ELUA_CONF_IPADDR2 1
#define ELUA_CONF_IPADDR3 218
#define ELUA_CONF_IPADDR0 192
#define ELUA_CONF_IPADDR1 168
#define ELUA_CONF_IPADDR2 1
#define ELUA_CONF_IPADDR3 218
#define ELUA_CONF_NETMASK0 255
#define ELUA_CONF_NETMASK1 255
#define ELUA_CONF_NETMASK2 255
#define ELUA_CONF_NETMASK3 0
#define ELUA_CONF_NETMASK0 255
#define ELUA_CONF_NETMASK1 255
#define ELUA_CONF_NETMASK2 255
#define ELUA_CONF_NETMASK3 0
#define ELUA_CONF_DEFGW0 192
#define ELUA_CONF_DEFGW1 168
#define ELUA_CONF_DEFGW2 1
#define ELUA_CONF_DEFGW3 1
#define ELUA_CONF_DEFGW0 192
#define ELUA_CONF_DEFGW1 168
#define ELUA_CONF_DEFGW2 1
#define ELUA_CONF_DEFGW3 1
#define ELUA_CONF_DNS0 192
#define ELUA_CONF_DNS1 168
#define ELUA_CONF_DNS2 1
#define ELUA_CONF_DNS3 1
#define ELUA_CONF_DNS0 192
#define ELUA_CONF_DNS1 168
#define ELUA_CONF_DNS2 1
#define ELUA_CONF_DNS3 1
// *****************************************************************************
// Configuration data
// Virtual timers (0 if not used)
#define VTMR_NUM_TIMERS 4
#define VTMR_FREQ_HZ 4
// Number of resources (0 if not available/not implemented)
#define NUM_PIO 7
#define NUM_SPI 1
#ifdef FORLM3S8962
#define NUM_UART 2
#else
#define NUM_UART 3
#endif
#define NUM_TIMER 4
#define NUM_PWM 6
// CPU frequency (needed by the CPU module, 0 if not used)
#define CPU_FREQUENCY SysCtlClockGet()
// PIO prefix ('0' for P0, P1, ... or 'A' for PA, PB, ...)
#define PIO_PREFIX 'A'
// 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_PIN_ARRAY { 8, 8, 8, 8, 4, 4, 2 }
// Allocator data: define your free memory zones here in two arrays
// (start address and end address)
#define MEM_START_ADDRESS { ( void* )end }
#define MEM_END_ADDRESS { ( void* )( SRAM_BASE + 0x10000 - STACK_SIZE_TOTAL - 1 ) }
// *****************************************************************************
// CPU constants that should be exposed to the eLua "cpu" module

View File

@ -0,0 +1,9 @@
// Stack size definitions
#ifndef __STACKS_H__
#define __STACKS_H__
#define STACK_SIZE 512
#define STACK_SIZE_TOTAL ( STACK_SIZE )
#endif

View File

@ -13,6 +13,7 @@ SECTIONS
{
. = ALIGN(4);
_sfixed = .;
KEEP(*(.vectors))
*(.text .text.*)
*(.rodata .rodata.*)
*(.gnu.linkonce.t.*)

View File

@ -159,10 +159,12 @@
@ Area Definition and Entry Point
@ Startup Code must be linked first at Address at which it expects to run.
.section .text
.arm
.align 4
.global HardReset
.section .vectors, "a"
HardReset:
@ Exception Vectors
@ -196,6 +198,8 @@ IRQ_Handler: B IRQ_Handler
@ ==============================================================================
@ Reset handler
.text
Reset_Handler:
@ Clock Setup ------------------------------------------------------------------

View File

@ -14,19 +14,8 @@
#include "target.h"
#include "uart.h"
#include "utils.h"
// *****************************************************************************
// std functions
static void uart_send( int fd, char c )
{
uart_write( c );
}
static int uart_recv()
{
return uart_read();
}
#include "common.h"
#include "platform_conf.h"
// ****************************************************************************
// Platform initialization
@ -37,7 +26,7 @@ int platform_init()
lpc288x_init();
// Initialize UART
uart_init( 115200, 8, PLATFORM_UART_PARITY_NONE, PLATFORM_UART_STOPBITS_1 );
uart_init( CON_UART_SPEED, 8, PLATFORM_UART_PARITY_NONE, PLATFORM_UART_STOPBITS_1 );
// Initialize timers
T0CTRL = 0;
@ -45,9 +34,7 @@ int platform_init()
INT_REQ5 = ( 1 << 28 ) | ( 1 << 27 ) | ( 1 << 26 ) | ( 1 << 16 ) | 0x1;
INT_REQ6 = ( 1 << 28 ) | ( 1 << 27 ) | ( 1 << 26 ) | ( 1 << 16 ) | 0x1;
// Set the send/recv functions
std_set_send_func( uart_send );
std_set_get_func( uart_recv );
cmn_platform_init();
return PLATFORM_OK;
}
@ -66,26 +53,6 @@ static const vu_ptr pio_m0_regs[] = { &MODE0_0, &MODE0_1, &MODE0_2, &MODE0_3, &M
static const vu_ptr pio_m1_regs[] = { &MODE1_0, &MODE1_1, &MODE1_2, &MODE1_3, &MODE1_4, &MODE1_5, &MODE1_6, &MODE1_7 };
static const vu_ptr pio_pin_regs[] = { &PINS_0, &PINS_1, &PINS_2, &PINS_3, &PINS_4, &PINS_5, &PINS_6, &PINS_7 };
int platform_pio_has_port( unsigned port )
{
return port < 8;
}
const char* platform_pio_get_prefix( unsigned port )
{
static char c[ 3 ];
sprintf( c, "P%d", port );
return c;
}
// Maximum number of pins per port
static const unsigned pins_per_port[] = { 32, 20, 4, 6, 12, 6, 4, 1 };
int platform_pio_has_pin( unsigned port, unsigned pin )
{
return port < 8 && pin < pins_per_port[ port ];
}
pio_type platform_pio_op( unsigned port, pio_type pinmask, int op )
{
pio_type retval = 1;
@ -140,11 +107,6 @@ pio_type platform_pio_op( unsigned port, pio_type pinmask, int op )
// ****************************************************************************
// UART
int platform_uart_exists( unsigned id )
{
return id < 1;
}
u32 platform_uart_setup( unsigned id, u32 baud, int databits, int parity, int stopbits )
{
return uart_init( baud, databits, parity, stopbits );
@ -155,35 +117,14 @@ void platform_uart_send( unsigned id, u8 data )
uart_write( data );
}
int platform_uart_recv( unsigned id, unsigned timer_id, int timeout )
int platform_s_uart_recv( unsigned id, unsigned timer_id, int timeout )
{
timer_data_type tmr_start, tmr_crt;
int res;
if( timeout == 0 )
{
// Return data only if already available
return uart_read_nb();
}
else if( timeout == PLATFORM_UART_INFINITE_TIMEOUT )
{
// Wait for data
return uart_read();
}
else
{
// Receive char with the specified timeout
tmr_start = platform_timer_op( timer_id, PLATFORM_TIMER_OP_START,0 );
while( 1 )
{
if( ( res = uart_read_nb() ) > 0 )
break;
tmr_crt = platform_timer_op( timer_id, PLATFORM_TIMER_OP_READ, 0 );
if( platform_timer_get_diff_us( timer_id, tmr_crt, tmr_start ) >= timeout )
break;
}
return res;
}
return uart_read();
}
// ****************************************************************************
@ -212,12 +153,8 @@ static u32 platform_timer_set_clock( unsigned id, u32 clock )
*tmr_ctrl[ id ] = ( *tmr_ctrl[ id ] & ~0xB ) | ( mini << 2 );
return MAIN_CLOCK / tmr_prescale[ mini ];
}
int platform_timer_exists( unsigned id )
{
return id < 2;
}
void platform_timer_delay( unsigned id, u32 delay_us )
void platform_s_timer_delay( unsigned id, u32 delay_us )
{
u32 freq;
u64 final;
@ -234,7 +171,7 @@ void platform_timer_delay( unsigned id, u32 delay_us )
while( ( INT_PENDING & mask ) == 0 );
}
u32 platform_timer_op( unsigned id, int op, u32 data )
u32 platform_s_timer_op( unsigned id, int op, u32 data )
{
u32 res = 0;
@ -270,50 +207,3 @@ u32 platform_timer_op( unsigned id, int op, u32 data )
return res;
}
u32 platform_timer_get_diff_us( unsigned id, timer_data_type end, timer_data_type start )
{
timer_data_type temp;
u32 freq;
freq = platform_timer_get_clock( id );
if( start < end )
{
temp = end;
end = start;
start = temp;
}
return ( ( u64 )( start - end ) * 1000000 ) / freq;
}
// ****************************************************************************
// CPU functions
u32 platform_cpu_get_frequency()
{
return Fcclk;
}
// ****************************************************************************
// Allocator support
extern char end[];
void* platform_get_first_free_ram( unsigned id )
{
if( id > 1 )
return NULL;
else
return id == 0 ? ( void* )end : ( void* )SDRAM_BASE_ADDR;
}
#define SRAM_ORIGIN 0x00400000
#define SRAM_SIZE 0x10000
void* platform_get_last_free_ram( unsigned id )
{
if( id > 1 )
return NULL;
else
return id == 0 ? ( void* )( SRAM_ORIGIN + SRAM_SIZE - STACK_SIZE_TOTAL - 1 ) :
( void* )( SDRAM_BASE_ADDR + SDRAM_SIZE - 1 );
}

View File

@ -4,6 +4,8 @@
#define __PLATFORM_CONF_H__
#include "auxmods.h"
#include "stacks.h"
#include "target.h"
// *****************************************************************************
// Define here what components you want for this platform
@ -17,14 +19,45 @@
// *****************************************************************************
// UART/Timer IDs configuration data (used in main.c)
#define XMODEM_UART_ID 0
#define CON_UART_ID 0
#define CON_UART_SPEED 115200
#define XMODEM_TIMER_ID 0
#define TERM_UART_ID 0
#define TERM_TIMER_ID 0
#define TERM_LINES 25
#define TERM_COLS 80
#define TERM_TIMEOUT 100000
// *****************************************************************************
// Configuration data
// Virtual timers (0 if not used)
#define VTMR_NUM_TIMERS 0
// Number of resources (0 if not available/not implemented)
#define NUM_PIO 8
#define NUM_SPI 0
#define NUM_UART 1
#define NUM_TIMER 2
#define NUM_PWM 0
// 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_PIN_ARRAY { 32, 20, 4, 6, 12, 6, 4, 1 }
// Allocator data: define your free memory zones here in two arrays
// (start address and end address)
#define SRAM_ORIGIN 0x00400000
#define SRAM_SIZE 0x10000
#define MEM_START_ADDRESS { ( void* )end, ( void* )SDRAM_BASE_ADDR }
#define MEM_END_ADDRESS { ( void* )( SRAM_ORIGIN + SRAM_SIZE - STACK_SIZE_TOTAL - 1 ), ( void* )( SDRAM_BASE_ADDR + SDRAM_SIZE - 1 ) }
// *****************************************************************************
// Auxiliary libraries that will be compiled for this platform

View File

@ -1374,7 +1374,7 @@ ITStatus ADC_GetITStatus(ADC_TypeDef* ADCx, u16 ADC_IT)
/*******************************************************************************
* Function Name : ADC_ClearITPendingBit
* Description : Clears the ADCx<EFBFBD>s interrupt pending bits.
* Description : Clears the ADCx's interrupt pending bits.
* Input : - ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
* - ADC_IT: specifies the ADC interrupt pending bit to clear.
* This parameter can be any combination of the following values:

View File

@ -825,7 +825,7 @@ ITStatus CAN_GetITStatus(u32 CAN_IT)
/*******************************************************************************
* Function Name : CAN_ClearITPendingBit
* Description : Clears the CAN<EFBFBD>s interrupt pending bits.
* Description : Clears the CAN's interrupt pending bits.
* Input : CAN_IT: specifies the interrupt pending bit to clear.
* Output : None.
* Return : None.

View File

@ -601,7 +601,7 @@ ITStatus DMA_GetITStatus(u32 DMA_IT)
/*******************************************************************************
* Function Name : DMA_ClearITPendingBit
* Description : Clears the DMAy Channelx<EFBFBD>s interrupt pending bits.
* Description : Clears the DMAy Channelx's interrupt pending bits.
* Input : - DMA_IT: specifies the DMA interrupt pending bit to clear.
* This parameter can be any combination (for the same DMA) of
* the following values:

View File

@ -154,7 +154,7 @@ FlagStatus EXTI_GetFlagStatus(u32 EXTI_Line)
/*******************************************************************************
* Function Name : EXTI_ClearFlag
* Description : Clears the EXTI<EFBFBD>s line pending flags.
* Description : Clears the EXTI's line pending flags.
* Input : - EXTI_Line: specifies the EXTI lines flags to clear.
* This parameter can be any combination of EXTI_Linex where
* x can be (0..18).
@ -201,7 +201,7 @@ ITStatus EXTI_GetITStatus(u32 EXTI_Line)
/*******************************************************************************
* Function Name : EXTI_ClearITPendingBit
* Description : Clears the EXTI<EFBFBD>s line pending bits.
* Description : Clears the EXTI's line pending bits.
* Input : - EXTI_Line: specifies the EXTI lines to clear.
* This parameter can be any combination of EXTI_Linex where
* x can be (0..18).

View File

@ -801,7 +801,7 @@ FlagStatus FLASH_GetFlagStatus(u16 FLASH_FLAG)
/*******************************************************************************
* Function Name : FLASH_ClearFlag
* Description : Clears the FLASH<EFBFBD>s pending flags.
* Description : Clears the FLASH's pending flags.
* Input : - FLASH_FLAG: specifies the FLASH flags to clear.
* This parameter can be any combination of the following values:
* - FLASH_FLAG_BSY: FLASH Busy flag

View File

@ -728,7 +728,7 @@ FlagStatus FSMC_GetFlagStatus(u32 FSMC_Bank, u32 FSMC_FLAG)
/*******************************************************************************
* Function Name : FSMC_ClearFlag
* Description : Clears the FSMC<EFBFBD>s pending flags.
* Description : Clears the FSMC's pending flags.
* Input : - FSMC_Bank: specifies the FSMC Bank to be used
* This parameter can be one of the following values:
* - FSMC_Bank2_NAND: FSMC Bank2 NAND
@ -819,7 +819,7 @@ ITStatus FSMC_GetITStatus(u32 FSMC_Bank, u32 FSMC_IT)
/*******************************************************************************
* Function Name : FSMC_ClearITPendingBit
* Description : Clears the FSMC<EFBFBD>s interrupt pending bits.
* Description : Clears the FSMC's interrupt pending bits.
* Input : - FSMC_Bank: specifies the FSMC Bank to be used
* This parameter can be one of the following values:
* - FSMC_Bank2_NAND: FSMC Bank2 NAND

View File

@ -997,8 +997,8 @@ ErrorStatus I2C_CheckEvent(I2C_TypeDef* I2Cx, u32 I2C_EVENT)
* - I2C_FLAG_STOPF: Stop detection flag (Slave mode)
* - I2C_FLAG_ADD10: 10-bit header sent flag (Master mode)
* - I2C_FLAG_BTF: Byte transfer finished flag
* - I2C_FLAG_ADDR: Address sent flag (Master mode) <EFBFBD>ADSL<EFBFBD>
* Address matched flag (Slave mode)<EFBFBD>ENDAD<EFBFBD>
* - I2C_FLAG_ADDR: Address sent flag (Master mode) 'ADSL'
* Address matched flag (Slave mode)'ENDAD'
* - I2C_FLAG_SB: Start bit flag (Master mode)
* Output : None
* Return : The new state of I2C_FLAG (SET or RESET).
@ -1122,8 +1122,8 @@ void I2C_ClearFlag(I2C_TypeDef* I2Cx, u32 I2C_FLAG)
* - I2C_IT_STOPF: Stop detection flag (Slave mode)
* - I2C_IT_ADD10: 10-bit header sent flag (Master mode)
* - I2C_IT_BTF: Byte transfer finished flag
* - I2C_IT_ADDR: Address sent flag (Master mode) <EFBFBD>ADSL<EFBFBD>
* Address matched flag (Slave mode)<EFBFBD>ENDAD<EFBFBD>
* - I2C_IT_ADDR: Address sent flag (Master mode) 'ADSL'
* Address matched flag (Slave mode)'ENDAD'
* - I2C_IT_SB: Start bit flag (Master mode)
* Output : None
* Return : The new state of I2C_IT (SET or RESET).
@ -1160,7 +1160,7 @@ ITStatus I2C_GetITStatus(I2C_TypeDef* I2Cx, u32 I2C_IT)
/*******************************************************************************
* Function Name : I2C_ClearITPendingBit
* Description : Clears the I2Cx<EFBFBD>s interrupt pending bits.
* Description : Clears the I2Cx's interrupt pending bits.
* Input : - I2Cx: where x can be 1 or 2 to select the I2C peripheral.
* - I2C_IT: specifies the interrupt pending bit to clear.
* This parameter can be any combination of the following

View File

@ -294,7 +294,7 @@ ITStatus NVIC_GetIRQChannelPendingBitStatus(u8 NVIC_IRQChannel)
/*******************************************************************************
* Function Name : NVIC_SetIRQChannelPendingBit
* Description : Sets the NVIC<EFBFBD>s interrupt pending bit.
* Description : Sets the NVIC's interrupt pending bit.
* Input : - NVIC_IRQChannel: specifies the interrupt pending bit to Set.
* Output : None
* Return : None
@ -309,7 +309,7 @@ void NVIC_SetIRQChannelPendingBit(u8 NVIC_IRQChannel)
/*******************************************************************************
* Function Name : NVIC_ClearIRQChannelPendingBit
* Description : Clears the NVIC<EFBFBD>s interrupt pending bit.
* Description : Clears the NVIC's interrupt pending bit.
* Input : - NVIC_IRQChannel: specifies the interrupt pending bit to clear.
* Output : None
* Return : None

View File

@ -619,7 +619,7 @@ void RCC_LSICmd(FunctionalState NewState)
/*******************************************************************************
* Function Name : RCC_RTCCLKConfig
* Description : Configures the RTC clock (RTCCLK).
* Once the RTC clock is selected it can<EFBFBD>t be changed unless the
* Once the RTC clock is selected it can't be changed unless the
* Backup domain is reset.
* Input : - RCC_RTCCLKSource: specifies the RTC clock source.
* This parameter can be one of the following values:
@ -1080,7 +1080,7 @@ ITStatus RCC_GetITStatus(u8 RCC_IT)
/*******************************************************************************
* Function Name : RCC_ClearITPendingBit
* Description : Clears the RCC<EFBFBD>s interrupt pending bits.
* Description : Clears the RCC's interrupt pending bits.
* Input : - RCC_IT: specifies the interrupt pending bit to clear.
* This parameter can be any combination of the following values:
* - RCC_IT_LSIRDY: LSI ready interrupt

View File

@ -246,7 +246,7 @@ FlagStatus RTC_GetFlagStatus(u16 RTC_FLAG)
/*******************************************************************************
* Function Name : RTC_ClearFlag
* Description : Clears the RTC<EFBFBD>s pending flags.
* Description : Clears the RTC's pending flags.
* Input : - RTC_FLAG: specifies the flag to clear.
* This parameter can be any combination of the following values:
* - RTC_FLAG_RSF: Registers Synchronized flag. This flag
@ -299,7 +299,7 @@ ITStatus RTC_GetITStatus(u16 RTC_IT)
/*******************************************************************************
* Function Name : RTC_ClearITPendingBit
* Description : Clears the RTC<EFBFBD>s interrupt pending bits.
* Description : Clears the RTC's interrupt pending bits.
* Input : - RTC_IT: specifies the interrupt pending bit to clear.
* This parameter can be any combination of the following values:
* - RTC_IT_OW: Overflow interrupt

View File

@ -795,7 +795,7 @@ ITStatus SDIO_GetITStatus(u32 SDIO_IT)
/*******************************************************************************
* Function Name : SDIO_ClearITPendingBit
* Description : Clears the SDIO<EFBFBD>s interrupt pending bits.
* Description : Clears the SDIO's interrupt pending bits.
* Input : SDIO_IT: specifies the interrupt pending bit to clear.
* This parameter can be one or a combination of the following
* values:

View File

@ -938,7 +938,7 @@ void TIM_GenerateEvent(TIM_TypeDef* TIMx, u16 TIM_EventSource)
/*******************************************************************************
* Function Name : TIM_DMAConfig
* Description : Configures the TIMx<EFBFBD>s DMA interface.
* Description : Configures the TIMx's DMA interface.
* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM
* peripheral.
* - TIM_DMABase: DMA Base address.
@ -969,7 +969,7 @@ void TIM_DMAConfig(TIM_TypeDef* TIMx, u16 TIM_DMABase, u16 TIM_DMABurstLength)
/*******************************************************************************
* Function Name : TIM_DMACmd
* Description : Enables or disables the TIMx<EFBFBD>s DMA Requests.
* Description : Enables or disables the TIMx's DMA Requests.
* Input : - TIMx: where x can be 1 to 8 to select the TIM peripheral.
* - TIM_DMASources: specifies the DMA Request sources.
* This parameter can be any combination of the following values:
@ -2406,7 +2406,7 @@ void TIM_UpdateRequestConfig(TIM_TypeDef* TIMx, u16 TIM_UpdateSource)
/*******************************************************************************
* Function Name : TIM_SelectHallSensor
* Description : Enables or disables the TIMx<EFBFBD>s Hall sensor interface.
* Description : Enables or disables the TIMx's Hall sensor interface.
* Input : - TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
* - NewState: new state of the TIMx Hall sensor interface.
* This parameter can be: ENABLE or DISABLE.
@ -2433,7 +2433,7 @@ void TIM_SelectHallSensor(TIM_TypeDef* TIMx, FunctionalState NewState)
/*******************************************************************************
* Function Name : TIM_SelectOnePulseMode
* Description : Selects the TIMx<EFBFBD>s One Pulse Mode.
* Description : Selects the TIMx's One Pulse Mode.
* Input : - TIMx: where x can be 1 to 8 to select the TIM peripheral.
* - TIM_OPMode: specifies the OPM Mode to be used.
* This parameter can be one of the following values:

View File

@ -396,7 +396,7 @@ void USART_ITConfig(USART_TypeDef* USARTx, u16 USART_IT, FunctionalState NewStat
/*******************************************************************************
* Function Name : USART_DMACmd
* Description : Enables or disables the USART<EFBFBD>s DMA interface.
* Description : Enables or disables the USART's DMA interface.
* Input : - USARTx: Select the USART or the UART peripheral.
* This parameter can be one of the following values:
* - USART1, USART2, USART3 or UART4.
@ -531,7 +531,7 @@ void USART_LINBreakDetectLengthConfig(USART_TypeDef* USARTx, u16 USART_LINBreakD
/*******************************************************************************
* Function Name : USART_LINCmd
* Description : Enables or disables the USART<EFBFBD>s LIN mode.
* Description : Enables or disables the USART's LIN mode.
* Input : - USARTx: Select the USART or the UART peripheral.
* This parameter can be one of the following values:
* - USART1, USART2, USART3, UART4 or UART5.
@ -659,7 +659,7 @@ void USART_SetPrescaler(USART_TypeDef* USARTx, u8 USART_Prescaler)
/*******************************************************************************
* Function Name : USART_SmartCardCmd
* Description : Enables or disables the USART<EFBFBD>s Smart Card mode.
* Description : Enables or disables the USART's Smart Card mode.
* Input : - USARTx: where x can be 1, 2 or 3 to select the USART
* peripheral.
* Note: The Smart Card mode is not available for UART4 and UART5.
@ -717,7 +717,7 @@ void USART_SmartCardNACKCmd(USART_TypeDef* USARTx, FunctionalState NewState)
/*******************************************************************************
* Function Name : USART_HalfDuplexCmd
* Description : Enables or disables the USART<EFBFBD>s Half Duplex communication.
* Description : Enables or disables the USART's Half Duplex communication.
* Input : - USARTx: Select the USART or the UART peripheral.
* This parameter can be one of the following values:
* - USART1, USART2, USART3, UART4 or UART5.
@ -746,7 +746,7 @@ void USART_HalfDuplexCmd(USART_TypeDef* USARTx, FunctionalState NewState)
/*******************************************************************************
* Function Name : USART_IrDAConfig
* Description : Configures the USART<EFBFBD>s IrDA interface.
* Description : Configures the USART's IrDA interface.
* Input : - USARTx: Select the USART or the UART peripheral.
* This parameter can be one of the following values:
* - USART1, USART2, USART3, UART4 or UART5.
@ -769,7 +769,7 @@ void USART_IrDAConfig(USART_TypeDef* USARTx, u16 USART_IrDAMode)
/*******************************************************************************
* Function Name : USART_IrDACmd
* Description : Enables or disables the USART<EFBFBD>s IrDA interface.
* Description : Enables or disables the USART's IrDA interface.
* Input : - USARTx: Select the USART or the UART peripheral.
* This parameter can be one of the following values:
* - USART1, USART2, USART3, UART4 or UART5.
@ -953,7 +953,7 @@ ITStatus USART_GetITStatus(USART_TypeDef* USARTx, u16 USART_IT)
/*******************************************************************************
* Function Name : USART_ClearITPendingBit
* Description : Clears the USARTx<EFBFBD>s interrupt pending bits.
* Description : Clears the USARTx's interrupt pending bits.
* Input : - USARTx: Select the USART or the UART peripheral.
* This parameter can be one of the following values:
* - USART1, USART2, USART3, UART4 or UART5.

View File

@ -16,6 +16,9 @@ ldscript = "stm32.ld"
specific_files = fwlib_files + " " + " ".join( [ "src/platform/%s/%s" % ( platform, f ) for f in specific_files.split() ] )
ldscript = "src/platform/%s/%s" % ( platform, ldscript )
if boardname == 'STM3210E-EVAL':
cdefs = cdefs + " -DFORSTM3210E_EVAL"
cdefs = cdefs + " -Dgcc"
# Toolset data

View File

@ -12,7 +12,7 @@
#include "lcd.h"
#if ELUA_BOARD == STM3210E-EVAL
#ifdef FORSTM3210E_EVAL
static int lcd_init(lua_State * L)
{

View File

@ -13,6 +13,7 @@
#include "elua_uip.h"
#include "uip-conf.h"
#include "platform_conf.h"
#include "common.h"
// Platform specific includes
#include "stm32f10x_lib.h"
@ -34,37 +35,11 @@
#define STM32_USE_PIO
#define STM32_USE_USART
#define CONSOLE 0
void exit(int ret)
{
while(1);
}
// *****************************************************************************
// std function
// TODO: Update to interrupt driven routines.
static void uart_send( int fd, char c )
{
fd = fd;
/* Loop until USART1 DR register is empty */
while(USART_GetFlagStatus(USART1, USART_FLAG_TXE) == RESET)
{
}
USART_SendData(USART1, c);
}
static int uart_recv()
{
/* Loop until the USART1 Receive Data Register is not empty */
while(USART_GetFlagStatus(USART1, USART_FLAG_RXNE) == RESET)
{
}
return USART_ReceiveData(USART1);
}
// ****************************************************************************
// Platform initialization
@ -114,9 +89,7 @@ int platform_init()
// Setup ethernet (TCP/IP)
//eth_init();
// Set the send/recv functions
std_set_send_func( uart_send );
std_set_get_func( uart_recv );
cmn_platform_init();
// All done
return PLATFORM_OK;
@ -134,7 +107,7 @@ int platform_init()
* Output : None
* Return : None
*******************************************************************************/
void RCC_Configuration(void)
static void RCC_Configuration(void)
{
ErrorStatus HSEStartUpStatus;
/* RCC system reset(for debug purpose) */
@ -197,7 +170,7 @@ void RCC_Configuration(void)
* Output : None
* Return : None
*******************************************************************************/
void NVIC_Configuration(void)
static void NVIC_Configuration(void)
{
NVIC_InitTypeDef NVIC_InitStructure;
@ -224,18 +197,14 @@ void NVIC_Configuration(void)
// todo: Needs updates to support different processor lines.
#ifdef STM32_USE_PIO
static GPIO_TypeDef * const pio_port[] = { GPIOA, GPIOB, GPIOC, GPIOD, GPIOE, GPIOF, GPIOG };
static const u8 pio_port_pins[] = { 16, 16, 16, 16, 16, 16, 16 }; // Update to reality later
static const u32 pio_port_clk[] = { RCC_APB2Periph_GPIOA, RCC_APB2Periph_GPIOB, RCC_APB2Periph_GPIOC, RCC_APB2Periph_GPIOD, RCC_APB2Periph_GPIOE, RCC_APB2Periph_GPIOF, RCC_APB2Periph_GPIOG };
#define PIOS_COUNT 112
#define PIOS_PORT_COUNT 7
static void pios_init()
{
GPIO_InitTypeDef GPIO_InitStructure;
int port;
for( port = 0; port < PIOS_PORT_COUNT; port++ )
for( port = 0; port < NUM_PIO; port++ )
{
// Enable clock to port.
RCC_APB2PeriphClockCmd(pio_port_clk[port], ENABLE);
@ -248,24 +217,6 @@ static void pios_init()
}
}
int platform_pio_has_port( unsigned port )
{
return port < PIOS_PORT_COUNT;
}
const char* platform_pio_get_prefix( unsigned port )
{
static char c[ 3 ];
sprintf( c, "P%c", ( char )( port + 'A' ) );
return c;
}
int platform_pio_has_pin( unsigned port, unsigned pin )
{
return pin < pio_port_pins[ port ];
}
pio_type platform_pio_op( unsigned port, pio_type pinmask, int op )
{
pio_type retval = 1;
@ -412,13 +363,6 @@ void platform_spi_select( unsigned id, int is_select )
// UART
// TODO: Support timeouts.
// Different configurations for different processors
#if ELUA_CPU == STM32F103ZE
#define UARTS_COUNT 4 // Ignore UART5 because it spans 2 GPIO ports.
#else
# error "CPU type unknown!"
#endif
// All possible STM32 uarts defs
static USART_TypeDef * usart[] = { USART1, USART2, USART3, UART4 };
static GPIO_TypeDef * usart_gpio_port[] = { GPIOA, GPIOA, GPIOB, GPIOC };
@ -467,19 +411,14 @@ static void uarts_init()
// Configure the U(S)ART for 115,200, 8-N-1 operation.
USART_InitStructure.USART_BaudRate = 115200;
USART_InitStructure.USART_BaudRate = CON_UART_SPEED;
USART_InitStructure.USART_WordLength = USART_WordLength_8b;
USART_InitStructure.USART_StopBits = USART_StopBits_1;
USART_InitStructure.USART_Parity = USART_Parity_No;
USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
usart_init(CONSOLE, &USART_InitStructure);
}
int platform_uart_exists( unsigned id )
{
return id < UARTS_COUNT;
usart_init(CON_UART_ID, &USART_InitStructure);
}
u32 platform_uart_setup( unsigned id, u32 baud, int databits, int parity, int stopbits )
@ -546,51 +485,18 @@ void platform_uart_send( unsigned id, u8 data )
USART_SendData(usart[id], data);
}
int platform_uart_recv( unsigned id, unsigned timer_id, int timeout )
int platform_s_uart_recv( unsigned id, unsigned timer_id, int timeout )
{
timer_data_type tmr_start, tmr_crt;
int res;
if( timeout == 0 )
{
while(USART_GetFlagStatus(usart[id], USART_FLAG_RXNE) == RESET)
{
}
// if (USART_GetFlagStatus(usart[id], USART_FLAG_RXNE) == RESET)
// {
// return -1;
// }
return USART_ReceiveData(usart[id]);
}
else if( timeout == PLATFORM_UART_INFINITE_TIMEOUT )
{
// Receive char blocking
while(USART_GetFlagStatus(usart[id], USART_FLAG_RXNE) == RESET)
{
}
return USART_ReceiveData(usart[id]);
}
else
{
// Receive char blocking
while(USART_GetFlagStatus(usart[id], USART_FLAG_RXNE) == RESET)
{
}
return USART_ReceiveData(usart[id]);
#if 0
// Receive char with the specified timeout
tmr_start = platform_timer_op( timer_id, PLATFORM_TIMER_OP_START, 0 );
while( 1 )
{
if( ( res = UARTCharGetNonBlocking( base ) ) >= 0 )
break;
tmr_crt = platform_timer_op( timer_id, PLATFORM_TIMER_OP_READ, 0 );
if( platform_timer_get_diff_us( timer_id, tmr_crt, tmr_start ) >= timeout )
break;
}
return res;
#endif
if (USART_GetFlagStatus(usart[id], USART_FLAG_RXNE) == RESET)
return -1;
else
return USART_ReceiveData(usart[id]);
}
// Receive char blocking
while(USART_GetFlagStatus(usart[id], USART_FLAG_RXNE) == RESET);
return USART_ReceiveData(usart[id]);
}
#endif
@ -601,14 +507,13 @@ int platform_uart_recv( unsigned id, unsigned timer_id, int timeout )
// All possible LM3S timers defs
static TIM_TypeDef * timer[] = { TIM2, TIM3, TIM4, TIM5};
#define TIMERS_COUNT 4
static void timers_init()
{
#if 0
unsigned i;
for( i = 0; i < TIMERS_COUNT; i ++ )
for( i = 0; i < NUM_TIMER; i ++ )
{
SysCtlPeripheralEnable(timer_sysctl[ i ]);
TimerConfigure(timer_base[ i ], TIMER_CFG_32_BIT_PER);
@ -645,12 +550,7 @@ static u32 platform_timer_set_clock(unsigned id, u32 clock)
return pclk / clkdiv; // Return actual clock rate used.
}
int platform_timer_exists( unsigned id )
{
return id < TIMERS_COUNT;
}
void platform_timer_delay( unsigned id, u32 delay_us )
void platform_s_timer_delay( unsigned id, u32 delay_us )
{
timer_data_type final;
u32 base = timer_base[ id ];
@ -660,7 +560,7 @@ void platform_timer_delay( unsigned id, u32 delay_us )
while( TimerValueGet( base, TIMER_A ) > final );
}
u32 platform_timer_op( unsigned id, int op, u32 data )
u32 platform_s_timer_op( unsigned id, int op, u32 data )
{
u32 res = 0;
u32 base = timer_base[ id ];
@ -693,19 +593,10 @@ u32 platform_timer_op( unsigned id, int op, u32 data )
}
return res;
}
u32 platform_timer_get_diff_us( unsigned id, timer_data_type end, timer_data_type start )
#else
u32 platform_s_timer_op( unsigned id, int op, u32 data )
{
timer_data_type temp;
id = id;
if( start < end )
{
temp = end;
end = start;
start = temp;
}
return ( ( u64 )( start - end ) * 1000000 ) / SysCtlClockGet();
return 0;
}
#endif
@ -825,7 +716,7 @@ void platform_cpu_disable_interrupts()
//IntMasterDisable();
}
u32 platform_cpu_get_frequency()
u32 platform_s_cpu_get_frequency()
{
RCC_ClocksTypeDef clocks;
@ -993,20 +884,3 @@ void EthernetIntHandler()
{
}
#endif // #ifdef ELUA_UIP
// ****************************************************************************
// Allocator support
extern char end[];
void* platform_get_first_free_ram( unsigned id )
{
return id > 0 ? NULL : ( void* )end;
}
#define STACK_SIZE 256
#define SRAM_SIZE ( 64 * 1024 )
void* platform_get_last_free_ram( unsigned id )
{
return id > 0 ? NULL : ( void* )( SRAM_BASE + SRAM_SIZE - STACK_SIZE - 1 );
}

View File

@ -4,6 +4,7 @@
#define __PLATFORM_CONF_H__
#include "auxmods.h"
#include "type.h"
// *****************************************************************************
// Define here what components you want for this platform
@ -22,13 +23,13 @@
// *****************************************************************************
// UART/Timer IDs configuration data (used in main.c)
#define XMODEM_UART_ID 0
#define CON_UART_ID 0
#define CON_UART_SPEED 115200
#define XMODEM_TIMER_ID 0
#define TERM_UART_ID 0
#define TERM_TIMER_ID 0
#define TERM_LINES 25
#define TERM_COLS 80
#define TERM_TIMEOUT 0
#define TERM_TIMEOUT 100000
// *****************************************************************************
// Auxiliary libraries that will be compiled for this platform
@ -63,25 +64,58 @@
// Configuration data
// Static TCP/IP configuration
#define ELUA_CONF_IPADDR0 192
#define ELUA_CONF_IPADDR1 168
#define ELUA_CONF_IPADDR2 1
#define ELUA_CONF_IPADDR3 13
#define ELUA_CONF_IPADDR0 192
#define ELUA_CONF_IPADDR1 168
#define ELUA_CONF_IPADDR2 1
#define ELUA_CONF_IPADDR3 13
#define ELUA_CONF_NETMASK0 255
#define ELUA_CONF_NETMASK1 255
#define ELUA_CONF_NETMASK2 255
#define ELUA_CONF_NETMASK3 0
#define ELUA_CONF_NETMASK0 255
#define ELUA_CONF_NETMASK1 255
#define ELUA_CONF_NETMASK2 255
#define ELUA_CONF_NETMASK3 0
#define ELUA_CONF_DEFGW0 192
#define ELUA_CONF_DEFGW1 168
#define ELUA_CONF_DEFGW2 1
#define ELUA_CONF_DEFGW3 1
#define ELUA_CONF_DEFGW0 192
#define ELUA_CONF_DEFGW1 168
#define ELUA_CONF_DEFGW2 1
#define ELUA_CONF_DEFGW3 1
#define ELUA_CONF_DNS0 192
#define ELUA_CONF_DNS1 168
#define ELUA_CONF_DNS2 1
#define ELUA_CONF_DNS3 1
#define ELUA_CONF_DNS0 192
#define ELUA_CONF_DNS1 168
#define ELUA_CONF_DNS2 1
#define ELUA_CONF_DNS3 1
// *****************************************************************************
// 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 7
#define NUM_SPI 0
#define NUM_UART 4
#define NUM_TIMER 0
#define NUM_PWM 0
// CPU frequency (needed by the CPU module, 0 if not used)
u32 platform_s_cpu_get_frequency();
#define CPU_FREQUENCY platform_s_cpu_get_frequency()
// PIO prefix ('0' for P0, P1, ... or 'A' for PA, PB, ...)
#define PIO_PREFIX 'A'
// 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_PIN_ARRAY { 16, 16, 16, 16, 16, 16, 16 }
// Allocator data: define your free memory zones here in two arrays
// (start address and end address)
#define STACK_SIZE 256
#define SRAM_SIZE ( 64 * 1024 )
#define MEM_START_ADDRESS { ( void* )end }
#define MEM_END_ADDRESS { ( void* )( SRAM_BASE + SRAM_SIZE - STACK_SIZE - 1 ) }
// *****************************************************************************
// CPU constants that should be exposed to the eLua "cpu" module

View File

@ -20,4 +20,7 @@ typedef unsigned short WORD;
typedef unsigned long DWORD;
typedef unsigned int BOOL;
typedef unsigned long long u64;
typedef signed long long s64;
#endif

View File

@ -11,26 +11,12 @@
#include <ctype.h>
#include <stdio.h>
#include "utils.h"
#include "common.h"
#include "platform_conf.h"
// Platform includes
#include "71x_lib.h"
#define CON_UART 1
// *****************************************************************************
// std functions
static void uart_send( int fd, char c )
{
fd = fd;
platform_uart_send( CON_UART, c );
}
static int uart_recv()
{
return platform_uart_recv( CON_UART, 0, PLATFORM_UART_INFINITE_TIMEOUT );
}
// ****************************************************************************
// Platform initialization
@ -64,14 +50,12 @@ int platform_init()
clock_init();
// Setup UART1 for operation
platform_uart_setup( CON_UART, 38400, 8, PLATFORM_UART_PARITY_NONE, PLATFORM_UART_STOPBITS_1 );
platform_uart_setup( CON_UART_ID, CON_UART_SPEED, 8, PLATFORM_UART_PARITY_NONE, PLATFORM_UART_STOPBITS_1 );
// Initialize Timer 0 for XMODEM
platform_timer_op( 0, PLATFORM_TIMER_OP_SET_CLOCK, 39000 );
// Set the send/recv functions
std_set_send_func( uart_send );
std_set_get_func( uart_recv );
cmn_platform_init();
return PLATFORM_OK;
}
@ -79,27 +63,7 @@ int platform_init()
// ****************************************************************************
// PIO functions
#define NUM_PORTS 2
static const GPIO_TypeDef *gpio_periph[ NUM_PORTS ] = { GPIO0, GPIO1 };
int platform_pio_has_port( unsigned port )
{
return port < 2;
}
const char* platform_pio_get_prefix( unsigned port )
{
static char c[ 3 ];
sprintf( c, "P%d", port );
return c;
}
int platform_pio_has_pin( unsigned port, unsigned pin )
{
return port < 2 && pin < 16;
}
static const GPIO_TypeDef *gpio_periph[ NUM_PIO ] = { GPIO0, GPIO1 };
pio_type platform_pio_op( unsigned port, pio_type pinmask, int op )
{
@ -150,16 +114,9 @@ pio_type platform_pio_op( unsigned port, pio_type pinmask, int op )
// ****************************************************************************
// UART
#define NUM_UARTS 4
static const u16 uart_rx_pins[ NUM_UARTS ] = { 0x0001 << 8, 0x0001 << 10, 0x0001 << 13, 0x0001 << 1 };
static const u16 uart_tx_pins[ NUM_UARTS ] = { 0x0001 << 9, 0x0001 << 11, 0x0001 << 14, 0x0001 << 0 };
static const UART_TypeDef *uart_periph[ NUM_UARTS ] = { UART0, UART1, UART2, UART3 };
int platform_uart_exists( unsigned id )
{
return id < NUM_UARTS;
}
static const u16 uart_rx_pins[ NUM_UART ] = { 0x0001 << 8, 0x0001 << 10, 0x0001 << 13, 0x0001 << 1 };
static const u16 uart_tx_pins[ NUM_UART ] = { 0x0001 << 9, 0x0001 << 11, 0x0001 << 14, 0x0001 << 0 };
static const UART_TypeDef *uart_periph[ NUM_UART ] = { UART0, UART1, UART2, UART3 };
u32 platform_uart_setup( unsigned id, u32 baud, int databits, int parity, int stopbits )
{
@ -223,10 +180,8 @@ void platform_uart_send( unsigned id, u8 data )
UART_ByteSend( pport, &data );
}
int platform_uart_recv( unsigned id, unsigned timer_id, int timeout )
int platform_s_uart_recv( unsigned id, unsigned timer_id, int timeout )
{
timer_data_type tmr_start, tmr_crt;
int res;
UART_TypeDef* pport = ( UART_TypeDef* )uart_periph[ id ];
if( timeout == 0 )
@ -237,30 +192,7 @@ int platform_uart_recv( unsigned id, unsigned timer_id, int timeout )
else
return -1;
}
else if( timeout == PLATFORM_UART_INFINITE_TIMEOUT )
{
// Wait for dataa
return UART_ByteReceive( pport );
}
else
{
// Receive char with the specified timeout
tmr_start = platform_timer_op( timer_id, PLATFORM_TIMER_OP_START,0 );
while( 1 )
{
if( UART_FlagStatus( pport ) & UART_RxBufNotEmpty )
{
res = UART_ByteReceive( pport );
break;
}
else
res = -1;
tmr_crt = platform_timer_op( timer_id, PLATFORM_TIMER_OP_READ, 0 );
if( platform_timer_get_diff_us( timer_id, tmr_crt, tmr_start ) >= timeout )
break;
}
return res;
}
return UART_ByteReceive( pport );
}
// ****************************************************************************
@ -268,12 +200,7 @@ int platform_uart_recv( unsigned id, unsigned timer_id, int timeout )
#define NUM_TIMERS 4
static const TIM_TypeDef *tim_periph[ NUM_TIMERS ] = { TIM0, TIM1, TIM2, TIM3 };
int platform_timer_exists( unsigned id )
{
return id < NUM_TIMERS;
}
static const TIM_TypeDef *tim_periph[ NUM_TIMER ] = { TIM0, TIM1, TIM2, TIM3 };
// Helper: get timer clock
static u32 platform_timer_get_clock( unsigned id )
@ -300,7 +227,7 @@ static u32 platform_timer_set_clock( unsigned id, u32 clock )
return baseclk / bestdiv;
}
void platform_timer_delay( unsigned id, u32 delay_us )
void platform_s_timer_delay( unsigned id, u32 delay_us )
{
TIM_TypeDef* ptimer = ( TIM_TypeDef* )tim_periph[ id ];
u32 freq;
@ -321,7 +248,7 @@ void platform_timer_delay( unsigned id, u32 delay_us )
while( TIM_CounterValue( ptimer ) < final );
}
u32 platform_timer_op( unsigned id, int op, u32 data )
u32 platform_s_timer_op( unsigned id, int op, u32 data )
{
u32 res = 0;
TIM_TypeDef* ptimer = ( TIM_TypeDef* )tim_periph[ id ];
@ -362,33 +289,11 @@ u32 platform_timer_op( unsigned id, int op, u32 data )
return res;
}
u32 platform_timer_get_diff_us( unsigned id, timer_data_type end, timer_data_type start )
{
timer_data_type temp;
u32 freq;
freq = platform_timer_get_clock( id );
if( start < end )
{
temp = end;
end = start;
start = temp;
}
return ( ( u64 )( start - end ) * 1000000 ) / freq;
}
// ****************************************************************************
// PWM functions
#define PLATFORM_NUM_PWMS 3
static const u16 pwm_pins[ PLATFORM_NUM_PWMS ] = { 1 << 7, 1 << 13, 1 << 2 };
static const u8 pwm_ports[ PLATFORM_NUM_PWMS ] = { 1, 0, 1 };
int platform_pwm_exists( unsigned id )
{
return id < PLATFORM_NUM_PWMS;
}
static const u16 pwm_pins[ NUM_PWM ] = { 1 << 7, 1 << 13, 1 << 2 };
static const u8 pwm_ports[ NUM_PWM ] = { 1, 0, 1 };
u32 platform_pwm_setup( unsigned id, u32 frequency, unsigned duty )
{
@ -436,21 +341,3 @@ u32 platform_pwm_op( unsigned id, int op, u32 data )
return res;
}
// ****************************************************************************
// Allocator support
extern char end[];
void* platform_get_first_free_ram( unsigned id )
{
return id > 0 ? NULL : ( void* )end;
}
#define SRAM_ORIGIN 0x20000000
#define SRAM_SIZE 0x10000
void* platform_get_last_free_ram( unsigned id )
{
return id > 0 ? NULL : ( void* )( SRAM_ORIGIN + SRAM_SIZE - STACK_SIZE_TOTAL - 1 );
}

View File

@ -4,6 +4,7 @@
#define __PLATFORM_CONF_H__
#include "auxmods.h"
#include "stacks.h"
// *****************************************************************************
// Define here what components you want for this platform
@ -17,9 +18,9 @@
// *****************************************************************************
// UART/Timer IDs configuration data (used in main.c)
#define XMODEM_UART_ID 1
#define CON_UART_ID 1
#define CON_UART_SPEED 38400
#define XMODEM_TIMER_ID 0
#define TERM_UART_ID 1
#define TERM_TIMER_ID 0
#define TERM_LINES 25
#define TERM_COLS 80
@ -39,4 +40,36 @@
{ AUXLIB_BIT, luaopen_bit },\
{ LUA_MATHLIBNAME, luaopen_math }
// *****************************************************************************
// 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 2
#define NUM_SPI 0
#define NUM_UART 4
#define NUM_TIMER 4
#define NUM_PWM 3
// CPU frequency (needed by the CPU module, 0 if not used)
#define CPU_FREQUENCY 0
// 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 16
// Allocator data: define your free memory zones here in two arrays
// (start address and end address)
#define SRAM_ORIGIN 0x20000000
#define SRAM_SIZE 0x10000
#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

@ -1,239 +0,0 @@
/********************************************************************
* Project: STR9-comStick GNU (UART)
* File: main.c
*
* System: ARM9TDMI 32 Bit (STR912FW44X)
* Compiler: GCC 4.0.3
*
* Date: 2006-12-20
* Author: Applications@Hitex.de
*
* Rights: Hitex Development Tools GmbH
* Greschbachstr. 12
* D-76229 Karlsruhe
********************************************************************
* Description:
*
* This file is part of the GNU Example chain
* The code is bassed on usage of the STmicro library functions
* This is a small implementation of UART1 feature echoing external input
* The application runs in ARM mode with high optimization level.
*
********************************************************************
* History:
*
* Revision 1.0 2006/12/20 Gn
* Initial revision
********************************************************************
* This is a preliminary version.
*
* WARRANTY: HITEX warrants that the media on which the SOFTWARE is
* furnished is free from defects in materials and workmanship under
* normal use and service for a period of ninety (90) days. HITEX entire
* liability and your exclusive remedy shall be the replacement of the
* SOFTWARE if the media is defective. This Warranty is void if failure
* of the media resulted from unauthorized modification, accident, abuse,
* or misapplication.
*
* DISCLAIMER: OTHER THAN THE ABOVE WARRANTY, THE SOFTWARE IS FURNISHED
* "AS IS" WITHOUT WARRANTY OF ANY KIND. HITEX DISCLAIMS ALL OTHER WARRANTIES,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO IMPLIED WARRANTIES
* OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
*
* NEITHER HITEX NOR ITS AFFILIATES SHALL BE LIABLE FOR ANY DAMAGES ARISING
* OUT OF THE USE OF OR INABILITY TO USE THE SOFTWARE, INCLUDING DAMAGES FOR
* LOSS OF PROFITS, BUSINESS INTERRUPTION, OR ANY SPECIAL, INCIDENTAL, INDIRECT
* OR CONSEQUENTIAL DAMAGES EVEN IF HITEX HAS BEEN ADVISED OF THE POSSIBILITY
* OF SUCH DAMAGES.
********************************************************************/
#include "defines.h"
#define global extern /* to declare external variables and functions */
#include "91x_lib.h"
#include "main.h"
#define GPIO_Alt1 0x01
#define TxBufferSize (countof(TxBuffer) - 1)
#define RxBufferSize 0xFF
/* Private macro -------------------------------------------------------------*/
#define countof(a) (sizeof(a) / sizeof(*(a)))
/* Private variables ---------------------------------------------------------*/
UART_InitTypeDef UART_InitStructure;
u8 TxBuffer[] = "UART1 - 1,8,N,1@115.2k communication without flow control\n\r";
u8 RxBuffer[RxBufferSize];
u8 NbrOfDataToTransfer = TxBufferSize;
u8 TxCounter = 0;
u8 RxCounter = 0;
GPIO_InitTypeDef GPIO_InitStructure;
TIM_InitTypeDef TIM_InitStructure;
/* Private function prototypes -----------------------------------------------*/
void SCU_Configuration(void);
void GPIO_Configuration(void);
void UART1_Configuration(void);
static void Delay(u32 nCount);
int main (void)
{
/* Configure the system clocks */
SCU_Configuration();
/* Configure the GPIOs */
GPIO_Configuration();
/* Configure and start the UART1 */
UART1_Configuration();
/* endless loop */
while (1)
{
{
if((UART_GetFlagStatus(UART1, UART_FLAG_RxFIFOEmpty) != SET)&&(RxCounter < RxBufferSize))
{
RxBuffer[0] = UART1->DR;
UART_SendData(UART1, RxBuffer[0]);
}
}
/* Turn OFF leds connected to P9.0, P9.1 pins */
GPIO_WriteBit(GPIO8, GPIO_Pin_0, Bit_SET);
/* Insert delay */
Delay(0x1FFFF);
/* Turn ON leds connected to P9.0, P9.1 pins */
GPIO_WriteBit(GPIO8, GPIO_Pin_0, Bit_RESET);
/* Insert delay */
Delay(0x1FFFF);
}
}
void SCU_Configuration(void)
{
SCU_MCLKSourceConfig(SCU_MCLK_OSC);
SCU_PLLFactorsConfig(192,25,2); /* PLL = 96 MHz */
SCU_PLLCmd(ENABLE); /* PLL Enabled */
SCU_MCLKSourceConfig(SCU_MCLK_PLL); /* MCLK = PLL */
FMI_BankRemapConfig(4, 2, 0, 0x80000); /* Set Flash banks size & address */
FMI_Config(FMI_READ_WAIT_STATE_2, FMI_WRITE_WAIT_STATE_0, FMI_PWD_ENABLE,\
FMI_LVD_ENABLE, FMI_FREQ_HIGH); /* FMI Waite States */
/* Enable VIC clock */
SCU_AHBPeriphClockConfig(__VIC, ENABLE);
SCU_AHBPeriphReset(__VIC, DISABLE);
/* Set the PCLK Clock to MCLK/2 */
SCU_PCLKDivisorConfig(SCU_PCLK_Div1);
/* Enable the UART0 Clock */
SCU_APBPeriphClockConfig(__UART1, ENABLE);
/* Enable the clock for TIM0 and TIM1 */
SCU_APBPeriphClockConfig(__TIM01, ENABLE);
SCU_APBPeriphReset(__TIM01, DISABLE);
SCU_APBPeriphClockConfig(__TIM23, ENABLE);
SCU_APBPeriphReset(__TIM23, DISABLE);
/* Enable the GPIO3 Clock */
SCU_APBPeriphClockConfig(__GPIO3, ENABLE);
SCU_APBPeriphClockConfig(__GPIO4, ENABLE); /* Enable the clock for the GPIO4 */
/* Enable the __GPIO8 */
SCU_APBPeriphClockConfig(__GPIO8 ,ENABLE);
/* Enable the __GPIO9 */
SCU_APBPeriphClockConfig(__GPIO9 ,ENABLE);
}
/* GPIO Configuration --------------------------------------------------------*/
void GPIO_Configuration(void)
{
GPIO_DeInit(GPIO3);
GPIO_DeInit(GPIO4); /* GPIO4 Deinitialization */
GPIO_DeInit(GPIO9);
/* IOs */
GPIO_InitStructure.GPIO_Direction = GPIO_PinOutput;
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_All;
GPIO_InitStructure.GPIO_Type = GPIO_Type_PushPull ;
GPIO_Init (GPIO4, &GPIO_InitStructure);
/* onboard LED */
GPIO_InitStructure.GPIO_Direction = GPIO_PinOutput;
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0;
GPIO_InitStructure.GPIO_Type = GPIO_Type_PushPull ;
GPIO_Init (GPIO9, &GPIO_InitStructure);
GPIO_WriteBit(GPIO9, GPIO_Pin_0, Bit_RESET);
/* configure UART1_Rx pin GPIO3.2*/
GPIO_InitStructure.GPIO_Direction = GPIO_PinInput;
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_2;
GPIO_InitStructure.GPIO_Type = GPIO_Type_PushPull ;
GPIO_InitStructure.GPIO_IPConnected = GPIO_IPConnected_Enable;
GPIO_InitStructure.GPIO_Alternate = GPIO_InputAlt1 ;
GPIO_Init (GPIO3, &GPIO_InitStructure);
/*Gonfigure UART1_Tx pin GPIO3.3*/
GPIO_InitStructure.GPIO_Direction = GPIO_PinInput;
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_3;
GPIO_InitStructure.GPIO_Type = GPIO_Type_PushPull ;
GPIO_InitStructure.GPIO_Alternate = GPIO_OutputAlt2 ;
GPIO_Init (GPIO3, &GPIO_InitStructure);
}
/* UART1 configuration -------------------------------------------------------*/
void UART1_Configuration(void)
{
/* UART1 configured as follow:
- Word Length = 8 Bits
- One Stop Bit
- No parity
- BaudRate = 115200 baud
- no Hardware flow control enabled (RTS and CTS signals)
- Receive and transmit enabled
- Receive and transmit FIFOs are enabled
- Transmit and Receive FIFOs levels have 8 bytes depth
*/
UART_InitStructure.UART_WordLength = UART_WordLength_8D;
UART_InitStructure.UART_StopBits = UART_StopBits_1;
UART_InitStructure.UART_Parity = UART_Parity_No ;
UART_InitStructure.UART_BaudRate = 115200;
UART_InitStructure.UART_HardwareFlowControl = UART_HardwareFlowControl_None;
UART_InitStructure.UART_Mode = UART_Mode_Tx_Rx;
UART_InitStructure.UART_FIFO = UART_FIFO_Enable;//UART_FIFO_Enable;
UART_InitStructure.UART_TxFIFOLevel = UART_FIFOLevel_1_2; /* FIFO size 16 bytes, FIFO level 8 bytes */
UART_InitStructure.UART_RxFIFOLevel = UART_FIFOLevel_1_2; /* FIFO size 16 bytes, FIFO level 8 bytes */
UART_DeInit(UART1);
UART_Init(UART1, &UART_InitStructure);
/* Enable the UART0 */
UART_Cmd(UART1, ENABLE);
while(NbrOfDataToTransfer--)
{
UART_SendData(UART1, TxBuffer[TxCounter++]);
while(UART_GetFlagStatus(UART1, UART_FLAG_TxFIFOFull) != RESET);
}
}
/*******************************************************************************
* Function Name : Delay
* Description : Inserts a delay time.
* Input : nCount: specifies the delay time length.
*******************************************************************************/
static void Delay(u32 nCount)
{
u32 j = 0;
for(j = nCount; j != 0; j--);
}
/************************************** EOF *********************************/

View File

@ -15,24 +15,12 @@
#include "91x_gpio.h"
#include "91x_uart.h"
#include "91x_tim.h"
#include "common.h"
#include "platform_conf.h"
// We define here the UART used by this porting layer
#define STR9_UART UART1
// *****************************************************************************
// std functions
static void uart_send( int fd, char c )
{
fd = fd;
platform_uart_send( 0, c );
}
static int uart_recv()
{
return platform_uart_recv( 0, 0, PLATFORM_UART_INFINITE_TIMEOUT );
}
// ****************************************************************************
// Platform initialization
static const GPIO_TypeDef* port_data[] = { GPIO0, GPIO1, GPIO2, GPIO3, GPIO4, GPIO5, GPIO6, GPIO7, GPIO8, GPIO9 };
@ -89,7 +77,7 @@ int platform_init()
GPIO_DeInit( ( GPIO_TypeDef* )port_data[ i ] );
// UART setup (only STR9_UART is used in this example)
platform_uart_setup( 0, 115200, 8, PLATFORM_UART_PARITY_NONE, PLATFORM_UART_STOPBITS_1 );
platform_uart_setup( CON_UART_ID, CON_UART_SPEED, 8, PLATFORM_UART_PARITY_NONE, PLATFORM_UART_STOPBITS_1 );
// Initialize timers
for( i = 0; i < 4; i ++ )
@ -103,9 +91,7 @@ int platform_init()
TIM_CounterCmd( base, TIM_START );
}
// Set the send/recv functions
std_set_send_func( uart_send );
std_set_get_func( uart_recv );
cmn_platform_init();
return PLATFORM_OK;
}
@ -113,24 +99,6 @@ int platform_init()
// ****************************************************************************
// PIO functions
int platform_pio_has_port( unsigned port )
{
return port < 10;
}
const char* platform_pio_get_prefix( unsigned port )
{
static char c[ 3 ];
sprintf( c, "P%d", port );
return c;
}
int platform_pio_has_pin( unsigned port, unsigned pin )
{
return port < 10 && pin < 8;
}
pio_type platform_pio_op( unsigned port, pio_type pinmask, int op )
{
GPIO_TypeDef* base = ( GPIO_TypeDef* )port_data[ port ];
@ -187,11 +155,6 @@ pio_type platform_pio_op( unsigned port, pio_type pinmask, int op )
// ****************************************************************************
// UART
int platform_uart_exists( unsigned id )
{
return id < 1;
}
u32 platform_uart_setup( unsigned id, u32 baud, int databits, int parity, int stopbits )
{
UART_InitTypeDef UART_InitStructure;
@ -259,11 +222,8 @@ void platform_uart_send( unsigned id, u8 data )
UART_SendData( STR9_UART, data );
}
int platform_uart_recv( unsigned id, unsigned timer_id, int timeout )
int platform_s_uart_recv( unsigned id, unsigned timer_id, int timeout )
{
timer_data_type tmr_start, tmr_crt;
int res;
if( timeout == 0 )
{
// Return data only if already available
@ -272,41 +232,13 @@ int platform_uart_recv( unsigned id, unsigned timer_id, int timeout )
else
return -1;
}
else if( timeout == PLATFORM_UART_INFINITE_TIMEOUT )
{
// Wait for data
while( UART_GetFlagStatus(STR9_UART, UART_FLAG_RxFIFOEmpty) == SET );
return UART_ReceiveData( STR9_UART );
}
else
{
// Receive char with the specified timeout
tmr_start = platform_timer_op( timer_id, PLATFORM_TIMER_OP_START,0 );
while( 1 )
{
if( UART_GetFlagStatus(STR9_UART, UART_FLAG_RxFIFOEmpty) != SET )
{
res = UART_ReceiveData( STR9_UART );
break;
}
else
res = -1;
tmr_crt = platform_timer_op( timer_id, PLATFORM_TIMER_OP_READ, 0 );
if( platform_timer_get_diff_us( timer_id, tmr_crt, tmr_start ) >= timeout )
break;
}
return res;
}
while( UART_GetFlagStatus(STR9_UART, UART_FLAG_RxFIFOEmpty) == SET );
return UART_ReceiveData( STR9_UART );
}
// ****************************************************************************
// Timer
int platform_timer_exists( unsigned id )
{
return id < 4;
}
// Helper: get timer clock
static u32 platform_timer_get_clock( unsigned id )
{
@ -330,7 +262,7 @@ static u32 platform_timer_set_clock( unsigned id, u32 clock )
return baseclk / bestdiv;
}
void platform_timer_delay( unsigned id, u32 delay_us )
void platform_s_timer_delay( unsigned id, u32 delay_us )
{
TIM_TypeDef* base = ( TIM_TypeDef* )timer_data[ id ];
u32 freq;
@ -351,7 +283,7 @@ void platform_timer_delay( unsigned id, u32 delay_us )
while( TIM_GetCounterValue( base ) < final );
}
u32 platform_timer_op( unsigned id, int op, u32 data )
u32 platform_s_timer_op( unsigned id, int op, u32 data )
{
u32 res = 0;
TIM_TypeDef* base = ( TIM_TypeDef* )timer_data[ id ];
@ -387,43 +319,3 @@ u32 platform_timer_op( unsigned id, int op, u32 data )
}
return res;
}
u32 platform_timer_get_diff_us( unsigned id, timer_data_type end, timer_data_type start )
{
timer_data_type temp;
u32 freq;
freq = platform_timer_get_clock( id );
if( start < end )
{
temp = end;
end = start;
start = temp;
}
return ( ( u64 )( start - end ) * 1000000 ) / freq;
}
// ****************************************************************************
// CPU functions
u32 platform_cpu_get_frequency()
{
return SCU_GetMCLKFreqValue() * 1000;
}
// ****************************************************************************
// Allocator support
extern char end[];
void* platform_get_first_free_ram( unsigned id )
{
return id > 0 ? NULL : ( void* )end;
}
#define SRAM_ORIGIN 0x40000000
#define SRAM_SIZE 0x18000
void* platform_get_last_free_ram( unsigned id )
{
return id > 0 ? NULL : ( void* )( SRAM_ORIGIN + SRAM_SIZE - STACK_SIZE_TOTAL - 1 );
}

View File

@ -4,6 +4,8 @@
#define __PLATFORM_CONF_H__
#include "auxmods.h"
#include "stacks.h"
#include "type.h"
// *****************************************************************************
// Define here what components you want for this platform
@ -17,14 +19,47 @@
// *****************************************************************************
// UART/Timer IDs configuration data (used in main.c)
#define XMODEM_UART_ID 0
#define CON_UART_ID 0
#define CON_UART_SPEED 115200
#define XMODEM_TIMER_ID 0
#define TERM_UART_ID 0
#define TERM_TIMER_ID 0
#define TERM_LINES 25
#define TERM_COLS 80
#define TERM_TIMEOUT 100000
// *****************************************************************************
// 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 10
#define NUM_SPI 0
#define NUM_UART 1
#define NUM_TIMER 4
#define NUM_PWM 0
// CPU frequency (needed by the CPU module, 0 if not used)
u32 SCU_GetMCLKFreqValue();
#define CPU_FREQUENCY ( SCU_GetMCLKFreqValue() * 1000 )
// 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 8
// Allocator data: define your free memory zones here in two arrays
// (start address and end address)
#define SRAM_ORIGIN 0x40000000
#define SRAM_SIZE 0x18000
#define MEM_START_ADDRESS { ( void* )end }
#define MEM_END_ADDRESS { ( void* )( SRAM_ORIGIN + SRAM_SIZE - STACK_SIZE_TOTAL - 1 ) }
// *****************************************************************************
// Auxiliary libraries that will be compiled for this platform

View File

@ -88,11 +88,13 @@
# STARTUP EXECUTABLE CODE
#*************************************************************************
.text
.align 4
.arm
.extern main
.global _startup
.section .vectors, "a"
_startup:
#*************************************************************************
@ -130,6 +132,8 @@ DAbt_Handler: B DAbt_Handler
IRQ_Handler: B IRQ_Handler /* should never get here as IRQ is via VIC slot... */
FIQ_Handler: B FIQ_Handler
.text
#*************************************************************************
# Reset Handler Entry Point

View File

@ -13,6 +13,7 @@ SECTIONS
{
. = ALIGN(4);
_sfixed = .;
KEEP(*(.vectors))
*(.text .text.*)
*(.rodata .rodata.*)
*(.gnu.linkonce.t.*)

View File

@ -121,8 +121,8 @@ long xmodem_receive( char** dest )
xmodem_out_func(ACK);
// completed transmission normally
return totalbytes;
case CAN:
if((c = xmodem_in_func(XMODEM_TIMEOUT_DELAY)) == CAN)
case XMODEM_CAN:
if((c = xmodem_in_func(XMODEM_TIMEOUT_DELAY)) == XMODEM_CAN)
{
xmodem_flush();
xmodem_out_func(ACK);
@ -182,9 +182,9 @@ long xmodem_receive( char** dest )
{
// Cancel transmission
xmodem_flush();
xmodem_out_func(CAN);
xmodem_out_func(CAN);
xmodem_out_func(CAN);
xmodem_out_func(XMODEM_CAN);
xmodem_out_func(XMODEM_CAN);
xmodem_out_func(XMODEM_CAN);
return XMODEM_ERROR_OUTOFMEM;
}
}
@ -210,9 +210,9 @@ long xmodem_receive( char** dest )
// we are completely out of sync
// cancel transmission
xmodem_flush();
xmodem_out_func(CAN);
xmodem_out_func(CAN);
xmodem_out_func(CAN);
xmodem_out_func(XMODEM_CAN);
xmodem_out_func(XMODEM_CAN);
xmodem_out_func(XMODEM_CAN);
return XMODEM_ERROR_OUTOFSYNC;
}
}
@ -229,9 +229,9 @@ long xmodem_receive( char** dest )
// exceeded retry count
xmodem_flush();
xmodem_out_func(CAN);
xmodem_out_func(CAN);
xmodem_out_func(CAN);
xmodem_out_func(XMODEM_CAN);
xmodem_out_func(XMODEM_CAN);
xmodem_out_func(XMODEM_CAN);
return XMODEM_ERROR_RETRYEXCEED;
}