1
0
mirror of https://github.com/esp8266/Arduino.git synced 2025-07-30 16:24:09 +03:00

[sam] state-of-the-art commit

This commit is contained in:
aethaniel
2011-07-11 01:51:24 +02:00
parent ef4abb62b0
commit 03c064e946
94 changed files with 551 additions and 1051 deletions

View File

@ -1,23 +0,0 @@
# Makefile for compiling libboard
SUBMAKE_OPTIONS=--no-builtin-rules --no-builtin-variables
#-------------------------------------------------------------------------------
# Rules
#-------------------------------------------------------------------------------
all: sam3s_ek
.PHONY: sam3s_ek
sam3s_ek:
@echo --- Making sam3s_ek
@$(MAKE) DEBUG=1 $(SUBMAKE_OPTIONS) -f sam3s_ek.mk
@$(MAKE) $(SUBMAKE_OPTIONS) -f sam3s_ek.mk
.PHONY: clean
clean:
@echo --- Cleaning sam3s_ek
@$(MAKE) $(SUBMAKE_OPTIONS) -f sam3s_ek.mk $@
@$(MAKE) DEBUG=1 $(SUBMAKE_OPTIONS) -f sam3s_ek.mk $@

View File

@ -1,7 +0,0 @@
# Optimization level
# -O1 Optimize
# -O2 Optimize even more
# -O3 Optimize yet more
# -O0 Reduce compilation time and make debugging produce the expected results
# -Os Optimize for size
OPTIMIZATION = -g -O0 -DDEBUG

View File

@ -1,39 +0,0 @@
# Tool suffix when cross-compiling
#CROSS_COMPILE = ../../CodeSourcery_arm/bin/arm-none-eabi-
CROSS_COMPILE = C:/CodeSourcery_2011.03-42/bin/arm-none-eabi-
# Compilation tools
AR = $(CROSS_COMPILE)ar
CC = $(CROSS_COMPILE)gcc
AS = $(CROSS_COMPILE)as
#LD = $(CROSS_COMPILE)ld
#SIZE = $(CROSS_COMPILE)size
NM = $(CROSS_COMPILE)nm
#OBJCOPY = $(CROSS_COMPILE)objcopy
RM=cs-rm -Rf
SEP=/
# Flags
CFLAGS += -Wall -Wchar-subscripts -Wcomment -Wformat=2 -Wimplicit-int
CFLAGS += -Werror-implicit-function-declaration -Wmain -Wparentheses
CFLAGS += -Wsequence-point -Wreturn-type -Wswitch -Wtrigraphs -Wunused
CFLAGS += -Wuninitialized -Wunknown-pragmas -Wfloat-equal -Wundef
CFLAGS += -Wshadow -Wpointer-arith -Wbad-function-cast -Wwrite-strings
CFLAGS += -Wsign-compare -Waggregate-return -Wstrict-prototypes
CFLAGS += -Wmissing-prototypes -Wmissing-declarations
CFLAGS += -Wformat -Wmissing-format-attribute -Wno-deprecated-declarations
CFLAGS += -Wpacked -Wredundant-decls -Wnested-externs -Winline -Wlong-long
CFLAGS += -Wunreachable-code
CFLAGS += -Wcast-align
#CFLAGS += -Wmissing-noreturn
#CFLAGS += -Wconversion
# To reduce application size use only integer printf function.
CFLAGS += -Dprintf=iprintf
CFLAGS += --param max-inline-insns-single=500 -mcpu=cortex-m3 -mthumb -mlong-calls -ffunction-sections
CFLAGS += $(OPTIMIZATION) $(INCLUDES) -D$(CHIP)
ASFLAGS = -mcpu=cortex-m3 -mthumb -Wall -a -g $(INCLUDES)

View File

@ -1,7 +0,0 @@
# Optimization level
# -O1 Optimize
# -O2 Optimize even more
# -O3 Optimize yet more
# -O0 Reduce compilation time and make debugging produce the expected results
# -Os Optimize for size
OPTIMIZATION = -Os

View File

@ -1,122 +0,0 @@
# Makefile for compiling libboard
.SUFFIXES: .o .a .c .s
CHIP=sam3s4
BOARD=sam3s_ek
LIBNAME=libboard
TOOLCHAIN=gcc
#-------------------------------------------------------------------------------
# Path
#-------------------------------------------------------------------------------
# Output directories
OUTPUT_BIN = ../lib
# Libraries
PROJECT_BASE_PATH = ..
#-------------------------------------------------------------------------------
# Files
#-------------------------------------------------------------------------------
vpath %.h $(PROJECT_BASE_PATH)/include
vpath %.c $(PROJECT_BASE_PATH)/source
vpath %.s $(PROJECT_BASE_PATH)/source
VPATH+=$(PROJECT_BASE_PATH)/source
INCLUDES = -I$(PROJECT_BASE_PATH)
INCLUDES += -I$(PROJECT_BASE_PATH)/include
INCLUDES += -I$(PROJECT_BASE_PATH)/../libchip_sam3s
#-------------------------------------------------------------------------------
ifdef DEBUG
include debug.mk
else
include release.mk
endif
#-------------------------------------------------------------------------------
# Tools
#-------------------------------------------------------------------------------
include $(TOOLCHAIN).mk
#-------------------------------------------------------------------------------
ifdef DEBUG
OUTPUT_OBJ=debug
OUTPUT_LIB=$(LIBNAME)_$(BOARD)_$(TOOLCHAIN)_dbg.a
else
OUTPUT_OBJ=release
OUTPUT_LIB=$(LIBNAME)_$(BOARD)_$(TOOLCHAIN)_rel.a
endif
OUTPUT_PATH=$(OUTPUT_OBJ)_$(BOARD)
#-------------------------------------------------------------------------------
# C source files and objects
#-------------------------------------------------------------------------------
C_SRC=$(wildcard $(PROJECT_BASE_PATH)/source/*.c)
C_OBJ_TEMP = $(patsubst %.c, %.o, $(notdir $(C_SRC)))
# during development, remove some files
C_OBJ_FILTER=
C_OBJ=$(filter-out $(C_OBJ_FILTER), $(C_OBJ_TEMP))
#-------------------------------------------------------------------------------
# Assembler source files and objects
#-------------------------------------------------------------------------------
A_SRC=$(wildcard $(PROJECT_BASE_PATH)/source/*.s)
A_OBJ_TEMP=$(patsubst %.s, %.o, $(notdir $(A_SRC)))
# during development, remove some files
A_OBJ_FILTER=
A_OBJ=$(filter-out $(A_OBJ_FILTER), $(A_OBJ_TEMP))
#-------------------------------------------------------------------------------
# Rules
#-------------------------------------------------------------------------------
all: $(BOARD)
$(BOARD): create_output $(OUTPUT_LIB)
.PHONY: create_output
create_output:
@echo --- Preparing $(BOARD) files $(OUTPUT_PATH) $(OUTPUT_BIN)
# @echo -------------------------
# @echo *$(C_SRC)
# @echo -------------------------
# @echo *$(C_OBJ)
# @echo -------------------------
# @echo *$(addprefix $(OUTPUT_PATH)/, $(C_OBJ))
# @echo -------------------------
# @echo *$(A_SRC)
# @echo -------------------------
-@mkdir $(subst /,$(SEP),$(OUTPUT_BIN)) 1>NUL 2>&1
-@mkdir $(OUTPUT_PATH) 1>NUL 2>&1
$(addprefix $(OUTPUT_PATH)/,$(C_OBJ)): $(OUTPUT_PATH)/%.o: %.c
@$(CC) -c $(CFLAGS) $< -o $@
$(addprefix $(OUTPUT_PATH)/,$(A_OBJ)): $(OUTPUT_PATH)/%.o: %.s
@$(AS) -c $(ASFLAGS) $< -o $@
$(OUTPUT_LIB): $(addprefix $(OUTPUT_PATH)/, $(C_OBJ)) $(addprefix $(OUTPUT_PATH)/, $(A_OBJ))
@$(AR) -r "$(OUTPUT_BIN)/$@" $^
@$(NM) "$(OUTPUT_BIN)/$@" > "$(OUTPUT_BIN)/$@.txt"
.PHONY: clean
clean:
@echo --- Cleaning $(BOARD) files [$(OUTPUT_PATH)$(SEP)*.o]
-@$(RM) $(OUTPUT_PATH) 1>NUL 2>&1
-@$(RM) $(OUTPUT_BIN)/$(OUTPUT_LIB) 1>NUL 2>&1
-@$(RM) $(OUTPUT_BIN)/$(OUTPUT_LIB).txt 1>NUL 2>&1
# dependencies
$(addprefix $(OUTPUT_PATH)/,$(C_OBJ)): $(OUTPUT_PATH)/%.o: $(PROJECT_BASE_PATH)/board.h $(wildcard $(PROJECT_BASE_PATH)/include/*.h)

View File

@ -1,108 +0,0 @@
/* ----------------------------------------------------------------------------
* ATMEL Microcontroller Software Support
* ----------------------------------------------------------------------------
* Copyright (c) 2009, 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.
* ----------------------------------------------------------------------------
*/
#ifndef _BITBANDING_
#define _BITBANDING_
/*----------------------------------------------------------------------------
* \file bitbanding.h
* Include Defines & macros for bit-banding.
*----------------------------------------------------------------------------*/
/*----------------------------------------------------------------------------
* Header files
*----------------------------------------------------------------------------*/
#include <stdint.h>
/*----------------------------------------------------------------------------
* Global Macros
*----------------------------------------------------------------------------*/
/**
* \brief Check if the address is in bit banding sram region.
*
* \note The address should be in area of 0x2000000 ~ 0x200FFFFF
*
* \param x The address to check.
*/
#define IS_BITBAND_SRAM_ADDR(x) \
( ((uint32_t)(x)) >= 0x20000000 && \
((uint32_t)(x)) < (0x20000000+0x100000) )
/**
* \brief Check if the address is in bit banding peripheral region
*
* \note The address should be in area of 0x4000000 ~ 0x400FFFFF
* \param x The address to check
*/
#define IS_BITBAND_PERIPH_ADDR(x) \
( ((uint32_t)(x)) >= 0x40000000 && \
((uint32_t)(x)) < (0x40000000+0x100000) )
/**
* \brief Calculate bit band alias address.
*
* Calculate the bit band alias address and return a pointer address to word.
*
* \param addr The byte address of bitbanding bit.
* \param bit The bit position of bitbanding bit.
* \callergraph
*/
#define BITBAND_ALIAS_ADDRESS(addr, bit) \
((volatile uint32_t*)((((uint32_t)(addr) & 0xF0000000) + 0x02000000) \
+((((uint32_t)(addr)&0xFFFFF)*32)\
+( (uint32_t)(bit)*4))))
/**
* \brief Bit write through bit banding.
*
* \param addr32 32-bit aligned byte address where the bit exists.
* \param bit Bit position.
* \param val The value that the bit is set to.
* \callergraph
*/
#define WRITE_BITBANDING(addr32, bit, val) do {\
*BITBAND_ALIAS_ADDRESS(addr32,bit) = (val); \
} while (0);
/**
* \brief Toggle bit through bit banding
*
* \param addr32 32-bit aligned byte address where the bit exists.
* \param bit Bit position.
*/
#define TOGGLE_BITBANDING(addr32, bit) do {\
volatile uint32_t * p = \
BITBAND_ALIAS_ADDRESS(addr32,bit); \
if (*p) *p = 0; \
else *p = 1; \
}while(0);
#endif /* #ifndef _BITBANDING_ */

View File

@ -1,46 +0,0 @@
/* ----------------------------------------------------------------------------
* ATMEL Microcontroller Software Support
* ----------------------------------------------------------------------------
* Copyright (c) 2009, 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.
* ----------------------------------------------------------------------------
*/
/**
* \file
*
* Interface for the low-level initialization function.
*
*/
#ifndef BOARD_LOWLEVEL_H
#define BOARD_LOWLEVEL_H
/*----------------------------------------------------------------------------
* Exported functions
*----------------------------------------------------------------------------*/
extern void LowLevelInit( void ) ;
#endif /* BOARD_LOWLEVEL_H */

View File

@ -1,71 +0,0 @@
/* ----------------------------------------------------------------------------
* ATMEL Microcontroller Software Support
* ----------------------------------------------------------------------------
* Copyright (c) 2009, 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.
* ----------------------------------------------------------------------------
*/
/**
* \file syscalls.h
*
* Implementation of newlib syscall.
*
*/
/*----------------------------------------------------------------------------
* Headers
*----------------------------------------------------------------------------*/
#include <stdio.h>
#include <stdarg.h>
#include <sys/types.h>
#include <sys/stat.h>
/*----------------------------------------------------------------------------
* Exported functions
*----------------------------------------------------------------------------*/
#ifdef __cplusplus
extern "C" {
#endif
extern caddr_t _sbrk( int incr ) ;
extern int link( char *cOld, char *cNew ) ;
extern int _close( int file ) ;
extern int _fstat( int file, struct stat *st ) ;
extern int _isatty( int file ) ;
extern int _lseek( int file, int ptr, int dir ) ;
extern int _read(int file, char *ptr, int len) ;
extern int _write( int file, char *ptr, int len ) ;
#ifdef __cplusplus
}
#endif

View File

@ -1,78 +0,0 @@
/* ----------------------------------------------------------------------------
* ATMEL Microcontroller Software Support
* ----------------------------------------------------------------------------
* Copyright (c) 2009, 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.
* ----------------------------------------------------------------------------
*/
/**
* \file
*
* \par Purpose
*
* Methods and definitions for Global time tick and wait functions.
*
* Defines a common and simpliest use of Time Tick, to increase tickCount
* every 1ms, the application can get this value through GetTickCount().
*
* \par Usage
*
* -# Configure the System Tick with TimeTick_Configure() when MCK changed
* \note
* Must be done before any invoke of GetTickCount(), Wait() or Sleep().
* -# Uses GetTickCount to get current tick value.
* -# Uses Wait to wait several ms.
* -# Uses Sleep to enter wait for interrupt mode to wait several ms.
*
*/
#ifndef _TIMETICK_
#define _TIMETICK_
/*----------------------------------------------------------------------------
* Headers
*----------------------------------------------------------------------------*/
#include <stdint.h>
/*----------------------------------------------------------------------------
* Definitions
*----------------------------------------------------------------------------*/
/*----------------------------------------------------------------------------
* Global functions
*----------------------------------------------------------------------------*/
extern uint32_t TimeTick_Configure( uint32_t dwNew_MCK ) ;
extern void TimeTick_Increment( void ) ;
extern uint32_t GetTickCount( void ) ;
extern void Wait( volatile uint32_t dwMs ) ;
extern void Sleep( volatile uint32_t dwMs ) ;
#endif /* _TIMETICK_ */

View File

@ -1,6 +1,9 @@
files to be used for Arduino API build:
flash_arduino.ld
files to be used for Arduino Bootloader build:
flash_arduino_bootloader.ld
files to be used for other uses of board
flash.ld
sram.ld

View File

@ -38,8 +38,8 @@ SEARCH_DIR(.)
/* Memory Spaces Definitions */
MEMORY
{
rom (rx) : ORIGIN = 0x00400000, LENGTH = 0x00040000 /* flash, 256K */
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 0x0000c000 /* sram, 48K */
rom (rx) : ORIGIN = 0x00404000, LENGTH = 0x0003c000 /* flash, 240KB = 256K minus 16KB of bootloader */
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 0x0000c000 /* sram, 48KB */
}
/* Section Definitions */

View File

@ -0,0 +1,140 @@
/* ----------------------------------------------------------------------------
* ATMEL Microcontroller Software Support
* ----------------------------------------------------------------------------
* Copyright (c) 2009, 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.
* ----------------------------------------------------------------------------
*/
/*------------------------------------------------------------------------------
* Linker script for running in internal FLASH on the ATSAM3S4
*----------------------------------------------------------------------------*/
OUTPUT_FORMAT("elf32-littlearm", "elf32-littlearm", "elf32-littlearm")
OUTPUT_ARCH(arm)
SEARCH_DIR(.)
/* Memory Spaces Definitions */
MEMORY
{
rom (rx) : ORIGIN = 0x00400000, LENGTH = 0x00004000 /* flash, 16KB */
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 0x0000c000 /* sram, 48KB */
}
/* Section Definitions */
SECTIONS
{
.text :
{
. = ALIGN(4);
_sfixed = .;
KEEP(*(.vectors .vectors.*))
*(.text .text.* .gnu.linkonce.t.*)
*(.glue_7t) *(.glue_7)
*(.rodata .rodata* .gnu.linkonce.r.*)
*(.ARM.extab* .gnu.linkonce.armextab.*)
/* Support C constructors, and C destructors in both user code
and the C library. This also provides support for C++ code. */
. = ALIGN(4);
KEEP(*(.init))
. = ALIGN(4);
__preinit_array_start = .;
KEEP (*(.preinit_array))
__preinit_array_end = .;
. = ALIGN(4);
__init_array_start = .;
KEEP (*(SORT(.init_array.*)))
KEEP (*(.init_array))
__init_array_end = .;
. = ALIGN(0x4);
KEEP (*crtbegin.o(.ctors))
KEEP (*(EXCLUDE_FILE (*crtend.o) .ctors))
KEEP (*(SORT(.ctors.*)))
KEEP (*crtend.o(.ctors))
. = ALIGN(4);
KEEP(*(.fini))
. = ALIGN(4);
__fini_array_start = .;
KEEP (*(.fini_array))
KEEP (*(SORT(.fini_array.*)))
__fini_array_end = .;
KEEP (*crtbegin.o(.dtors))
KEEP (*(EXCLUDE_FILE (*crtend.o) .dtors))
KEEP (*(SORT(.dtors.*)))
KEEP (*crtend.o(.dtors))
. = ALIGN(4);
_efixed = .; /* End of text section */
} > rom
/* .ARM.exidx is sorted, so has to go in its own output section. */
PROVIDE_HIDDEN (__exidx_start = .);
.ARM.exidx :
{
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
} > rom
PROVIDE_HIDDEN (__exidx_end = .);
. = ALIGN(4);
_etext = .;
.relocate : AT (_etext)
{
. = ALIGN(4);
_srelocate = .;
*(.ramfunc .ramfunc.*);
*(.data .data.*);
. = ALIGN(4);
_erelocate = .;
} > ram
/* .bss section which is used for uninitialized data */
.bss (NOLOAD) :
{
. = ALIGN(4);
_sbss = . ;
_szero = .;
*(.bss .bss.*)
*(COMMON)
. = ALIGN(4);
_ebss = . ;
_ezero = .;
} > ram
/* stack section */
.stack (NOLOAD):
{
. = ALIGN(8);
*(.stack .stack.*)
} > ram
. = ALIGN(4);
_end = . ;
}

View File

@ -17,39 +17,6 @@ const static uint8_t SCK = 33 ;
#define PINS_UART (16u)
typedef enum _EAnalogChannel
{
ADC0,
ADC1,
ADC2,
ADC3,
ADC4,
ADC5,
ADC6,
ADC7,
ADC8,
ADC9,
ADC10,
ADC11,
ADC12,
ADC13,
ADC14,
ADC15,
DAC0,
DAC1
} EAnalogChannel ;
/* Types used for the tables below */
typedef struct _PinDescription
{
Pio* pPort ;
uint32_t dwPin ;
uint32_t dwPeripheralId ;
EPioType dwPinType ;
uint32_t dwPinAttribute ;
EAnalogChannel dwAnalogChannel ;
} PinDescription ;
static const PinDescription APinDescription[]=
{
// LEDS, 0..2

View File

@ -1,171 +0,0 @@
/* ----------------------------------------------------------------------------
* ATMEL Microcontroller Software Support
* ----------------------------------------------------------------------------
* 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.
* ----------------------------------------------------------------------------
*/
/*----------------------------------------------------------------------------
* Headers
*----------------------------------------------------------------------------*/
#include "board.h"
/*----------------------------------------------------------------------------
* Exported variables
*----------------------------------------------------------------------------*/
/* Stack Configuration */
#define STACK_SIZE 0x900 /** Stack size (in DWords) */
__attribute__ ((aligned(8),section(".stack")))
uint32_t pdwStack[STACK_SIZE] ;
/* Initialize segments */
extern uint32_t _sfixed;
extern uint32_t _efixed;
extern uint32_t _etext;
extern uint32_t _srelocate;
extern uint32_t _erelocate;
extern uint32_t _szero;
extern uint32_t _ezero;
/*----------------------------------------------------------------------------
* Prototypes
*----------------------------------------------------------------------------*/
/** \cond DOXYGEN_SHOULD_SKIP_THIS */
extern int main( void ) ;
/** \endcond */
void Reset_Handler( void ) ;
extern void __libc_init_array( void ) ;
/*------------------------------------------------------------------------------
* Exception Table
*------------------------------------------------------------------------------*/
void* vector_table[] __attribute__ ((section(".vectors"))) = {
/* Configure Initial Stack Pointer, using linker-generated symbols */
(IntFunc)(&pdwStack[STACK_SIZE-1]),
Reset_Handler,
NMI_Handler,
HardFault_Handler,
MemManage_Handler,
BusFault_Handler,
UsageFault_Handler,
0, 0, 0, 0, /* Reserved */
SVC_Handler,
DebugMon_Handler,
0, /* Reserved */
PendSV_Handler,
SysTick_Handler,
/* Configurable interrupts */
SUPC_IrqHandler, /* 0 Supply Controller */
RSTC_IrqHandler, /* 1 Reset Controller */
RTC_IrqHandler, /* 2 Real Time Clock */
RTT_IrqHandler, /* 3 Real Time Timer */
WDT_IrqHandler, /* 4 Watchdog Timer */
PMC_IrqHandler, /* 5 PMC */
EEFC_IrqHandler, /* 6 EEFC */
Dummy_Handler, /* 7 Reserved */
UART0_IrqHandler, /* 8 UART0 */
UART1_IrqHandler, /* 9 UART1 */
SMC_IrqHandler, /* 10 SMC */
PIOA_IrqHandler, /* 11 Parallel IO Controller A */
PIOB_IrqHandler, /* 12 Parallel IO Controller B */
PIOC_IrqHandler, /* 13 Parallel IO Controller C */
USART0_IrqHandler, /* 14 USART 0 */
USART1_IrqHandler, /* 15 USART 1 */
Dummy_Handler, /* 16 Reserved */
Dummy_Handler, /* 17 Reserved */
MCI_IrqHandler, /* 18 MCI */
TWI0_IrqHandler, /* 19 TWI 0 */
TWI1_IrqHandler, /* 20 TWI 1 */
SPI_IrqHandler, /* 21 SPI */
SSC_IrqHandler, /* 22 SSC */
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 */
ADC_IrqHandler, /* 29 ADC controller */
DAC_IrqHandler, /* 30 DAC controller */
PWM_IrqHandler, /* 31 PWM */
CRCCU_IrqHandler, /* 32 CRC Calculation Unit */
ACC_IrqHandler, /* 33 Analog Comparator */
USBD_IrqHandler, /* 34 USB Device Port */
Dummy_Handler /* 35 not used */
};
/**
* \brief This is the code that gets called on processor reset.
* To initialize the device, and call the main() routine.
*/
void Reset_Handler( void )
{
uint32_t *pSrc, *pDest ;
/* Low level Initialize */
LowLevelInit() ;
/* Initialize the relocate segment */
pSrc = &_etext ;
pDest = &_srelocate ;
if ( pSrc != pDest )
{
for ( ; pDest < &_erelocate ; )
{
*pDest++ = *pSrc++ ;
}
}
/* Clear the zero segment */
for ( pDest = &_szero ; pDest < &_ezero ; )
{
*pDest++ = 0;
}
/* 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 ;
}
/* Initialize the C library */
__libc_init_array() ;
/* Branch to main function */
main() ;
/* Infinite loop */
while ( 1 ) ;
}

View File

@ -1,111 +0,0 @@
/* ----------------------------------------------------------------------------
* ATMEL Microcontroller Software Support
* ----------------------------------------------------------------------------
* Copyright (c) 2009, 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.
* ----------------------------------------------------------------------------
*/
/**
* \file
*
* Provides the low-level initialization function that called on chip startup.
*/
/*----------------------------------------------------------------------------
* Headers
*----------------------------------------------------------------------------*/
#include "board.h"
/*----------------------------------------------------------------------------
* Local definitions
*----------------------------------------------------------------------------*/
/* Clock settings at 48MHz */
#if (BOARD_MCK == 48000000)
#define BOARD_OSCOUNT (CKGR_MOR_MOSCXTST(0x8))
#define BOARD_PLLAR (CKGR_PLLAR_STUCKTO1 \
| CKGR_PLLAR_MULA(0x7) \
| CKGR_PLLAR_PLLACOUNT(0x1) \
| CKGR_PLLAR_DIVA(0x1))
#define BOARD_MCKR (PMC_MCKR_PRES_CLK_2 | PMC_MCKR_CSS_PLLA_CLK)
/* Clock settings at 64MHz */
#elif (BOARD_MCK == 64000000)
#define BOARD_OSCOUNT (CKGR_MOR_MOSCXTST(0x8))
#define BOARD_PLLAR (CKGR_PLLAR_STUCKTO1 \
| CKGR_PLLAR_MULA(0x0f) \
| CKGR_PLLAR_PLLACOUNT(0x1) \
| CKGR_PLLAR_DIVA(0x3))
#define BOARD_MCKR (PMC_MCKR_PRES_CLK | PMC_MCKR_CSS_PLLA_CLK)
#else
#error "No settings for current BOARD_MCK."
#endif
/* Define clock timeout */
#define CLOCK_TIMEOUT 0xFFFFFFFF
/*----------------------------------------------------------------------------
* Exported functions
*----------------------------------------------------------------------------*/
/**
* \brief Performs the low-level initialization of the chip.
* This includes EFC and master clock configuration.
* It also enable a low level on the pin NRST triggers a user reset.
*/
extern WEAK void LowLevelInit( void )
{
uint32_t dwTimeOut = 0 ;
/* Set 3 FWS for Embedded Flash Access @ 64MHz, we are now at 4MHz on Internal FastRC */
EFC->EEFC_FMR = EEFC_FMR_FWS( 3 ) ;
/* Initialize main oscillator */
if ( !(PMC->CKGR_MOR & CKGR_MOR_MOSCSEL) )
{
PMC->CKGR_MOR = CKGR_MOR_KEY(0x37) | BOARD_OSCOUNT | CKGR_MOR_MOSCRCEN | CKGR_MOR_MOSCXTEN;
for ( dwTimeOut = 0 ; !(PMC->PMC_SR & PMC_SR_MOSCXTS) && (dwTimeOut++ < CLOCK_TIMEOUT) ; ) ;
}
/* Switch to 3-20MHz Xtal oscillator */
PMC->CKGR_MOR = CKGR_MOR_KEY(0x37) | BOARD_OSCOUNT | CKGR_MOR_MOSCRCEN | CKGR_MOR_MOSCXTEN | CKGR_MOR_MOSCSEL;
for ( dwTimeOut = 0 ; !(PMC->PMC_SR & PMC_SR_MOSCSELS) && (dwTimeOut++ < CLOCK_TIMEOUT) ; ) ;
PMC->PMC_MCKR = (PMC->PMC_MCKR & ~(uint32_t)PMC_MCKR_CSS_Msk) | PMC_MCKR_CSS_MAIN_CLK;
for ( dwTimeOut = 0 ; !(PMC->PMC_SR & PMC_SR_MCKRDY) && (dwTimeOut++ < CLOCK_TIMEOUT) ; ) ;
/* Initialize PLLA */
PMC->CKGR_PLLAR = BOARD_PLLAR ;
for ( dwTimeOut = 0 ; !(PMC->PMC_SR & PMC_SR_LOCKA) && (dwTimeOut++ < CLOCK_TIMEOUT) ; ) ;
/* Switch to main clock */
PMC->PMC_MCKR = (BOARD_MCKR & ~PMC_MCKR_CSS_Msk) | PMC_MCKR_CSS_MAIN_CLK;
for ( dwTimeOut = 0 ; !(PMC->PMC_SR & PMC_SR_MCKRDY) && (dwTimeOut++ < CLOCK_TIMEOUT) ; ) ;
PMC->PMC_MCKR = BOARD_MCKR ;
for ( dwTimeOut = 0 ; !(PMC->PMC_SR & PMC_SR_MCKRDY) && (dwTimeOut++ < CLOCK_TIMEOUT) ; ) ;
}

View File

@ -1,141 +0,0 @@
/* ----------------------------------------------------------------------------
* ATMEL Microcontroller Software Support
* ----------------------------------------------------------------------------
* Copyright (c) 2009, 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.
* ----------------------------------------------------------------------------
*/
/**
* \file syscalls.c
*
* Implementation of newlib syscall.
*
*/
/*----------------------------------------------------------------------------
* Headers
*----------------------------------------------------------------------------*/
#include "board.h"
#include <stdio.h>
#include <stdarg.h>
#include <sys/types.h>
#include <sys/stat.h>
/*----------------------------------------------------------------------------
* Exported variables
*----------------------------------------------------------------------------*/
#undef errno
extern int errno ;
extern int _end ;
/*----------------------------------------------------------------------------
* Exported functions
*----------------------------------------------------------------------------*/
extern void _exit( int status ) ;
extern void _kill( int pid, int sig ) ;
extern int _getpid ( void ) ;
extern caddr_t _sbrk ( int incr )
{
static unsigned char *heap = NULL ;
unsigned char *prev_heap ;
if ( heap == NULL )
{
heap = (unsigned char *)&_end ;
}
prev_heap = heap;
heap += incr ;
return (caddr_t) prev_heap ;
}
extern int link( char *cOld, char *cNew )
{
return -1 ;
}
extern int _close( int file )
{
return -1 ;
}
extern int _fstat( int file, struct stat *st )
{
st->st_mode = S_IFCHR ;
return 0 ;
}
extern int _isatty( int file )
{
return 1 ;
}
extern int _lseek( int file, int ptr, int dir )
{
return 0 ;
}
extern int _read(int file, char *ptr, int len)
{
return 0 ;
}
extern int _write( int file, char *ptr, int len )
{
int iIndex ;
// for ( ; *ptr != 0 ; ptr++ )
for ( iIndex=0 ; iIndex < len ; iIndex++, ptr++ )
{
// UART_PutChar( *ptr ) ;
}
return iIndex ;
}
extern void _exit( int status )
{
printf( "Exiting with status %d.\n", status ) ;
for ( ; ; ) ;
}
extern void _kill( int pid, int sig )
{
return ;
}
extern int _getpid ( void )
{
return -1 ;
}

View File

@ -1,118 +0,0 @@
/* ----------------------------------------------------------------------------
* ATMEL Microcontroller Software Support
* ----------------------------------------------------------------------------
* Copyright (c) 2009, 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.
* ----------------------------------------------------------------------------
*/
/**
* \file
* Implement simple system tick usage.
*/
/*----------------------------------------------------------------------------
* Headers
*----------------------------------------------------------------------------*/
#include "board.h"
/*----------------------------------------------------------------------------
* Local variables
*----------------------------------------------------------------------------*/
/** Tick Counter united by ms */
static volatile uint32_t _dwTickCount=0 ;
/*----------------------------------------------------------------------------
* Exported Functions
*----------------------------------------------------------------------------*/
/**
* \brief Handler for Sytem Tick interrupt.
*/
extern void TimeTick_Increment( void )
{
_dwTickCount++ ;
}
/**
* \brief Configures the SAM3 SysTick & reset tickCount.
* Systick interrupt handler will generates 1ms interrupt and increase a
* tickCount.
* \param dwNew_MCK Current master clock.
*/
extern uint32_t TimeTick_Configure( uint32_t dwNew_MCK )
{
_dwTickCount = 0 ;
return SysTick_Config( dwNew_MCK/1000 ) ;
}
/**
* \brief Get current Tick Count, in ms.
*/
extern uint32_t GetTickCount( void )
{
return _dwTickCount ;
}
/**
* \brief Sync Wait for several ms
*/
extern void Wait( volatile uint32_t dwMs )
{
uint32_t dwStart ;
uint32_t dwCurrent ;
dwStart = _dwTickCount ;
do
{
dwCurrent = _dwTickCount ;
} while ( dwCurrent - dwStart < dwMs ) ;
}
/**
* \brief Sync Sleep for several ms
*/
extern void Sleep( volatile uint32_t dwMs )
{
uint32_t dwStart ;
uint32_t dwCurrent ;
dwStart = _dwTickCount ;
do
{
dwCurrent = _dwTickCount ;
if ( dwCurrent - dwStart > dwMs )
{
break ;
}
__WFI() ;
} while( 1 ) ;
}

View File

@ -1,5 +1,5 @@
#ifndef _BOARD_
#define _BOARD_
#ifndef _VARIANT_
#define _VARIANT_
/*----------------------------------------------------------------------------
* Headers
@ -7,15 +7,11 @@
#include "libsam/chip.h"
#include "include/bitbanding.h"
#include "include/board_lowlevel.h"
#include "include/timetick.h"
/**
* Libc porting layers
*/
#if defined ( __GNUC__ ) /* GCC CS3 */
# include "include/syscalls.h" /** RedHat Newlib minimal stub */
# include <syscalls.h> /** RedHat Newlib minimal stub */
#endif
/*----------------------------------------------------------------------------
@ -25,29 +21,34 @@
/*----------------------------------------------------------------------------*/
/** Name of the board */
#define BOARD_NAME "SAM3S-EK"
#define VARIANT_NAME "SAM3S-EK"
/*
#define BOARD_REV_A
#define VARIANT_REV_A
*/
#define BOARD_REV_B
#define VARIANT_REV_B
/** Frequency of the board main oscillator */
#define BOARD_MAINOSC 12000000
#define VARIANT_MAINOSC 12000000
/** Master clock frequency (when using board_lowlevel.c) */
#define BOARD_MCK 64000000
/** Master clock frequency */
#define VARIANT_MCK 64000000
/*----------------------------------------------------------------------------
* Arduino objects
* Arduino objects - C++ only
*----------------------------------------------------------------------------*/
# ifdef __cplusplus
# include "UART.h"
# include "USART.h"
extern UARTClass Serial1 ;
extern UARTClass Serial2 ;
extern USARTClass Serial3 ;
extern USARTClass Serial4 ;
//extern USARTClass Serial3 ;
//extern USARTClass Serial4 ;
# endif
#endif /* #ifndef _BOARD_ */
#endif /* #ifndef _VARIANT_ */