[sam] UART/USART write(char) working and cmsis update

This commit is contained in:
Thibaut VIARD 2011-09-16 23:07:44 +02:00
parent d1d60447e9
commit 04432caacd
52 changed files with 602 additions and 364 deletions

View File

@ -28,6 +28,7 @@ extern "C"{
#include "wiring_digital.h"
#include "wiring_analog.h"
#include "wiring_shift.h"
#include "WInterrupts.h"
/* sketch */
extern void setup( void ) ;
@ -52,6 +53,19 @@ extern void loop( void ) ;
#define NOT_ON_TIMER 0
#define TIMER0 1
typedef enum _EExt_Interrupts
{
EXTERNAL_INT_0=0,
EXTERNAL_INT_1=1,
EXTERNAL_INT_2=2,
EXTERNAL_INT_3=3,
EXTERNAL_INT_4=4,
EXTERNAL_INT_5=5,
EXTERNAL_INT_6=6,
EXTERNAL_INT_7=7,
EXTERNAL_NUM_INTERRUPTS
} EExt_Interrupts ;
typedef void (*voidFuncPtr)( void ) ;
/* Define attribute */

View File

@ -24,9 +24,9 @@ class HardwareSerial : public Stream
virtual void flush( void ) =0 ;
virtual void write( const uint8_t c ) =0 ;
virtual void write( const char *str ) ;
virtual void write( const uint8_t *buffer, size_t size ) ;
// using Print::write ; // pull in write(str) and write(buf, size) from Print
// virtual void write( const char *str ) ;
// virtual void write( const uint8_t *buffer, size_t size ) ;
using Print::write ; // pull in write(str) and write(buf, size) from Print
} ;
#endif // HardwareSerial_h

View File

@ -1,6 +1,42 @@
//#include <inttypes.h>
//#include <stdio.h>
/*
%atmel_license%
*/
#include "WInterrupts.h"
#include "wiring_private.h"
#ifdef __cplusplus
extern "C" {
#endif
/** PIO interrupt handlers array */
/*volatile*/ static voidFuncPtr g_apfn_IntFunc[EXTERNAL_NUM_INTERRUPTS]={ 0 } ;
void attachInterrupt( uint32_t ulInterrupt, void (*pfn_UserFunc)(void), uint32_t ulMode )
{
if ( ulInterrupt < EXTERNAL_NUM_INTERRUPTS )
{
g_apfn_IntFunc[ulInterrupt] = pfn_UserFunc ;
// Configure the interrupt mode (trigger on low input, any change, rising
// edge, or falling edge). The mode constants were chosen to correspond
// to the configuration bits in the hardware register, so we simply shift
// the mode into place.
// Enable the interrupt.
}
}
void detachInterrupt( uint32_t ulInterrupt )
{
if ( ulInterrupt < EXTERNAL_NUM_INTERRUPTS )
{
/* Disable the interrupt. */
g_apfn_IntFunc[ulInterrupt] = NULL ;
}
}
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,68 @@
/*
%atmel_license%
*/
#ifndef _WIRING_INTERRUPTS_
#define _WIRING_INTERRUPTS_
#include "Arduino.h"
#ifdef __cplusplus
extern "C" {
#endif
//typedef struct _InterruptSource
//{
// /* Pointer to the source pin instance. */
// PinDescription *pPin ;
//
// /* Interrupt handler. */
// void (*handler)( const PinDescription *pPin ) ;
//} InterruptSource ;
/*
* \brief Specifies a function to call when an external interrupt occurs.
* Replaces any previous function that was attached to the interrupt.
* All Arduino SAM3 based boards pins can be switched into INPUT mode and have
* an interrupt user function attached to an event.
*
* \param ulInterrupt
* \param pfn_UserFunc
* \param ulMode
*
PIO_IT_RE_OR_HL = Interrupt High Level/Rising Edge detection is active
PIO_IT_EDGE = Interrupt Edge detection is active
PIO_IT_LOW_LEVEL = Low level interrupt is active
PIO_IT_HIGH_LEVEL = High level interrupt is active
PIO_IT_FALL_EDGE = Falling edge interrupt is active
PIO_IT_RISE_EDGE = Rising edge interrupt is active
interrupt: the number of the interrupt (int)
function: the function to call when the interrupt occurs; this function must take no parameters and return nothing. This function is sometimes referred to as an interrupt service routine.
mode defines when the interrupt should be triggered. Four contstants are predefined as valid values:
LOW to trigger the interrupt whenever the pin is low,
CHANGE to trigger the interrupt whenever the pin changes value
RISING to trigger when the pin goes from low to high,
FALLING for when the pin goes from high to low.
*/
extern void attachInterrupt( uint32_t ulInterrupt, void (*pfn_UserFunc)(void), uint32_t ulMode ) ;
/*
Turns off the given interrupt.
Parameters
interrupt: the number of interrupt to disable (0 or 1).
*/
extern void detachInterrupt( uint32_t ulInterrupt ) ;
#ifdef __cplusplus
}
#endif
#endif /* _WIRING_INTERRUPTS_ */

View File

@ -6,6 +6,7 @@ extern "C" {
#include "stdlib.h"
#include "stdint.h"
}
#include "WMath.h"
extern void randomSeed( uint32_t dwSeed )
{
@ -42,7 +43,7 @@ extern long map(long x, long in_min, long in_max, long out_min, long out_max)
return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
}
extern uint16_t makeWord( uint32_t w )
extern uint16_t makeWord( uint16_t w )
{
return w ;
}

View File

@ -11,7 +11,7 @@ extern void randomSeed( uint32_t dwSeed ) ;
extern long map( long, long, long, long, long ) ;
extern uint16_t makeWord( uint16_t w ) ;
extern uint16_t makeWord( byte h, byte l ) ;
extern uint16_t makeWord( uint8_t h, uint8_t l ) ;
#define word(...) makeWord(__VA_ARGS__)

View File

@ -20,6 +20,7 @@
*/
#include "WString.h"
#include "itoa.h"
/*********************************************/
@ -64,7 +65,7 @@ String::String(unsigned char value, unsigned char base)
{
init();
char buf[9];
// utoa(value, buf, base);
utoa(value, buf, base);
*this = buf;
}
@ -72,7 +73,7 @@ String::String(int value, unsigned char base)
{
init();
char buf[18];
// itoa(value, buf, base);
itoa(value, buf, base);
*this = buf;
}
@ -80,7 +81,7 @@ String::String(unsigned int value, unsigned char base)
{
init();
char buf[17];
// utoa(value, buf, base);
utoa(value, buf, base);
*this = buf;
}
@ -88,7 +89,7 @@ String::String(long value, unsigned char base)
{
init();
char buf[34];
// ltoa(value, buf, base);
ltoa(value, buf, base);
*this = buf;
}
@ -96,7 +97,7 @@ String::String(unsigned long value, unsigned char base)
{
init();
char buf[33];
// ultoa(value, buf, base);
ultoa(value, buf, base);
*this = buf;
}
@ -258,28 +259,28 @@ unsigned char String::concat(unsigned char num)
unsigned char String::concat(int num)
{
char buf[7];
// itoa(num, buf, 10);
itoa(num, buf, 10);
return concat(buf, strlen(buf));
}
unsigned char String::concat(unsigned int num)
{
char buf[6];
// utoa(num, buf, 10);
utoa(num, buf, 10);
return concat(buf, strlen(buf));
}
unsigned char String::concat(long num)
{
char buf[12];
// ltoa(num, buf, 10);
ltoa(num, buf, 10);
return concat(buf, strlen(buf));
}
unsigned char String::concat(unsigned long num)
{
char buf[11];
// ultoa(num, buf, 10);
ultoa(num, buf, 10);
return concat(buf, strlen(buf));
}

View File

@ -1,5 +1,7 @@
ifeq ("$(VARIANTS)", "")
#VARIANTS = sam3s_ek sam3u_ek arduino_due
VARIANTS = arduino_due
VARIANTS = sam3u_ek
endif
SUBMAKE_OPTIONS=--no-builtin-rules --no-builtin-variables

View File

@ -53,7 +53,8 @@ CPPFLAGS += -Wpacked -Wredundant-decls -Winline -Wlong-long
#CPPFLAGS += -Wmissing-noreturn
#CPPFLAGS += -Wconversion
CPPFLAGS += --param max-inline-insns-single=500 -mcpu=cortex-m3 -mthumb -mlong-calls -ffunction-sections -fno-rtti -fno-exceptions
#-fno-rtti -fno-exceptions
CPPFLAGS += --param max-inline-insns-single=500 -mcpu=cortex-m3 -mthumb -mlong-calls -ffunction-sections
CPPFLAGS += $(OPTIMIZATION) $(INCLUDES) -D$(CHIP)
# To reduce application size use only integer printf function.

View File

@ -2745,9 +2745,9 @@
</file>
<file>
<name>$PROJ_DIR$\..\WInterrupts.c</name>
<excluded>
<configuration>Debug</configuration>
</excluded>
</file>
<file>
<name>$PROJ_DIR$\..\WInterrupts.h</name>
</file>
<file>
<name>$PROJ_DIR$\..\wiring.c</name>

View File

@ -1,3 +1,5 @@
extern "C" void __cxa_pure_virtual(void) ;
/* We compile with nodefaultlibs, so we need to provide an error
* handler for an empty pure virtual function */
extern "C" void __cxa_pure_virtual(void) {

View File

@ -1,6 +1,15 @@
/*
%atmel_license%
*/
#include "itoa.h"
#include <string.h>
#ifdef __cplusplus
extern "C"{
#endif // __cplusplus
#if 0
/* reverse: reverse string s in place */
static void reverse( char s[] )
{
@ -15,7 +24,6 @@ static void reverse( char s[] )
}
}
/* itoa: convert n to characters in s */
extern void itoa( int n, char s[] )
{
@ -41,3 +49,108 @@ extern void itoa( int n, char s[] )
reverse( s ) ;
}
#else
extern char* itoa( int value, char *string, int radix )
{
return ltoa( value, string, radix ) ;
}
extern char* ltoa( long value, char *string, int radix )
{
char tmp[33];
char *tp = tmp;
long i;
unsigned long v;
int sign;
char *sp;
if ( string == NULL )
{
return 0 ;
}
if (radix > 36 || radix <= 1)
{
return 0 ;
}
sign = (radix == 10 && value < 0);
if (sign)
{
v = -value;
}
else
{
v = (unsigned long)value;
}
while (v || tp == tmp)
{
i = v % radix;
v = v / radix;
if (i < 10)
*tp++ = i+'0';
else
*tp++ = i + 'a' - 10;
}
sp = string;
if (sign)
*sp++ = '-';
while (tp > tmp)
*sp++ = *--tp;
*sp = 0;
return string;
}
extern char* utoa( unsigned long value, char *string, int radix )
{
return ultoa( value, string, radix ) ;
}
extern char* ultoa( unsigned long value, char *string, int radix )
{
char tmp[33];
char *tp = tmp;
long i;
unsigned long v = value;
char *sp;
if ( string == NULL )
{
return 0;
}
if (radix > 36 || radix <= 1)
{
return 0;
}
while (v || tp == tmp)
{
i = v % radix;
v = v / radix;
if (i < 10)
*tp++ = i+'0';
else
*tp++ = i + 'a' - 10;
}
sp = string;
while (tp > tmp)
*sp++ = *--tp;
*sp = 0;
return string;
}
#endif /* 0 */
#ifdef __cplusplus
} // extern "C"
#endif // __cplusplus

View File

@ -1,6 +1,24 @@
#ifndef _ITOA_
#define _ITOA_
#ifdef __cplusplus
extern "C"{
#endif // __cplusplus
#if 0
extern void itoa( int n, char s[] ) ;
#else
extern char* itoa( int value, char *string, int radix ) ;
extern char* ltoa( long value, char *string, int radix ) ;
extern char* utoa( unsigned long value, char *string, int radix ) ;
extern char* ultoa( unsigned long value, char *string, int radix ) ;
#endif /* 0 */
#ifdef __cplusplus
} // extern "C"
#endif // __cplusplus
#endif // _ITOA_

View File

@ -49,7 +49,8 @@ CPPFLAGS += -Wsign-compare -Waggregate-return -Wmissing-declarations
CPPFLAGS += -Wformat -Wmissing-format-attribute -Wno-deprecated-declarations
CPPFLAGS += -Wpacked -Wredundant-decls -Winline -Wlong-long
CPPFLAGS += --param max-inline-insns-single=500 -mcpu=cortex-m3 -mthumb -mlong-calls -ffunction-sections -fno-rtti -fno-exceptions
#-fno-rtti -fno-exceptions
CPPFLAGS += --param max-inline-insns-single=500 -mcpu=cortex-m3 -mthumb -mlong-calls -ffunction-sections
CPPFLAGS += $(OPTIMIZATION) $(INCLUDES) -D$(CHIP)
# To reduce application size use only integer printf function.

View File

@ -4,8 +4,8 @@
# putting default variant
ifeq ("$(VARIANT)", "")
#VARIANT=sam3s_ek
#VARIANT=sam3u_ek
VARIANT=arduino_due
VARIANT=sam3u_ek
#VARIANT=arduino_due
endif
ifeq ("$(VARIANT)", "sam3s_ek")
@ -88,12 +88,12 @@ endif
OUTPUT_BIN=test_$(TOOLCHAIN)_$(LIBS_POSTFIX)
#LIBS=-L../libsam_$(CHIP_NAME)_$(TOOLCHAIN)_rel.a -L../arduino_$(VARIANT)_$(TOOLCHAIN)_rel.a
#-lstdc++
LIBS=-Wl,--start-group -lgcc -lc -lsam_$(CHIP_NAME)_$(TOOLCHAIN)_$(LIBS_POSTFIX) -larduino_$(VARIANT)_$(TOOLCHAIN)_$(LIBS_POSTFIX) -lvariant_$(VARIANT)_$(TOOLCHAIN)_$(LIBS_POSTFIX) -Wl,--end-group
#
LIBS=-Wl,--start-group -lgcc -lc -lstdc++ -lsam_$(CHIP_NAME)_$(TOOLCHAIN)_$(LIBS_POSTFIX) -larduino_$(VARIANT)_$(TOOLCHAIN)_$(LIBS_POSTFIX) -lvariant_$(VARIANT)_$(TOOLCHAIN)_$(LIBS_POSTFIX) -Wl,--end-group
LIB_PATH =-L$(PROJECT_BASE_PATH)/..
LIB_PATH+=-L=/lib/thumb2
LIB_PATH+=-L=/../lib/gcc/arm-none-eabi/4.4.1/thumb2
#LIB_PATH+=-L=/../lib/gcc/arm-none-eabi/4.5.2/thumb2
LDFLAGS= -mcpu=cortex-m3 -mthumb -Wl,--cref -Wl,--check-sections -Wl,--gc-sections -Wl,--entry=Reset_Handler -Wl,--unresolved-symbols=report-all -Wl,--warn-common -Wl,--warn-section-align -Wl,--warn-unresolved-symbols
@ -141,13 +141,14 @@ create_output:
$(addprefix $(OUTPUT_PATH)/,$(CPP_OBJ)): $(OUTPUT_PATH)/%.o: %.cpp
# @$(CC) -c $(CPPFLAGS) $< -o $@
# @$(CXX) -c $(CPPFLAGS) $< -o $@
$(CXX) -v -c $(CPPFLAGS) $< -o $@
@$(CXX) -c $(CPPFLAGS) $< -o $@
# @$(CXX) -v -c $(CPPFLAGS) $< -o $@
$(OUTPUT_BIN): $(addprefix $(OUTPUT_PATH)/, $(C_OBJ)) $(addprefix $(OUTPUT_PATH)/, $(CPP_OBJ)) $(addprefix $(OUTPUT_PATH)/, $(A_OBJ))
$(CC) $(LIB_PATH) $(LDFLAGS) -T"$(VARIANT_PATH)/linker_scripts/gcc/flash.ld" -Wl,-Map,$(OUTPUT_PATH)/$@.map -o $(OUTPUT_PATH)/$@.elf $^ $(LIBS)
$(NM) $(OUTPUT_PATH)/$@.elf >$(OUTPUT_PATH)/$@.elf.txt
$(OBJCOPY) -O binary $(OUTPUT_PATH)/$@.elf $(OUTPUT_PATH)/$@.bin
@$(CC) $(LIB_PATH) $(LDFLAGS) -T"$(VARIANT_PATH)/linker_scripts/gcc/flash.ld" -Wl,-Map,$(OUTPUT_PATH)/$@.map -o $(OUTPUT_PATH)/$@.elf $^ $(LIBS)
# @$(CC) $(LIB_PATH) $(LDFLAGS) -T"$(VARIANT_PATH)/linker_scripts/gcc/sram.ld" -Wl,-Map,$(OUTPUT_PATH)/$@.map -o $(OUTPUT_PATH)/$@.elf $^ $(LIBS)
@$(NM) $(OUTPUT_PATH)/$@.elf >$(OUTPUT_PATH)/$@.elf.txt
@$(OBJCOPY) -O binary $(OUTPUT_PATH)/$@.elf $(OUTPUT_PATH)/$@.bin
$(SIZE) $^ $(OUTPUT_PATH)/$@.elf
.PHONY: clean
@ -160,4 +161,5 @@ clean:
-@$(RM) $(OUTPUT_PATH)/$(OUTPUT_BIN).map 1>NUL 2>&1
debug: test
$(GDB) -x "$(VARIANT_PATH)/debug_scripts/gcc/$(VARIANT)_flash.gdb" -ex "reset" -readnow -se $(OUTPUT_PATH)/$(OUTPUT_BIN).elf
@$(GDB) -x "$(VARIANT_PATH)/debug_scripts/gcc/$(VARIANT)_flash.gdb" -ex "reset" -readnow -se $(OUTPUT_PATH)/$(OUTPUT_BIN).elf
# @$(GDB) -w -x "$(VARIANT_PATH)/debug_scripts/gcc/$(VARIANT)_sram.gdb" -ex "reset" -readnow -se $(OUTPUT_PATH)/$(OUTPUT_BIN).elf

View File

@ -15,20 +15,54 @@ void setup( void )
pinMode( PIN_LED2, OUTPUT ) ;
digitalWrite( PIN_LED2, HIGH ) ;
Serial.begin( 19200 ) ;
Serial.begin( 115200 ) ;
}
void led_step1( void )
{
#if defined sam3s_ek
digitalWrite( PIN_LED, HIGH ) ; // set the LED on
digitalWrite( PIN_LED2, LOW ) ; // set the red LED off
#endif /* sam3s_ek */
#if defined sam3u_ek
digitalWrite( PIN_LED, HIGH ) ; // set the LED on
digitalWrite( PIN_LED2, LOW ) ; // set the red LED off
#endif /* sam3u_ek */
#if defined arduino_due
digitalWrite( PIN_LED, LOW ) ; // set the LED on
digitalWrite( PIN_LED2, LOW ) ; // set the red LED off
#endif /* arduino_due */
}
void led_step2( void )
{
#if defined sam3s_ek
digitalWrite( PIN_LED, LOW ) ; // set the LED off
digitalWrite( PIN_LED2, HIGH ) ; // set the red LED on
#endif /* sam3s_ek */
#if defined sam3u_ek
digitalWrite( PIN_LED, LOW ) ; // set the LED off
digitalWrite( PIN_LED2, HIGH ) ; // set the red LED on
#endif /* sam3u_ek */
#if defined arduino_due
digitalWrite( PIN_LED, HIGH ) ; // set the LED off
digitalWrite( PIN_LED2, HIGH ) ; // set the red LED on
#endif /* arduino_due */
}
void loop( void )
{
digitalWrite( PIN_LED, HIGH ) ; // set the LED on
digitalWrite( PIN_LED2, LOW ) ; // set the red LED off
led_step1() ;
delay( 1000 ) ; // wait for a second
digitalWrite( PIN_LED, LOW ) ; // set the LED off
digitalWrite( PIN_LED2, HIGH ) ; // set the red LED on
led_step2() ;
delay( 1000 ) ; // wait for a second
// Serial.write( '*' ) ; // send an initial char
// Serial.println( "test1" ) ; // send an initial string
Serial.write( '-' ) ; // send an initial char
Serial.println( "test1\n" ) ; // send an initial string
// delay( 1000 ) ; // wait for a second
// Serial.println( "test2" ) ; // send an initial string
}

View File

@ -8,12 +8,12 @@
* published by the Free Software Foundation.
*/
#include "pins_arduino.h"
#include "SPI.h"
SPIClass SPI;
SPIClass SPI ;
void SPIClass::begin() {
void SPIClass::begin()
{
// Set direction register for SCK and MOSI pin.
// MISO pin automatically overrides to INPUT.
// When the SS pin is set as OUTPUT, it can be used as

View File

@ -11,9 +11,8 @@
#ifndef _SPI_H_INCLUDED
#define _SPI_H_INCLUDED
#include "variant.h"
#include <stdio.h>
#include <Arduino.h>
#include <avr/pgmspace.h>
#define SPI_CLOCK_DIV4 0x00
#define SPI_CLOCK_DIV16 0x01

View File

@ -10,9 +10,6 @@
*/
#include "include/sam3.h"
/** Define MAX number of Interrupts: (IRQn_Type+1) + 8 for CM3 core */
#define EXTERNAL_NUM_INTERRUPTS (UDP_IRQn+1+8)
/* Define attribute */
#if defined ( __GNUC__ ) /* GCC CS3 */
#define WEAK __attribute__ ((weak))

View File

@ -4,7 +4,7 @@
*
* \par Purpose
*
* This file provides basic support for Cortex-M processor based
* This file provides basic support for Cortex-M processor based
* microcontrollers.
*
* \author Atmel Corporation: http://www.atmel.com \n
@ -26,7 +26,7 @@ extern "C" {
/* @endcond */
/* Function prototype for exception table items (interrupt handler). */
typedef void( *IntFunc )( void ) ;
typedef void (*IntFunc) (void);
/* Default empty handler */
extern void Dummy_Handler( void ) ;

View File

@ -1,31 +1,16 @@
/* ----------------------------------------------------------------------------
* ATMEL Microcontroller Software Support
* ----------------------------------------------------------------------------
* Copyright (c) 2010, Atmel Corporation
/*! \file *********************************************************************
*
* All rights reserved.
* \brief Startup file for SAM3N.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
* This file defines common SAM series.
*
* - Redistributions of source code must retain the above copyright notice,
* this list of conditions and the disclaimer below.
* - Compiler: ARMGCC
* - Supported devices: All SAM3N devices can be used.
* - AppNote:
*
* 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.
* ----------------------------------------------------------------------------
*/
******************************************************************************/
/* $asf_license$ */
/*----------------------------------------------------------------------------
* Headers
@ -61,9 +46,9 @@ extern int main(void);
void ResetException( void ) ;
extern void __libc_init_array( void ) ;
/*------------------------------------------------------------------------------
/*----------------------------------------------------------------------------
* Exception Table
*------------------------------------------------------------------------------*/
*----------------------------------------------------------------------------*/
__attribute__((section(".vectors")))
IntFunc exception_table[] = {

View File

@ -10,7 +10,7 @@
*
******************************************************************************/
// $asf_license$
/* $asf_license$ */
/*------------------------------------------------------------------------------
* Headers
@ -42,7 +42,6 @@ extern int __low_level_init( void ) ;
#pragma language=extended
#pragma segment="CSTACK"
/* The name "__vector_table" has special meaning for C-SPY: */
/* it is where the SP start value is found, and the NVIC vector */
/* table register (VTOR) is initialized to this address if != 0. */
@ -65,7 +64,7 @@ const intvec_elem __vector_table[] =
0, /* Reserved */
PendSV_Handler,
SysTick_Handler,
/* Configurable interrupts */
SUPC_IrqHandler, /* 0 Supply Controller */
RSTC_IrqHandler, /* 1 Reset Controller */
@ -80,7 +79,7 @@ const intvec_elem __vector_table[] =
Dummy_Handler, /* 10 Reserved */
PIOA_IrqHandler, /* 11 Parallel IO Controller A */
PIOB_IrqHandler, /* 12 Parallel IO Controller B */
PIOC_IrqHandler, /* 13 Parallel IO Controller C */
PIOC_IrqHandler, /* 13 Parallel IO Controller C */
USART0_IrqHandler, /* 14 USART 0 */
USART1_IrqHandler, /* 15 USART 1 */
Dummy_Handler, /* 16 Reserved */
@ -88,14 +87,14 @@ const intvec_elem __vector_table[] =
Dummy_Handler, /* 18 Reserved */
TWI0_IrqHandler, /* 19 TWI 0 */
TWI1_IrqHandler, /* 20 TWI 1 */
SPI_IrqHandler, /* 21 SPI */
SPI_IrqHandler, /* 21 SPI */
Dummy_Handler, /* 22 Reserved */
TC0_IrqHandler, /* 23 Timer Counter 0 */
TC1_IrqHandler, /* 24 Timer Counter 1 */
TC2_IrqHandler, /* 25 Timer Counter 2 */
TC3_IrqHandler, /* 26 Timer Counter 3 */
TC4_IrqHandler, /* 27 Timer Counter 4 */
TC5_IrqHandler, /* 28 Timer Counter 5 */
TC5_IrqHandler, /* 28 Timer Counter 5 */
ADC_IrqHandler, /* 29 ADC controller */
DACC_IrqHandler, /* 30 DAC controller */
PWM_IrqHandler, /* 31 PWM */
@ -111,7 +110,7 @@ extern int __low_level_init( void )
uint32_t* pSrc = __section_begin( ".intvec" ) ;
SCB->VTOR = ( (uint32_t)pSrc & SCB_VTOR_TBLOFF_Msk ) ;
if ( ((uint32_t)pSrc >= IRAM_ADDR) && ((uint32_t)pSrc < IRAM_ADDR+IRAM_SIZE) )
{
SCB->VTOR |= 1 << SCB_VTOR_TBLBASE_Pos ;

View File

@ -29,10 +29,10 @@ extern "C" {
/* Clock settings (48MHz) */
#define BOARD_OSCOUNT (CKGR_MOR_MOSCXTST(0x8))
#define BOARD_PLLR (CKGR_PLLR_STUCKTO1 \
| CKGR_PLLR_MUL(0x7) \
| CKGR_PLLR_MUL(0x3) \
| CKGR_PLLR_PLLCOUNT(0x3f) \
| CKGR_PLLR_DIV(0x1))
#define BOARD_MCKR (PMC_MCKR_PRES_CLK_2 | PMC_MCKR_CSS_PLL_CLK)
#define BOARD_MCKR (PMC_MCKR_PRES_CLK | PMC_MCKR_CSS_PLL_CLK)
/* Clock Definitions */
#define XTAL32 ( 32768UL) /* 32k crystal frequency */
@ -43,7 +43,7 @@ extern "C" {
#define MCK_HZ (48000000UL) /* Processor frequency */
/* FIXME: should be generated by sock */
uint32_t SystemCoreClock = 4000000;
uint32_t SystemCoreClock = EFRC_OSC;
/**
* \brief Setup the microcontroller system.

View File

@ -5,7 +5,7 @@
*
* \par Purpose
*
* This file provides basic support for Cortex-M processor based
* This file provides basic support for Cortex-M processor based
* microcontrollers.
*
* \author Atmel Corporation: http://www.atmel.com \n
@ -28,19 +28,19 @@ extern "C" {
#include <stdint.h>
extern uint32_t SystemCoreClock; /* System Clock Frequency (Core Clock) */
extern uint32_t SystemCoreClock; /* System Clock Frequency (Core Clock) */
/**
* @brief Setup the microcontroller system.
* Initialize the System and update the SystemCoreClock variable.
*/
extern void SystemInit (void);
extern void SystemInit(void);
/**
* @brief Updates the SystemCoreClock with current core Clock
* @brief Updates the SystemCoreClock with current core Clock
* retrieved from cpu registers.
*/
extern void SystemCoreClockUpdate (void);
extern void SystemCoreClockUpdate(void);
/* @cond 0 */
/**INDENT-OFF**/

View File

@ -1,31 +1,16 @@
/* ----------------------------------------------------------------------------
* ATMEL Microcontroller Software Support
* ----------------------------------------------------------------------------
* Copyright (c) 2010, Atmel Corporation
/*! \file *********************************************************************
*
* All rights reserved.
* \brief Startup file for SAM3S.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
* This file defines common SAM series.
*
* - Redistributions of source code must retain the above copyright notice,
* this list of conditions and the disclaimer below.
* - Compiler: ARMGCC
* - Supported devices: All SAM3S devices can be used.
* - AppNote:
*
* 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.
* ----------------------------------------------------------------------------
*/
******************************************************************************/
/* $asf_license$ */
/*----------------------------------------------------------------------------
* Headers
@ -39,10 +24,10 @@
* Exported variables
*----------------------------------------------------------------------------*/
/* Stack Configuration */
/* Stack Configuration */
#define STACK_SIZE 0x900 /** Stack size (in DWords) */
__attribute__ ((aligned(8),section(".stack")))
uint32_t pdwStack[STACK_SIZE] ;
uint32_t pdwStack[STACK_SIZE] ;
/* Initialize segments */
extern uint32_t _sfixed;
@ -158,7 +143,7 @@ void Reset_Handler( void )
/* Set the vector table base address */
pSrc = (uint32_t *)&_sfixed;
SCB->VTOR = ( (uint32_t)pSrc & SCB_VTOR_TBLOFF_Msk ) ;
if ( ((uint32_t)pSrc >= IRAM_ADDR) && ((uint32_t)pSrc < IRAM_ADDR+IRAM_SIZE) )
{
SCB->VTOR |= 1 << SCB_VTOR_TBLBASE_Pos ;

View File

@ -20,7 +20,7 @@
#include "sam3.h"
/*----------------------------------------------------------------------------
* Definitions
* Exported variables
*----------------------------------------------------------------------------*/
/*------------------------------------------------------------------------------

View File

@ -26,11 +26,11 @@ extern "C" {
/* @endcond */
/* Clock Settings (64MHz) */
#define BOARD_OSCOUNT (CKGR_MOR_MOSCXTST(0x8))
#define BOARD_OSCOUNT (CKGR_MOR_MOSCXTST(0x8U))
#define BOARD_PLLAR (CKGR_PLLAR_STUCKTO1 \
| CKGR_PLLAR_MULA(0xf) \
| CKGR_PLLAR_PLLACOUNT(0x3f) \
| CKGR_PLLAR_DIVA(0x3))
| CKGR_PLLAR_MULA(0xfU) \
| CKGR_PLLAR_PLLACOUNT(0x3fU) \
| CKGR_PLLAR_DIVA(0x3U))
#define BOARD_MCKR (PMC_MCKR_PRES_CLK | PMC_MCKR_CSS_PLLA_CLK)
/* Clock Definitions */

View File

@ -28,19 +28,19 @@ extern "C" {
#include <stdint.h>
extern uint32_t SystemCoreClock; /* System Clock Frequency (Core Clock) */
extern uint32_t SystemCoreClock; /* System Clock Frequency (Core Clock) */
/**
* @brief Setup the microcontroller system.
* Initialize the System and update the SystemCoreClock variable.
*/
extern void SystemInit (void);
extern void SystemInit(void);
/**
* @brief Updates the SystemCoreClock with current core Clock
* retrieved from cpu registers.
*/
extern void SystemCoreClockUpdate (void);
extern void SystemCoreClockUpdate(void);
/* @cond 0 */
/**INDENT-OFF**/

View File

@ -1,31 +1,16 @@
/* ----------------------------------------------------------------------------
* ATMEL Microcontroller Software Support
* ----------------------------------------------------------------------------
* Copyright (c) 2010, Atmel Corporation
/*! \file *********************************************************************
*
* All rights reserved.
* \brief Startup file for SAM3S8/SAM3SD.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
* This file defines common SAM series.
*
* - Redistributions of source code must retain the above copyright notice,
* this list of conditions and the disclaimer below.
* - Compiler: ARMGCC
* - Supported devices: All SAM3S8/SAM3SD devices can be used.
* - AppNote:
*
* 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.
* ----------------------------------------------------------------------------
*/
******************************************************************************/
/* $asf_license$ */
/*----------------------------------------------------------------------------
* Headers
@ -39,10 +24,10 @@
* Exported variables
*----------------------------------------------------------------------------*/
/* Stack Configuration */
/* Stack Configuration */
#define STACK_SIZE 0x900 /** Stack size (in DWords) */
__attribute__ ((aligned(8),section(".stack")))
uint32_t pdwStack[STACK_SIZE] ;
uint32_t pdwStack[STACK_SIZE] ;
/* Initialize segments */
extern uint32_t _sfixed;
@ -64,9 +49,9 @@ extern int main( void ) ;
void ResetException( void ) ;
extern void __libc_init_array( void ) ;
/*------------------------------------------------------------------------------
/*----------------------------------------------------------------------------
* Exception Table
*------------------------------------------------------------------------------*/
*----------------------------------------------------------------------------*/
__attribute__((section(".vectors")))
IntFunc exception_table[] = {
@ -159,7 +144,7 @@ void ResetException( void )
/* Set the vector table base address */
pSrc = (uint32_t *)&_sfixed;
SCB->VTOR = ( (uint32_t)pSrc & SCB_VTOR_TBLOFF_Msk ) ;
if ( ((uint32_t)pSrc >= IRAM_ADDR) && ((uint32_t)pSrc < IRAM_ADDR+IRAM_SIZE) )
{
SCB->VTOR |= 1 << SCB_VTOR_TBLBASE_Pos ;

View File

@ -1,27 +1,27 @@
/*! \file *********************************************************************
*
* \brief Startup file for SAM3S.
* \brief Startup file for SAM3S8/SAM3SD.
*
* This file defines common SAM series.
*
* - Compiler: IAR EWARM
* - Supported devices: All SAM3S devices can be used.
* - Supported devices: All SAM3S8/SAM3SD devices can be used.
* - AppNote:
*
******************************************************************************/
// $asf_license$
/* $asf_license$ */
/*------------------------------------------------------------------------------
* Headers
*------------------------------------------------------------------------------*/
/*----------------------------------------------------------------------------
* Headers
*----------------------------------------------------------------------------*/
#include "exceptions.h"
#include "sam3s8.h"
#include "system_sam3sd8.h"
/*----------------------------------------------------------------------------
* Definitions
* Exported variables
*----------------------------------------------------------------------------*/
/*------------------------------------------------------------------------------
@ -114,7 +114,7 @@ extern int __low_level_init( void )
uint32_t* pSrc = __section_begin( ".intvec" ) ;
SCB->VTOR = ( (uint32_t)pSrc & SCB_VTOR_TBLOFF_Msk ) ;
if ( ((uint32_t)pSrc >= IRAM_ADDR) && ((uint32_t)pSrc < IRAM_ADDR+IRAM_SIZE) )
{
SCB->VTOR |= 1 << SCB_VTOR_TBLBASE_Pos ;

View File

@ -134,7 +134,7 @@ extern void SystemCoreClockUpdate( void )
break;
}
}
if (PMC->PMC_MCKR & PMC_MCKR_CSS_Msk == PMC_MCKR_CSS_PLLA_CLK) {
if ((PMC->PMC_MCKR & PMC_MCKR_CSS_Msk) == PMC_MCKR_CSS_PLLA_CLK) {
SystemCoreClock *= ((((PMC->CKGR_PLLAR) >> CKGR_PLLAR_MULA_Pos) & 0x7FF) + 1);
SystemCoreClock /= ((((PMC->CKGR_PLLAR) >> CKGR_PLLAR_DIVA_Pos) & 0x0FF));
}

View File

@ -5,7 +5,7 @@
*
* \par Purpose
*
* This file provides basic support for Cortex-M processor based
* This file provides basic support for Cortex-M processor based
* microcontrollers.
*
* \author Atmel Corporation: http://www.atmel.com \n
@ -28,19 +28,19 @@ extern "C" {
#include <stdint.h>
extern uint32_t SystemCoreClock; /* System Clock Frequency (Core Clock) */
extern uint32_t SystemCoreClock; /* System Clock Frequency (Core Clock) */
/**
* @brief Setup the microcontroller system.
* Initialize the System and update the SystemCoreClock variable.
*/
extern void SystemInit (void);
extern void SystemInit(void);
/**
* @brief Updates the SystemCoreClock with current core Clock
* @brief Updates the SystemCoreClock with current core Clock
* retrieved from cpu registers.
*/
extern void SystemCoreClockUpdate (void);
extern void SystemCoreClockUpdate(void);
/* @cond 0 */
/**INDENT-OFF**/

View File

@ -4,13 +4,13 @@
*
* This file defines common SAM series.
*
* - Compiler: Codesoucery
* - Compiler: ARMGCC
* - Supported devices: All SAM3U devices can be used.
* - AppNote:
*
******************************************************************************/
// $asf_license$
/* $asf_license$ */
/*----------------------------------------------------------------------------
* Headers

View File

@ -10,23 +10,23 @@
*
******************************************************************************/
// $asf_license$
/* $asf_license$ */
/*------------------------------------------------------------------------------
* Headers
*------------------------------------------------------------------------------*/
/*----------------------------------------------------------------------------
* Headers
*----------------------------------------------------------------------------*/
#include "exceptions.h"
#include "board.h"
#include "system_sam3u.h"
/*----------------------------------------------------------------------------
* Definitions
* Exported variables
*----------------------------------------------------------------------------*/
/*------------------------------------------------------------------------------
* Types
*------------------------------------------------------------------------------*/
/*----------------------------------------------------------------------------
* Types
*----------------------------------------------------------------------------*/
typedef void( *intfunc )( void );
typedef union { intfunc __fun; void * __ptr; } intvec_elem;
@ -36,9 +36,9 @@ typedef union { intfunc __fun; void * __ptr; } intvec_elem;
extern void __iar_program_start( void ) ;
extern int __low_level_init( void ) ;
/*------------------------------------------------------------------------------
/*----------------------------------------------------------------------------
* Exception Table
*------------------------------------------------------------------------------*/
*----------------------------------------------------------------------------*/
#pragma language=extended
#pragma segment="CSTACK"

View File

@ -5,7 +5,7 @@
*
* \par Purpose
*
* This file provides basic support for Cortex-M processor based
* This file provides basic support for Cortex-M processor based
* microcontrollers.
*
* \author Atmel Corporation: http://www.atmel.com \n
@ -28,19 +28,19 @@ extern "C" {
#include <stdint.h>
extern uint32_t SystemCoreClock; /* System Clock Frequency (Core Clock) */
extern uint32_t SystemCoreClock; /* System Clock Frequency (Core Clock) */
/**
* @brief Setup the microcontroller system.
* Initialize the System and update the SystemCoreClock variable.
*/
extern void SystemInit (void);
extern void SystemInit(void);
/**
* @brief Updates the SystemCoreClock with current core Clock
* @brief Updates the SystemCoreClock with current core Clock
* retrieved from cpu registers.
*/
extern void SystemCoreClockUpdate (void);
extern void SystemCoreClockUpdate(void);
/* @cond 0 */
/**INDENT-OFF**/

View File

@ -1,38 +1,16 @@
/* ----------------------------------------------------------------------------
* ATMEL Microcontroller Software Support
* ----------------------------------------------------------------------------
* Copyright (c) 2010, Atmel Corporation
/*! \file *********************************************************************
*
* All rights reserved.
* \brief Startup file for SAM3X.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
* This file defines common SAM series.
*
* - Redistributions of source code must retain the above copyright notice,
* this list of conditions and the disclaimer below.
* - Compiler: ARMGCC
* - Supported devices: All SAM3X devices can be used.
* - AppNote:
*
* 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.
* ----------------------------------------------------------------------------
*/
******************************************************************************/
/**
* \file
*
* Implementation of start up code for GNU.
*
*/
/* $asf_license$ */
/*----------------------------------------------------------------------------
* Headers
@ -71,9 +49,9 @@ extern int main( void ) ;
void ResetException( void ) ;
extern void __libc_init_array( void ) ;
/*------------------------------------------------------------------------------
/*----------------------------------------------------------------------------
* Exception Table
*------------------------------------------------------------------------------*/
*----------------------------------------------------------------------------*/
__attribute__((section(".vectors")))
IntFunc exception_table[] = {
@ -153,7 +131,7 @@ IntFunc exception_table[] = {
void ResetException( void )
{
uint32_t *pSrc, *pDest ;
/* Initialize the relocate segment */
pSrc = &_etext ;
pDest = &_srelocate ;

View File

@ -10,18 +10,18 @@
*
******************************************************************************/
// $asf_license$
/* $asf_license$ */
/*------------------------------------------------------------------------------
* Headers
*------------------------------------------------------------------------------*/
/*----------------------------------------------------------------------------
* Headers
*----------------------------------------------------------------------------*/
#include "exceptions.h"
#include "sam3xa.h"
#include "system_sam3x.h"
/*----------------------------------------------------------------------------
* Definitions
* Exported variables
*----------------------------------------------------------------------------*/
/*------------------------------------------------------------------------------
@ -51,7 +51,7 @@ extern int __low_level_init( void ) ;
const intvec_elem __vector_table[] =
{
{ .__ptr = __sfe( "CSTACK" ) },
__iar_program_start,
Reset_Handler,
NMI_Handler,
HardFault_Handler,

View File

@ -16,7 +16,7 @@
/* $asf_license$ */
#include "system_sam3x.h"
#include "sam3.h"
#include "sam3xa.h"
/* @cond 0 */
/**INDENT-OFF**/
@ -29,10 +29,10 @@ extern "C" {
/* Clock settings (84MHz) */
#define BOARD_OSCOUNT (CKGR_MOR_MOSCXTST(0x8))
#define BOARD_PLLAR (CKGR_PLLAR_STUCKTO1 \
| CKGR_PLLAR_MULA(0xd) \
| CKGR_PLLAR_MULA(0x6) \
| CKGR_PLLAR_PLLACOUNT(0x3f) \
| CKGR_PLLAR_DIVA(0x1))
#define BOARD_MCKR (PMC_MCKR_PRES_CLK_2 | PMC_MCKR_CSS_PLLA_CLK)
#define BOARD_MCKR (PMC_MCKR_PRES_CLK_1 | PMC_MCKR_CSS_PLLA_CLK)
/* Clock Definitions */
#define XTAL32 ( 32768UL) /* 32k crystal frequency */
@ -135,7 +135,7 @@ extern void SystemCoreClockUpdate( void )
break;
}
}
if (PMC->PMC_MCKR & PMC_MCKR_CSS_Msk == PMC_MCKR_CSS_PLLA_CLK) {
if ((PMC->PMC_MCKR & PMC_MCKR_CSS_Msk) == PMC_MCKR_CSS_PLLA_CLK) {
SystemCoreClock *= ((((PMC->CKGR_PLLAR) >> CKGR_PLLAR_MULA_Pos) & 0x7FF) + 1);
SystemCoreClock /= ((((PMC->CKGR_PLLAR) >> CKGR_PLLAR_DIVA_Pos) & 0x0FF));
}

View File

@ -5,7 +5,7 @@
*
* \par Purpose
*
* This file provides basic support for Cortex-M processor based
* This file provides basic support for Cortex-M processor based
* microcontrollers.
*
* \author Atmel Corporation: http://www.atmel.com \n
@ -28,19 +28,19 @@ extern "C" {
#include <stdint.h>
extern uint32_t SystemCoreClock; /* System Clock Frequency (Core Clock) */
extern uint32_t SystemCoreClock; /* System Clock Frequency (Core Clock) */
/**
* @brief Setup the microcontroller system.
* Initialize the System and update the SystemCoreClock variable.
*/
extern void SystemInit (void);
extern void SystemInit(void);
/**
* @brief Updates the SystemCoreClock with current core Clock
* @brief Updates the SystemCoreClock with current core Clock
* retrieved from cpu registers.
*/
extern void SystemCoreClockUpdate (void);
extern void SystemCoreClockUpdate(void);
/* @cond 0 */
/**INDENT-OFF**/

View File

@ -1 +1,33 @@
Makefile into build_gcc folder build the SAM peripheral library and put it into ../../../cores/sam Arduino API folder
Makefile into build_gcc folder build the SAM peripheral library and put it into ../../../cores/sam Arduino API folder
/*
%atmel_license%
*/
=
/* ----------------------------------------------------------------------------
* SAM Software Package License
* ----------------------------------------------------------------------------
* Copyright (c) 2010, 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.
* ----------------------------------------------------------------------------

View File

@ -74,7 +74,7 @@ C_SRC=$(wildcard $(PROJECT_BASE_PATH)/*.c)
C_OBJ_TEMP = $(patsubst %.c, %.o, $(notdir $(C_SRC)))
# during development, remove some files
C_OBJ_FILTER=wiring_analog.o wiring_pulse.o
C_OBJ_FILTER=
C_OBJ=$(filter-out $(C_OBJ_FILTER), $(C_OBJ_TEMP))
@ -87,7 +87,7 @@ CPP_SRC+=$(wildcard $(VARIANT_COMMON_PATH)/*.cpp)
CPP_OBJ_TEMP = $(patsubst %.cpp, %.o, $(notdir $(CPP_SRC)))
# during development, remove some files
CPP_OBJ_FILTER=Tone.o
CPP_OBJ_FILTER=
CPP_OBJ=$(filter-out $(CPP_OBJ_FILTER), $(CPP_OBJ_TEMP))

View File

@ -19,38 +19,38 @@ extern const PinDescription g_APinDescription[]=
{ PIOA, PIO_PA12A_UTXD, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT }, // UTXD
{ PIOA, PIO_PA11A_URXD|PIO_PA12A_UTXD, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT }, // All UART pins
// USART0 (Serial2), 3..5
// USART0 (Serial2), 6..8
{ PIOA, PIO_PA19A_RXD0, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT }, // RXD0
{ PIOA, PIO_PA18A_TXD0, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT }, // TXD0
{ PIOA, PIO_PA19A_RXD0|PIO_PA18A_TXD0, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT }, // All USART0 pins
// USART1 (Serial3), 6..8
// USART1 (Serial3), 9..11
{ PIOA, PIO_PA21A_RXD1, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT }, // RXD1
{ PIOA, PIO_PA20A_TXD1, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT }, // TXD1
{ PIOA, PIO_PA21A_RXD1|PIO_PA20A_TXD1, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT }, // All USART1 pins
// USART2 (Serial4), 9..11
// USART2 (Serial4), 12..14
{ PIOA, PIO_PA23A_RXD2, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT }, // RXD2
{ PIOA, PIO_PA22A_TXD2, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT }, // TXD2
{ PIOA, PIO_PA23A_RXD2|PIO_PA22A_TXD2, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT }, // All USART2 pins
// SPI, 12..15
// SPI, 15..18
{ PIOA, PIO_PA13A_MISO, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT }, // MISO
{ PIOA, PIO_PA14A_MOSI, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT }, // MOSI
{ PIOA, PIO_PA15A_SPCK, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT }, // SPCK
{ PIOC, PIO_PA16A_NPCS0, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT }, // NPCS0
// TWI0, 16..18
// TWI0, 19..21
{ PIOA, PIO_PA9A_TWD0, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT }, // TWD0 - SDA1
{ PIOA, PIO_PA10A_TWCK0, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT }, // TWCK0 - SCL1
{ PIOA, PIO_PA9A_TWD0|PIO_PA10A_TWCK0, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT }, // All TWI0 pins
// TWI1, 19..21
// TWI1, 22..24
{ PIOA, PIO_PA24A_TWD1, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT }, // TWD1 - SDA0
{ PIOA, PIO_PA25A_TWCK1, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT }, // TWCK1 - SCL0
{ PIOA, PIO_PA24A_TWD1|PIO_PA25A_TWCK1, ID_PIOA, PIO_PERIPH_A, PIO_DEFAULT }, // All TWI1 pins
// Analog, 22..35
// Analog, 25..38
{ PIOB, PIO_PB5X1_AD0, ID_PIOB, PIO_INPUT, PIO_DEFAULT }, // AD0
{ PIOB, PIO_PB6X1_AD1, ID_PIOB, PIO_INPUT, PIO_DEFAULT }, // AD1
{ PIOB, PIO_PB7X1_AD2, ID_PIOB, PIO_INPUT, PIO_DEFAULT }, // AD2
@ -67,12 +67,12 @@ extern const PinDescription g_APinDescription[]=
{ PIOC, PIO_PC17X1_AD12B6, ID_PIOC, PIO_INPUT, PIO_DEFAULT }, // AD12
{ PIOC, PIO_PC18X1_AD12B7, ID_PIOC, PIO_INPUT, PIO_DEFAULT }, // AD13
// External DAC, 36..38
// External DAC, 39..41
{ PIOB, PIO_PB9, ID_PIOB, PIO_OUTPUT_1, PIO_DEFAULT }, // DAC-CS
{ PIOB, PIO_PB10, ID_PIOB, PIO_OUTPUT_1, PIO_DEFAULT }, // DAC-SCK
{ PIOB, PIO_PB14, ID_PIOB, PIO_OUTPUT_1, PIO_DEFAULT }, // DAC-DIN
// PWM, 39..
// PWM, 42..50
{ PIOA, PIO_PA30B_TIOA2, ID_PIOA, PIO_PERIPH_B, PIO_DEFAULT }, // PWM
{ PIOA, PIO_PA4B_PWMH0, ID_PIOA, PIO_PERIPH_B, PIO_DEFAULT }, // PWMH0
{ PIOA, PIO_PA5B_PWMH1, ID_PIOA, PIO_PERIPH_B, PIO_DEFAULT }, // PWMH1
@ -83,9 +83,10 @@ extern const PinDescription g_APinDescription[]=
{ PIOC, PIO_PC8B_PWML2, ID_PIOC, PIO_PERIPH_B, PIO_DEFAULT }, // PWML2
{ PIOC, PIO_PC9B_PWML3, ID_PIOC, PIO_PERIPH_B, PIO_DEFAULT }, // PWML3
// Digital
// 51
{ PIOA, PIO_PA1, ID_PIOA, PIO_OUTPUT_0, PIO_DEFAULT }, // PIN 10
// Digital, 52..83
{ PIOC, PIO_PC3 , ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT }, // PIN 22
{ PIOC, PIO_PC2 , ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT }, // PIN 23
{ PIOC, PIO_PC1 , ID_PIOC, PIO_OUTPUT_0, PIO_DEFAULT }, // PIN 24

View File

@ -55,16 +55,16 @@
#define PIN_LED2 PIN_LED_RXL
#define PIN_LED3 PIN_LED_TXL
static const uint8_t SS = 15 ;
static const uint8_t MOSI = 13 ;
static const uint8_t MISO = 12 ;
static const uint8_t SCK = 14 ;
#define PINS_UART (3u)
#define PINS_UART (5u)
#define PINS_USART0 (6u)
#define PINS_USART1 (9u)
#define PINS_USART2 (12u)
#define PINS_USART0 (5u)
#define PINS_USART1 (5u)
#define PINS_USART2 (5u)
static const uint8_t SS = 18 ;
static const uint8_t MOSI = 16 ;
static const uint8_t MISO = 15 ;
static const uint8_t SCK = 17 ;
/*----------------------------------------------------------------------------
* Arduino objects - C++ only

View File

@ -34,11 +34,17 @@ void UARTClass::begin( const uint32_t dwBaudRate )
/* Configure baudrate */
/* Asynchronous, no oversampling */
_pUart->UART_BRGR = (SystemCoreClock / dwBaudRate) / 16 ;
_pUart->UART_BRGR = (SystemCoreClock / dwBaudRate) >> 4 ;
/* Disable PDC channel */
_pUart->UART_PTCR = UART_PTCR_RXTDIS | UART_PTCR_TXTDIS ;
/* Configure the ENDRX interrupt */
_pUart->UART_IER=UART_IER_ENDRX ;
/* Enable UART interrupt in NVIC */
// NVIC_EnableIRQ( _dwIrq ) ;
/* Enable receiver and transmitter */
_pUart->UART_CR = UART_CR_RXEN | UART_CR_TXEN ;
}
@ -46,9 +52,9 @@ void UARTClass::begin( const uint32_t dwBaudRate )
void UARTClass::end( void )
{
// wait for transmission of outgoing data
while ( _tx_buffer->_iHead != _tx_buffer->_iTail )
{
}
//while ( _tx_buffer->_iHead != _tx_buffer->_iTail )
//{
//}
// clear any received data
_rx_buffer->_iHead = _rx_buffer->_iTail ;
@ -75,66 +81,46 @@ int UARTClass::peek( void )
int UARTClass::read( void )
{
// if the head isn't ahead of the _iTail, we don't have any characters
// if the head isn't ahead of the tail, we don't have any characters
if ( _rx_buffer->_iHead == _rx_buffer->_iTail )
{
return -1 ;
}
else
{
unsigned char c = _rx_buffer->_aucBuffer[_rx_buffer->_iTail] ;
uint8_t uc = _rx_buffer->_aucBuffer[_rx_buffer->_iTail] ;
_rx_buffer->_iTail = (unsigned int)(_rx_buffer->_iTail + 1) % SERIAL_BUFFER_SIZE ;
return c ;
return uc ;
}
}
void UARTClass::flush( void )
{
while ( _tx_buffer->_iHead != _tx_buffer->_iTail )
{
}
//while ( _tx_buffer->_iHead != _tx_buffer->_iTail )
//{
//}
}
void UARTClass::write( const uint8_t uc )
void UARTClass::write( const uint8_t uc_data )
{
int i = (_tx_buffer->_iHead + 1) % SERIAL_BUFFER_SIZE ;
// If the output buffer is full, there's nothing for it other than to
// wait for the interrupt handler to empty it a bit
while ( i == _tx_buffer->_iTail )
/* Check if the transmitter is ready */
if ( (_pUart->UART_SR & UART_SR_TXRDY) != UART_SR_TXRDY )
{
return ;
}
_tx_buffer->_aucBuffer[_tx_buffer->_iHead] = uc ;
_tx_buffer->_iHead = i ;
/* Wait for the transmitter to be ready */
while ( (_pUart->UART_SR & UART_SR_TXEMPTY) == 0 ) ;
/* Send character */
_pUart->UART_THR=uc ;
_pUart->UART_THR = uc_data ;
}
void UARTClass::IrqHandler( void )
{
// RX char IT
uint8_t uc = _pUart->UART_RHR ;
_rx_buffer->store_char( uc ) ;
// TX FIFO empty IT
if ( _tx_buffer->_iHead == _tx_buffer->_iTail )
/* Did we receive data ? */
if ( (_pUart->UART_IER & UART_IER_ENDRX) == UART_IER_ENDRX )
{
// Buffer empty, so disable interrupts
}
else
{
// There is more data in the output buffer. Send the next byte
uc = _tx_buffer->_aucBuffer[_tx_buffer->_iTail] ;
_tx_buffer->_iTail = (_tx_buffer->_iTail + 1) % SERIAL_BUFFER_SIZE ;
_pUart->UART_THR = uc ;
_rx_buffer->store_char( _pUart->UART_RHR ) ;
}
}

View File

@ -1,13 +1,18 @@
/*
%atmel_license%
*/
#ifndef _UART_CLASS_
#define _UART_CLASS_
// UART.cpp need this class to be predefined
//class UARTClass ;
#include "Arduino.h"
class UARTClass : public HardwareSerial
{
protected:
RingBuffer *_rx_buffer ;
RingBuffer *_tx_buffer ;
protected:
Uart* _pUart ;
IRQn_Type _dwIrq ;
@ -29,8 +34,8 @@ class UARTClass : public HardwareSerial
#if defined __GNUC__ /* GCC CS3 */
using Print::write ; // pull in write(str) and write(buf, size) from Print
#elif defined __ICCARM__ /* IAR Ewarm 5.41+ */
virtual void write( const char *str ) ;
virtual void write( const uint8_t *buffer, size_t size ) ;
// virtual void write( const char *str ) ;
// virtual void write( const uint8_t *buffer, size_t size ) ;
#endif
};

View File

@ -36,16 +36,19 @@ void USARTClass::begin( const uint32_t dwBaudRate )
/* Disable PDC channel */
_pUsart->US_PTCR = US_PTCR_RXTDIS | US_PTCR_TXTDIS ;
/* Enable UART interrupt in NVIC */
// NVIC_EnableIRQ( _dwIrq ) ;
/* Enable receiver and transmitter */
_pUsart->US_CR = US_CR_RXEN | US_CR_TXEN ;
}
void USARTClass::end()
void USARTClass::end( void )
{
// wait for transmission of outgoing data
while ( _tx_buffer->_iHead != _tx_buffer->_iTail )
{
}
//while ( _tx_buffer->_iHead != _tx_buffer->_iTail )
//{
//}
// clear any received data
_rx_buffer->_iHead = _rx_buffer->_iTail ;
@ -55,7 +58,7 @@ void USARTClass::end()
int USARTClass::available( void )
{
return (unsigned int)(SERIAL_BUFFER_SIZE + _rx_buffer->_iHead - _rx_buffer->_iTail) % SERIAL_BUFFER_SIZE ;
return (uint32_t)(SERIAL_BUFFER_SIZE + _rx_buffer->_iHead - _rx_buffer->_iTail) % SERIAL_BUFFER_SIZE ;
}
int USARTClass::peek( void )
@ -72,67 +75,46 @@ int USARTClass::peek( void )
int USARTClass::read( void )
{
// if the _iHead isn't ahead of the _iTail, we don't have any characters
// if the head isn't ahead of the tail, we don't have any characters
if ( _rx_buffer->_iHead == _rx_buffer->_iTail )
{
return -1 ;
}
else
{
unsigned char c = _rx_buffer->_aucBuffer[_rx_buffer->_iTail] ;
uint8_t uc = _rx_buffer->_aucBuffer[_rx_buffer->_iTail] ;
_rx_buffer->_iTail = (unsigned int)(_rx_buffer->_iTail + 1) % SERIAL_BUFFER_SIZE ;
return c ;
return uc ;
}
}
void USARTClass::flush( void )
{
while ( _tx_buffer->_iHead != _tx_buffer->_iTail )
{
}
//while ( _tx_buffer->_iHead != _tx_buffer->_iTail )
//{
//}
}
void USARTClass::write( uint8_t uc )
void USARTClass::write( const uint8_t uc_data )
{
int i = (_tx_buffer->_iHead + 1) % SERIAL_BUFFER_SIZE ;
// If the output buffer is full, there's nothing for it other than to
// wait for the interrupt handler to empty it a bit
while ( i == _tx_buffer->_iTail )
/* Check if the transmitter is ready */
if ( (_pUsart->US_CSR & US_CSR_TXRDY) != US_CSR_TXRDY )
{
return ;
}
_tx_buffer->_aucBuffer[_tx_buffer->_iHead] = uc ;
_tx_buffer->_iHead = i ;
/* Wait for the transmitter to be ready */
while ( (_pUsart->US_CSR & US_CSR_TXEMPTY) == 0 ) ;
/* Send character */
_pUsart->US_THR=uc ;
_pUsart->US_THR=uc_data ;
}
void USARTClass::IrqHandler( void )
{
// RX char IT
uint8_t uc = _pUsart->US_RHR ;
_rx_buffer->store_char( uc ) ;
// TX FIFO empty IT
if ( _tx_buffer->_iHead == _tx_buffer->_iTail )
/* Did we receive data ? */
if ( (_pUsart->US_IER & US_IER_ENDRX) == US_IER_ENDRX )
{
// Buffer empty, so disable interrupts
}
else
{
// There is more data in the output buffer. Send the next byte
uc = _tx_buffer->_aucBuffer[_tx_buffer->_iTail] ;
_tx_buffer->_iTail = (_tx_buffer->_iTail + 1) % SERIAL_BUFFER_SIZE ;
_pUsart->US_THR = uc ;
_rx_buffer->store_char( _pUsart->US_RHR ) ;
}
}

View File

@ -1,13 +1,14 @@
#ifndef _USART_CLASS_
#define _USART_CLASS_
// USART.cpp need this class to be predefined
//class USARTClass ;
#include "Arduino.h"
class USARTClass : public HardwareSerial
class USARTClass // : public HardwareSerial
{
protected:
RingBuffer *_rx_buffer ;
RingBuffer *_tx_buffer ;
protected:
Usart* _pUsart ;
IRQn_Type _dwIrq ;
@ -27,10 +28,10 @@ class USARTClass : public HardwareSerial
void IrqHandler( void ) ;
#if defined __GNUC__ /* GCC CS3 */
using Print::write ; // pull in write(str) and write(buf, size) from Print
// using Print::write ; // pull in write(str) and write(buf, size) from Print
#elif defined __ICCARM__ /* IAR Ewarm 5.41+ */
virtual void write( const char *str ) ;
virtual void write( const uint8_t *buffer, size_t size ) ;
// virtual void write( const char *str ) ;
// virtual void write( const uint8_t *buffer, size_t size ) ;
#endif
};

View File

@ -52,7 +52,8 @@ CPPFLAGS += -Wpacked -Wredundant-decls -Winline -Wlong-long
#CPPFLAGS += -Wmissing-noreturn
#CPPFLAGS += -Wconversion
CPPFLAGS += --param max-inline-insns-single=500 -mcpu=cortex-m3 -mthumb -mlong-calls -ffunction-sections -fno-rtti -fno-exceptions
# -fno-rtti -fno-exceptions
CPPFLAGS += --param max-inline-insns-single=500 -mcpu=cortex-m3 -mthumb -mlong-calls -ffunction-sections
CPPFLAGS += $(OPTIMIZATION) $(INCLUDES) -D$(CHIP)
# To reduce application size use only integer printf function.

View File

@ -27,5 +27,7 @@ set *0x80004 = *0x80004 & 0xFFFFFFFE
mon reg pc=(0x80004)
info reg
break main
# end of 'reset' command
end

View File

@ -1,23 +1,29 @@
#*************************************************
#*******************************************************
#
# Connect to J-Link and debug application in sram on SAM3U
# Connect to J-Link and debug application in flash.
#
# Note:
# First,users should do Step1 and Step2 according to your project,
# then do Step3.
# Step1: Connect to the J-Link gdb server
#target remote localhost:2331
#mon reset
# define 'reset' command
define reset
# Step2: Load file(eg. getting-started project)
#load bin/basic-dhrystone-project-at91sam3u-ek-at91sam3u4-sram.elf
#symbol-file bin/basic-dhrystone-project-at91sam3u-ek-at91sam3u4-sram.elf
# Connect to the J-Link gdb server
target remote localhost:2331
# Reset the chip to get to a known state
monitor reset
# Step3: Initializing PC and stack pointer
# Perpheral reset RSTC_CR
# Load the program
load
# Reset peripheral (RSTC_CR)
set *0x400e1200 = 0xA5000004
# Modify pc value to even before writing pc register
# Initializing PC and stack pointer
mon reg sp=(0x20000000)
set *0x20000004 = *0x20000004 & 0xFFFFFFFE
mon reg pc=(0x20000004)
info reg
break main
# end of 'reset' command
end

View File

@ -142,7 +142,7 @@ extern void init( void )
/* Disable watchdog, common to all SAM variants */
WDT_Disable( WDT ) ;
// Initialize Serial port UART0, common to all SAM3 variants
// Initialize UART Serial port
PIO_Configure( g_APinDescription[PINS_UART].pPort, g_APinDescription[PINS_UART].ulPinType,
g_APinDescription[PINS_UART].ulPin, g_APinDescription[PINS_UART].ulPinAttribute ) ;

View File

@ -54,6 +54,7 @@
#define PIN_LED_GREEN (1u)
#define PIN_LED_RED (2u)
#define PIN_LED PIN_LED_BLUE
#define PIN_LED2 PIN_LED_GREEN
static const uint8_t SS = 23 ;
static const uint8_t MOSI = 21 ;