1
0
mirror of https://github.com/esp8266/Arduino.git synced 2025-12-01 17:57:53 +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,18 +1,18 @@
#ifndef Arduino_h
#define Arduino_h
#include <stdint.h>
//#include <sys/types.h>
#include <stdlib.h>
#include <string.h>
#include <math.h>
//! Include SAM3S-EK BSP headers
#include "variant.h"
#include "binary.h"
#ifdef __cplusplus
extern "C"{
#endif
#endif // __cplusplus
#define HIGH 0x1
#define LOW 0x0
@@ -45,7 +45,7 @@ extern "C"{
// undefine stdlib's abs if encountered
#ifdef abs
#undef abs
#endif
#endif // abs
#define min(a,b) ((a)<(b)?(a):(b))
#define max(a,b) ((a)>(b)?(a):(b))
@@ -76,32 +76,33 @@ typedef unsigned int word;
#define bit(b) (1UL << (b))
typedef uint8_t boolean;
typedef uint8_t byte;
// TODO: to be checked
typedef uint8_t boolean ;
typedef uint8_t byte ;
void init(void);
void init( void ) ;
void pinMode(uint8_t, uint8_t);
void digitalWrite(uint8_t, uint8_t);
int digitalRead(uint8_t);
int analogRead(uint8_t);
void analogReference(uint8_t mode);
void analogWrite(uint8_t, int);
void pinMode( uint8_t, uint8_t ) ;
void digitalWrite( uint8_t, uint8_t ) ;
int digitalRead( uint8_t ) ;
int analogRead( uint8_t ) ;
void analogReference( uint8_t mode ) ;
void analogWrite( uint8_t, int ) ;
unsigned long millis(void);
unsigned long micros(void);
unsigned long millis( void ) ;
unsigned long micros( void ) ;
//void delay(unsigned long);
#define delay( dwMs ) Wait( dwMs )
void delayMicroseconds(unsigned int us);
void delayMicroseconds( unsigned int us ) ;
void shiftOut(uint8_t dataPin, uint8_t clockPin, uint8_t bitOrder, uint8_t val);
uint8_t shiftIn(uint8_t dataPin, uint8_t clockPin, uint8_t bitOrder);
void shiftOut( uint8_t dataPin, uint8_t clockPin, uint8_t bitOrder, uint8_t val ) ;
uint8_t shiftIn( uint8_t dataPin, uint8_t clockPin, uint8_t bitOrder ) ;
void attachInterrupt(uint8_t, void (*)(void), int mode);
void detachInterrupt(uint8_t);
void attachInterrupt( uint8_t, void (*)(void), int mode ) ;
void detachInterrupt( uint8_t ) ;
void setup(void);
void loop(void);
void setup( void ) ;
void loop( void ) ;
// Get the bit location within the hardware port of the given virtual pin.
// This comes from the pins_*.c file for the active board configuration.
@@ -125,31 +126,68 @@ void loop(void);
#ifdef __cplusplus
} // extern "C"
#endif
#endif // __cplusplus
#ifdef __cplusplus
#include "WCharacter.h"
#include "WString.h"
#include "HardwareSerial.h"
# include "WCharacter.h"
# include "WString.h"
# include "HardwareSerial.h"
uint16_t makeWord(uint16_t w);
uint16_t makeWord(byte h, byte l);
uint16_t makeWord( uint16_t w ) ;
uint16_t makeWord( byte h, byte l ) ;
#define word(...) makeWord(__VA_ARGS__)
unsigned long pulseIn(uint8_t pin, uint8_t state, unsigned long timeout = 1000000L);
unsigned long pulseIn( uint8_t pin, uint8_t state, unsigned long timeout = 1000000L ) ;
void tone(uint8_t _pin, unsigned int frequency, unsigned long duration = 0);
void noTone(uint8_t _pin);
void tone( uint8_t _pin, unsigned int frequency, unsigned long duration = 0 ) ;
void noTone( uint8_t _pin ) ;
// WMath prototypes
long random(long);
long random(long, long);
void randomSeed(unsigned int);
long map(long, long, long, long, long);
long random( long ) ;
long random( long, long ) ;
void randomSeed( unsigned int ) ;
long map( long, long, long, long, long ) ;
#endif
#endif // __cplusplus
//! Include variant header
#include "variant.h"
//! Definitions and types for pins
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 ;
#include "pins_arduino.h"
#endif
#endif // Arduino_h

View File

@@ -1,8 +1,9 @@
#include "wiring_private.h"
//#include "wiring_private.h"
#include <stdint.h>
#include "HardwareSerial.h"
inline void store_char( uint8_t c, ring_buffer *pBuffer )
extern void store_char( uint8_t c, ring_buffer* pBuffer )
{
int i = (unsigned int)(pBuffer->head + 1) % SERIAL_BUFFER_SIZE;

View File

@@ -1,8 +1,7 @@
#ifndef HardwareSerial_h
#define HardwareSerial_h
#include <inttypes.h>
#include <stdint.h>
#include "Stream.h"
// Define constants and variables for buffering incoming serial data. We're
@@ -34,6 +33,9 @@ class HardwareSerial : public Stream
virtual void write( const uint8_t c ) =0 ;
using Print::write ; // pull in write(str) and write(buf, size) from Print
};
} ;
// Complementary API
extern void store_char( uint8_t c, ring_buffer* pBuffer ) ;
#endif // HardwareSerial_h

View File

@@ -43,10 +43,11 @@ void Print::write(const uint8_t *buffer, size_t size)
write(*buffer++);
}
void Print::print(const String &s)
void Print::print( const String &s )
{
for (int i = 0; i < s.length(); i++) {
write(s[i]);
for ( int i = 0 ; i < (int)s.length() ; i++ )
{
write( s[i] ) ;
}
}

View File

@@ -3,13 +3,12 @@
#include <string.h>
#include "UART.h"
// Constructors ////////////////////////////////////////////////////////////////
UARTClass::UARTClass( ring_buffer* rx_buffer, ring_buffer* tx_buffer, Uart* pUart, IRQn_Type dwIrq, uint32_t dwId )
UARTClass::UARTClass( Uart* pUart, IRQn_Type dwIrq, uint32_t dwId, ring_buffer* pRx_buffer, ring_buffer *pTx_buffer )
{
_rx_buffer = rx_buffer ;
_tx_buffer = tx_buffer ;
_rx_buffer = pRx_buffer ;
_tx_buffer = pTx_buffer ;
_pUart=pUart ;
_dwIrq=dwIrq ;
@@ -31,7 +30,7 @@ void UARTClass::begin( const uint32_t dwBaudRate )
/* Configure baudrate */
/* Asynchronous, no oversampling */
_pUart->UART_BRGR = (BOARD_MCK / dwBaudRate) / 16 ;
_pUart->UART_BRGR = (VARIANT_MCK / dwBaudRate) / 16 ;
/* Disable PDC channel */
_pUart->UART_PTCR = UART_PTCR_RXTDIS | UART_PTCR_TXTDIS ;
@@ -116,10 +115,9 @@ void UARTClass::write( const uint8_t c )
void UARTClass::IrqHandler( void )
{
/*
// RX char IT
unsigned char c = _pUart->UART_RHR ;
store_char(c, &rx_buffer3);
store_char( c, _rx_buffer ) ;
// TX FIFO empty IT
if ( _tx_buffer->head == _tx_buffer->tail )
@@ -129,11 +127,10 @@ void UARTClass::IrqHandler( void )
else
{
// There is more data in the output buffer. Send the next byte
unsigned char c = _tx_buffer->buffer[_tx_buffer->tail] ;
c = _tx_buffer->buffer[_tx_buffer->tail] ;
_tx_buffer->tail = (_tx_buffer->tail + 1) % SERIAL_BUFFER_SIZE ;
_pUart->UART_THR = c ;
}
*/
}

View File

@@ -1,7 +1,9 @@
#ifndef _UART_
#define _UART_
#include <inttypes.h>
// UART.cpp need this class to be predefined
class UARTClass ;
#include "wiring_private.h"
class UARTClass : public HardwareSerial
@@ -12,7 +14,7 @@ class UARTClass : public HardwareSerial
uint32_t _dwId ;
public:
UARTClass( ring_buffer *rx_buffer, ring_buffer *tx_buffer, Uart* pUart, IRQn_Type dwIrq, uint32_t dwId ) ;
UARTClass( Uart* pUart, IRQn_Type dwIrq, uint32_t dwId, ring_buffer* pRx_buffer, ring_buffer *pTx_buffer ) ;
void begin( const uint32_t dwBaudRate ) ;
void end( void ) ;

View File

@@ -5,10 +5,10 @@
// Constructors ////////////////////////////////////////////////////////////////
USARTClass::USARTClass( ring_buffer *rx_buffer, ring_buffer *tx_buffer, Usart* pUsart, IRQn_Type dwIrq, uint32_t dwId )
USARTClass::USARTClass( Usart* pUsart, IRQn_Type dwIrq, uint32_t dwId, ring_buffer* pRx_buffer, ring_buffer *pTx_buffer )
{
_rx_buffer = rx_buffer ;
_tx_buffer = tx_buffer ;
_rx_buffer = pRx_buffer ;
_tx_buffer = pTx_buffer ;
_pUsart=pUsart ;
_dwIrq=dwIrq ;
@@ -19,7 +19,7 @@ USARTClass::USARTClass( ring_buffer *rx_buffer, ring_buffer *tx_buffer, Usart* p
void USARTClass::begin( const uint32_t dwBaudRate )
{
/* Configure PMC */
/* Configure PMC */
PMC_EnablePeripheral( _dwId ) ;
/* Reset and disable receiver & transmitter */
@@ -31,7 +31,7 @@ void USARTClass::begin( const uint32_t dwBaudRate )
/* Configure baudrate */
/* Asynchronous, no oversampling */
_pUsart->US_BRGR = (BOARD_MCK / dwBaudRate) / 16 ;
_pUsart->US_BRGR = (VARIANT_MCK / dwBaudRate) / 16 ;
/* Disable PDC channel */
_pUsart->US_PTCR = US_PTCR_RXTDIS | US_PTCR_TXTDIS ;
@@ -42,32 +42,96 @@ void USARTClass::begin( const uint32_t dwBaudRate )
void USARTClass::end()
{
// wait for transmission of outgoing data
while ( _tx_buffer->head != _tx_buffer->tail )
{
}
// clear any received data
_rx_buffer->head = _rx_buffer->tail ;
PMC_DisablePeripheral( _dwId ) ;
}
int USARTClass::available( void )
{
return 0 ;
return (unsigned int)(SERIAL_BUFFER_SIZE + _rx_buffer->head - _rx_buffer->tail) % SERIAL_BUFFER_SIZE ;
}
int USARTClass::peek( void )
{
return 0 ;
if ( _rx_buffer->head == _rx_buffer->tail )
{
return -1 ;
}
else
{
return _rx_buffer->buffer[_rx_buffer->tail] ;
}
}
int USARTClass::read( void )
{
return 0 ;
// if the head isn't ahead of the tail, we don't have any characters
if ( _rx_buffer->head == _rx_buffer->tail )
{
return -1 ;
}
else
{
unsigned char c = _rx_buffer->buffer[_rx_buffer->tail] ;
_rx_buffer->tail = (unsigned int)(_rx_buffer->tail + 1) % SERIAL_BUFFER_SIZE ;
return c ;
}
}
void USARTClass::flush( void )
{
while ( _tx_buffer->head != _tx_buffer->tail )
{
}
}
void USARTClass::write( uint8_t c )
{
int i = (_tx_buffer->head + 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->tail )
{
}
_tx_buffer->buffer[_tx_buffer->head] = c ;
_tx_buffer->head = i ;
/* Wait for the transmitter to be ready */
while ( (_pUsart->US_CSR & US_CSR_TXEMPTY) == 0 ) ;
/* Send character */
_pUsart->US_THR=c ;
}
void USARTClass::IrqHandler( void )
{
// RX char IT
unsigned char c = _pUsart->US_RHR ;
store_char( c, _rx_buffer ) ;
// TX FIFO empty IT
if ( _tx_buffer->head == _tx_buffer->tail )
{
// Buffer empty, so disable interrupts
}
else
{
// There is more data in the output buffer. Send the next byte
c = _tx_buffer->buffer[_tx_buffer->tail] ;
_tx_buffer->tail = (_tx_buffer->tail + 1) % SERIAL_BUFFER_SIZE ;
_pUsart->US_THR = c ;
}
}

View File

@@ -1,7 +1,9 @@
#ifndef _USART_
#define _USART_
#include <inttypes.h>
// USART.cpp need this class to be predefined
class USARTClass ;
#include "wiring_private.h"
class USARTClass : public HardwareSerial
@@ -12,7 +14,7 @@ class USARTClass : public HardwareSerial
uint32_t _dwId ;
public:
USARTClass( ring_buffer *rx_buffer, ring_buffer *tx_buffer, Usart* pUsart, IRQn_Type dwIrq, uint32_t dwId ) ;
USARTClass( Usart* pUsart, IRQn_Type dwIrq, uint32_t dwId, ring_buffer* pRx_buffer, ring_buffer *pTx_buffer ) ;
void begin( const uint32_t dwBaudRate ) ;
void end( void ) ;

View File

@@ -1,7 +1,5 @@
#include "board.h"
#include <inttypes.h>
#include <stdio.h>
//#include <inttypes.h>
//#include <stdio.h>
#include "wiring_private.h"

View File

@@ -0,0 +1,171 @@
/* ----------------------------------------------------------------------------
* 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 "Arduino.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 ;
/* Arduino board Low level Initialization */
init() ;
/* 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,8 +1,8 @@
# Makefile for compiling libboard
# Makefile for compiling libArduino
.SUFFIXES: .o .a .c .s
CHIP=sam3s4
BOARD=sam3s_ek
VARIANT=sam3s_ek
LIBNAME=arduino_sam3s_ek
TOOLCHAIN=gcc
@@ -15,22 +15,27 @@ OUTPUT_BIN = ../lib
# Libraries
PROJECT_BASE_PATH = ..
BSP_PATH = ../../../../tools
SYSTEM_PATH = ../../../system
CMSIS_PATH = $(SYSTEM_PATH)/CMSIS/CM3/CoreSupport
VARIANT_PATH = ../../../variants/sam3s-ek
#-------------------------------------------------------------------------------
# Files
#-------------------------------------------------------------------------------
vpath %.h $(PROJECT_BASE_PATH) $(BSP_PATH)/libchip_sam3s $(BSP_PATH)/libboard_sam3s-ek
vpath %.h $(PROJECT_BASE_PATH) $(SYSTEM_PATH) $(VARIANT_PATH)
vpath %.c $(PROJECT_BASE_PATH)
vpath %.cpp $(PROJECT_BASE_PATH) $(PROJECT_BASE_PATH)/sam3s_ek
vpath %.cpp $(PROJECT_BASE_PATH) $(PROJECT_BASE_PATH)
VPATH+=$(PROJECT_BASE_PATH)
INCLUDES = -I$(PROJECT_BASE_PATH)
INCLUDES = -I$(PROJECT_BASE_PATH)/sam3s_ek
INCLUDES += -I$(BSP_PATH)/libchip_sam3s
INCLUDES += -I$(BSP_PATH)/libboard_sam3s-ek
INCLUDES = -I$(PROJECT_BASE_PATH)
INCLUDES += -I$(SYSTEM_PATH)
INCLUDES += -I$(SYSTEM_PATH)/libsam
INCLUDES += -I$(VARIANT_PATH)
INCLUDES += -I$(VARIANT_PATH)
INCLUDES += -I$(CMSIS_PATH)
#-------------------------------------------------------------------------------
ifdef DEBUG
@@ -76,7 +81,8 @@ CPP_SRC=$(wildcard $(PROJECT_BASE_PATH)/*.cpp)
CPP_OBJ_TEMP = $(patsubst %.cpp, %.o, $(notdir $(CPP_SRC)))
# during development, remove some files
CPP_OBJ_FILTER=Tone.o WMath.o WString.o
CPP_OBJ_FILTER=Tone.o WMath.o
#WString.o
CPP_OBJ=$(filter-out $(CPP_OBJ_FILTER), $(CPP_OBJ_TEMP))
@@ -103,6 +109,8 @@ sam3s_ek: create_output $(OUTPUT_LIB)
create_output:
@echo --- Preparing sam3s_ek files in $(OUTPUT_PATH) $(OUTPUT_BIN)
@echo -------------------------
@echo *$(INCLUDES)
@echo -------------------------
@echo *$(C_SRC)
@echo -------------------------
@echo *$(C_OBJ)
@@ -127,7 +135,8 @@ $(addprefix $(OUTPUT_PATH)/,$(C_OBJ)): $(OUTPUT_PATH)/%.o: %.c
@$(CC) -c $(CFLAGS) $< -o $@
$(addprefix $(OUTPUT_PATH)/,$(CPP_OBJ)): $(OUTPUT_PATH)/%.o: %.cpp
@$(CC) -c $(CPPFLAGS) $< -o $@
# @$(CC) -c $(CPPFLAGS) $< -o $@
$(CC) -xc++ -c $(CPPFLAGS) $< -o $@
$(addprefix $(OUTPUT_PATH)/,$(A_OBJ)): $(OUTPUT_PATH)/%.o: %.s
@$(AS) -c $(ASFLAGS) $< -o $@
@@ -142,5 +151,5 @@ clean:
-@$(RM) $(OUTPUT_PATH) 1>NUL 2>&1
-@$(RM) $(OUTPUT_BIN)/$(OUTPUT_LIB) 1>NUL 2>&1
#$(addprefix $(OUTPUT_PATH)/,$(C_OBJ)): $(OUTPUT_PATH)/%.o: $(PROJECT_BASE_PATH)/board.h $(wildcard $(PROJECT_BASE_PATH)/include/*.h)
#$(addprefix $(OUTPUT_PATH)/,$(CPP_OBJ)): $(OUTPUT_PATH)/%.o: $(PROJECT_BASE_PATH)/board.h $(wildcard $(PROJECT_BASE_PATH)/include/*.h)
#$(addprefix $(OUTPUT_PATH)/,$(C_OBJ)): $(OUTPUT_PATH)/%.o: $(PROJECT_BASE_PATH)/chip.h $(wildcard $(PROJECT_BASE_PATH)/include/*.h)
#$(addprefix $(OUTPUT_PATH)/,$(CPP_OBJ)): $(OUTPUT_PATH)/%.o: $(PROJECT_BASE_PATH)/chip.h $(wildcard $(PROJECT_BASE_PATH)/include/*.h)

View File

@@ -32,7 +32,7 @@ CFLAGS += -Wcast-align
#CFLAGS += -Wconversion
CFLAGS += --param max-inline-insns-single=500 -mcpu=cortex-m3 -mthumb -mlong-calls -ffunction-sections
CFLAGS += $(OPTIMIZATION) $(INCLUDES) -D$(CHIP)
CFLAGS += $(OPTIMIZATION) $(INCLUDES) -D$(CHIP) -D$(VARIANT)
# To reduce application size use only integer printf function.
CFLAGS += -Dprintf=iprintf

View File

@@ -1,199 +0,0 @@
WInterrupts.o:
00000000 r LED_BLUE
00000001 r LED_GREEN
00000002 r LED_RED
00000005 r MISO
00000004 r MOSI
00000006 r SCK
00000003 r SS
00000000 T attachInterrupt
00000000 T detachInterrupt
00000000 b intFunc
wiring.o:
00000004 r APinDescription
U GetTickCount
U LowLevelInit
00000002 r MISO
00000001 r MOSI
00000000 t NVIC_SetPriority
U PIO_Configure
00000003 r SCK
00000000 r SS
00000000 t SysTick_Config
00000000 T SysTick_Handler
U TimeTick_Increment
U WDT_Disable
00000000 T Wait
00000000 T delayMicroseconds
00000000 T init
00000000 T micros
00000000 T millis
00000008 b timer0_fract
00000004 B timer0_millis
00000000 B timer0_overflow_count
wiring_shift.o:
00000004 r APinDescription
00000002 r MISO
00000001 r MOSI
00000003 r SCK
00000000 r SS
U digitalRead
U digitalWrite
00000000 T shiftIn
00000000 T shiftOut
HardwareSerial.o:
00000004 r _ZL15APinDescription
00000000 r _ZL2SS
00000003 r _ZL3SCK
00000002 r _ZL4MISO
00000001 r _ZL4MOSI
Print.o:
00000030 r _ZL15APinDescription
0000002b r _ZL2SS
0000002e r _ZL3SCK
0000002d r _ZL4MISO
0000002c r _ZL4MOSI
00000000 T _ZN5Print10printFloatEdh
00000000 T _ZN5Print11printNumberEmh
00000000 T _ZN5Print5printEPKc
00000000 T _ZN5Print5printERK6String
00000000 T _ZN5Print5printEc
00000000 T _ZN5Print5printEdi
00000000 T _ZN5Print5printEhi
00000000 T _ZN5Print5printEii
00000000 T _ZN5Print5printEji
00000000 T _ZN5Print5printEli
00000000 T _ZN5Print5printEmi
00000000 T _ZN5Print5writeEPKc
00000000 T _ZN5Print5writeEPKhj
00000000 T _ZN5Print7printlnEPKc
00000000 T _ZN5Print7printlnERK6String
00000000 T _ZN5Print7printlnEc
00000000 T _ZN5Print7printlnEdi
00000000 T _ZN5Print7printlnEhi
00000000 T _ZN5Print7printlnEii
00000000 T _ZN5Print7printlnEji
00000000 T _ZN5Print7printlnEli
00000000 T _ZN5Print7printlnEmi
00000000 T _ZN5Print7printlnEv
00000000 W _ZNK6String6lengthEv
U _ZNK6StringixEj
0000001c R _ZTI5Print
00000024 R _ZTS5Print
00000008 R _ZTV5Print
U _ZTVN10__cxxabiv117__class_type_infoE
U __aeabi_d2iz
U __aeabi_d2uiz
U __aeabi_dadd
U __aeabi_dcmplt
U __aeabi_ddiv
U __aeabi_dmul
U __aeabi_dsub
U __aeabi_i2d
U __aeabi_ui2d
U __aeabi_unwind_cpp_pr1
U __cxa_pure_virtual
UART.o:
U PMC_DisablePeripheral
U PMC_EnablePeripheral
00000048 r _ZL15APinDescription
00000043 r _ZL2SS
00000046 r _ZL3SCK
00000045 r _ZL4MISO
00000044 r _ZL4MOSI
00000000 W _ZN14HardwareSerialC1Ev
00000000 W _ZN14HardwareSerialC2Ev
00000000 n _ZN14HardwareSerialC5Ev
U _ZN5Print5writeEPKc
U _ZN5Print5writeEPKhj
00000000 W _ZN5PrintC1Ev
00000000 W _ZN5PrintC2Ev
00000000 n _ZN5PrintC5Ev
00000000 W _ZN6StreamC1Ev
00000000 W _ZN6StreamC2Ev
00000000 n _ZN6StreamC5Ev
00000000 T _ZN9UARTClass10IrqHandlerEv
00000000 T _ZN9UARTClass3endEv
00000000 T _ZN9UARTClass4peekEv
00000000 T _ZN9UARTClass4readEv
00000000 T _ZN9UARTClass5beginEm
00000000 T _ZN9UARTClass5flushEv
00000000 T _ZN9UARTClass5writeEh
00000000 T _ZN9UARTClass9availableEv
00000000 T _ZN9UARTClassC1EP12_ring_bufferS1_P4Uart4IRQnm
00000000 T _ZN9UARTClassC2EP12_ring_bufferS1_P4Uart4IRQnm
00000000 V _ZTI14HardwareSerial
U _ZTI5Print
00000000 V _ZTI6Stream
0000002c R _ZTI9UARTClass
00000000 V _ZTS14HardwareSerial
00000000 V _ZTS6Stream
00000038 R _ZTS9UARTClass
00000000 V _ZTV14HardwareSerial
U _ZTV5Print
00000000 V _ZTV6Stream
00000000 R _ZTV9UARTClass
U _ZTVN10__cxxabiv120__si_class_type_infoE
U __aeabi_unwind_cpp_pr1
U __cxa_pure_virtual
USART.o:
U PMC_EnablePeripheral
0000004c r _ZL15APinDescription
00000045 r _ZL2SS
00000048 r _ZL3SCK
00000047 r _ZL4MISO
00000046 r _ZL4MOSI
00000000 T _ZN10USARTClass10IrqHandlerEv
00000000 T _ZN10USARTClass3endEv
00000000 T _ZN10USARTClass4peekEv
00000000 T _ZN10USARTClass4readEv
00000000 T _ZN10USARTClass5beginEm
00000000 T _ZN10USARTClass5flushEv
00000000 T _ZN10USARTClass5writeEh
00000000 T _ZN10USARTClass9availableEv
00000000 T _ZN10USARTClassC1EP12_ring_bufferS1_P5Usart4IRQnm
00000000 T _ZN10USARTClassC2EP12_ring_bufferS1_P5Usart4IRQnm
00000000 W _ZN14HardwareSerialC1Ev
00000000 W _ZN14HardwareSerialC2Ev
00000000 n _ZN14HardwareSerialC5Ev
U _ZN5Print5writeEPKc
U _ZN5Print5writeEPKhj
00000000 W _ZN5PrintC1Ev
00000000 W _ZN5PrintC2Ev
00000000 n _ZN5PrintC5Ev
00000000 W _ZN6StreamC1Ev
00000000 W _ZN6StreamC2Ev
00000000 n _ZN6StreamC5Ev
0000002c R _ZTI10USARTClass
00000000 V _ZTI14HardwareSerial
U _ZTI5Print
00000000 V _ZTI6Stream
00000038 R _ZTS10USARTClass
00000000 V _ZTS14HardwareSerial
00000000 V _ZTS6Stream
00000000 R _ZTV10USARTClass
00000000 V _ZTV14HardwareSerial
U _ZTV5Print
00000000 V _ZTV6Stream
U _ZTVN10__cxxabiv120__si_class_type_infoE
U __aeabi_unwind_cpp_pr1
U __cxa_pure_virtual
main.o:
00000004 r _ZL15APinDescription
00000000 r _ZL2SS
00000003 r _ZL3SCK
00000002 r _ZL4MISO
00000001 r _ZL4MOSI
U __aeabi_unwind_cpp_pr0
U init
U loop
00000000 T main
U setup

View File

@@ -1,135 +0,0 @@
WInterrupts.o:
00000000 T attachInterrupt
00000000 T detachInterrupt
00000000 b intFunc
wiring.o:
U GetTickCount
U LowLevelInit
U PIO_Configure
00000000 T SysTick_Handler
U TimeTick_Increment
U WDT_Disable
00000000 T Wait
00000000 T delayMicroseconds
00000000 T init
00000000 T micros
00000000 T millis
00000004 B timer0_millis
00000000 B timer0_overflow_count
wiring_shift.o:
U digitalRead
U digitalWrite
00000000 T shiftIn
00000000 T shiftOut
HardwareSerial.o:
Print.o:
00000000 T _ZN5Print10printFloatEdh
00000000 T _ZN5Print11printNumberEmh
00000000 T _ZN5Print5printEPKc
00000000 T _ZN5Print5printERK6String
00000000 T _ZN5Print5printEc
00000000 T _ZN5Print5printEdi
00000000 T _ZN5Print5printEhi
00000000 T _ZN5Print5printEii
00000000 T _ZN5Print5printEji
00000000 T _ZN5Print5printEli
00000000 T _ZN5Print5printEmi
00000000 T _ZN5Print5writeEPKc
00000000 T _ZN5Print5writeEPKhj
00000000 T _ZN5Print7printlnEPKc
00000000 T _ZN5Print7printlnERK6String
00000000 T _ZN5Print7printlnEc
00000000 T _ZN5Print7printlnEdi
00000000 T _ZN5Print7printlnEhi
00000000 T _ZN5Print7printlnEii
00000000 T _ZN5Print7printlnEji
00000000 T _ZN5Print7printlnEli
00000000 T _ZN5Print7printlnEmi
00000000 T _ZN5Print7printlnEv
U _ZNK6StringixEj
0000001c R _ZTI5Print
00000014 R _ZTS5Print
00000000 R _ZTV5Print
U _ZTVN10__cxxabiv117__class_type_infoE
U __aeabi_d2iz
U __aeabi_d2uiz
U __aeabi_dadd
U __aeabi_dcmplt
U __aeabi_ddiv
U __aeabi_dmul
U __aeabi_dsub
U __aeabi_i2d
U __aeabi_ui2d
U __aeabi_unwind_cpp_pr0
U __aeabi_unwind_cpp_pr1
U __cxa_pure_virtual
UART.o:
U PMC_DisablePeripheral
U PMC_EnablePeripheral
U _ZN5Print5writeEPKc
U _ZN5Print5writeEPKhj
00000000 T _ZN9UARTClass10IrqHandlerEv
00000000 T _ZN9UARTClass3endEv
00000000 T _ZN9UARTClass4peekEv
00000000 T _ZN9UARTClass4readEv
00000000 T _ZN9UARTClass5beginEm
00000000 T _ZN9UARTClass5flushEv
00000000 T _ZN9UARTClass5writeEh
00000000 T _ZN9UARTClass9availableEv
00000000 T _ZN9UARTClassC1EP12_ring_bufferS1_P4Uart4IRQnm
00000000 T _ZN9UARTClassC2EP12_ring_bufferS1_P4Uart4IRQnm
00000000 V _ZTI14HardwareSerial
U _ZTI5Print
00000000 V _ZTI6Stream
00000038 R _ZTI9UARTClass
00000000 V _ZTS14HardwareSerial
00000000 V _ZTS6Stream
0000002c R _ZTS9UARTClass
00000000 V _ZTV14HardwareSerial
00000000 V _ZTV6Stream
00000000 R _ZTV9UARTClass
U _ZTVN10__cxxabiv120__si_class_type_infoE
U __aeabi_unwind_cpp_pr0
U __aeabi_unwind_cpp_pr1
U __cxa_pure_virtual
USART.o:
U PMC_EnablePeripheral
00000000 T _ZN10USARTClass10IrqHandlerEv
00000000 T _ZN10USARTClass3endEv
00000000 T _ZN10USARTClass4peekEv
00000000 T _ZN10USARTClass4readEv
00000000 T _ZN10USARTClass5beginEm
00000000 T _ZN10USARTClass5flushEv
00000000 T _ZN10USARTClass5writeEh
00000000 T _ZN10USARTClass9availableEv
00000000 T _ZN10USARTClassC1EP12_ring_bufferS1_P5Usart4IRQnm
00000000 T _ZN10USARTClassC2EP12_ring_bufferS1_P5Usart4IRQnm
U _ZN5Print5writeEPKc
U _ZN5Print5writeEPKhj
0000003c R _ZTI10USARTClass
00000000 V _ZTI14HardwareSerial
U _ZTI5Print
00000000 V _ZTI6Stream
0000002c R _ZTS10USARTClass
00000000 V _ZTS14HardwareSerial
00000000 V _ZTS6Stream
00000000 R _ZTV10USARTClass
00000000 V _ZTV14HardwareSerial
00000000 V _ZTV6Stream
U _ZTVN10__cxxabiv120__si_class_type_infoE
U __aeabi_unwind_cpp_pr0
U __cxa_pure_virtual
main.o:
U __aeabi_unwind_cpp_pr1
U init
U loop
00000000 T main
U setup

View File

@@ -0,0 +1,71 @@
/* ----------------------------------------------------------------------------
* 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

@@ -0,0 +1,141 @@
/* ----------------------------------------------------------------------------
* 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 "variant.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

@@ -119,24 +119,75 @@ void delayMicroseconds(unsigned int us)
/*
* Cortex-M3 Systick IT handler
*/
void SysTick_Handler( void )
extern void SysTick_Handler( void )
{
// Increment tick count each ms
TimeTick_Increment() ;
}
//! Check Variant for PLL/Clock inits
#if defined sam3s_ek
#define VARIANT_PLLAR (CKGR_PLLAR_STUCKTO1 | \
CKGR_PLLAR_MULA( 0x0f ) | \
CKGR_PLLAR_PLLACOUNT( 0x1 ) | \
CKGR_PLLAR_DIVA( 0x3 ))
#else
#error "No settings for current VARIANT"
#endif
/**
* \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.
*/
static void LowLevelInit_sam3s_ek( void )
{
/* 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) | CKGR_MOR_MOSCXTST(0x8) | CKGR_MOR_MOSCRCEN | CKGR_MOR_MOSCXTEN ;
for ( ; !(PMC->PMC_SR & PMC_SR_MOSCXTS) ; ) ;
}
/* Switch to 3-20MHz Xtal oscillator */
PMC->CKGR_MOR = CKGR_MOR_KEY(0x37) | CKGR_MOR_MOSCXTST(0x8) | CKGR_MOR_MOSCRCEN | CKGR_MOR_MOSCXTEN | CKGR_MOR_MOSCSEL ;
for ( ; !(PMC->PMC_SR & PMC_SR_MOSCSELS) ; ) ;
PMC->PMC_MCKR = (PMC->PMC_MCKR & ~(uint32_t)PMC_MCKR_CSS_Msk) | PMC_MCKR_CSS_MAIN_CLK ;
for ( ; !(PMC->PMC_SR & PMC_SR_MCKRDY) ; ) ;
/* Initialize PLLA */
PMC->CKGR_PLLAR = VARIANT_PLLAR ;
for ( ; !(PMC->PMC_SR & PMC_SR_LOCKA) ; ) ;
/* Switch to main clock */
PMC->PMC_MCKR = ((PMC_MCKR_PRES_CLK | PMC_MCKR_CSS_PLLA_CLK) & ~PMC_MCKR_CSS_Msk) | PMC_MCKR_CSS_MAIN_CLK ;
for ( ; !(PMC->PMC_SR & PMC_SR_MCKRDY) ; ) ;
PMC->PMC_MCKR = (PMC_MCKR_PRES_CLK | PMC_MCKR_CSS_PLLA_CLK) ;
for ( ; !(PMC->PMC_SR & PMC_SR_MCKRDY) ; ) ;
}
void init( void )
{
// Disable watchdog
// Disable watchdog, common to all SAM variants
WDT_Disable( WDT ) ;
#if defined sam3s_ek
// Set Main clock to 64MHz using external 12MHz
LowLevelInit() ;
LowLevelInit_sam3s_ek() ;
#else
# error "Board/Variant not defined"
#endif
// Set Systick to 1ms interval
SysTick_Config( BOARD_MCK/1000 ) ;
// Set Systick to 1ms interval, common to all SAM3 variants
SysTick_Config( VARIANT_MCK/1000 ) ;
// Initialize Serial port UART0
// Initialize Serial port UART0, common to all SAM3 variants
PIO_Configure( APinDescription[PINS_UART].pPort, APinDescription[PINS_UART].dwPinType,
APinDescription[PINS_UART].dwPin, APinDescription[PINS_UART].dwPinAttribute ) ;
}

View File

@@ -25,6 +25,7 @@
#ifndef WiringPrivate_h
#define WiringPrivate_h
#include <stdint.h>
#include <stdio.h>
#include <stdarg.h>