1
0
mirror of https://github.com/elua/elua.git synced 2025-01-08 20:56:17 +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 );
@ -85,10 +84,19 @@ int platform_init()
PWMC_EnableChannel( i );
PWMC_EnableChannelIt( i );
}
cmn_platform_init();
// Set the send/recv functions
std_set_send_func( uart_send );
std_set_get_func( uart_recv );
#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,10 +101,31 @@ 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
@ -195,6 +197,8 @@ IRQ_Handler: B IRQ_Handler
@ ==============================================================================
@ Reset handler
.text
Reset_Handler:

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

File diff suppressed because it is too large Load Diff

View File

@ -1,272 +1,272 @@
/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
* File Name : stm32f10x_bkp.c
* Author : MCD Application Team
* Version : V2.0.3
* Date : 09/22/2008
* Description : This file provides all the BKP firmware functions.
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x_bkp.h"
#include "stm32f10x_rcc.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* ------------ BKP registers bit address in the alias region ----------- */
#define BKP_OFFSET (BKP_BASE - PERIPH_BASE)
/* --- CR Register ---*/
/* Alias word address of TPAL bit */
#define CR_OFFSET (BKP_OFFSET + 0x30)
#define TPAL_BitNumber 0x01
#define CR_TPAL_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (TPAL_BitNumber * 4))
/* Alias word address of TPE bit */
#define TPE_BitNumber 0x00
#define CR_TPE_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (TPE_BitNumber * 4))
/* --- CSR Register ---*/
/* Alias word address of TPIE bit */
#define CSR_OFFSET (BKP_OFFSET + 0x34)
#define TPIE_BitNumber 0x02
#define CSR_TPIE_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (TPIE_BitNumber * 4))
/* Alias word address of TIF bit */
#define TIF_BitNumber 0x09
#define CSR_TIF_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (TIF_BitNumber * 4))
/* Alias word address of TEF bit */
#define TEF_BitNumber 0x08
#define CSR_TEF_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (TEF_BitNumber * 4))
/* ---------------------- BKP registers bit mask ------------------------ */
/* RTCCR register bit mask */
#define RTCCR_CAL_Mask ((u16)0xFF80)
#define RTCCR_Mask ((u16)0xFC7F)
/* CSR register bit mask */
#define CSR_CTE_Set ((u16)0x0001)
#define CSR_CTI_Set ((u16)0x0002)
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : BKP_DeInit
* Description : Deinitializes the BKP peripheral registers to their default
* reset values.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void BKP_DeInit(void)
{
RCC_BackupResetCmd(ENABLE);
RCC_BackupResetCmd(DISABLE);
}
/*******************************************************************************
* Function Name : BKP_TamperPinLevelConfig
* Description : Configures the Tamper Pin active level.
* Input : - BKP_TamperPinLevel: specifies the Tamper Pin active level.
* This parameter can be one of the following values:
* - BKP_TamperPinLevel_High: Tamper pin active on high level
* - BKP_TamperPinLevel_Low: Tamper pin active on low level
* Output : None
* Return : None
*******************************************************************************/
void BKP_TamperPinLevelConfig(u16 BKP_TamperPinLevel)
{
/* Check the parameters */
assert_param(IS_BKP_TAMPER_PIN_LEVEL(BKP_TamperPinLevel));
*(vu32 *) CR_TPAL_BB = BKP_TamperPinLevel;
}
/*******************************************************************************
* Function Name : BKP_TamperPinCmd
* Description : Enables or disables the Tamper Pin activation.
* Input : - NewState: new state of the Tamper Pin activation.
* This parameter can be: ENABLE or DISABLE.
* Output : None
* Return : None
*******************************************************************************/
void BKP_TamperPinCmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
*(vu32 *) CR_TPE_BB = (u32)NewState;
}
/*******************************************************************************
* Function Name : BKP_ITConfig
* Description : Enables or disables the Tamper Pin Interrupt.
* Input : - NewState: new state of the Tamper Pin Interrupt.
* This parameter can be: ENABLE or DISABLE.
* Output : None
* Return : None
*******************************************************************************/
void BKP_ITConfig(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
*(vu32 *) CSR_TPIE_BB = (u32)NewState;
}
/*******************************************************************************
* Function Name : BKP_RTCOutputConfig
* Description : Select the RTC output source to output on the Tamper pin.
* Input : - BKP_RTCOutputSource: specifies the RTC output source.
* This parameter can be one of the following values:
* - BKP_RTCOutputSource_None: no RTC output on the Tamper pin.
* - BKP_RTCOutputSource_CalibClock: output the RTC clock
* with frequency divided by 64 on the Tamper pin.
* - BKP_RTCOutputSource_Alarm: output the RTC Alarm pulse
* signal on the Tamper pin.
* - BKP_RTCOutputSource_Second: output the RTC Second pulse
* signal on the Tamper pin.
* Output : None
* Return : None
*******************************************************************************/
void BKP_RTCOutputConfig(u16 BKP_RTCOutputSource)
{
u16 tmpreg = 0;
/* Check the parameters */
assert_param(IS_BKP_RTC_OUTPUT_SOURCE(BKP_RTCOutputSource));
tmpreg = BKP->RTCCR;
/* Clear CCO, ASOE and ASOS bits */
tmpreg &= RTCCR_Mask;
/* Set CCO, ASOE and ASOS bits according to BKP_RTCOutputSource value */
tmpreg |= BKP_RTCOutputSource;
/* Store the new value */
BKP->RTCCR = tmpreg;
}
/*******************************************************************************
* Function Name : BKP_SetRTCCalibrationValue
* Description : Sets RTC Clock Calibration value.
* Input : - CalibrationValue: specifies the RTC Clock Calibration value.
* This parameter must be a number between 0 and 0x7F.
* Output : None
* Return : None
*******************************************************************************/
void BKP_SetRTCCalibrationValue(u8 CalibrationValue)
{
u16 tmpreg = 0;
/* Check the parameters */
assert_param(IS_BKP_CALIBRATION_VALUE(CalibrationValue));
tmpreg = BKP->RTCCR;
/* Clear CAL[6:0] bits */
tmpreg &= RTCCR_CAL_Mask;
/* Set CAL[6:0] bits according to CalibrationValue value */
tmpreg |= CalibrationValue;
/* Store the new value */
BKP->RTCCR = tmpreg;
}
/*******************************************************************************
* Function Name : BKP_WriteBackupRegister
* Description : Writes user data to the specified Data Backup Register.
* Input : - BKP_DR: specifies the Data Backup Register.
* This parameter can be BKP_DRx where x:[1, 42]
* - Data: data to write
* Output : None
* Return : None
*******************************************************************************/
void BKP_WriteBackupRegister(u16 BKP_DR, u16 Data)
{
/* Check the parameters */
assert_param(IS_BKP_DR(BKP_DR));
*(vu16 *) (BKP_BASE + BKP_DR) = Data;
}
/*******************************************************************************
* Function Name : BKP_ReadBackupRegister
* Description : Reads data from the specified Data Backup Register.
* Input : - BKP_DR: specifies the Data Backup Register.
* This parameter can be BKP_DRx where x:[1, 42]
* Output : None
* Return : The content of the specified Data Backup Register
*******************************************************************************/
u16 BKP_ReadBackupRegister(u16 BKP_DR)
{
/* Check the parameters */
assert_param(IS_BKP_DR(BKP_DR));
return (*(vu16 *) (BKP_BASE + BKP_DR));
}
/*******************************************************************************
* Function Name : BKP_GetFlagStatus
* Description : Checks whether the Tamper Pin Event flag is set or not.
* Input : None
* Output : None
* Return : The new state of the Tamper Pin Event flag (SET or RESET).
*******************************************************************************/
FlagStatus BKP_GetFlagStatus(void)
{
return (FlagStatus)(*(vu32 *) CSR_TEF_BB);
}
/*******************************************************************************
* Function Name : BKP_ClearFlag
* Description : Clears Tamper Pin Event pending flag.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void BKP_ClearFlag(void)
{
/* Set CTE bit to clear Tamper Pin Event flag */
BKP->CSR |= CSR_CTE_Set;
}
/*******************************************************************************
* Function Name : BKP_GetITStatus
* Description : Checks whether the Tamper Pin Interrupt has occurred or not.
* Input : None
* Output : None
* Return : The new state of the Tamper Pin Interrupt (SET or RESET).
*******************************************************************************/
ITStatus BKP_GetITStatus(void)
{
return (ITStatus)(*(vu32 *) CSR_TIF_BB);
}
/*******************************************************************************
* Function Name : BKP_ClearITPendingBit
* Description : Clears Tamper Pin Interrupt pending bit.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void BKP_ClearITPendingBit(void)
{
/* Set CTI bit to clear Tamper Pin Interrupt pending bit */
BKP->CSR |= CSR_CTI_Set;
}
/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
* File Name : stm32f10x_bkp.c
* Author : MCD Application Team
* Version : V2.0.3
* Date : 09/22/2008
* Description : This file provides all the BKP firmware functions.
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x_bkp.h"
#include "stm32f10x_rcc.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* ------------ BKP registers bit address in the alias region ----------- */
#define BKP_OFFSET (BKP_BASE - PERIPH_BASE)
/* --- CR Register ---*/
/* Alias word address of TPAL bit */
#define CR_OFFSET (BKP_OFFSET + 0x30)
#define TPAL_BitNumber 0x01
#define CR_TPAL_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (TPAL_BitNumber * 4))
/* Alias word address of TPE bit */
#define TPE_BitNumber 0x00
#define CR_TPE_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (TPE_BitNumber * 4))
/* --- CSR Register ---*/
/* Alias word address of TPIE bit */
#define CSR_OFFSET (BKP_OFFSET + 0x34)
#define TPIE_BitNumber 0x02
#define CSR_TPIE_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (TPIE_BitNumber * 4))
/* Alias word address of TIF bit */
#define TIF_BitNumber 0x09
#define CSR_TIF_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (TIF_BitNumber * 4))
/* Alias word address of TEF bit */
#define TEF_BitNumber 0x08
#define CSR_TEF_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (TEF_BitNumber * 4))
/* ---------------------- BKP registers bit mask ------------------------ */
/* RTCCR register bit mask */
#define RTCCR_CAL_Mask ((u16)0xFF80)
#define RTCCR_Mask ((u16)0xFC7F)
/* CSR register bit mask */
#define CSR_CTE_Set ((u16)0x0001)
#define CSR_CTI_Set ((u16)0x0002)
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : BKP_DeInit
* Description : Deinitializes the BKP peripheral registers to their default
* reset values.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void BKP_DeInit(void)
{
RCC_BackupResetCmd(ENABLE);
RCC_BackupResetCmd(DISABLE);
}
/*******************************************************************************
* Function Name : BKP_TamperPinLevelConfig
* Description : Configures the Tamper Pin active level.
* Input : - BKP_TamperPinLevel: specifies the Tamper Pin active level.
* This parameter can be one of the following values:
* - BKP_TamperPinLevel_High: Tamper pin active on high level
* - BKP_TamperPinLevel_Low: Tamper pin active on low level
* Output : None
* Return : None
*******************************************************************************/
void BKP_TamperPinLevelConfig(u16 BKP_TamperPinLevel)
{
/* Check the parameters */
assert_param(IS_BKP_TAMPER_PIN_LEVEL(BKP_TamperPinLevel));
*(vu32 *) CR_TPAL_BB = BKP_TamperPinLevel;
}
/*******************************************************************************
* Function Name : BKP_TamperPinCmd
* Description : Enables or disables the Tamper Pin activation.
* Input : - NewState: new state of the Tamper Pin activation.
* This parameter can be: ENABLE or DISABLE.
* Output : None
* Return : None
*******************************************************************************/
void BKP_TamperPinCmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
*(vu32 *) CR_TPE_BB = (u32)NewState;
}
/*******************************************************************************
* Function Name : BKP_ITConfig
* Description : Enables or disables the Tamper Pin Interrupt.
* Input : - NewState: new state of the Tamper Pin Interrupt.
* This parameter can be: ENABLE or DISABLE.
* Output : None
* Return : None
*******************************************************************************/
void BKP_ITConfig(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
*(vu32 *) CSR_TPIE_BB = (u32)NewState;
}
/*******************************************************************************
* Function Name : BKP_RTCOutputConfig
* Description : Select the RTC output source to output on the Tamper pin.
* Input : - BKP_RTCOutputSource: specifies the RTC output source.
* This parameter can be one of the following values:
* - BKP_RTCOutputSource_None: no RTC output on the Tamper pin.
* - BKP_RTCOutputSource_CalibClock: output the RTC clock
* with frequency divided by 64 on the Tamper pin.
* - BKP_RTCOutputSource_Alarm: output the RTC Alarm pulse
* signal on the Tamper pin.
* - BKP_RTCOutputSource_Second: output the RTC Second pulse
* signal on the Tamper pin.
* Output : None
* Return : None
*******************************************************************************/
void BKP_RTCOutputConfig(u16 BKP_RTCOutputSource)
{
u16 tmpreg = 0;
/* Check the parameters */
assert_param(IS_BKP_RTC_OUTPUT_SOURCE(BKP_RTCOutputSource));
tmpreg = BKP->RTCCR;
/* Clear CCO, ASOE and ASOS bits */
tmpreg &= RTCCR_Mask;
/* Set CCO, ASOE and ASOS bits according to BKP_RTCOutputSource value */
tmpreg |= BKP_RTCOutputSource;
/* Store the new value */
BKP->RTCCR = tmpreg;
}
/*******************************************************************************
* Function Name : BKP_SetRTCCalibrationValue
* Description : Sets RTC Clock Calibration value.
* Input : - CalibrationValue: specifies the RTC Clock Calibration value.
* This parameter must be a number between 0 and 0x7F.
* Output : None
* Return : None
*******************************************************************************/
void BKP_SetRTCCalibrationValue(u8 CalibrationValue)
{
u16 tmpreg = 0;
/* Check the parameters */
assert_param(IS_BKP_CALIBRATION_VALUE(CalibrationValue));
tmpreg = BKP->RTCCR;
/* Clear CAL[6:0] bits */
tmpreg &= RTCCR_CAL_Mask;
/* Set CAL[6:0] bits according to CalibrationValue value */
tmpreg |= CalibrationValue;
/* Store the new value */
BKP->RTCCR = tmpreg;
}
/*******************************************************************************
* Function Name : BKP_WriteBackupRegister
* Description : Writes user data to the specified Data Backup Register.
* Input : - BKP_DR: specifies the Data Backup Register.
* This parameter can be BKP_DRx where x:[1, 42]
* - Data: data to write
* Output : None
* Return : None
*******************************************************************************/
void BKP_WriteBackupRegister(u16 BKP_DR, u16 Data)
{
/* Check the parameters */
assert_param(IS_BKP_DR(BKP_DR));
*(vu16 *) (BKP_BASE + BKP_DR) = Data;
}
/*******************************************************************************
* Function Name : BKP_ReadBackupRegister
* Description : Reads data from the specified Data Backup Register.
* Input : - BKP_DR: specifies the Data Backup Register.
* This parameter can be BKP_DRx where x:[1, 42]
* Output : None
* Return : The content of the specified Data Backup Register
*******************************************************************************/
u16 BKP_ReadBackupRegister(u16 BKP_DR)
{
/* Check the parameters */
assert_param(IS_BKP_DR(BKP_DR));
return (*(vu16 *) (BKP_BASE + BKP_DR));
}
/*******************************************************************************
* Function Name : BKP_GetFlagStatus
* Description : Checks whether the Tamper Pin Event flag is set or not.
* Input : None
* Output : None
* Return : The new state of the Tamper Pin Event flag (SET or RESET).
*******************************************************************************/
FlagStatus BKP_GetFlagStatus(void)
{
return (FlagStatus)(*(vu32 *) CSR_TEF_BB);
}
/*******************************************************************************
* Function Name : BKP_ClearFlag
* Description : Clears Tamper Pin Event pending flag.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void BKP_ClearFlag(void)
{
/* Set CTE bit to clear Tamper Pin Event flag */
BKP->CSR |= CSR_CTE_Set;
}
/*******************************************************************************
* Function Name : BKP_GetITStatus
* Description : Checks whether the Tamper Pin Interrupt has occurred or not.
* Input : None
* Output : None
* Return : The new state of the Tamper Pin Interrupt (SET or RESET).
*******************************************************************************/
ITStatus BKP_GetITStatus(void)
{
return (ITStatus)(*(vu32 *) CSR_TIF_BB);
}
/*******************************************************************************
* Function Name : BKP_ClearITPendingBit
* Description : Clears Tamper Pin Interrupt pending bit.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void BKP_ClearITPendingBit(void)
{
/* Set CTI bit to clear Tamper Pin Interrupt pending bit */
BKP->CSR |= CSR_CTI_Set;
}
/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/

File diff suppressed because it is too large Load Diff

View File

@ -1,114 +1,114 @@
/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
* File Name : stm32f10x_crc.c
* Author : MCD Application Team
* Version : V2.0.3
* Date : 09/22/2008
* Description : This file provides all the CRC firmware functions.
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x_crc.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* CR register bit mask */
#define CR_RESET_Set ((u32)0x00000001)
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : CRC_ResetDR
* Description : Resets the CRC Data register (DR).
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void CRC_ResetDR(void)
{
/* Reset CRC generator */
CRC->CR = CR_RESET_Set;
}
/*******************************************************************************
* Function Name : CRC_CalcCRC
* Description : Computes the 32-bit CRC of a given data word(32-bit).
* Input : - Data: data word(32-bit) to compute its CRC
* Output : None
* Return : 32-bit CRC
*******************************************************************************/
u32 CRC_CalcCRC(u32 Data)
{
CRC->DR = Data;
return (CRC->DR);
}
/*******************************************************************************
* Function Name : CRC_CalcBlockCRC
* Description : Computes the 32-bit CRC of a given buffer of data word(32-bit).
* Input : - pBuffer: pointer to the buffer containing the data to be
* computed
* - BufferLength: length of the buffer to be computed
* Output : None
* Return : 32-bit CRC
*******************************************************************************/
u32 CRC_CalcBlockCRC(u32 pBuffer[], u32 BufferLength)
{
u32 index = 0;
for(index = 0; index < BufferLength; index++)
{
CRC->DR = pBuffer[index];
}
return (CRC->DR);
}
/*******************************************************************************
* Function Name : CRC_GetCRC
* Description : Returns the current CRC value.
* Input : None
* Output : None
* Return : 32-bit CRC
*******************************************************************************/
u32 CRC_GetCRC(void)
{
return (CRC->DR);
}
/*******************************************************************************
* Function Name : CRC_SetIDRegister
* Description : Stores a 8-bit data in the Independent Data(ID) register.
* Input : - IDValue: 8-bit value to be stored in the ID register
* Output : None
* Return : None
*******************************************************************************/
void CRC_SetIDRegister(u8 IDValue)
{
CRC->IDR = IDValue;
}
/*******************************************************************************
* Function Name : CRC_GetIDRegister
* Description : Returns the 8-bit data stored in the Independent Data(ID) register
* Input : None
* Output : None
* Return : 8-bit value of the ID register
*******************************************************************************/
u8 CRC_GetIDRegister(void)
{
return (CRC->IDR);
}
/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
* File Name : stm32f10x_crc.c
* Author : MCD Application Team
* Version : V2.0.3
* Date : 09/22/2008
* Description : This file provides all the CRC firmware functions.
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x_crc.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* CR register bit mask */
#define CR_RESET_Set ((u32)0x00000001)
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : CRC_ResetDR
* Description : Resets the CRC Data register (DR).
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void CRC_ResetDR(void)
{
/* Reset CRC generator */
CRC->CR = CR_RESET_Set;
}
/*******************************************************************************
* Function Name : CRC_CalcCRC
* Description : Computes the 32-bit CRC of a given data word(32-bit).
* Input : - Data: data word(32-bit) to compute its CRC
* Output : None
* Return : 32-bit CRC
*******************************************************************************/
u32 CRC_CalcCRC(u32 Data)
{
CRC->DR = Data;
return (CRC->DR);
}
/*******************************************************************************
* Function Name : CRC_CalcBlockCRC
* Description : Computes the 32-bit CRC of a given buffer of data word(32-bit).
* Input : - pBuffer: pointer to the buffer containing the data to be
* computed
* - BufferLength: length of the buffer to be computed
* Output : None
* Return : 32-bit CRC
*******************************************************************************/
u32 CRC_CalcBlockCRC(u32 pBuffer[], u32 BufferLength)
{
u32 index = 0;
for(index = 0; index < BufferLength; index++)
{
CRC->DR = pBuffer[index];
}
return (CRC->DR);
}
/*******************************************************************************
* Function Name : CRC_GetCRC
* Description : Returns the current CRC value.
* Input : None
* Output : None
* Return : 32-bit CRC
*******************************************************************************/
u32 CRC_GetCRC(void)
{
return (CRC->DR);
}
/*******************************************************************************
* Function Name : CRC_SetIDRegister
* Description : Stores a 8-bit data in the Independent Data(ID) register.
* Input : - IDValue: 8-bit value to be stored in the ID register
* Output : None
* Return : None
*******************************************************************************/
void CRC_SetIDRegister(u8 IDValue)
{
CRC->IDR = IDValue;
}
/*******************************************************************************
* Function Name : CRC_GetIDRegister
* Description : Returns the 8-bit data stored in the Independent Data(ID) register
* Input : None
* Output : None
* Return : 8-bit value of the ID register
*******************************************************************************/
u8 CRC_GetIDRegister(void)
{
return (CRC->IDR);
}
/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/

View File

@ -1,389 +1,389 @@
/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
* File Name : stm32f10x_dac.c
* Author : MCD Application Team
* Version : V2.0.3
* Date : 09/22/2008
* Description : This file provides all the DAC firmware functions.
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x_dac.h"
#include "stm32f10x_rcc.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* DAC EN mask */
#define CR_EN_Set ((u32)0x00000001)
/* DAC DMAEN mask */
#define CR_DMAEN_Set ((u32)0x00001000)
/* CR register Mask */
#define CR_CLEAR_Mask ((u32)0x00000FFE)
/* DAC SWTRIG mask */
#define SWTRIGR_SWTRIG_Set ((u32)0x00000001)
/* DAC Dual Channels SWTRIG masks */
#define DUAL_SWTRIG_Set ((u32)0x00000003)
#define DUAL_SWTRIG_Reset ((u32)0xFFFFFFFC)
/* DHR registers offsets */
#define DHR12R1_Offset ((u32)0x00000008)
#define DHR12R2_Offset ((u32)0x00000014)
#define DHR12RD_Offset ((u32)0x00000020)
/* DOR register offset */
#define DOR_Offset ((u32)0x0000002C)
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : DAC_DeInit
* Description : Deinitializes the DAC peripheral registers to their default
* reset values.
* Input : None.
* Output : None
* Return : None
*******************************************************************************/
void DAC_DeInit(void)
{
/* Enable DAC reset state */
RCC_APB1PeriphResetCmd(RCC_APB1Periph_DAC, ENABLE);
/* Release DAC from reset state */
RCC_APB1PeriphResetCmd(RCC_APB1Periph_DAC, DISABLE);
}
/*******************************************************************************
* Function Name : DAC_Init
* Description : Initializes the DAC peripheral according to the specified
* parameters in the DAC_InitStruct.
* Input : - DAC_Channel: the selected DAC channel.
* This parameter can be one of the following values:
* - DAC_Channel_1: DAC Channel1 selected
* - DAC_Channel_2: DAC Channel2 selected
* - DAC_InitStruct: pointer to a DAC_InitTypeDef structure that
* contains the configuration information for the specified
* DAC channel.
* Output : None
* Return : None
*******************************************************************************/
void DAC_Init(u32 DAC_Channel, DAC_InitTypeDef* DAC_InitStruct)
{
u32 tmpreg1 = 0, tmpreg2 = 0;
/* Check the DAC parameters */
assert_param(IS_DAC_TRIGGER(DAC_InitStruct->DAC_Trigger));
assert_param(IS_DAC_GENERATE_WAVE(DAC_InitStruct->DAC_WaveGeneration));
assert_param(IS_DAC_LFSR_UNMASK_TRIANGLE_AMPLITUDE(DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude));
assert_param(IS_DAC_OUTPUT_BUFFER_STATE(DAC_InitStruct->DAC_OutputBuffer));
/*---------------------------- DAC CR Configuration --------------------------*/
/* Get the DAC CR value */
tmpreg1 = DAC->CR;
/* Clear BOFFx, TENx, TSELx, WAVEx and MAMPx bits */
tmpreg1 &= ~(CR_CLEAR_Mask << DAC_Channel);
/* Configure for the selected DAC channel: buffer output, trigger, wave genration,
mask/amplitude for wave genration */
/* Set TSELx and TENx bits according to DAC_Trigger value */
/* Set WAVEx bits according to DAC_WaveGeneration value */
/* Set MAMPx bits according to DAC_LFSRUnmask_TriangleAmplitude value */
/* Set BOFFx bit according to DAC_OutputBuffer value */
tmpreg2 = (DAC_InitStruct->DAC_Trigger | DAC_InitStruct->DAC_WaveGeneration |
DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude | DAC_InitStruct->DAC_OutputBuffer);
/* Calculate CR register value depending on DAC_Channel */
tmpreg1 |= tmpreg2 << DAC_Channel;
/* Write to DAC CR */
DAC->CR = tmpreg1;
}
/*******************************************************************************
* Function Name : DAC_StructInit
* Description : Fills each DAC_InitStruct member with its default value.
* Input : - DAC_InitStruct : pointer to a DAC_InitTypeDef structure
* which will be initialized.
* Output : None
* Return : None
*******************************************************************************/
void DAC_StructInit(DAC_InitTypeDef* DAC_InitStruct)
{
/*--------------- Reset DAC init structure parameters values -----------------*/
/* Initialize the DAC_Trigger member */
DAC_InitStruct->DAC_Trigger = DAC_Trigger_None;
/* Initialize the DAC_WaveGeneration member */
DAC_InitStruct->DAC_WaveGeneration = DAC_WaveGeneration_None;
/* Initialize the DAC_LFSRUnmask_TriangleAmplitude member */
DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude = DAC_LFSRUnmask_Bit0;
/* Initialize the DAC_OutputBuffer member */
DAC_InitStruct->DAC_OutputBuffer = DAC_OutputBuffer_Enable;
}
/*******************************************************************************
* Function Name : DAC_Cmd
* Description : Enables or disables the specified DAC channel.
* Input - DAC_Channel: the selected DAC channel.
* This parameter can be one of the following values:
* - DAC_Channel_1: DAC Channel1 selected
* - DAC_Channel_2: DAC Channel2 selected
* - NewState: new state of the DAC channel.
* This parameter can be: ENABLE or DISABLE.
* Output : None
* Return : None
*******************************************************************************/
void DAC_Cmd(u32 DAC_Channel, FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_DAC_CHANNEL(DAC_Channel));
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the selected DAC channel */
DAC->CR |= CR_EN_Set << DAC_Channel;
}
else
{
/* Disable the selected DAC channel */
DAC->CR &= ~(CR_EN_Set << DAC_Channel);
}
}
/*******************************************************************************
* Function Name : DAC_DMACmd
* Description : Enables or disables the specified DAC channel DMA request.
* Input - DAC_Channel: the selected DAC channel.
* This parameter can be one of the following values:
* - DAC_Channel_1: DAC Channel1 selected
* - DAC_Channel_2: DAC Channel2 selected
* - NewState: new state of the selected DAC channel DMA request.
* This parameter can be: ENABLE or DISABLE.
* Output : None
* Return : None
*******************************************************************************/
void DAC_DMACmd(u32 DAC_Channel, FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_DAC_CHANNEL(DAC_Channel));
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the selected DAC channel DMA request */
DAC->CR |= CR_DMAEN_Set << DAC_Channel;
}
else
{
/* Disable the selected DAC channel DMA request */
DAC->CR &= ~(CR_DMAEN_Set << DAC_Channel);
}
}
/*******************************************************************************
* Function Name : DAC_SoftwareTriggerCmd
* Description : Enables or disables the selected DAC channel software trigger.
* Input - DAC_Channel: the selected DAC channel.
* This parameter can be one of the following values:
* - DAC_Channel_1: DAC Channel1 selected
* - DAC_Channel_2: DAC Channel2 selected
* - NewState: new state of the selected DAC channel software trigger.
* This parameter can be: ENABLE or DISABLE.
* Output : None
* Return : None
*******************************************************************************/
void DAC_SoftwareTriggerCmd(u32 DAC_Channel, FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_DAC_CHANNEL(DAC_Channel));
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable software trigger for the selected DAC channel */
DAC->SWTRIGR |= SWTRIGR_SWTRIG_Set << (DAC_Channel >> 4);
}
else
{
/* Disable software trigger for the selected DAC channel */
DAC->SWTRIGR &= ~(SWTRIGR_SWTRIG_Set << (DAC_Channel >> 4));
}
}
/*******************************************************************************
* Function Name : DAC_DualSoftwareTriggerCmd
* Description : Enables or disables simultaneously the two DAC channels software
* triggers.
* Input - NewState: new state of the DAC channels software triggers.
* This parameter can be: ENABLE or DISABLE.
* Output : None
* Return : None
*******************************************************************************/
void DAC_DualSoftwareTriggerCmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable software trigger for both DAC channels */
DAC->SWTRIGR |= DUAL_SWTRIG_Set ;
}
else
{
/* Disable software trigger for both DAC channels */
DAC->SWTRIGR &= DUAL_SWTRIG_Reset;
}
}
/*******************************************************************************
* Function Name : DAC_WaveGenerationCmd
* Description : Enables or disables the selected DAC channel wave generation.
* Input - DAC_Channel: the selected DAC channel.
* This parameter can be one of the following values:
* - DAC_Channel_1: DAC Channel1 selected
* - DAC_Channel_2: DAC Channel2 selected
* - DAC_Wave: Specifies the wave type to enable or disable.
* This parameter can be one of the following values:
* - DAC_Wave_Noise: noise wave generation
* - DAC_Wave_Triangle: triangle wave generation
* - NewState: new state of the selected DAC channel wave generation.
* This parameter can be: ENABLE or DISABLE.
* Output : None
* Return : None
*******************************************************************************/
void DAC_WaveGenerationCmd(u32 DAC_Channel, u32 DAC_Wave, FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_DAC_CHANNEL(DAC_Channel));
assert_param(IS_DAC_WAVE(DAC_Wave));
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the selected wave generation for the selected DAC channel */
DAC->CR |= DAC_Wave << DAC_Channel;
}
else
{
/* Disable the selected wave generation for the selected DAC channel */
DAC->CR &= ~(DAC_Wave << DAC_Channel);
}
}
/*******************************************************************************
* Function Name : DAC_SetChannel1Data
* Description : Set the specified data holding register value for DAC channel1.
* Input : - DAC_Align: Specifies the data alignement for DAC channel1.
* This parameter can be one of the following values:
* - DAC_Align_8b_R: 8bit right data alignement selected
* - DAC_Align_12b_L: 12bit left data alignement selected
* - DAC_Align_12b_R: 12bit right data alignement selected
* - Data : Data to be loaded in the selected data holding
* register.
* Output : None
* Return : None
*******************************************************************************/
void DAC_SetChannel1Data(u32 DAC_Align, u16 Data)
{
/* Check the parameters */
assert_param(IS_DAC_ALIGN(DAC_Align));
assert_param(IS_DAC_DATA(Data));
/* Set the DAC channel1 selected data holding register */
*((vu32 *)(DAC_BASE + DHR12R1_Offset + DAC_Align)) = (u32)Data;
}
/*******************************************************************************
* Function Name : DAC_SetChannel2Data
* Description : Set the specified data holding register value for DAC channel2.
* Input : - DAC_Align: Specifies the data alignement for DAC channel2.
* This parameter can be one of the following values:
* - DAC_Align_8b_R: 8bit right data alignement selected
* - DAC_Align_12b_L: 12bit left data alignement selected
* - DAC_Align_12b_R: 12bit right data alignement selected
* - Data : Data to be loaded in the selected data holding
* register.
* Output : None
* Return : None
*******************************************************************************/
void DAC_SetChannel2Data(u32 DAC_Align, u16 Data)
{
/* Check the parameters */
assert_param(IS_DAC_ALIGN(DAC_Align));
assert_param(IS_DAC_DATA(Data));
/* Set the DAC channel2 selected data holding register */
*((vu32 *)(DAC_BASE + DHR12R2_Offset + DAC_Align)) = (u32)Data;
}
/*******************************************************************************
* Function Name : DAC_SetDualChannelData
* Description : Set the specified data holding register value for dual channel
* DAC.
* Input : - DAC_Align: Specifies the data alignement for dual channel DAC.
* This parameter can be one of the following values:
* - DAC_Align_8b_R: 8bit right data alignement selected
* - DAC_Align_12b_L: 12bit left data alignement selected
* - DAC_Align_12b_R: 12bit right data alignement selected
* - Data2: Data for DAC Channel2 to be loaded in the selected data
* holding register.
* - Data1: Data for DAC Channel1 to be loaded in the selected data
* holding register.
* Output : None
* Return : None
*******************************************************************************/
void DAC_SetDualChannelData(u32 DAC_Align, u16 Data2, u16 Data1)
{
u32 data = 0;
/* Check the parameters */
assert_param(IS_DAC_ALIGN(DAC_Align));
assert_param(IS_DAC_DATA(Data1));
assert_param(IS_DAC_DATA(Data2));
/* Calculate and set dual DAC data holding register value */
if (DAC_Align == DAC_Align_8b_R)
{
data = ((u32)Data2 << 8) | Data1;
}
else
{
data = ((u32)Data2 << 16) | Data1;
}
/* Set the dual DAC selected data holding register */
*((vu32 *)(DAC_BASE + DHR12RD_Offset + DAC_Align)) = data;
}
/*******************************************************************************
* Function Name : DAC_GetDataOutputValue
* Description : Returns the last data output value of the selected DAC cahnnel.
* Input - DAC_Channel: the selected DAC channel.
* This parameter can be one of the following values:
* - DAC_Channel_1: DAC Channel1 selected
* - DAC_Channel_2: DAC Channel2 selected
* Output : None
* Return : The selected DAC channel data output value.
*******************************************************************************/
u16 DAC_GetDataOutputValue(u32 DAC_Channel)
{
/* Check the parameters */
assert_param(IS_DAC_CHANNEL(DAC_Channel));
/* Returns the DAC channel data output register value */
return (u16) (*(vu32*)(DAC_BASE + DOR_Offset + ((u32)DAC_Channel >> 2)));
}
/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
* File Name : stm32f10x_dac.c
* Author : MCD Application Team
* Version : V2.0.3
* Date : 09/22/2008
* Description : This file provides all the DAC firmware functions.
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x_dac.h"
#include "stm32f10x_rcc.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* DAC EN mask */
#define CR_EN_Set ((u32)0x00000001)
/* DAC DMAEN mask */
#define CR_DMAEN_Set ((u32)0x00001000)
/* CR register Mask */
#define CR_CLEAR_Mask ((u32)0x00000FFE)
/* DAC SWTRIG mask */
#define SWTRIGR_SWTRIG_Set ((u32)0x00000001)
/* DAC Dual Channels SWTRIG masks */
#define DUAL_SWTRIG_Set ((u32)0x00000003)
#define DUAL_SWTRIG_Reset ((u32)0xFFFFFFFC)
/* DHR registers offsets */
#define DHR12R1_Offset ((u32)0x00000008)
#define DHR12R2_Offset ((u32)0x00000014)
#define DHR12RD_Offset ((u32)0x00000020)
/* DOR register offset */
#define DOR_Offset ((u32)0x0000002C)
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : DAC_DeInit
* Description : Deinitializes the DAC peripheral registers to their default
* reset values.
* Input : None.
* Output : None
* Return : None
*******************************************************************************/
void DAC_DeInit(void)
{
/* Enable DAC reset state */
RCC_APB1PeriphResetCmd(RCC_APB1Periph_DAC, ENABLE);
/* Release DAC from reset state */
RCC_APB1PeriphResetCmd(RCC_APB1Periph_DAC, DISABLE);
}
/*******************************************************************************
* Function Name : DAC_Init
* Description : Initializes the DAC peripheral according to the specified
* parameters in the DAC_InitStruct.
* Input : - DAC_Channel: the selected DAC channel.
* This parameter can be one of the following values:
* - DAC_Channel_1: DAC Channel1 selected
* - DAC_Channel_2: DAC Channel2 selected
* - DAC_InitStruct: pointer to a DAC_InitTypeDef structure that
* contains the configuration information for the specified
* DAC channel.
* Output : None
* Return : None
*******************************************************************************/
void DAC_Init(u32 DAC_Channel, DAC_InitTypeDef* DAC_InitStruct)
{
u32 tmpreg1 = 0, tmpreg2 = 0;
/* Check the DAC parameters */
assert_param(IS_DAC_TRIGGER(DAC_InitStruct->DAC_Trigger));
assert_param(IS_DAC_GENERATE_WAVE(DAC_InitStruct->DAC_WaveGeneration));
assert_param(IS_DAC_LFSR_UNMASK_TRIANGLE_AMPLITUDE(DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude));
assert_param(IS_DAC_OUTPUT_BUFFER_STATE(DAC_InitStruct->DAC_OutputBuffer));
/*---------------------------- DAC CR Configuration --------------------------*/
/* Get the DAC CR value */
tmpreg1 = DAC->CR;
/* Clear BOFFx, TENx, TSELx, WAVEx and MAMPx bits */
tmpreg1 &= ~(CR_CLEAR_Mask << DAC_Channel);
/* Configure for the selected DAC channel: buffer output, trigger, wave genration,
mask/amplitude for wave genration */
/* Set TSELx and TENx bits according to DAC_Trigger value */
/* Set WAVEx bits according to DAC_WaveGeneration value */
/* Set MAMPx bits according to DAC_LFSRUnmask_TriangleAmplitude value */
/* Set BOFFx bit according to DAC_OutputBuffer value */
tmpreg2 = (DAC_InitStruct->DAC_Trigger | DAC_InitStruct->DAC_WaveGeneration |
DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude | DAC_InitStruct->DAC_OutputBuffer);
/* Calculate CR register value depending on DAC_Channel */
tmpreg1 |= tmpreg2 << DAC_Channel;
/* Write to DAC CR */
DAC->CR = tmpreg1;
}
/*******************************************************************************
* Function Name : DAC_StructInit
* Description : Fills each DAC_InitStruct member with its default value.
* Input : - DAC_InitStruct : pointer to a DAC_InitTypeDef structure
* which will be initialized.
* Output : None
* Return : None
*******************************************************************************/
void DAC_StructInit(DAC_InitTypeDef* DAC_InitStruct)
{
/*--------------- Reset DAC init structure parameters values -----------------*/
/* Initialize the DAC_Trigger member */
DAC_InitStruct->DAC_Trigger = DAC_Trigger_None;
/* Initialize the DAC_WaveGeneration member */
DAC_InitStruct->DAC_WaveGeneration = DAC_WaveGeneration_None;
/* Initialize the DAC_LFSRUnmask_TriangleAmplitude member */
DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude = DAC_LFSRUnmask_Bit0;
/* Initialize the DAC_OutputBuffer member */
DAC_InitStruct->DAC_OutputBuffer = DAC_OutputBuffer_Enable;
}
/*******************************************************************************
* Function Name : DAC_Cmd
* Description : Enables or disables the specified DAC channel.
* Input - DAC_Channel: the selected DAC channel.
* This parameter can be one of the following values:
* - DAC_Channel_1: DAC Channel1 selected
* - DAC_Channel_2: DAC Channel2 selected
* - NewState: new state of the DAC channel.
* This parameter can be: ENABLE or DISABLE.
* Output : None
* Return : None
*******************************************************************************/
void DAC_Cmd(u32 DAC_Channel, FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_DAC_CHANNEL(DAC_Channel));
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the selected DAC channel */
DAC->CR |= CR_EN_Set << DAC_Channel;
}
else
{
/* Disable the selected DAC channel */
DAC->CR &= ~(CR_EN_Set << DAC_Channel);
}
}
/*******************************************************************************
* Function Name : DAC_DMACmd
* Description : Enables or disables the specified DAC channel DMA request.
* Input - DAC_Channel: the selected DAC channel.
* This parameter can be one of the following values:
* - DAC_Channel_1: DAC Channel1 selected
* - DAC_Channel_2: DAC Channel2 selected
* - NewState: new state of the selected DAC channel DMA request.
* This parameter can be: ENABLE or DISABLE.
* Output : None
* Return : None
*******************************************************************************/
void DAC_DMACmd(u32 DAC_Channel, FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_DAC_CHANNEL(DAC_Channel));
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the selected DAC channel DMA request */
DAC->CR |= CR_DMAEN_Set << DAC_Channel;
}
else
{
/* Disable the selected DAC channel DMA request */
DAC->CR &= ~(CR_DMAEN_Set << DAC_Channel);
}
}
/*******************************************************************************
* Function Name : DAC_SoftwareTriggerCmd
* Description : Enables or disables the selected DAC channel software trigger.
* Input - DAC_Channel: the selected DAC channel.
* This parameter can be one of the following values:
* - DAC_Channel_1: DAC Channel1 selected
* - DAC_Channel_2: DAC Channel2 selected
* - NewState: new state of the selected DAC channel software trigger.
* This parameter can be: ENABLE or DISABLE.
* Output : None
* Return : None
*******************************************************************************/
void DAC_SoftwareTriggerCmd(u32 DAC_Channel, FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_DAC_CHANNEL(DAC_Channel));
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable software trigger for the selected DAC channel */
DAC->SWTRIGR |= SWTRIGR_SWTRIG_Set << (DAC_Channel >> 4);
}
else
{
/* Disable software trigger for the selected DAC channel */
DAC->SWTRIGR &= ~(SWTRIGR_SWTRIG_Set << (DAC_Channel >> 4));
}
}
/*******************************************************************************
* Function Name : DAC_DualSoftwareTriggerCmd
* Description : Enables or disables simultaneously the two DAC channels software
* triggers.
* Input - NewState: new state of the DAC channels software triggers.
* This parameter can be: ENABLE or DISABLE.
* Output : None
* Return : None
*******************************************************************************/
void DAC_DualSoftwareTriggerCmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable software trigger for both DAC channels */
DAC->SWTRIGR |= DUAL_SWTRIG_Set ;
}
else
{
/* Disable software trigger for both DAC channels */
DAC->SWTRIGR &= DUAL_SWTRIG_Reset;
}
}
/*******************************************************************************
* Function Name : DAC_WaveGenerationCmd
* Description : Enables or disables the selected DAC channel wave generation.
* Input - DAC_Channel: the selected DAC channel.
* This parameter can be one of the following values:
* - DAC_Channel_1: DAC Channel1 selected
* - DAC_Channel_2: DAC Channel2 selected
* - DAC_Wave: Specifies the wave type to enable or disable.
* This parameter can be one of the following values:
* - DAC_Wave_Noise: noise wave generation
* - DAC_Wave_Triangle: triangle wave generation
* - NewState: new state of the selected DAC channel wave generation.
* This parameter can be: ENABLE or DISABLE.
* Output : None
* Return : None
*******************************************************************************/
void DAC_WaveGenerationCmd(u32 DAC_Channel, u32 DAC_Wave, FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_DAC_CHANNEL(DAC_Channel));
assert_param(IS_DAC_WAVE(DAC_Wave));
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
/* Enable the selected wave generation for the selected DAC channel */
DAC->CR |= DAC_Wave << DAC_Channel;
}
else
{
/* Disable the selected wave generation for the selected DAC channel */
DAC->CR &= ~(DAC_Wave << DAC_Channel);
}
}
/*******************************************************************************
* Function Name : DAC_SetChannel1Data
* Description : Set the specified data holding register value for DAC channel1.
* Input : - DAC_Align: Specifies the data alignement for DAC channel1.
* This parameter can be one of the following values:
* - DAC_Align_8b_R: 8bit right data alignement selected
* - DAC_Align_12b_L: 12bit left data alignement selected
* - DAC_Align_12b_R: 12bit right data alignement selected
* - Data : Data to be loaded in the selected data holding
* register.
* Output : None
* Return : None
*******************************************************************************/
void DAC_SetChannel1Data(u32 DAC_Align, u16 Data)
{
/* Check the parameters */
assert_param(IS_DAC_ALIGN(DAC_Align));
assert_param(IS_DAC_DATA(Data));
/* Set the DAC channel1 selected data holding register */
*((vu32 *)(DAC_BASE + DHR12R1_Offset + DAC_Align)) = (u32)Data;
}
/*******************************************************************************
* Function Name : DAC_SetChannel2Data
* Description : Set the specified data holding register value for DAC channel2.
* Input : - DAC_Align: Specifies the data alignement for DAC channel2.
* This parameter can be one of the following values:
* - DAC_Align_8b_R: 8bit right data alignement selected
* - DAC_Align_12b_L: 12bit left data alignement selected
* - DAC_Align_12b_R: 12bit right data alignement selected
* - Data : Data to be loaded in the selected data holding
* register.
* Output : None
* Return : None
*******************************************************************************/
void DAC_SetChannel2Data(u32 DAC_Align, u16 Data)
{
/* Check the parameters */
assert_param(IS_DAC_ALIGN(DAC_Align));
assert_param(IS_DAC_DATA(Data));
/* Set the DAC channel2 selected data holding register */
*((vu32 *)(DAC_BASE + DHR12R2_Offset + DAC_Align)) = (u32)Data;
}
/*******************************************************************************
* Function Name : DAC_SetDualChannelData
* Description : Set the specified data holding register value for dual channel
* DAC.
* Input : - DAC_Align: Specifies the data alignement for dual channel DAC.
* This parameter can be one of the following values:
* - DAC_Align_8b_R: 8bit right data alignement selected
* - DAC_Align_12b_L: 12bit left data alignement selected
* - DAC_Align_12b_R: 12bit right data alignement selected
* - Data2: Data for DAC Channel2 to be loaded in the selected data
* holding register.
* - Data1: Data for DAC Channel1 to be loaded in the selected data
* holding register.
* Output : None
* Return : None
*******************************************************************************/
void DAC_SetDualChannelData(u32 DAC_Align, u16 Data2, u16 Data1)
{
u32 data = 0;
/* Check the parameters */
assert_param(IS_DAC_ALIGN(DAC_Align));
assert_param(IS_DAC_DATA(Data1));
assert_param(IS_DAC_DATA(Data2));
/* Calculate and set dual DAC data holding register value */
if (DAC_Align == DAC_Align_8b_R)
{
data = ((u32)Data2 << 8) | Data1;
}
else
{
data = ((u32)Data2 << 16) | Data1;
}
/* Set the dual DAC selected data holding register */
*((vu32 *)(DAC_BASE + DHR12RD_Offset + DAC_Align)) = data;
}
/*******************************************************************************
* Function Name : DAC_GetDataOutputValue
* Description : Returns the last data output value of the selected DAC cahnnel.
* Input - DAC_Channel: the selected DAC channel.
* This parameter can be one of the following values:
* - DAC_Channel_1: DAC Channel1 selected
* - DAC_Channel_2: DAC Channel2 selected
* Output : None
* Return : The selected DAC channel data output value.
*******************************************************************************/
u16 DAC_GetDataOutputValue(u32 DAC_Channel)
{
/* Check the parameters */
assert_param(IS_DAC_CHANNEL(DAC_Channel));
/* Returns the DAC channel data output register value */
return (u16) (*(vu32*)(DAC_BASE + DOR_Offset + ((u32)DAC_Channel >> 2)));
}
/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/

View File

@ -1,97 +1,97 @@
/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
* File Name : stm32f10x_dbgmcu.c
* Author : MCD Application Team
* Version : V2.0.3
* Date : 09/22/2008
* Description : This file provides all the DBGMCU firmware functions.
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x_dbgmcu.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
#define IDCODE_DEVID_Mask ((u32)0x00000FFF)
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : DBGMCU_GetREVID
* Description : Returns the device revision identifier.
* Input : None
* Output : None
* Return : Device revision identifier
*******************************************************************************/
u32 DBGMCU_GetREVID(void)
{
return(DBGMCU->IDCODE >> 16);
}
/*******************************************************************************
* Function Name : DBGMCU_GetDEVID
* Description : Returns the device identifier.
* Input : None
* Output : None
* Return : Device identifier
*******************************************************************************/
u32 DBGMCU_GetDEVID(void)
{
return(DBGMCU->IDCODE & IDCODE_DEVID_Mask);
}
/*******************************************************************************
* Function Name : DBGMCU_Config
* Description : Configures the specified peripheral and low power mode behavior
* when the MCU under Debug mode.
* Input : - DBGMCU_Periph: specifies the peripheral and low power mode.
* This parameter can be any combination of the following values:
* - DBGMCU_SLEEP: Keep debugger connection during SLEEP mode
* - DBGMCU_STOP: Keep debugger connection during STOP mode
* - DBGMCU_STANDBY: Keep debugger connection during STANDBY mode
* - DBGMCU_IWDG_STOP: Debug IWDG stopped when Core is halted
* - DBGMCU_WWDG_STOP: Debug WWDG stopped when Core is halted
* - DBGMCU_TIM1_STOP: TIM1 counter stopped when Core is halted
* - DBGMCU_TIM2_STOP: TIM2 counter stopped when Core is halted
* - DBGMCU_TIM3_STOP: TIM3 counter stopped when Core is halted
* - DBGMCU_TIM4_STOP: TIM4 counter stopped when Core is halted
* - DBGMCU_CAN_STOP: Debug CAN stopped when Core is halted
* - DBGMCU_I2C1_SMBUS_TIMEOUT: I2C1 SMBUS timeout mode stopped
* when Core is halted
* - DBGMCU_I2C2_SMBUS_TIMEOUT: I2C2 SMBUS timeout mode stopped
* when Core is halted
* - DBGMCU_TIM5_STOP: TIM5 counter stopped when Core is halted
* - DBGMCU_TIM6_STOP: TIM6 counter stopped when Core is halted
* - DBGMCU_TIM7_STOP: TIM7 counter stopped when Core is halted
* - DBGMCU_TIM8_STOP: TIM8 counter stopped when Core is halted
* - NewState: new state of the specified peripheral in Debug mode.
* This parameter can be: ENABLE or DISABLE.
* Output : None
* Return : None
*******************************************************************************/
void DBGMCU_Config(u32 DBGMCU_Periph, FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_DBGMCU_PERIPH(DBGMCU_Periph));
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
DBGMCU->CR |= DBGMCU_Periph;
}
else
{
DBGMCU->CR &= ~DBGMCU_Periph;
}
}
/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
* File Name : stm32f10x_dbgmcu.c
* Author : MCD Application Team
* Version : V2.0.3
* Date : 09/22/2008
* Description : This file provides all the DBGMCU firmware functions.
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x_dbgmcu.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
#define IDCODE_DEVID_Mask ((u32)0x00000FFF)
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : DBGMCU_GetREVID
* Description : Returns the device revision identifier.
* Input : None
* Output : None
* Return : Device revision identifier
*******************************************************************************/
u32 DBGMCU_GetREVID(void)
{
return(DBGMCU->IDCODE >> 16);
}
/*******************************************************************************
* Function Name : DBGMCU_GetDEVID
* Description : Returns the device identifier.
* Input : None
* Output : None
* Return : Device identifier
*******************************************************************************/
u32 DBGMCU_GetDEVID(void)
{
return(DBGMCU->IDCODE & IDCODE_DEVID_Mask);
}
/*******************************************************************************
* Function Name : DBGMCU_Config
* Description : Configures the specified peripheral and low power mode behavior
* when the MCU under Debug mode.
* Input : - DBGMCU_Periph: specifies the peripheral and low power mode.
* This parameter can be any combination of the following values:
* - DBGMCU_SLEEP: Keep debugger connection during SLEEP mode
* - DBGMCU_STOP: Keep debugger connection during STOP mode
* - DBGMCU_STANDBY: Keep debugger connection during STANDBY mode
* - DBGMCU_IWDG_STOP: Debug IWDG stopped when Core is halted
* - DBGMCU_WWDG_STOP: Debug WWDG stopped when Core is halted
* - DBGMCU_TIM1_STOP: TIM1 counter stopped when Core is halted
* - DBGMCU_TIM2_STOP: TIM2 counter stopped when Core is halted
* - DBGMCU_TIM3_STOP: TIM3 counter stopped when Core is halted
* - DBGMCU_TIM4_STOP: TIM4 counter stopped when Core is halted
* - DBGMCU_CAN_STOP: Debug CAN stopped when Core is halted
* - DBGMCU_I2C1_SMBUS_TIMEOUT: I2C1 SMBUS timeout mode stopped
* when Core is halted
* - DBGMCU_I2C2_SMBUS_TIMEOUT: I2C2 SMBUS timeout mode stopped
* when Core is halted
* - DBGMCU_TIM5_STOP: TIM5 counter stopped when Core is halted
* - DBGMCU_TIM6_STOP: TIM6 counter stopped when Core is halted
* - DBGMCU_TIM7_STOP: TIM7 counter stopped when Core is halted
* - DBGMCU_TIM8_STOP: TIM8 counter stopped when Core is halted
* - NewState: new state of the specified peripheral in Debug mode.
* This parameter can be: ENABLE or DISABLE.
* Output : None
* Return : None
*******************************************************************************/
void DBGMCU_Config(u32 DBGMCU_Periph, FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_DBGMCU_PERIPH(DBGMCU_Periph));
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
DBGMCU->CR |= DBGMCU_Periph;
}
else
{
DBGMCU->CR &= ~DBGMCU_Periph;
}
}
/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/

File diff suppressed because it is too large Load Diff

View File

@ -1,219 +1,219 @@
/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
* File Name : stm32f10x_exti.c
* Author : MCD Application Team
* Version : V2.0.3
* Date : 09/22/2008
* Description : This file provides all the EXTI firmware functions.
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x_exti.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
#define EXTI_LineNone ((u32)0x00000) /* No interrupt selected */
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : EXTI_DeInit
* Description : Deinitializes the EXTI peripheral registers to their default
* reset values.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void EXTI_DeInit(void)
{
EXTI->IMR = 0x00000000;
EXTI->EMR = 0x00000000;
EXTI->RTSR = 0x00000000;
EXTI->FTSR = 0x00000000;
EXTI->PR = 0x0007FFFF;
}
/*******************************************************************************
* Function Name : EXTI_Init
* Description : Initializes the EXTI peripheral according to the specified
* parameters in the EXTI_InitStruct.
* Input : - EXTI_InitStruct: pointer to a EXTI_InitTypeDef structure
* that contains the configuration information for the EXTI
* peripheral.
* Output : None
* Return : None
*******************************************************************************/
void EXTI_Init(EXTI_InitTypeDef* EXTI_InitStruct)
{
/* Check the parameters */
assert_param(IS_EXTI_MODE(EXTI_InitStruct->EXTI_Mode));
assert_param(IS_EXTI_TRIGGER(EXTI_InitStruct->EXTI_Trigger));
assert_param(IS_EXTI_LINE(EXTI_InitStruct->EXTI_Line));
assert_param(IS_FUNCTIONAL_STATE(EXTI_InitStruct->EXTI_LineCmd));
if (EXTI_InitStruct->EXTI_LineCmd != DISABLE)
{
/* Clear EXTI line configuration */
EXTI->IMR &= ~EXTI_InitStruct->EXTI_Line;
EXTI->EMR &= ~EXTI_InitStruct->EXTI_Line;
*(vu32 *)(EXTI_BASE + (u32)EXTI_InitStruct->EXTI_Mode)|= EXTI_InitStruct->EXTI_Line;
/* Clear Rising Falling edge configuration */
EXTI->RTSR &= ~EXTI_InitStruct->EXTI_Line;
EXTI->FTSR &= ~EXTI_InitStruct->EXTI_Line;
/* Select the trigger for the selected external interrupts */
if (EXTI_InitStruct->EXTI_Trigger == EXTI_Trigger_Rising_Falling)
{
/* Rising Falling edge */
EXTI->RTSR |= EXTI_InitStruct->EXTI_Line;
EXTI->FTSR |= EXTI_InitStruct->EXTI_Line;
}
else
{
*(vu32 *)(EXTI_BASE + (u32)EXTI_InitStruct->EXTI_Trigger)|= EXTI_InitStruct->EXTI_Line;
}
}
else
{
/* Disable the selected external lines */
*(vu32 *)(EXTI_BASE + (u32)EXTI_InitStruct->EXTI_Mode)&= ~EXTI_InitStruct->EXTI_Line;
}
}
/*******************************************************************************
* Function Name : EXTI_StructInit
* Description : Fills each EXTI_InitStruct member with its reset value.
* Input : - EXTI_InitStruct: pointer to a EXTI_InitTypeDef structure
* which will be initialized.
* Output : None
* Return : None
*******************************************************************************/
void EXTI_StructInit(EXTI_InitTypeDef* EXTI_InitStruct)
{
EXTI_InitStruct->EXTI_Line = EXTI_LineNone;
EXTI_InitStruct->EXTI_Mode = EXTI_Mode_Interrupt;
EXTI_InitStruct->EXTI_Trigger = EXTI_Trigger_Falling;
EXTI_InitStruct->EXTI_LineCmd = DISABLE;
}
/*******************************************************************************
* Function Name : EXTI_GenerateSWInterrupt
* Description : Generates a Software interrupt.
* Input : - EXTI_Line: specifies the EXTI lines to be enabled or
* disabled.
* This parameter can be any combination of EXTI_Linex where
* x can be (0..18).
* Output : None
* Return : None
*******************************************************************************/
void EXTI_GenerateSWInterrupt(u32 EXTI_Line)
{
/* Check the parameters */
assert_param(IS_EXTI_LINE(EXTI_Line));
EXTI->SWIER |= EXTI_Line;
}
/*******************************************************************************
* Function Name : EXTI_GetFlagStatus
* Description : Checks whether the specified EXTI line flag is set or not.
* Input : - EXTI_Line: specifies the EXTI line flag to check.
* This parameter can be:
* - EXTI_Linex: External interrupt line x where x(0..18)
* Output : None
* Return : The new state of EXTI_Line (SET or RESET).
*******************************************************************************/
FlagStatus EXTI_GetFlagStatus(u32 EXTI_Line)
{
FlagStatus bitstatus = RESET;
/* Check the parameters */
assert_param(IS_GET_EXTI_LINE(EXTI_Line));
if ((EXTI->PR & EXTI_Line) != (u32)RESET)
{
bitstatus = SET;
}
else
{
bitstatus = RESET;
}
return bitstatus;
}
/*******************************************************************************
* Function Name : EXTI_ClearFlag
* Description : Clears the EXTI<EFBFBD>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).
* Output : None
* Return : None
*******************************************************************************/
void EXTI_ClearFlag(u32 EXTI_Line)
{
/* Check the parameters */
assert_param(IS_EXTI_LINE(EXTI_Line));
EXTI->PR = EXTI_Line;
}
/*******************************************************************************
* Function Name : EXTI_GetITStatus
* Description : Checks whether the specified EXTI line is asserted or not.
* Input : - EXTI_Line: specifies the EXTI line to check.
* This parameter can be:
* - EXTI_Linex: External interrupt line x where x(0..18)
* Output : None
* Return : The new state of EXTI_Line (SET or RESET).
*******************************************************************************/
ITStatus EXTI_GetITStatus(u32 EXTI_Line)
{
ITStatus bitstatus = RESET;
u32 enablestatus = 0;
/* Check the parameters */
assert_param(IS_GET_EXTI_LINE(EXTI_Line));
enablestatus = EXTI->IMR & EXTI_Line;
if (((EXTI->PR & EXTI_Line) != (u32)RESET) && (enablestatus != (u32)RESET))
{
bitstatus = SET;
}
else
{
bitstatus = RESET;
}
return bitstatus;
}
/*******************************************************************************
* Function Name : EXTI_ClearITPendingBit
* Description : Clears the EXTI<EFBFBD>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).
* Output : None
* Return : None
*******************************************************************************/
void EXTI_ClearITPendingBit(u32 EXTI_Line)
{
/* Check the parameters */
assert_param(IS_EXTI_LINE(EXTI_Line));
EXTI->PR = EXTI_Line;
}
/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
* File Name : stm32f10x_exti.c
* Author : MCD Application Team
* Version : V2.0.3
* Date : 09/22/2008
* Description : This file provides all the EXTI firmware functions.
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x_exti.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
#define EXTI_LineNone ((u32)0x00000) /* No interrupt selected */
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : EXTI_DeInit
* Description : Deinitializes the EXTI peripheral registers to their default
* reset values.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void EXTI_DeInit(void)
{
EXTI->IMR = 0x00000000;
EXTI->EMR = 0x00000000;
EXTI->RTSR = 0x00000000;
EXTI->FTSR = 0x00000000;
EXTI->PR = 0x0007FFFF;
}
/*******************************************************************************
* Function Name : EXTI_Init
* Description : Initializes the EXTI peripheral according to the specified
* parameters in the EXTI_InitStruct.
* Input : - EXTI_InitStruct: pointer to a EXTI_InitTypeDef structure
* that contains the configuration information for the EXTI
* peripheral.
* Output : None
* Return : None
*******************************************************************************/
void EXTI_Init(EXTI_InitTypeDef* EXTI_InitStruct)
{
/* Check the parameters */
assert_param(IS_EXTI_MODE(EXTI_InitStruct->EXTI_Mode));
assert_param(IS_EXTI_TRIGGER(EXTI_InitStruct->EXTI_Trigger));
assert_param(IS_EXTI_LINE(EXTI_InitStruct->EXTI_Line));
assert_param(IS_FUNCTIONAL_STATE(EXTI_InitStruct->EXTI_LineCmd));
if (EXTI_InitStruct->EXTI_LineCmd != DISABLE)
{
/* Clear EXTI line configuration */
EXTI->IMR &= ~EXTI_InitStruct->EXTI_Line;
EXTI->EMR &= ~EXTI_InitStruct->EXTI_Line;
*(vu32 *)(EXTI_BASE + (u32)EXTI_InitStruct->EXTI_Mode)|= EXTI_InitStruct->EXTI_Line;
/* Clear Rising Falling edge configuration */
EXTI->RTSR &= ~EXTI_InitStruct->EXTI_Line;
EXTI->FTSR &= ~EXTI_InitStruct->EXTI_Line;
/* Select the trigger for the selected external interrupts */
if (EXTI_InitStruct->EXTI_Trigger == EXTI_Trigger_Rising_Falling)
{
/* Rising Falling edge */
EXTI->RTSR |= EXTI_InitStruct->EXTI_Line;
EXTI->FTSR |= EXTI_InitStruct->EXTI_Line;
}
else
{
*(vu32 *)(EXTI_BASE + (u32)EXTI_InitStruct->EXTI_Trigger)|= EXTI_InitStruct->EXTI_Line;
}
}
else
{
/* Disable the selected external lines */
*(vu32 *)(EXTI_BASE + (u32)EXTI_InitStruct->EXTI_Mode)&= ~EXTI_InitStruct->EXTI_Line;
}
}
/*******************************************************************************
* Function Name : EXTI_StructInit
* Description : Fills each EXTI_InitStruct member with its reset value.
* Input : - EXTI_InitStruct: pointer to a EXTI_InitTypeDef structure
* which will be initialized.
* Output : None
* Return : None
*******************************************************************************/
void EXTI_StructInit(EXTI_InitTypeDef* EXTI_InitStruct)
{
EXTI_InitStruct->EXTI_Line = EXTI_LineNone;
EXTI_InitStruct->EXTI_Mode = EXTI_Mode_Interrupt;
EXTI_InitStruct->EXTI_Trigger = EXTI_Trigger_Falling;
EXTI_InitStruct->EXTI_LineCmd = DISABLE;
}
/*******************************************************************************
* Function Name : EXTI_GenerateSWInterrupt
* Description : Generates a Software interrupt.
* Input : - EXTI_Line: specifies the EXTI lines to be enabled or
* disabled.
* This parameter can be any combination of EXTI_Linex where
* x can be (0..18).
* Output : None
* Return : None
*******************************************************************************/
void EXTI_GenerateSWInterrupt(u32 EXTI_Line)
{
/* Check the parameters */
assert_param(IS_EXTI_LINE(EXTI_Line));
EXTI->SWIER |= EXTI_Line;
}
/*******************************************************************************
* Function Name : EXTI_GetFlagStatus
* Description : Checks whether the specified EXTI line flag is set or not.
* Input : - EXTI_Line: specifies the EXTI line flag to check.
* This parameter can be:
* - EXTI_Linex: External interrupt line x where x(0..18)
* Output : None
* Return : The new state of EXTI_Line (SET or RESET).
*******************************************************************************/
FlagStatus EXTI_GetFlagStatus(u32 EXTI_Line)
{
FlagStatus bitstatus = RESET;
/* Check the parameters */
assert_param(IS_GET_EXTI_LINE(EXTI_Line));
if ((EXTI->PR & EXTI_Line) != (u32)RESET)
{
bitstatus = SET;
}
else
{
bitstatus = RESET;
}
return bitstatus;
}
/*******************************************************************************
* Function Name : EXTI_ClearFlag
* 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).
* Output : None
* Return : None
*******************************************************************************/
void EXTI_ClearFlag(u32 EXTI_Line)
{
/* Check the parameters */
assert_param(IS_EXTI_LINE(EXTI_Line));
EXTI->PR = EXTI_Line;
}
/*******************************************************************************
* Function Name : EXTI_GetITStatus
* Description : Checks whether the specified EXTI line is asserted or not.
* Input : - EXTI_Line: specifies the EXTI line to check.
* This parameter can be:
* - EXTI_Linex: External interrupt line x where x(0..18)
* Output : None
* Return : The new state of EXTI_Line (SET or RESET).
*******************************************************************************/
ITStatus EXTI_GetITStatus(u32 EXTI_Line)
{
ITStatus bitstatus = RESET;
u32 enablestatus = 0;
/* Check the parameters */
assert_param(IS_GET_EXTI_LINE(EXTI_Line));
enablestatus = EXTI->IMR & EXTI_Line;
if (((EXTI->PR & EXTI_Line) != (u32)RESET) && (enablestatus != (u32)RESET))
{
bitstatus = SET;
}
else
{
bitstatus = RESET;
}
return bitstatus;
}
/*******************************************************************************
* Function Name : EXTI_ClearITPendingBit
* 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).
* Output : None
* Return : None
*******************************************************************************/
void EXTI_ClearITPendingBit(u32 EXTI_Line)
{
/* Check the parameters */
assert_param(IS_EXTI_LINE(EXTI_Line));
EXTI->PR = EXTI_Line;
}
/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -1,148 +1,148 @@
/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
* File Name : stm32f10x_iwdg.c
* Author : MCD Application Team
* Version : V2.0.3
* Date : 09/22/2008
* Description : This file provides all the IWDG firmware functions.
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x_iwdg.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* ---------------------- IWDG registers bit mask ------------------------ */
/* KR register bit mask */
#define KR_KEY_Reload ((u16)0xAAAA)
#define KR_KEY_Enable ((u16)0xCCCC)
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : IWDG_WriteAccessCmd
* Description : Enables or disables write access to IWDG_PR and IWDG_RLR
* registers.
* Input : - IWDG_WriteAccess: new state of write access to IWDG_PR and
* IWDG_RLR registers.
* This parameter can be one of the following values:
* - IWDG_WriteAccess_Enable: Enable write access to
* IWDG_PR and IWDG_RLR registers
* - IWDG_WriteAccess_Disable: Disable write access to
* IWDG_PR and IWDG_RLR registers
* Output : None
* Return : None
*******************************************************************************/
void IWDG_WriteAccessCmd(u16 IWDG_WriteAccess)
{
/* Check the parameters */
assert_param(IS_IWDG_WRITE_ACCESS(IWDG_WriteAccess));
IWDG->KR = IWDG_WriteAccess;
}
/*******************************************************************************
* Function Name : IWDG_SetPrescaler
* Description : Sets IWDG Prescaler value.
* Input : - IWDG_Prescaler: specifies the IWDG Prescaler value.
* This parameter can be one of the following values:
* - IWDG_Prescaler_4: IWDG prescaler set to 4
* - IWDG_Prescaler_8: IWDG prescaler set to 8
* - IWDG_Prescaler_16: IWDG prescaler set to 16
* - IWDG_Prescaler_32: IWDG prescaler set to 32
* - IWDG_Prescaler_64: IWDG prescaler set to 64
* - IWDG_Prescaler_128: IWDG prescaler set to 128
* - IWDG_Prescaler_256: IWDG prescaler set to 256
* Output : None
* Return : None
*******************************************************************************/
void IWDG_SetPrescaler(u8 IWDG_Prescaler)
{
/* Check the parameters */
assert_param(IS_IWDG_PRESCALER(IWDG_Prescaler));
IWDG->PR = IWDG_Prescaler;
}
/*******************************************************************************
* Function Name : IWDG_SetReload
* Description : Sets IWDG Reload value.
* Input : - Reload: specifies the IWDG Reload value.
* This parameter must be a number between 0 and 0x0FFF.
* Output : None
* Return : None
*******************************************************************************/
void IWDG_SetReload(u16 Reload)
{
/* Check the parameters */
assert_param(IS_IWDG_RELOAD(Reload));
IWDG->RLR = Reload;
}
/*******************************************************************************
* Function Name : IWDG_ReloadCounter
* Description : Reloads IWDG counter with value defined in the reload register
* (write access to IWDG_PR and IWDG_RLR registers disabled).
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void IWDG_ReloadCounter(void)
{
IWDG->KR = KR_KEY_Reload;
}
/*******************************************************************************
* Function Name : IWDG_Enable
* Description : Enables IWDG (write access to IWDG_PR and IWDG_RLR registers
* disabled).
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void IWDG_Enable(void)
{
IWDG->KR = KR_KEY_Enable;
}
/*******************************************************************************
* Function Name : IWDG_GetFlagStatus
* Description : Checks whether the specified IWDG flag is set or not.
* Input : - IWDG_FLAG: specifies the flag to check.
* This parameter can be one of the following values:
* - IWDG_FLAG_PVU: Prescaler Value Update on going
* - IWDG_FLAG_RVU: Reload Value Update on going
* Output : None
* Return : The new state of IWDG_FLAG (SET or RESET).
*******************************************************************************/
FlagStatus IWDG_GetFlagStatus(u16 IWDG_FLAG)
{
FlagStatus bitstatus = RESET;
/* Check the parameters */
assert_param(IS_IWDG_FLAG(IWDG_FLAG));
if ((IWDG->SR & IWDG_FLAG) != (u32)RESET)
{
bitstatus = SET;
}
else
{
bitstatus = RESET;
}
/* Return the flag status */
return bitstatus;
}
/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
* File Name : stm32f10x_iwdg.c
* Author : MCD Application Team
* Version : V2.0.3
* Date : 09/22/2008
* Description : This file provides all the IWDG firmware functions.
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x_iwdg.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* ---------------------- IWDG registers bit mask ------------------------ */
/* KR register bit mask */
#define KR_KEY_Reload ((u16)0xAAAA)
#define KR_KEY_Enable ((u16)0xCCCC)
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : IWDG_WriteAccessCmd
* Description : Enables or disables write access to IWDG_PR and IWDG_RLR
* registers.
* Input : - IWDG_WriteAccess: new state of write access to IWDG_PR and
* IWDG_RLR registers.
* This parameter can be one of the following values:
* - IWDG_WriteAccess_Enable: Enable write access to
* IWDG_PR and IWDG_RLR registers
* - IWDG_WriteAccess_Disable: Disable write access to
* IWDG_PR and IWDG_RLR registers
* Output : None
* Return : None
*******************************************************************************/
void IWDG_WriteAccessCmd(u16 IWDG_WriteAccess)
{
/* Check the parameters */
assert_param(IS_IWDG_WRITE_ACCESS(IWDG_WriteAccess));
IWDG->KR = IWDG_WriteAccess;
}
/*******************************************************************************
* Function Name : IWDG_SetPrescaler
* Description : Sets IWDG Prescaler value.
* Input : - IWDG_Prescaler: specifies the IWDG Prescaler value.
* This parameter can be one of the following values:
* - IWDG_Prescaler_4: IWDG prescaler set to 4
* - IWDG_Prescaler_8: IWDG prescaler set to 8
* - IWDG_Prescaler_16: IWDG prescaler set to 16
* - IWDG_Prescaler_32: IWDG prescaler set to 32
* - IWDG_Prescaler_64: IWDG prescaler set to 64
* - IWDG_Prescaler_128: IWDG prescaler set to 128
* - IWDG_Prescaler_256: IWDG prescaler set to 256
* Output : None
* Return : None
*******************************************************************************/
void IWDG_SetPrescaler(u8 IWDG_Prescaler)
{
/* Check the parameters */
assert_param(IS_IWDG_PRESCALER(IWDG_Prescaler));
IWDG->PR = IWDG_Prescaler;
}
/*******************************************************************************
* Function Name : IWDG_SetReload
* Description : Sets IWDG Reload value.
* Input : - Reload: specifies the IWDG Reload value.
* This parameter must be a number between 0 and 0x0FFF.
* Output : None
* Return : None
*******************************************************************************/
void IWDG_SetReload(u16 Reload)
{
/* Check the parameters */
assert_param(IS_IWDG_RELOAD(Reload));
IWDG->RLR = Reload;
}
/*******************************************************************************
* Function Name : IWDG_ReloadCounter
* Description : Reloads IWDG counter with value defined in the reload register
* (write access to IWDG_PR and IWDG_RLR registers disabled).
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void IWDG_ReloadCounter(void)
{
IWDG->KR = KR_KEY_Reload;
}
/*******************************************************************************
* Function Name : IWDG_Enable
* Description : Enables IWDG (write access to IWDG_PR and IWDG_RLR registers
* disabled).
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void IWDG_Enable(void)
{
IWDG->KR = KR_KEY_Enable;
}
/*******************************************************************************
* Function Name : IWDG_GetFlagStatus
* Description : Checks whether the specified IWDG flag is set or not.
* Input : - IWDG_FLAG: specifies the flag to check.
* This parameter can be one of the following values:
* - IWDG_FLAG_PVU: Prescaler Value Update on going
* - IWDG_FLAG_RVU: Reload Value Update on going
* Output : None
* Return : The new state of IWDG_FLAG (SET or RESET).
*******************************************************************************/
FlagStatus IWDG_GetFlagStatus(u16 IWDG_FLAG)
{
FlagStatus bitstatus = RESET;
/* Check the parameters */
assert_param(IS_IWDG_FLAG(IWDG_FLAG));
if ((IWDG->SR & IWDG_FLAG) != (u32)RESET)
{
bitstatus = SET;
}
else
{
bitstatus = RESET;
}
/* Return the flag status */
return bitstatus;
}
/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/

View File

@ -1,303 +1,303 @@
/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
* File Name : stm32f10x_lib.c
* Author : MCD Application Team
* Version : V2.0.3
* Date : 09/22/2008
* Description : This file provides all peripherals pointers initialization.
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
#define EXT
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x_lib.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
#ifdef DEBUG
/*******************************************************************************
* Function Name : debug
* Description : This function initialize peripherals pointers.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void debug(void)
{
/************************************* ADC ************************************/
#ifdef _ADC1
ADC1 = (ADC_TypeDef *) ADC1_BASE;
#endif /*_ADC1 */
#ifdef _ADC2
ADC2 = (ADC_TypeDef *) ADC2_BASE;
#endif /*_ADC2 */
#ifdef _ADC3
ADC3 = (ADC_TypeDef *) ADC3_BASE;
#endif /*_ADC3 */
/************************************* BKP ************************************/
#ifdef _BKP
BKP = (BKP_TypeDef *) BKP_BASE;
#endif /*_BKP */
/************************************* CAN ************************************/
#ifdef _CAN
CAN = (CAN_TypeDef *) CAN_BASE;
#endif /*_CAN */
/************************************* CRC ************************************/
#ifdef _CRC
CRC = (CRC_TypeDef *) CRC_BASE;
#endif /*_CRC */
/************************************* DAC ************************************/
#ifdef _DAC
DAC = (DAC_TypeDef *) DAC_BASE;
#endif /*_DAC */
/************************************* DBGMCU**********************************/
#ifdef _DBGMCU
DBGMCU = (DBGMCU_TypeDef *) DBGMCU_BASE;
#endif /*_DBGMCU */
/************************************* DMA ************************************/
#ifdef _DMA
DMA1 = (DMA_TypeDef *) DMA1_BASE;
DMA2 = (DMA_TypeDef *) DMA2_BASE;
#endif /*_DMA */
#ifdef _DMA1_Channel1
DMA1_Channel1 = (DMA_Channel_TypeDef *) DMA1_Channel1_BASE;
#endif /*_DMA1_Channel1 */
#ifdef _DMA1_Channel2
DMA1_Channel2 = (DMA_Channel_TypeDef *) DMA1_Channel2_BASE;
#endif /*_DMA1_Channel2 */
#ifdef _DMA1_Channel3
DMA1_Channel3 = (DMA_Channel_TypeDef *) DMA1_Channel3_BASE;
#endif /*_DMA1_Channel3 */
#ifdef _DMA1_Channel4
DMA1_Channel4 = (DMA_Channel_TypeDef *) DMA1_Channel4_BASE;
#endif /*_DMA1_Channel4 */
#ifdef _DMA1_Channel5
DMA1_Channel5 = (DMA_Channel_TypeDef *) DMA1_Channel5_BASE;
#endif /*_DMA1_Channel5 */
#ifdef _DMA1_Channel6
DMA1_Channel6 = (DMA_Channel_TypeDef *) DMA1_Channel6_BASE;
#endif /*_DMA1_Channel6 */
#ifdef _DMA1_Channel7
DMA1_Channel7 = (DMA_Channel_TypeDef *) DMA1_Channel7_BASE;
#endif /*_DMA1_Channel7 */
#ifdef _DMA2_Channel1
DMA2_Channel1 = (DMA_Channel_TypeDef *) DMA2_Channel1_BASE;
#endif /*_DMA2_Channel1 */
#ifdef _DMA2_Channel2
DMA2_Channel2 = (DMA_Channel_TypeDef *) DMA2_Channel2_BASE;
#endif /*_DMA2_Channel2 */
#ifdef _DMA2_Channel3
DMA2_Channel3 = (DMA_Channel_TypeDef *) DMA2_Channel3_BASE;
#endif /*_DMA2_Channel3 */
#ifdef _DMA2_Channel4
DMA2_Channel4 = (DMA_Channel_TypeDef *) DMA2_Channel4_BASE;
#endif /*_DMA2_Channel4 */
#ifdef _DMA2_Channel5
DMA2_Channel5 = (DMA_Channel_TypeDef *) DMA2_Channel5_BASE;
#endif /*_DMA2_Channel5 */
/************************************* EXTI ***********************************/
#ifdef _EXTI
EXTI = (EXTI_TypeDef *) EXTI_BASE;
#endif /*_EXTI */
/************************************* FLASH and Option Bytes *****************/
#ifdef _FLASH
FLASH = (FLASH_TypeDef *) FLASH_R_BASE;
OB = (OB_TypeDef *) OB_BASE;
#endif /*_FLASH */
/************************************* FSMC ***********************************/
#ifdef _FSMC
FSMC_Bank1 = (FSMC_Bank1_TypeDef *) FSMC_Bank1_R_BASE;
FSMC_Bank1E = (FSMC_Bank1E_TypeDef *) FSMC_Bank1E_R_BASE;
FSMC_Bank2 = (FSMC_Bank2_TypeDef *) FSMC_Bank2_R_BASE;
FSMC_Bank3 = (FSMC_Bank3_TypeDef *) FSMC_Bank3_R_BASE;
FSMC_Bank4 = (FSMC_Bank4_TypeDef *) FSMC_Bank4_R_BASE;
#endif /*_FSMC */
/************************************* GPIO ***********************************/
#ifdef _GPIOA
GPIOA = (GPIO_TypeDef *) GPIOA_BASE;
#endif /*_GPIOA */
#ifdef _GPIOB
GPIOB = (GPIO_TypeDef *) GPIOB_BASE;
#endif /*_GPIOB */
#ifdef _GPIOC
GPIOC = (GPIO_TypeDef *) GPIOC_BASE;
#endif /*_GPIOC */
#ifdef _GPIOD
GPIOD = (GPIO_TypeDef *) GPIOD_BASE;
#endif /*_GPIOD */
#ifdef _GPIOE
GPIOE = (GPIO_TypeDef *) GPIOE_BASE;
#endif /*_GPIOE */
#ifdef _GPIOF
GPIOF = (GPIO_TypeDef *) GPIOF_BASE;
#endif /*_GPIOF */
#ifdef _GPIOG
GPIOG = (GPIO_TypeDef *) GPIOG_BASE;
#endif /*_GPIOG */
#ifdef _AFIO
AFIO = (AFIO_TypeDef *) AFIO_BASE;
#endif /*_AFIO */
/************************************* I2C ************************************/
#ifdef _I2C1
I2C1 = (I2C_TypeDef *) I2C1_BASE;
#endif /*_I2C1 */
#ifdef _I2C2
I2C2 = (I2C_TypeDef *) I2C2_BASE;
#endif /*_I2C2 */
/************************************* IWDG ***********************************/
#ifdef _IWDG
IWDG = (IWDG_TypeDef *) IWDG_BASE;
#endif /*_IWDG */
/************************************* NVIC ***********************************/
#ifdef _NVIC
NVIC = (NVIC_TypeDef *) NVIC_BASE;
SCB = (SCB_TypeDef *) SCB_BASE;
#endif /*_NVIC */
/************************************* PWR ************************************/
#ifdef _PWR
PWR = (PWR_TypeDef *) PWR_BASE;
#endif /*_PWR */
/************************************* RCC ************************************/
#ifdef _RCC
RCC = (RCC_TypeDef *) RCC_BASE;
#endif /*_RCC */
/************************************* RTC ************************************/
#ifdef _RTC
RTC = (RTC_TypeDef *) RTC_BASE;
#endif /*_RTC */
/************************************* SDIO ***********************************/
#ifdef _SDIO
SDIO = (SDIO_TypeDef *) SDIO_BASE;
#endif /*_SDIO */
/************************************* SPI ************************************/
#ifdef _SPI1
SPI1 = (SPI_TypeDef *) SPI1_BASE;
#endif /*_SPI1 */
#ifdef _SPI2
SPI2 = (SPI_TypeDef *) SPI2_BASE;
#endif /*_SPI2 */
#ifdef _SPI3
SPI3 = (SPI_TypeDef *) SPI3_BASE;
#endif /*_SPI3 */
/************************************* SysTick ********************************/
#ifdef _SysTick
SysTick = (SysTick_TypeDef *) SysTick_BASE;
#endif /*_SysTick */
/************************************* TIM ************************************/
#ifdef _TIM1
TIM1 = (TIM_TypeDef *) TIM1_BASE;
#endif /*_TIM1 */
#ifdef _TIM2
TIM2 = (TIM_TypeDef *) TIM2_BASE;
#endif /*_TIM2 */
#ifdef _TIM3
TIM3 = (TIM_TypeDef *) TIM3_BASE;
#endif /*_TIM3 */
#ifdef _TIM4
TIM4 = (TIM_TypeDef *) TIM4_BASE;
#endif /*_TIM4 */
#ifdef _TIM5
TIM5 = (TIM_TypeDef *) TIM5_BASE;
#endif /*_TIM5 */
#ifdef _TIM6
TIM6 = (TIM_TypeDef *) TIM6_BASE;
#endif /*_TIM6 */
#ifdef _TIM7
TIM7 = (TIM_TypeDef *) TIM7_BASE;
#endif /*_TIM7 */
#ifdef _TIM8
TIM8 = (TIM_TypeDef *) TIM8_BASE;
#endif /*_TIM8 */
/************************************* USART **********************************/
#ifdef _USART1
USART1 = (USART_TypeDef *) USART1_BASE;
#endif /*_USART1 */
#ifdef _USART2
USART2 = (USART_TypeDef *) USART2_BASE;
#endif /*_USART2 */
#ifdef _USART3
USART3 = (USART_TypeDef *) USART3_BASE;
#endif /*_USART3 */
#ifdef _UART4
UART4 = (USART_TypeDef *) UART4_BASE;
#endif /*_UART4 */
#ifdef _UART5
UART5 = (USART_TypeDef *) UART5_BASE;
#endif /*_UART5 */
/************************************* WWDG ***********************************/
#ifdef _WWDG
WWDG = (WWDG_TypeDef *) WWDG_BASE;
#endif /*_WWDG */
}
#endif /* DEBUG*/
/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
* File Name : stm32f10x_lib.c
* Author : MCD Application Team
* Version : V2.0.3
* Date : 09/22/2008
* Description : This file provides all peripherals pointers initialization.
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
#define EXT
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x_lib.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
#ifdef DEBUG
/*******************************************************************************
* Function Name : debug
* Description : This function initialize peripherals pointers.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void debug(void)
{
/************************************* ADC ************************************/
#ifdef _ADC1
ADC1 = (ADC_TypeDef *) ADC1_BASE;
#endif /*_ADC1 */
#ifdef _ADC2
ADC2 = (ADC_TypeDef *) ADC2_BASE;
#endif /*_ADC2 */
#ifdef _ADC3
ADC3 = (ADC_TypeDef *) ADC3_BASE;
#endif /*_ADC3 */
/************************************* BKP ************************************/
#ifdef _BKP
BKP = (BKP_TypeDef *) BKP_BASE;
#endif /*_BKP */
/************************************* CAN ************************************/
#ifdef _CAN
CAN = (CAN_TypeDef *) CAN_BASE;
#endif /*_CAN */
/************************************* CRC ************************************/
#ifdef _CRC
CRC = (CRC_TypeDef *) CRC_BASE;
#endif /*_CRC */
/************************************* DAC ************************************/
#ifdef _DAC
DAC = (DAC_TypeDef *) DAC_BASE;
#endif /*_DAC */
/************************************* DBGMCU**********************************/
#ifdef _DBGMCU
DBGMCU = (DBGMCU_TypeDef *) DBGMCU_BASE;
#endif /*_DBGMCU */
/************************************* DMA ************************************/
#ifdef _DMA
DMA1 = (DMA_TypeDef *) DMA1_BASE;
DMA2 = (DMA_TypeDef *) DMA2_BASE;
#endif /*_DMA */
#ifdef _DMA1_Channel1
DMA1_Channel1 = (DMA_Channel_TypeDef *) DMA1_Channel1_BASE;
#endif /*_DMA1_Channel1 */
#ifdef _DMA1_Channel2
DMA1_Channel2 = (DMA_Channel_TypeDef *) DMA1_Channel2_BASE;
#endif /*_DMA1_Channel2 */
#ifdef _DMA1_Channel3
DMA1_Channel3 = (DMA_Channel_TypeDef *) DMA1_Channel3_BASE;
#endif /*_DMA1_Channel3 */
#ifdef _DMA1_Channel4
DMA1_Channel4 = (DMA_Channel_TypeDef *) DMA1_Channel4_BASE;
#endif /*_DMA1_Channel4 */
#ifdef _DMA1_Channel5
DMA1_Channel5 = (DMA_Channel_TypeDef *) DMA1_Channel5_BASE;
#endif /*_DMA1_Channel5 */
#ifdef _DMA1_Channel6
DMA1_Channel6 = (DMA_Channel_TypeDef *) DMA1_Channel6_BASE;
#endif /*_DMA1_Channel6 */
#ifdef _DMA1_Channel7
DMA1_Channel7 = (DMA_Channel_TypeDef *) DMA1_Channel7_BASE;
#endif /*_DMA1_Channel7 */
#ifdef _DMA2_Channel1
DMA2_Channel1 = (DMA_Channel_TypeDef *) DMA2_Channel1_BASE;
#endif /*_DMA2_Channel1 */
#ifdef _DMA2_Channel2
DMA2_Channel2 = (DMA_Channel_TypeDef *) DMA2_Channel2_BASE;
#endif /*_DMA2_Channel2 */
#ifdef _DMA2_Channel3
DMA2_Channel3 = (DMA_Channel_TypeDef *) DMA2_Channel3_BASE;
#endif /*_DMA2_Channel3 */
#ifdef _DMA2_Channel4
DMA2_Channel4 = (DMA_Channel_TypeDef *) DMA2_Channel4_BASE;
#endif /*_DMA2_Channel4 */
#ifdef _DMA2_Channel5
DMA2_Channel5 = (DMA_Channel_TypeDef *) DMA2_Channel5_BASE;
#endif /*_DMA2_Channel5 */
/************************************* EXTI ***********************************/
#ifdef _EXTI
EXTI = (EXTI_TypeDef *) EXTI_BASE;
#endif /*_EXTI */
/************************************* FLASH and Option Bytes *****************/
#ifdef _FLASH
FLASH = (FLASH_TypeDef *) FLASH_R_BASE;
OB = (OB_TypeDef *) OB_BASE;
#endif /*_FLASH */
/************************************* FSMC ***********************************/
#ifdef _FSMC
FSMC_Bank1 = (FSMC_Bank1_TypeDef *) FSMC_Bank1_R_BASE;
FSMC_Bank1E = (FSMC_Bank1E_TypeDef *) FSMC_Bank1E_R_BASE;
FSMC_Bank2 = (FSMC_Bank2_TypeDef *) FSMC_Bank2_R_BASE;
FSMC_Bank3 = (FSMC_Bank3_TypeDef *) FSMC_Bank3_R_BASE;
FSMC_Bank4 = (FSMC_Bank4_TypeDef *) FSMC_Bank4_R_BASE;
#endif /*_FSMC */
/************************************* GPIO ***********************************/
#ifdef _GPIOA
GPIOA = (GPIO_TypeDef *) GPIOA_BASE;
#endif /*_GPIOA */
#ifdef _GPIOB
GPIOB = (GPIO_TypeDef *) GPIOB_BASE;
#endif /*_GPIOB */
#ifdef _GPIOC
GPIOC = (GPIO_TypeDef *) GPIOC_BASE;
#endif /*_GPIOC */
#ifdef _GPIOD
GPIOD = (GPIO_TypeDef *) GPIOD_BASE;
#endif /*_GPIOD */
#ifdef _GPIOE
GPIOE = (GPIO_TypeDef *) GPIOE_BASE;
#endif /*_GPIOE */
#ifdef _GPIOF
GPIOF = (GPIO_TypeDef *) GPIOF_BASE;
#endif /*_GPIOF */
#ifdef _GPIOG
GPIOG = (GPIO_TypeDef *) GPIOG_BASE;
#endif /*_GPIOG */
#ifdef _AFIO
AFIO = (AFIO_TypeDef *) AFIO_BASE;
#endif /*_AFIO */
/************************************* I2C ************************************/
#ifdef _I2C1
I2C1 = (I2C_TypeDef *) I2C1_BASE;
#endif /*_I2C1 */
#ifdef _I2C2
I2C2 = (I2C_TypeDef *) I2C2_BASE;
#endif /*_I2C2 */
/************************************* IWDG ***********************************/
#ifdef _IWDG
IWDG = (IWDG_TypeDef *) IWDG_BASE;
#endif /*_IWDG */
/************************************* NVIC ***********************************/
#ifdef _NVIC
NVIC = (NVIC_TypeDef *) NVIC_BASE;
SCB = (SCB_TypeDef *) SCB_BASE;
#endif /*_NVIC */
/************************************* PWR ************************************/
#ifdef _PWR
PWR = (PWR_TypeDef *) PWR_BASE;
#endif /*_PWR */
/************************************* RCC ************************************/
#ifdef _RCC
RCC = (RCC_TypeDef *) RCC_BASE;
#endif /*_RCC */
/************************************* RTC ************************************/
#ifdef _RTC
RTC = (RTC_TypeDef *) RTC_BASE;
#endif /*_RTC */
/************************************* SDIO ***********************************/
#ifdef _SDIO
SDIO = (SDIO_TypeDef *) SDIO_BASE;
#endif /*_SDIO */
/************************************* SPI ************************************/
#ifdef _SPI1
SPI1 = (SPI_TypeDef *) SPI1_BASE;
#endif /*_SPI1 */
#ifdef _SPI2
SPI2 = (SPI_TypeDef *) SPI2_BASE;
#endif /*_SPI2 */
#ifdef _SPI3
SPI3 = (SPI_TypeDef *) SPI3_BASE;
#endif /*_SPI3 */
/************************************* SysTick ********************************/
#ifdef _SysTick
SysTick = (SysTick_TypeDef *) SysTick_BASE;
#endif /*_SysTick */
/************************************* TIM ************************************/
#ifdef _TIM1
TIM1 = (TIM_TypeDef *) TIM1_BASE;
#endif /*_TIM1 */
#ifdef _TIM2
TIM2 = (TIM_TypeDef *) TIM2_BASE;
#endif /*_TIM2 */
#ifdef _TIM3
TIM3 = (TIM_TypeDef *) TIM3_BASE;
#endif /*_TIM3 */
#ifdef _TIM4
TIM4 = (TIM_TypeDef *) TIM4_BASE;
#endif /*_TIM4 */
#ifdef _TIM5
TIM5 = (TIM_TypeDef *) TIM5_BASE;
#endif /*_TIM5 */
#ifdef _TIM6
TIM6 = (TIM_TypeDef *) TIM6_BASE;
#endif /*_TIM6 */
#ifdef _TIM7
TIM7 = (TIM_TypeDef *) TIM7_BASE;
#endif /*_TIM7 */
#ifdef _TIM8
TIM8 = (TIM_TypeDef *) TIM8_BASE;
#endif /*_TIM8 */
/************************************* USART **********************************/
#ifdef _USART1
USART1 = (USART_TypeDef *) USART1_BASE;
#endif /*_USART1 */
#ifdef _USART2
USART2 = (USART_TypeDef *) USART2_BASE;
#endif /*_USART2 */
#ifdef _USART3
USART3 = (USART_TypeDef *) USART3_BASE;
#endif /*_USART3 */
#ifdef _UART4
UART4 = (USART_TypeDef *) UART4_BASE;
#endif /*_UART4 */
#ifdef _UART5
UART5 = (USART_TypeDef *) UART5_BASE;
#endif /*_UART5 */
/************************************* WWDG ***********************************/
#ifdef _WWDG
WWDG = (WWDG_TypeDef *) WWDG_BASE;
#endif /*_WWDG */
}
#endif /* DEBUG*/
/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/

File diff suppressed because it is too large Load Diff

View File

@ -1,280 +1,280 @@
/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
* File Name : stm32f10x_pwr.c
* Author : MCD Application Team
* Version : V2.0.3
* Date : 09/22/2008
* Description : This file provides all the PWR firmware functions.
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x_pwr.h"
#include "stm32f10x_rcc.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* --------- PWR registers bit address in the alias region ---------- */
#define PWR_OFFSET (PWR_BASE - PERIPH_BASE)
/* --- CR Register ---*/
/* Alias word address of DBP bit */
#define CR_OFFSET (PWR_OFFSET + 0x00)
#define DBP_BitNumber 0x08
#define CR_DBP_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (DBP_BitNumber * 4))
/* Alias word address of PVDE bit */
#define PVDE_BitNumber 0x04
#define CR_PVDE_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PVDE_BitNumber * 4))
/* --- CSR Register ---*/
/* Alias word address of EWUP bit */
#define CSR_OFFSET (PWR_OFFSET + 0x04)
#define EWUP_BitNumber 0x08
#define CSR_EWUP_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (EWUP_BitNumber * 4))
/* ------------------ PWR registers bit mask ------------------------ */
/* CR register bit mask */
#define CR_PDDS_Set ((u32)0x00000002)
#define CR_DS_Mask ((u32)0xFFFFFFFC)
#define CR_CWUF_Set ((u32)0x00000004)
#define CR_PLS_Mask ((u32)0xFFFFFF1F)
/* --------- Cortex System Control register bit mask ---------------- */
/* Cortex System Control register address */
#define SCB_SysCtrl ((u32)0xE000ED10)
/* SLEEPDEEP bit mask */
#define SysCtrl_SLEEPDEEP_Set ((u32)0x00000004)
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : PWR_DeInit
* Description : Deinitializes the PWR peripheral registers to their default
* reset values.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void PWR_DeInit(void)
{
RCC_APB1PeriphResetCmd(RCC_APB1Periph_PWR, ENABLE);
RCC_APB1PeriphResetCmd(RCC_APB1Periph_PWR, DISABLE);
}
/*******************************************************************************
* Function Name : PWR_BackupAccessCmd
* Description : Enables or disables access to the RTC and backup registers.
* Input : - NewState: new state of the access to the RTC and backup
* registers. This parameter can be: ENABLE or DISABLE.
* Output : None
* Return : None
*******************************************************************************/
void PWR_BackupAccessCmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
*(vu32 *) CR_DBP_BB = (u32)NewState;
}
/*******************************************************************************
* Function Name : PWR_PVDCmd
* Description : Enables or disables the Power Voltage Detector(PVD).
* Input : - NewState: new state of the PVD.
* This parameter can be: ENABLE or DISABLE.
* Output : None
* Return : None
*******************************************************************************/
void PWR_PVDCmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
*(vu32 *) CR_PVDE_BB = (u32)NewState;
}
/*******************************************************************************
* Function Name : PWR_PVDLevelConfig
* Description : Configures the voltage threshold detected by the Power Voltage
* Detector(PVD).
* Input : - PWR_PVDLevel: specifies the PVD detection level
* This parameter can be one of the following values:
* - PWR_PVDLevel_2V2: PVD detection level set to 2.2V
* - PWR_PVDLevel_2V3: PVD detection level set to 2.3V
* - PWR_PVDLevel_2V4: PVD detection level set to 2.4V
* - PWR_PVDLevel_2V5: PVD detection level set to 2.5V
* - PWR_PVDLevel_2V6: PVD detection level set to 2.6V
* - PWR_PVDLevel_2V7: PVD detection level set to 2.7V
* - PWR_PVDLevel_2V8: PVD detection level set to 2.8V
* - PWR_PVDLevel_2V9: PVD detection level set to 2.9V
* Output : None
* Return : None
*******************************************************************************/
void PWR_PVDLevelConfig(u32 PWR_PVDLevel)
{
u32 tmpreg = 0;
/* Check the parameters */
assert_param(IS_PWR_PVD_LEVEL(PWR_PVDLevel));
tmpreg = PWR->CR;
/* Clear PLS[7:5] bits */
tmpreg &= CR_PLS_Mask;
/* Set PLS[7:5] bits according to PWR_PVDLevel value */
tmpreg |= PWR_PVDLevel;
/* Store the new value */
PWR->CR = tmpreg;
}
/*******************************************************************************
* Function Name : PWR_WakeUpPinCmd
* Description : Enables or disables the WakeUp Pin functionality.
* Input : - NewState: new state of the WakeUp Pin functionality.
* This parameter can be: ENABLE or DISABLE.
* Output : None
* Return : None
*******************************************************************************/
void PWR_WakeUpPinCmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
*(vu32 *) CSR_EWUP_BB = (u32)NewState;
}
/*******************************************************************************
* Function Name : PWR_EnterSTOPMode
* Description : Enters STOP mode.
* Input : - PWR_Regulator: specifies the regulator state in STOP mode.
* This parameter can be one of the following values:
* - PWR_Regulator_ON: STOP mode with regulator ON
* - PWR_Regulator_LowPower: STOP mode with
* regulator in low power mode
* - PWR_STOPEntry: specifies if STOP mode in entered with WFI or
* WFE instruction.
* This parameter can be one of the following values:
* - PWR_STOPEntry_WFI: enter STOP mode with WFI instruction
* - PWR_STOPEntry_WFE: enter STOP mode with WFE instruction
* Output : None
* Return : None
*******************************************************************************/
void PWR_EnterSTOPMode(u32 PWR_Regulator, u8 PWR_STOPEntry)
{
u32 tmpreg = 0;
/* Check the parameters */
assert_param(IS_PWR_REGULATOR(PWR_Regulator));
assert_param(IS_PWR_STOP_ENTRY(PWR_STOPEntry));
/* Select the regulator state in STOP mode ---------------------------------*/
tmpreg = PWR->CR;
/* Clear PDDS and LPDS bits */
tmpreg &= CR_DS_Mask;
/* Set LPDS bit according to PWR_Regulator value */
tmpreg |= PWR_Regulator;
/* Store the new value */
PWR->CR = tmpreg;
/* Set SLEEPDEEP bit of Cortex System Control Register */
*(vu32 *) SCB_SysCtrl |= SysCtrl_SLEEPDEEP_Set;
/* Select STOP mode entry --------------------------------------------------*/
if(PWR_STOPEntry == PWR_STOPEntry_WFI)
{
/* Request Wait For Interrupt */
__WFI();
}
else
{
/* Request Wait For Event */
__WFE();
}
}
/*******************************************************************************
* Function Name : PWR_EnterSTANDBYMode
* Description : Enters STANDBY mode.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void PWR_EnterSTANDBYMode(void)
{
/* Clear Wake-up flag */
PWR->CR |= CR_CWUF_Set;
/* Select STANDBY mode */
PWR->CR |= CR_PDDS_Set;
/* Set SLEEPDEEP bit of Cortex System Control Register */
*(vu32 *) SCB_SysCtrl |= SysCtrl_SLEEPDEEP_Set;
/* Request Wait For Interrupt */
__WFI();
}
/*******************************************************************************
* Function Name : PWR_GetFlagStatus
* Description : Checks whether the specified PWR flag is set or not.
* Input : - PWR_FLAG: specifies the flag to check.
* This parameter can be one of the following values:
* - PWR_FLAG_WU: Wake Up flag
* - PWR_FLAG_SB: StandBy flag
* - PWR_FLAG_PVDO: PVD Output
* Output : None
* Return : The new state of PWR_FLAG (SET or RESET).
*******************************************************************************/
FlagStatus PWR_GetFlagStatus(u32 PWR_FLAG)
{
FlagStatus bitstatus = RESET;
/* Check the parameters */
assert_param(IS_PWR_GET_FLAG(PWR_FLAG));
if ((PWR->CSR & PWR_FLAG) != (u32)RESET)
{
bitstatus = SET;
}
else
{
bitstatus = RESET;
}
/* Return the flag status */
return bitstatus;
}
/*******************************************************************************
* Function Name : PWR_ClearFlag
* Description : Clears the PWR's pending flags.
* Input : - PWR_FLAG: specifies the flag to clear.
* This parameter can be one of the following values:
* - PWR_FLAG_WU: Wake Up flag
* - PWR_FLAG_SB: StandBy flag
* Output : None
* Return : None
*******************************************************************************/
void PWR_ClearFlag(u32 PWR_FLAG)
{
/* Check the parameters */
assert_param(IS_PWR_CLEAR_FLAG(PWR_FLAG));
PWR->CR |= PWR_FLAG << 2;
}
/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
* File Name : stm32f10x_pwr.c
* Author : MCD Application Team
* Version : V2.0.3
* Date : 09/22/2008
* Description : This file provides all the PWR firmware functions.
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x_pwr.h"
#include "stm32f10x_rcc.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* --------- PWR registers bit address in the alias region ---------- */
#define PWR_OFFSET (PWR_BASE - PERIPH_BASE)
/* --- CR Register ---*/
/* Alias word address of DBP bit */
#define CR_OFFSET (PWR_OFFSET + 0x00)
#define DBP_BitNumber 0x08
#define CR_DBP_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (DBP_BitNumber * 4))
/* Alias word address of PVDE bit */
#define PVDE_BitNumber 0x04
#define CR_PVDE_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PVDE_BitNumber * 4))
/* --- CSR Register ---*/
/* Alias word address of EWUP bit */
#define CSR_OFFSET (PWR_OFFSET + 0x04)
#define EWUP_BitNumber 0x08
#define CSR_EWUP_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (EWUP_BitNumber * 4))
/* ------------------ PWR registers bit mask ------------------------ */
/* CR register bit mask */
#define CR_PDDS_Set ((u32)0x00000002)
#define CR_DS_Mask ((u32)0xFFFFFFFC)
#define CR_CWUF_Set ((u32)0x00000004)
#define CR_PLS_Mask ((u32)0xFFFFFF1F)
/* --------- Cortex System Control register bit mask ---------------- */
/* Cortex System Control register address */
#define SCB_SysCtrl ((u32)0xE000ED10)
/* SLEEPDEEP bit mask */
#define SysCtrl_SLEEPDEEP_Set ((u32)0x00000004)
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : PWR_DeInit
* Description : Deinitializes the PWR peripheral registers to their default
* reset values.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void PWR_DeInit(void)
{
RCC_APB1PeriphResetCmd(RCC_APB1Periph_PWR, ENABLE);
RCC_APB1PeriphResetCmd(RCC_APB1Periph_PWR, DISABLE);
}
/*******************************************************************************
* Function Name : PWR_BackupAccessCmd
* Description : Enables or disables access to the RTC and backup registers.
* Input : - NewState: new state of the access to the RTC and backup
* registers. This parameter can be: ENABLE or DISABLE.
* Output : None
* Return : None
*******************************************************************************/
void PWR_BackupAccessCmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
*(vu32 *) CR_DBP_BB = (u32)NewState;
}
/*******************************************************************************
* Function Name : PWR_PVDCmd
* Description : Enables or disables the Power Voltage Detector(PVD).
* Input : - NewState: new state of the PVD.
* This parameter can be: ENABLE or DISABLE.
* Output : None
* Return : None
*******************************************************************************/
void PWR_PVDCmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
*(vu32 *) CR_PVDE_BB = (u32)NewState;
}
/*******************************************************************************
* Function Name : PWR_PVDLevelConfig
* Description : Configures the voltage threshold detected by the Power Voltage
* Detector(PVD).
* Input : - PWR_PVDLevel: specifies the PVD detection level
* This parameter can be one of the following values:
* - PWR_PVDLevel_2V2: PVD detection level set to 2.2V
* - PWR_PVDLevel_2V3: PVD detection level set to 2.3V
* - PWR_PVDLevel_2V4: PVD detection level set to 2.4V
* - PWR_PVDLevel_2V5: PVD detection level set to 2.5V
* - PWR_PVDLevel_2V6: PVD detection level set to 2.6V
* - PWR_PVDLevel_2V7: PVD detection level set to 2.7V
* - PWR_PVDLevel_2V8: PVD detection level set to 2.8V
* - PWR_PVDLevel_2V9: PVD detection level set to 2.9V
* Output : None
* Return : None
*******************************************************************************/
void PWR_PVDLevelConfig(u32 PWR_PVDLevel)
{
u32 tmpreg = 0;
/* Check the parameters */
assert_param(IS_PWR_PVD_LEVEL(PWR_PVDLevel));
tmpreg = PWR->CR;
/* Clear PLS[7:5] bits */
tmpreg &= CR_PLS_Mask;
/* Set PLS[7:5] bits according to PWR_PVDLevel value */
tmpreg |= PWR_PVDLevel;
/* Store the new value */
PWR->CR = tmpreg;
}
/*******************************************************************************
* Function Name : PWR_WakeUpPinCmd
* Description : Enables or disables the WakeUp Pin functionality.
* Input : - NewState: new state of the WakeUp Pin functionality.
* This parameter can be: ENABLE or DISABLE.
* Output : None
* Return : None
*******************************************************************************/
void PWR_WakeUpPinCmd(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
*(vu32 *) CSR_EWUP_BB = (u32)NewState;
}
/*******************************************************************************
* Function Name : PWR_EnterSTOPMode
* Description : Enters STOP mode.
* Input : - PWR_Regulator: specifies the regulator state in STOP mode.
* This parameter can be one of the following values:
* - PWR_Regulator_ON: STOP mode with regulator ON
* - PWR_Regulator_LowPower: STOP mode with
* regulator in low power mode
* - PWR_STOPEntry: specifies if STOP mode in entered with WFI or
* WFE instruction.
* This parameter can be one of the following values:
* - PWR_STOPEntry_WFI: enter STOP mode with WFI instruction
* - PWR_STOPEntry_WFE: enter STOP mode with WFE instruction
* Output : None
* Return : None
*******************************************************************************/
void PWR_EnterSTOPMode(u32 PWR_Regulator, u8 PWR_STOPEntry)
{
u32 tmpreg = 0;
/* Check the parameters */
assert_param(IS_PWR_REGULATOR(PWR_Regulator));
assert_param(IS_PWR_STOP_ENTRY(PWR_STOPEntry));
/* Select the regulator state in STOP mode ---------------------------------*/
tmpreg = PWR->CR;
/* Clear PDDS and LPDS bits */
tmpreg &= CR_DS_Mask;
/* Set LPDS bit according to PWR_Regulator value */
tmpreg |= PWR_Regulator;
/* Store the new value */
PWR->CR = tmpreg;
/* Set SLEEPDEEP bit of Cortex System Control Register */
*(vu32 *) SCB_SysCtrl |= SysCtrl_SLEEPDEEP_Set;
/* Select STOP mode entry --------------------------------------------------*/
if(PWR_STOPEntry == PWR_STOPEntry_WFI)
{
/* Request Wait For Interrupt */
__WFI();
}
else
{
/* Request Wait For Event */
__WFE();
}
}
/*******************************************************************************
* Function Name : PWR_EnterSTANDBYMode
* Description : Enters STANDBY mode.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void PWR_EnterSTANDBYMode(void)
{
/* Clear Wake-up flag */
PWR->CR |= CR_CWUF_Set;
/* Select STANDBY mode */
PWR->CR |= CR_PDDS_Set;
/* Set SLEEPDEEP bit of Cortex System Control Register */
*(vu32 *) SCB_SysCtrl |= SysCtrl_SLEEPDEEP_Set;
/* Request Wait For Interrupt */
__WFI();
}
/*******************************************************************************
* Function Name : PWR_GetFlagStatus
* Description : Checks whether the specified PWR flag is set or not.
* Input : - PWR_FLAG: specifies the flag to check.
* This parameter can be one of the following values:
* - PWR_FLAG_WU: Wake Up flag
* - PWR_FLAG_SB: StandBy flag
* - PWR_FLAG_PVDO: PVD Output
* Output : None
* Return : The new state of PWR_FLAG (SET or RESET).
*******************************************************************************/
FlagStatus PWR_GetFlagStatus(u32 PWR_FLAG)
{
FlagStatus bitstatus = RESET;
/* Check the parameters */
assert_param(IS_PWR_GET_FLAG(PWR_FLAG));
if ((PWR->CSR & PWR_FLAG) != (u32)RESET)
{
bitstatus = SET;
}
else
{
bitstatus = RESET;
}
/* Return the flag status */
return bitstatus;
}
/*******************************************************************************
* Function Name : PWR_ClearFlag
* Description : Clears the PWR's pending flags.
* Input : - PWR_FLAG: specifies the flag to clear.
* This parameter can be one of the following values:
* - PWR_FLAG_WU: Wake Up flag
* - PWR_FLAG_SB: StandBy flag
* Output : None
* Return : None
*******************************************************************************/
void PWR_ClearFlag(u32 PWR_FLAG)
{
/* Check the parameters */
assert_param(IS_PWR_CLEAR_FLAG(PWR_FLAG));
PWR->CR |= PWR_FLAG << 2;
}
/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/

File diff suppressed because it is too large Load Diff

View File

@ -1,320 +1,320 @@
/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
* File Name : stm32f10x_rtc.c
* Author : MCD Application Team
* Version : V2.0.3
* Date : 09/22/2008
* Description : This file provides all the RTC firmware functions.
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x_rtc.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
#define CRL_CNF_Set ((u16)0x0010) /* Configuration Flag Enable Mask */
#define CRL_CNF_Reset ((u16)0xFFEF) /* Configuration Flag Disable Mask */
#define RTC_LSB_Mask ((u32)0x0000FFFF) /* RTC LSB Mask */
#define PRLH_MSB_Mask ((u32)0x000F0000) /* RTC Prescaler MSB Mask */
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : RTC_ITConfig
* Description : Enables or disables the specified RTC interrupts.
* Input : - RTC_IT: specifies the RTC interrupts sources to be enabled
* or disabled.
* This parameter can be any combination of the following values:
* - RTC_IT_OW: Overflow interrupt
* - RTC_IT_ALR: Alarm interrupt
* - RTC_IT_SEC: Second interrupt
* - NewState: new state of the specified RTC interrupts.
* This parameter can be: ENABLE or DISABLE.
* Output : None
* Return : None
*******************************************************************************/
void RTC_ITConfig(u16 RTC_IT, FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_RTC_IT(RTC_IT));
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
RTC->CRH |= RTC_IT;
}
else
{
RTC->CRH &= (u16)~RTC_IT;
}
}
/*******************************************************************************
* Function Name : RTC_EnterConfigMode
* Description : Enters the RTC configuration mode.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void RTC_EnterConfigMode(void)
{
/* Set the CNF flag to enter in the Configuration Mode */
RTC->CRL |= CRL_CNF_Set;
}
/*******************************************************************************
* Function Name : RTC_ExitConfigMode
* Description : Exits from the RTC configuration mode.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void RTC_ExitConfigMode(void)
{
/* Reset the CNF flag to exit from the Configuration Mode */
RTC->CRL &= CRL_CNF_Reset;
}
/*******************************************************************************
* Function Name : RTC_GetCounter
* Description : Gets the RTC counter value.
* Input : None
* Output : None
* Return : RTC counter value.
*******************************************************************************/
u32 RTC_GetCounter(void)
{
u16 tmp = 0;
tmp = RTC->CNTL;
return (((u32)RTC->CNTH << 16 ) | tmp) ;
}
/*******************************************************************************
* Function Name : RTC_SetCounter
* Description : Sets the RTC counter value.
* Input : - CounterValue: RTC counter new value.
* Output : None
* Return : None
*******************************************************************************/
void RTC_SetCounter(u32 CounterValue)
{
RTC_EnterConfigMode();
/* Set RTC COUNTER MSB word */
RTC->CNTH = CounterValue >> 16;
/* Set RTC COUNTER LSB word */
RTC->CNTL = (CounterValue & RTC_LSB_Mask);
RTC_ExitConfigMode();
}
/*******************************************************************************
* Function Name : RTC_SetPrescaler
* Description : Sets the RTC prescaler value.
* Input : - PrescalerValue: RTC prescaler new value.
* Output : None
* Return : None
*******************************************************************************/
void RTC_SetPrescaler(u32 PrescalerValue)
{
/* Check the parameters */
assert_param(IS_RTC_PRESCALER(PrescalerValue));
RTC_EnterConfigMode();
/* Set RTC PRESCALER MSB word */
RTC->PRLH = (PrescalerValue & PRLH_MSB_Mask) >> 16;
/* Set RTC PRESCALER LSB word */
RTC->PRLL = (PrescalerValue & RTC_LSB_Mask);
RTC_ExitConfigMode();
}
/*******************************************************************************
* Function Name : RTC_SetAlarm
* Description : Sets the RTC alarm value.
* Input : - AlarmValue: RTC alarm new value.
* Output : None
* Return : None
*******************************************************************************/
void RTC_SetAlarm(u32 AlarmValue)
{
RTC_EnterConfigMode();
/* Set the ALARM MSB word */
RTC->ALRH = AlarmValue >> 16;
/* Set the ALARM LSB word */
RTC->ALRL = (AlarmValue & RTC_LSB_Mask);
RTC_ExitConfigMode();
}
/*******************************************************************************
* Function Name : RTC_GetDivider
* Description : Gets the RTC divider value.
* Input : None
* Output : None
* Return : RTC Divider value.
*******************************************************************************/
u32 RTC_GetDivider(void)
{
u32 tmp = 0x00;
tmp = ((u32)RTC->DIVH & (u32)0x000F) << 16;
tmp |= RTC->DIVL;
return tmp;
}
/*******************************************************************************
* Function Name : RTC_WaitForLastTask
* Description : Waits until last write operation on RTC registers has finished.
* This function must be called before any write to RTC registers.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void RTC_WaitForLastTask(void)
{
/* Loop until RTOFF flag is set */
while ((RTC->CRL & RTC_FLAG_RTOFF) == (u16)RESET)
{
}
}
/*******************************************************************************
* Function Name : RTC_WaitForSynchro
* Description : Waits until the RTC registers (RTC_CNT, RTC_ALR and RTC_PRL)
* are synchronized with RTC APB clock.
* This function must be called before any read operation after
* an APB reset or an APB clock stop.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void RTC_WaitForSynchro(void)
{
/* Clear RSF flag */
RTC->CRL &= (u16)~RTC_FLAG_RSF;
/* Loop until RSF flag is set */
while ((RTC->CRL & RTC_FLAG_RSF) == (u16)RESET)
{
}
}
/*******************************************************************************
* Function Name : RTC_GetFlagStatus
* Description : Checks whether the specified RTC flag is set or not.
* Input : - RTC_FLAG: specifies the flag to check.
* This parameter can be one the following values:
* - RTC_FLAG_RTOFF: RTC Operation OFF flag
* - RTC_FLAG_RSF: Registers Synchronized flag
* - RTC_FLAG_OW: Overflow flag
* - RTC_FLAG_ALR: Alarm flag
* - RTC_FLAG_SEC: Second flag
* Output : None
* Return : The new state of RTC_FLAG (SET or RESET).
*******************************************************************************/
FlagStatus RTC_GetFlagStatus(u16 RTC_FLAG)
{
FlagStatus bitstatus = RESET;
/* Check the parameters */
assert_param(IS_RTC_GET_FLAG(RTC_FLAG));
if ((RTC->CRL & RTC_FLAG) != (u16)RESET)
{
bitstatus = SET;
}
else
{
bitstatus = RESET;
}
return bitstatus;
}
/*******************************************************************************
* Function Name : RTC_ClearFlag
* Description : Clears the RTC<EFBFBD>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
* is cleared only after an APB reset or an APB Clock stop.
* - RTC_FLAG_OW: Overflow flag
* - RTC_FLAG_ALR: Alarm flag
* - RTC_FLAG_SEC: Second flag
* Output : None
* Return : None
*******************************************************************************/
void RTC_ClearFlag(u16 RTC_FLAG)
{
/* Check the parameters */
assert_param(IS_RTC_CLEAR_FLAG(RTC_FLAG));
/* Clear the coressponding RTC flag */
RTC->CRL &= (u16)~RTC_FLAG;
}
/*******************************************************************************
* Function Name : RTC_GetITStatus
* Description : Checks whether the specified RTC interrupt has occured or not.
* Input : - RTC_IT: specifies the RTC interrupts sources to check.
* This parameter can be one of the following values:
* - RTC_IT_OW: Overflow interrupt
* - RTC_IT_ALR: Alarm interrupt
* - RTC_IT_SEC: Second interrupt
* Output : None
* Return : The new state of the RTC_IT (SET or RESET).
*******************************************************************************/
ITStatus RTC_GetITStatus(u16 RTC_IT)
{
ITStatus bitstatus = RESET;
/* Check the parameters */
assert_param(IS_RTC_GET_IT(RTC_IT));
bitstatus = (ITStatus)(RTC->CRL & RTC_IT);
if (((RTC->CRH & RTC_IT) != (u16)RESET) && (bitstatus != (u16)RESET))
{
bitstatus = SET;
}
else
{
bitstatus = RESET;
}
return bitstatus;
}
/*******************************************************************************
* Function Name : RTC_ClearITPendingBit
* Description : Clears the RTC<EFBFBD>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
* - RTC_IT_ALR: Alarm interrupt
* - RTC_IT_SEC: Second interrupt
* Output : None
* Return : None
*******************************************************************************/
void RTC_ClearITPendingBit(u16 RTC_IT)
{
/* Check the parameters */
assert_param(IS_RTC_IT(RTC_IT));
/* Clear the coressponding RTC pending bit */
RTC->CRL &= (u16)~RTC_IT;
}
/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
* File Name : stm32f10x_rtc.c
* Author : MCD Application Team
* Version : V2.0.3
* Date : 09/22/2008
* Description : This file provides all the RTC firmware functions.
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x_rtc.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
#define CRL_CNF_Set ((u16)0x0010) /* Configuration Flag Enable Mask */
#define CRL_CNF_Reset ((u16)0xFFEF) /* Configuration Flag Disable Mask */
#define RTC_LSB_Mask ((u32)0x0000FFFF) /* RTC LSB Mask */
#define PRLH_MSB_Mask ((u32)0x000F0000) /* RTC Prescaler MSB Mask */
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : RTC_ITConfig
* Description : Enables or disables the specified RTC interrupts.
* Input : - RTC_IT: specifies the RTC interrupts sources to be enabled
* or disabled.
* This parameter can be any combination of the following values:
* - RTC_IT_OW: Overflow interrupt
* - RTC_IT_ALR: Alarm interrupt
* - RTC_IT_SEC: Second interrupt
* - NewState: new state of the specified RTC interrupts.
* This parameter can be: ENABLE or DISABLE.
* Output : None
* Return : None
*******************************************************************************/
void RTC_ITConfig(u16 RTC_IT, FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_RTC_IT(RTC_IT));
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
RTC->CRH |= RTC_IT;
}
else
{
RTC->CRH &= (u16)~RTC_IT;
}
}
/*******************************************************************************
* Function Name : RTC_EnterConfigMode
* Description : Enters the RTC configuration mode.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void RTC_EnterConfigMode(void)
{
/* Set the CNF flag to enter in the Configuration Mode */
RTC->CRL |= CRL_CNF_Set;
}
/*******************************************************************************
* Function Name : RTC_ExitConfigMode
* Description : Exits from the RTC configuration mode.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void RTC_ExitConfigMode(void)
{
/* Reset the CNF flag to exit from the Configuration Mode */
RTC->CRL &= CRL_CNF_Reset;
}
/*******************************************************************************
* Function Name : RTC_GetCounter
* Description : Gets the RTC counter value.
* Input : None
* Output : None
* Return : RTC counter value.
*******************************************************************************/
u32 RTC_GetCounter(void)
{
u16 tmp = 0;
tmp = RTC->CNTL;
return (((u32)RTC->CNTH << 16 ) | tmp) ;
}
/*******************************************************************************
* Function Name : RTC_SetCounter
* Description : Sets the RTC counter value.
* Input : - CounterValue: RTC counter new value.
* Output : None
* Return : None
*******************************************************************************/
void RTC_SetCounter(u32 CounterValue)
{
RTC_EnterConfigMode();
/* Set RTC COUNTER MSB word */
RTC->CNTH = CounterValue >> 16;
/* Set RTC COUNTER LSB word */
RTC->CNTL = (CounterValue & RTC_LSB_Mask);
RTC_ExitConfigMode();
}
/*******************************************************************************
* Function Name : RTC_SetPrescaler
* Description : Sets the RTC prescaler value.
* Input : - PrescalerValue: RTC prescaler new value.
* Output : None
* Return : None
*******************************************************************************/
void RTC_SetPrescaler(u32 PrescalerValue)
{
/* Check the parameters */
assert_param(IS_RTC_PRESCALER(PrescalerValue));
RTC_EnterConfigMode();
/* Set RTC PRESCALER MSB word */
RTC->PRLH = (PrescalerValue & PRLH_MSB_Mask) >> 16;
/* Set RTC PRESCALER LSB word */
RTC->PRLL = (PrescalerValue & RTC_LSB_Mask);
RTC_ExitConfigMode();
}
/*******************************************************************************
* Function Name : RTC_SetAlarm
* Description : Sets the RTC alarm value.
* Input : - AlarmValue: RTC alarm new value.
* Output : None
* Return : None
*******************************************************************************/
void RTC_SetAlarm(u32 AlarmValue)
{
RTC_EnterConfigMode();
/* Set the ALARM MSB word */
RTC->ALRH = AlarmValue >> 16;
/* Set the ALARM LSB word */
RTC->ALRL = (AlarmValue & RTC_LSB_Mask);
RTC_ExitConfigMode();
}
/*******************************************************************************
* Function Name : RTC_GetDivider
* Description : Gets the RTC divider value.
* Input : None
* Output : None
* Return : RTC Divider value.
*******************************************************************************/
u32 RTC_GetDivider(void)
{
u32 tmp = 0x00;
tmp = ((u32)RTC->DIVH & (u32)0x000F) << 16;
tmp |= RTC->DIVL;
return tmp;
}
/*******************************************************************************
* Function Name : RTC_WaitForLastTask
* Description : Waits until last write operation on RTC registers has finished.
* This function must be called before any write to RTC registers.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void RTC_WaitForLastTask(void)
{
/* Loop until RTOFF flag is set */
while ((RTC->CRL & RTC_FLAG_RTOFF) == (u16)RESET)
{
}
}
/*******************************************************************************
* Function Name : RTC_WaitForSynchro
* Description : Waits until the RTC registers (RTC_CNT, RTC_ALR and RTC_PRL)
* are synchronized with RTC APB clock.
* This function must be called before any read operation after
* an APB reset or an APB clock stop.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void RTC_WaitForSynchro(void)
{
/* Clear RSF flag */
RTC->CRL &= (u16)~RTC_FLAG_RSF;
/* Loop until RSF flag is set */
while ((RTC->CRL & RTC_FLAG_RSF) == (u16)RESET)
{
}
}
/*******************************************************************************
* Function Name : RTC_GetFlagStatus
* Description : Checks whether the specified RTC flag is set or not.
* Input : - RTC_FLAG: specifies the flag to check.
* This parameter can be one the following values:
* - RTC_FLAG_RTOFF: RTC Operation OFF flag
* - RTC_FLAG_RSF: Registers Synchronized flag
* - RTC_FLAG_OW: Overflow flag
* - RTC_FLAG_ALR: Alarm flag
* - RTC_FLAG_SEC: Second flag
* Output : None
* Return : The new state of RTC_FLAG (SET or RESET).
*******************************************************************************/
FlagStatus RTC_GetFlagStatus(u16 RTC_FLAG)
{
FlagStatus bitstatus = RESET;
/* Check the parameters */
assert_param(IS_RTC_GET_FLAG(RTC_FLAG));
if ((RTC->CRL & RTC_FLAG) != (u16)RESET)
{
bitstatus = SET;
}
else
{
bitstatus = RESET;
}
return bitstatus;
}
/*******************************************************************************
* Function Name : RTC_ClearFlag
* 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
* is cleared only after an APB reset or an APB Clock stop.
* - RTC_FLAG_OW: Overflow flag
* - RTC_FLAG_ALR: Alarm flag
* - RTC_FLAG_SEC: Second flag
* Output : None
* Return : None
*******************************************************************************/
void RTC_ClearFlag(u16 RTC_FLAG)
{
/* Check the parameters */
assert_param(IS_RTC_CLEAR_FLAG(RTC_FLAG));
/* Clear the coressponding RTC flag */
RTC->CRL &= (u16)~RTC_FLAG;
}
/*******************************************************************************
* Function Name : RTC_GetITStatus
* Description : Checks whether the specified RTC interrupt has occured or not.
* Input : - RTC_IT: specifies the RTC interrupts sources to check.
* This parameter can be one of the following values:
* - RTC_IT_OW: Overflow interrupt
* - RTC_IT_ALR: Alarm interrupt
* - RTC_IT_SEC: Second interrupt
* Output : None
* Return : The new state of the RTC_IT (SET or RESET).
*******************************************************************************/
ITStatus RTC_GetITStatus(u16 RTC_IT)
{
ITStatus bitstatus = RESET;
/* Check the parameters */
assert_param(IS_RTC_GET_IT(RTC_IT));
bitstatus = (ITStatus)(RTC->CRL & RTC_IT);
if (((RTC->CRH & RTC_IT) != (u16)RESET) && (bitstatus != (u16)RESET))
{
bitstatus = SET;
}
else
{
bitstatus = RESET;
}
return bitstatus;
}
/*******************************************************************************
* Function Name : RTC_ClearITPendingBit
* 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
* - RTC_IT_ALR: Alarm interrupt
* - RTC_IT_SEC: Second interrupt
* Output : None
* Return : None
*******************************************************************************/
void RTC_ClearITPendingBit(u16 RTC_IT)
{
/* Check the parameters */
assert_param(IS_RTC_IT(RTC_IT));
/* Clear the coressponding RTC pending bit */
RTC->CRL &= (u16)~RTC_IT;
}
/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -1,181 +1,181 @@
/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
* File Name : stm32f10x_systick.c
* Author : MCD Application Team
* Version : V2.0.3
* Date : 09/22/2008
* Description : This file provides all the SysTick firmware functions.
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x_systick.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* ---------------------- SysTick registers bit mask -------------------- */
/* CTRL TICKINT Mask */
#define CTRL_TICKINT_Set ((u32)0x00000002)
#define CTRL_TICKINT_Reset ((u32)0xFFFFFFFD)
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : SysTick_CLKSourceConfig
* Description : Configures the SysTick clock source.
* Input : - SysTick_CLKSource: specifies the SysTick clock source.
* This parameter can be one of the following values:
* - SysTick_CLKSource_HCLK_Div8: AHB clock divided by 8
* selected as SysTick clock source.
* - SysTick_CLKSource_HCLK: AHB clock selected as
* SysTick clock source.
* Output : None
* Return : None
*******************************************************************************/
void SysTick_CLKSourceConfig(u32 SysTick_CLKSource)
{
/* Check the parameters */
assert_param(IS_SYSTICK_CLK_SOURCE(SysTick_CLKSource));
if (SysTick_CLKSource == SysTick_CLKSource_HCLK)
{
SysTick->CTRL |= SysTick_CLKSource_HCLK;
}
else
{
SysTick->CTRL &= SysTick_CLKSource_HCLK_Div8;
}
}
/*******************************************************************************
* Function Name : SysTick_SetReload
* Description : Sets SysTick Reload value.
* Input : - Reload: SysTick Reload new value.
* This parameter must be a number between 1 and 0xFFFFFF.
* Output : None
* Return : None
*******************************************************************************/
void SysTick_SetReload(u32 Reload)
{
/* Check the parameters */
assert_param(IS_SYSTICK_RELOAD(Reload));
SysTick->LOAD = Reload;
}
/*******************************************************************************
* Function Name : SysTick_CounterCmd
* Description : Enables or disables the SysTick counter.
* Input : - SysTick_Counter: new state of the SysTick counter.
* This parameter can be one of the following values:
* - SysTick_Counter_Disable: Disable counter
* - SysTick_Counter_Enable: Enable counter
* - SysTick_Counter_Clear: Clear counter value to 0
* Output : None
* Return : None
*******************************************************************************/
void SysTick_CounterCmd(u32 SysTick_Counter)
{
/* Check the parameters */
assert_param(IS_SYSTICK_COUNTER(SysTick_Counter));
if (SysTick_Counter == SysTick_Counter_Enable)
{
SysTick->CTRL |= SysTick_Counter_Enable;
}
else if (SysTick_Counter == SysTick_Counter_Disable)
{
SysTick->CTRL &= SysTick_Counter_Disable;
}
else /* SysTick_Counter == SysTick_Counter_Clear */
{
SysTick->VAL = SysTick_Counter_Clear;
}
}
/*******************************************************************************
* Function Name : SysTick_ITConfig
* Description : Enables or disables the SysTick Interrupt.
* Input : - NewState: new state of the SysTick Interrupt.
* This parameter can be: ENABLE or DISABLE.
* Output : None
* Return : None
*******************************************************************************/
void SysTick_ITConfig(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
SysTick->CTRL |= CTRL_TICKINT_Set;
}
else
{
SysTick->CTRL &= CTRL_TICKINT_Reset;
}
}
/*******************************************************************************
* Function Name : SysTick_GetCounter
* Description : Gets SysTick counter value.
* Input : None
* Output : None
* Return : SysTick current value
*******************************************************************************/
u32 SysTick_GetCounter(void)
{
return(SysTick->VAL);
}
/*******************************************************************************
* Function Name : SysTick_GetFlagStatus
* Description : Checks whether the specified SysTick flag is set or not.
* Input : - SysTick_FLAG: specifies the flag to check.
* This parameter can be one of the following values:
* - SysTick_FLAG_COUNT
* - SysTick_FLAG_SKEW
* - SysTick_FLAG_NOREF
* Output : None
* Return : None
*******************************************************************************/
FlagStatus SysTick_GetFlagStatus(u8 SysTick_FLAG)
{
u32 statusreg = 0, tmp = 0 ;
FlagStatus bitstatus = RESET;
/* Check the parameters */
assert_param(IS_SYSTICK_FLAG(SysTick_FLAG));
/* Get the SysTick register index */
tmp = SysTick_FLAG >> 3;
if (tmp == 2) /* The flag to check is in CTRL register */
{
statusreg = SysTick->CTRL;
}
else /* The flag to check is in CALIB register */
{
statusreg = SysTick->CALIB;
}
if ((statusreg & ((u32)1 << SysTick_FLAG)) != (u32)RESET)
{
bitstatus = SET;
}
else
{
bitstatus = RESET;
}
return bitstatus;
}
/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
* File Name : stm32f10x_systick.c
* Author : MCD Application Team
* Version : V2.0.3
* Date : 09/22/2008
* Description : This file provides all the SysTick firmware functions.
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x_systick.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* ---------------------- SysTick registers bit mask -------------------- */
/* CTRL TICKINT Mask */
#define CTRL_TICKINT_Set ((u32)0x00000002)
#define CTRL_TICKINT_Reset ((u32)0xFFFFFFFD)
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : SysTick_CLKSourceConfig
* Description : Configures the SysTick clock source.
* Input : - SysTick_CLKSource: specifies the SysTick clock source.
* This parameter can be one of the following values:
* - SysTick_CLKSource_HCLK_Div8: AHB clock divided by 8
* selected as SysTick clock source.
* - SysTick_CLKSource_HCLK: AHB clock selected as
* SysTick clock source.
* Output : None
* Return : None
*******************************************************************************/
void SysTick_CLKSourceConfig(u32 SysTick_CLKSource)
{
/* Check the parameters */
assert_param(IS_SYSTICK_CLK_SOURCE(SysTick_CLKSource));
if (SysTick_CLKSource == SysTick_CLKSource_HCLK)
{
SysTick->CTRL |= SysTick_CLKSource_HCLK;
}
else
{
SysTick->CTRL &= SysTick_CLKSource_HCLK_Div8;
}
}
/*******************************************************************************
* Function Name : SysTick_SetReload
* Description : Sets SysTick Reload value.
* Input : - Reload: SysTick Reload new value.
* This parameter must be a number between 1 and 0xFFFFFF.
* Output : None
* Return : None
*******************************************************************************/
void SysTick_SetReload(u32 Reload)
{
/* Check the parameters */
assert_param(IS_SYSTICK_RELOAD(Reload));
SysTick->LOAD = Reload;
}
/*******************************************************************************
* Function Name : SysTick_CounterCmd
* Description : Enables or disables the SysTick counter.
* Input : - SysTick_Counter: new state of the SysTick counter.
* This parameter can be one of the following values:
* - SysTick_Counter_Disable: Disable counter
* - SysTick_Counter_Enable: Enable counter
* - SysTick_Counter_Clear: Clear counter value to 0
* Output : None
* Return : None
*******************************************************************************/
void SysTick_CounterCmd(u32 SysTick_Counter)
{
/* Check the parameters */
assert_param(IS_SYSTICK_COUNTER(SysTick_Counter));
if (SysTick_Counter == SysTick_Counter_Enable)
{
SysTick->CTRL |= SysTick_Counter_Enable;
}
else if (SysTick_Counter == SysTick_Counter_Disable)
{
SysTick->CTRL &= SysTick_Counter_Disable;
}
else /* SysTick_Counter == SysTick_Counter_Clear */
{
SysTick->VAL = SysTick_Counter_Clear;
}
}
/*******************************************************************************
* Function Name : SysTick_ITConfig
* Description : Enables or disables the SysTick Interrupt.
* Input : - NewState: new state of the SysTick Interrupt.
* This parameter can be: ENABLE or DISABLE.
* Output : None
* Return : None
*******************************************************************************/
void SysTick_ITConfig(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
SysTick->CTRL |= CTRL_TICKINT_Set;
}
else
{
SysTick->CTRL &= CTRL_TICKINT_Reset;
}
}
/*******************************************************************************
* Function Name : SysTick_GetCounter
* Description : Gets SysTick counter value.
* Input : None
* Output : None
* Return : SysTick current value
*******************************************************************************/
u32 SysTick_GetCounter(void)
{
return(SysTick->VAL);
}
/*******************************************************************************
* Function Name : SysTick_GetFlagStatus
* Description : Checks whether the specified SysTick flag is set or not.
* Input : - SysTick_FLAG: specifies the flag to check.
* This parameter can be one of the following values:
* - SysTick_FLAG_COUNT
* - SysTick_FLAG_SKEW
* - SysTick_FLAG_NOREF
* Output : None
* Return : None
*******************************************************************************/
FlagStatus SysTick_GetFlagStatus(u8 SysTick_FLAG)
{
u32 statusreg = 0, tmp = 0 ;
FlagStatus bitstatus = RESET;
/* Check the parameters */
assert_param(IS_SYSTICK_FLAG(SysTick_FLAG));
/* Get the SysTick register index */
tmp = SysTick_FLAG >> 3;
if (tmp == 2) /* The flag to check is in CTRL register */
{
statusreg = SysTick->CTRL;
}
else /* The flag to check is in CALIB register */
{
statusreg = SysTick->CALIB;
}
if ((statusreg & ((u32)1 << SysTick_FLAG)) != (u32)RESET)
{
bitstatus = SET;
}
else
{
bitstatus = RESET;
}
return bitstatus;
}
/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -1,185 +1,185 @@
/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
* File Name : stm32f10x_wwdg.c
* Author : MCD Application Team
* Version : V2.0.3
* Date : 09/22/2008
* Description : This file provides all the WWDG firmware functions.
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x_wwdg.h"
#include "stm32f10x_rcc.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* ----------- WWDG registers bit address in the alias region ----------- */
#define WWDG_OFFSET (WWDG_BASE - PERIPH_BASE)
/* Alias word address of EWI bit */
#define CFR_OFFSET (WWDG_OFFSET + 0x04)
#define EWI_BitNumber 0x09
#define CFR_EWI_BB (PERIPH_BB_BASE + (CFR_OFFSET * 32) + (EWI_BitNumber * 4))
/* --------------------- WWDG registers bit mask ------------------------ */
/* CR register bit mask */
#define CR_WDGA_Set ((u32)0x00000080)
/* CFR register bit mask */
#define CFR_WDGTB_Mask ((u32)0xFFFFFE7F)
#define CFR_W_Mask ((u32)0xFFFFFF80)
#define BIT_Mask ((u8)0x7F)
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : WWDG_DeInit
* Description : Deinitializes the WWDG peripheral registers to their default
* reset values.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void WWDG_DeInit(void)
{
RCC_APB1PeriphResetCmd(RCC_APB1Periph_WWDG, ENABLE);
RCC_APB1PeriphResetCmd(RCC_APB1Periph_WWDG, DISABLE);
}
/*******************************************************************************
* Function Name : WWDG_SetPrescaler
* Description : Sets the WWDG Prescaler.
* Input : - WWDG_Prescaler: specifies the WWDG Prescaler.
* This parameter can be one of the following values:
* - WWDG_Prescaler_1: WWDG counter clock = (PCLK1/4096)/1
* - WWDG_Prescaler_2: WWDG counter clock = (PCLK1/4096)/2
* - WWDG_Prescaler_4: WWDG counter clock = (PCLK1/4096)/4
* - WWDG_Prescaler_8: WWDG counter clock = (PCLK1/4096)/8
* Output : None
* Return : None
*******************************************************************************/
void WWDG_SetPrescaler(u32 WWDG_Prescaler)
{
u32 tmpreg = 0;
/* Check the parameters */
assert_param(IS_WWDG_PRESCALER(WWDG_Prescaler));
/* Clear WDGTB[1:0] bits */
tmpreg = WWDG->CFR & CFR_WDGTB_Mask;
/* Set WDGTB[1:0] bits according to WWDG_Prescaler value */
tmpreg |= WWDG_Prescaler;
/* Store the new value */
WWDG->CFR = tmpreg;
}
/*******************************************************************************
* Function Name : WWDG_SetWindowValue
* Description : Sets the WWDG window value.
* Input : - WindowValue: specifies the window value to be compared to
* the downcounter.
* This parameter value must be lower than 0x80.
* Output : None
* Return : None
*******************************************************************************/
void WWDG_SetWindowValue(u8 WindowValue)
{
u32 tmpreg = 0;
/* Check the parameters */
assert_param(IS_WWDG_WINDOW_VALUE(WindowValue));
/* Clear W[6:0] bits */
tmpreg = WWDG->CFR & CFR_W_Mask;
/* Set W[6:0] bits according to WindowValue value */
tmpreg |= WindowValue & BIT_Mask;
/* Store the new value */
WWDG->CFR = tmpreg;
}
/*******************************************************************************
* Function Name : WWDG_EnableIT
* Description : Enables the WWDG Early Wakeup interrupt(EWI).
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void WWDG_EnableIT(void)
{
*(vu32 *) CFR_EWI_BB = (u32)ENABLE;
}
/*******************************************************************************
* Function Name : WWDG_SetCounter
* Description : Sets the WWDG counter value.
* Input : - Counter: specifies the watchdog counter value.
* This parameter must be a number between 0x40 and 0x7F.
* Output : None
* Return : None
*******************************************************************************/
void WWDG_SetCounter(u8 Counter)
{
/* Check the parameters */
assert_param(IS_WWDG_COUNTER(Counter));
/* Write to T[6:0] bits to configure the counter value, no need to do
a read-modify-write; writing a 0 to WDGA bit does nothing */
WWDG->CR = Counter & BIT_Mask;
}
/*******************************************************************************
* Function Name : WWDG_Enable
* Description : Enables WWDG and load the counter value.
* - Counter: specifies the watchdog counter value.
* This parameter must be a number between 0x40 and 0x7F.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void WWDG_Enable(u8 Counter)
{
/* Check the parameters */
assert_param(IS_WWDG_COUNTER(Counter));
WWDG->CR = CR_WDGA_Set | Counter;
}
/*******************************************************************************
* Function Name : WWDG_GetFlagStatus
* Description : Checks whether the Early Wakeup interrupt flag is set or not.
* Input : None
* Output : None
* Return : The new state of the Early Wakeup interrupt flag (SET or RESET)
*******************************************************************************/
FlagStatus WWDG_GetFlagStatus(void)
{
return (FlagStatus)(WWDG->SR);
}
/*******************************************************************************
* Function Name : WWDG_ClearFlag
* Description : Clears Early Wakeup interrupt flag.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void WWDG_ClearFlag(void)
{
WWDG->SR = (u32)RESET;
}
/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
* File Name : stm32f10x_wwdg.c
* Author : MCD Application Team
* Version : V2.0.3
* Date : 09/22/2008
* Description : This file provides all the WWDG firmware functions.
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Includes ------------------------------------------------------------------*/
#include "stm32f10x_wwdg.h"
#include "stm32f10x_rcc.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* ----------- WWDG registers bit address in the alias region ----------- */
#define WWDG_OFFSET (WWDG_BASE - PERIPH_BASE)
/* Alias word address of EWI bit */
#define CFR_OFFSET (WWDG_OFFSET + 0x04)
#define EWI_BitNumber 0x09
#define CFR_EWI_BB (PERIPH_BB_BASE + (CFR_OFFSET * 32) + (EWI_BitNumber * 4))
/* --------------------- WWDG registers bit mask ------------------------ */
/* CR register bit mask */
#define CR_WDGA_Set ((u32)0x00000080)
/* CFR register bit mask */
#define CFR_WDGTB_Mask ((u32)0xFFFFFE7F)
#define CFR_W_Mask ((u32)0xFFFFFF80)
#define BIT_Mask ((u8)0x7F)
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : WWDG_DeInit
* Description : Deinitializes the WWDG peripheral registers to their default
* reset values.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void WWDG_DeInit(void)
{
RCC_APB1PeriphResetCmd(RCC_APB1Periph_WWDG, ENABLE);
RCC_APB1PeriphResetCmd(RCC_APB1Periph_WWDG, DISABLE);
}
/*******************************************************************************
* Function Name : WWDG_SetPrescaler
* Description : Sets the WWDG Prescaler.
* Input : - WWDG_Prescaler: specifies the WWDG Prescaler.
* This parameter can be one of the following values:
* - WWDG_Prescaler_1: WWDG counter clock = (PCLK1/4096)/1
* - WWDG_Prescaler_2: WWDG counter clock = (PCLK1/4096)/2
* - WWDG_Prescaler_4: WWDG counter clock = (PCLK1/4096)/4
* - WWDG_Prescaler_8: WWDG counter clock = (PCLK1/4096)/8
* Output : None
* Return : None
*******************************************************************************/
void WWDG_SetPrescaler(u32 WWDG_Prescaler)
{
u32 tmpreg = 0;
/* Check the parameters */
assert_param(IS_WWDG_PRESCALER(WWDG_Prescaler));
/* Clear WDGTB[1:0] bits */
tmpreg = WWDG->CFR & CFR_WDGTB_Mask;
/* Set WDGTB[1:0] bits according to WWDG_Prescaler value */
tmpreg |= WWDG_Prescaler;
/* Store the new value */
WWDG->CFR = tmpreg;
}
/*******************************************************************************
* Function Name : WWDG_SetWindowValue
* Description : Sets the WWDG window value.
* Input : - WindowValue: specifies the window value to be compared to
* the downcounter.
* This parameter value must be lower than 0x80.
* Output : None
* Return : None
*******************************************************************************/
void WWDG_SetWindowValue(u8 WindowValue)
{
u32 tmpreg = 0;
/* Check the parameters */
assert_param(IS_WWDG_WINDOW_VALUE(WindowValue));
/* Clear W[6:0] bits */
tmpreg = WWDG->CFR & CFR_W_Mask;
/* Set W[6:0] bits according to WindowValue value */
tmpreg |= WindowValue & BIT_Mask;
/* Store the new value */
WWDG->CFR = tmpreg;
}
/*******************************************************************************
* Function Name : WWDG_EnableIT
* Description : Enables the WWDG Early Wakeup interrupt(EWI).
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void WWDG_EnableIT(void)
{
*(vu32 *) CFR_EWI_BB = (u32)ENABLE;
}
/*******************************************************************************
* Function Name : WWDG_SetCounter
* Description : Sets the WWDG counter value.
* Input : - Counter: specifies the watchdog counter value.
* This parameter must be a number between 0x40 and 0x7F.
* Output : None
* Return : None
*******************************************************************************/
void WWDG_SetCounter(u8 Counter)
{
/* Check the parameters */
assert_param(IS_WWDG_COUNTER(Counter));
/* Write to T[6:0] bits to configure the counter value, no need to do
a read-modify-write; writing a 0 to WDGA bit does nothing */
WWDG->CR = Counter & BIT_Mask;
}
/*******************************************************************************
* Function Name : WWDG_Enable
* Description : Enables WWDG and load the counter value.
* - Counter: specifies the watchdog counter value.
* This parameter must be a number between 0x40 and 0x7F.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void WWDG_Enable(u8 Counter)
{
/* Check the parameters */
assert_param(IS_WWDG_COUNTER(Counter));
WWDG->CR = CR_WDGA_Set | Counter;
}
/*******************************************************************************
* Function Name : WWDG_GetFlagStatus
* Description : Checks whether the Early Wakeup interrupt flag is set or not.
* Input : None
* Output : None
* Return : The new state of the Early Wakeup interrupt flag (SET or RESET)
*******************************************************************************/
FlagStatus WWDG_GetFlagStatus(void)
{
return (FlagStatus)(WWDG->SR);
}
/*******************************************************************************
* Function Name : WWDG_ClearFlag
* Description : Clears Early Wakeup interrupt flag.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void WWDG_ClearFlag(void)
{
WWDG->SR = (u32)RESET;
}
/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/

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)
{

File diff suppressed because it is too large Load Diff

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
@ -16,19 +17,19 @@
//#define BUILD_DHCPC
//#define BUILD_DNS
#define BUILD_CON_GENERIC
//#define BUILD_CON_TCP
//#define BUILD_CON_TCP
#define EXTENDED_PLATFORM_DATA
// *****************************************************************************
// 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
@ -46,42 +47,75 @@
{ AUXLIB_NET, luaopen_net },\
{ AUXLIB_CPU, luaopen_cpu },\
{ LUA_MATHLIBNAME, luaopen_math }
#else
#define LUA_PLATFORM_LIBS\
{ AUXLIB_PIO, luaopen_pio },\
{ AUXLIB_PD, luaopen_pd },\
{ AUXLIB_UART, luaopen_uart },\
{ AUXLIB_TERM, luaopen_term },\
{ AUXLIB_PACK, luaopen_pack },\
{ AUXLIB_BIT, luaopen_bit },\
{ AUXLIB_CPU, luaopen_cpu },\
{ AUXLIB_MOD, luaopen_mod },\
{ LUA_MATHLIBNAME, luaopen_math }
#endif
#else
#define LUA_PLATFORM_LIBS\
{ AUXLIB_PIO, luaopen_pio },\
{ AUXLIB_PD, luaopen_pd },\
{ AUXLIB_UART, luaopen_uart },\
{ AUXLIB_TERM, luaopen_term },\
{ AUXLIB_PACK, luaopen_pack },\
{ AUXLIB_BIT, luaopen_bit },\
{ AUXLIB_CPU, luaopen_cpu },\
{ AUXLIB_MOD, luaopen_mod },\
{ LUA_MATHLIBNAME, luaopen_math }
#endif
// *****************************************************************************
// 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,42 +50,20 @@ 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;
}
// ****************************************************************************
// 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,34 +289,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;
}
// ****************************************************************************
// 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 };
static const u16 pwm_pins[ NUM_PWM ] = { 1 << 7, 1 << 13, 1 << 2 };
static const u8 pwm_ports[ NUM_PWM ] = { 1, 0, 1 };
int platform_pwm_exists( unsigned id )
{
return id < PLATFORM_NUM_PWMS;
}
u32 platform_pwm_setup( unsigned id, u32 frequency, unsigned duty )
{
u32 pwmclk = platform_timer_get_clock( id + 1 );
@ -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
@ -38,5 +39,37 @@
{ AUXLIB_PACK, luaopen_pack },\
{ 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,34 +91,14 @@ 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;
}
// ****************************************************************************
// 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;
}