diff --git a/boards/arduino-due/Makefile b/boards/arduino-due/Makefile new file mode 100644 index 0000000000000000000000000000000000000000..64c99412f3706043de74408d8c809fb708e76de6 --- /dev/null +++ b/boards/arduino-due/Makefile @@ -0,0 +1,16 @@ + +# tell the Makefile.base which module to build +MODULE = $(BOARD)_base + +# add a list of board specific subdirectories that should also be build +DIRS = + +.PHONY: all clean + +all: $(BINDIR)$(MODULE).a + @for i in $(DIRS) ; do $(MAKE) -C $$i ; done ; + +include $(RIOTBASE)/Makefile.base + +clean:: + @for i in $(DIRS) ; do $(MAKE) -C $$i clean ; done ; diff --git a/boards/arduino-due/Makefile.include b/boards/arduino-due/Makefile.include new file mode 100644 index 0000000000000000000000000000000000000000..9596c37a02737ea19a0a0035ab2cc55d849fe658 --- /dev/null +++ b/boards/arduino-due/Makefile.include @@ -0,0 +1,48 @@ + +# define the cpu used by the arduino due board +export CPU = sam3x8e + +# define tools used for building the project +export PREFIX = arm-none-eabi- +export CC = $(PREFIX)gcc +export AR = $(PREFIX)ar +export AS = $(PREFIX)as +export LINK = $(PREFIX)gcc +export SIZE = $(PREFIX)size +export OBJCOPY = $(PREFIX)objcopy +export TERMPROG = $(RIOTBASE)/dist/tools/pyterm/pyterm.py + +#define the flash-tool and default port depending on the host operating system +OS = $(shell uname) +ifeq ($(OS),Linux) + PORT ?= /dev/ttyACM0 + FLASHER = stty -F $(PORT) raw ispeed 1200 ospeed 1200 cs8 -cstopb ignpar eol 255 eof 255; $(RIOTBOARD)/$(BOARD)/dist/bossac +else ifeq ($(OS),Darwin) + PORT ?= $(shell ls -1 /dev/tty.usbmodem* | head -n 1) + FLASHER = stty -f $(PORT) raw ispeed 1200 ospeed 1200 cs8 -cstopb ignpar eol 255 eof 255; $(RIOTBOARD)/$(BOARD)/dist/bossac_osx +else + $(info CAUTION: No flash tool for your host system found!) + # TODO: fix for building under windows +endif +export FLASHER +export PORT + +# define build specific options +export CPU_USAGE = -mcpu=cortex-m3 +export CFLAGS += -ggdb -g3 -std=gnu99 -Os -Wall -Wstrict-prototypes $(CPU_USAGE) -mlittle-endian -mthumb -mthumb-interwork -nostartfiles +export CFLAGS += -DREENTRANT_SYSCALLS_PROVIDED +export ASFLAGS += -ggdb -g3 -mcpu=cortex-m4 $(FPU_USAGE) -mlittle-endian +export LINKFLAGS += -g3 -ggdb -std=gnu99 $(CPU_USAGE) $(FPU_USAGE) -mlittle-endian -static -lgcc -mthumb -mthumb-interwork -nostartfiles +# linkerscript specified in cpu/Makefile.include +export LINKFLAGS += -T$(LINKERSCRIPT) +export OFLAGS += -O binary +export FFLAGS += -e -w -v -b bin/$(BOARD)/$(PROJECT).hex + +# additional compiler and linker flags to enable newlib-nano and optimize for it +# CAREFUL: newlib-nano is not supported by the ubuntu arm-none-eabi- toolchain, so its disabled by default +#export CFLAGS += -flto -ffunction-sections -fdata-sections -fno-builtin +#export LINKFLAGS += -specs=nano.specs -lc -lnosys + + +# export board specific includes to the global includes-listing +export INCLUDES += -I$(RIOTBOARD)/$(BOARD)/include diff --git a/boards/arduino-due/board.c b/boards/arduino-due/board.c new file mode 100644 index 0000000000000000000000000000000000000000..f3582b950a4880587cb847480b8f16741ac6b812 --- /dev/null +++ b/boards/arduino-due/board.c @@ -0,0 +1,64 @@ +/* + * Copyright (C) 2014 Freie Universität Berlin + * + * This file is subject to the terms and conditions of the GNU Lesser General + * Public License. See the file LICENSE in the top level directory for more + * details. + */ + +/** + * @ingroup board_arduino-due + * @{ + * + * @file board.c + * @brief Board specific implementations for the Arduino Due board + * + * @author Hauke Petersen <hauke.petersen@fu-berlin.de> + * + * @} + */ + +#include <stdio.h> + +#include "board.h" +#include "cpu.h" + + +void led_init(void); + + +void board_init(void) +{ + /* initialize core clocks via CMSIS function provided by Atmel */ + SystemInit(); + + /* initialize the CPU */ + cpu_init(); + + /* initialize the boards LEDs */ + led_init(); +} + + +/** + * @brief Initialize the boards on-board LED (Amber LED "L") + * + * The LED initialization is hard-coded in this function. As the LED is soldered + * onto the board it is fixed to its CPU pins. + * + * The LED is connected to the following pin: + * - LED: PB27 + */ +void led_init(void) +{ + /* enable PIO control of pin PD27 */ + LED_PORT->PIO_PER = LED_PIN; + /* set pin as output */ + LED_PORT->PIO_OER = LED_PIN; + /* enable direct write access to the LED pin */ + LED_PORT->PIO_OWER = LED_PIN; + /* disable pull-up */ + LED_PORT->PIO_PUDR = LED_PIN; + /* clear pin */ + LED_PORT->PIO_CODR = LED_PIN; +} diff --git a/boards/arduino-due/dist/bossac b/boards/arduino-due/dist/bossac new file mode 100755 index 0000000000000000000000000000000000000000..573e7d9e7716acf1d885f88da3f523cce67cb0da Binary files /dev/null and b/boards/arduino-due/dist/bossac differ diff --git a/boards/arduino-due/dist/bossac_osx b/boards/arduino-due/dist/bossac_osx new file mode 100755 index 0000000000000000000000000000000000000000..49a20b38a92e713bcc25b15de464642bc257220b Binary files /dev/null and b/boards/arduino-due/dist/bossac_osx differ diff --git a/boards/arduino-due/include/board.h b/boards/arduino-due/include/board.h new file mode 100644 index 0000000000000000000000000000000000000000..f30cce56620a38f1cf1c4a51b9b8df4337ffc64f --- /dev/null +++ b/boards/arduino-due/include/board.h @@ -0,0 +1,70 @@ +/* + * Copyright (C) 2014 Freie Universität Berlin + * + * This file is subject to the terms and conditions of the GNU Lesser General + * Public License. See the file LICENSE in the top level directory for more + * details. + */ + +/** + * @defgroup board_arduino-due Arduino Due + * @ingroup boards + * @brief Board specific files for the Arduino Due board. + * @{ + * + * @file board.h + * @brief Board specific definitions for the Arduino Due board. + * + * @author Hauke Petersen <hauke.petersen@fu-berlin.de> + */ + +#ifndef __BOARD_H +#define __BOARD_H + +#include "cpu.h" + +/** + * Define the nominal CPU core clock in this board + */ +#define F_CPU (84000000UL) + + +/** + * Assign the hardware timer + */ +#define HW_TIMER TIMER_0 + +/** + * @name LED pin definitions + * @{ + */ +#define LED_PORT PIOB +#define LED_PIN PIO_PB27 +/** @} */ + +/** + * @name Macros for controlling the on-board LEDs. + * @{ + */ +#define LED_ON LED_PORT->PIO_ODSR |= LED_PIN +#define LED_OFF LED_PORT->PIO_ODSR &= ~LED_PIN +#define LED_TOGGLE LED_PORT->PIO_ODSR ^= LED_PIN; + +/* for compatability to other boards */ +#define LED_GREEN_ON LED_ON +#define LED_GREEN_OFF LED_OFF +#define LED_GREEN_TOGGLE LED_TOGGLE +#define LED_RED_ON /* not available */ +#define LED_RED_OFF /* not available */ +#define LED_RED_TOGGLE /* not available */ +/** @} */ + + +/** + * @brief Initialize board specific hardware, including clock, LEDs and std-IO + */ +void board_init(void); + + +#endif /** __BOARD_H */ +/** @} */ diff --git a/boards/arduino-due/include/periph_conf.h b/boards/arduino-due/include/periph_conf.h new file mode 100644 index 0000000000000000000000000000000000000000..3e0022df3deb620580f31e2ed0ead68ed1225486 --- /dev/null +++ b/boards/arduino-due/include/periph_conf.h @@ -0,0 +1,337 @@ +/* + * Copyright (C) 2014 Freie Universität Berlin + * + * This file is subject to the terms and conditions of the GNU Lesser General + * Public License. See the file LICENSE in the top level directory for more + * details. + */ + +/** + * @ingroup board_arduino-due + * @{ + * + * @file periph_conf.h + * @brief Peripheral MCU configuration for the Arduino Due board + * + * @author Hauke Petersen <hauke.petersen@fu-berlin.de> + */ + +#ifndef __PERIPH_CONF_H +#define __PERIPH_CONF_H + + +/** + * @name Timer peripheral configuration + * @{ + */ +#define TIMER_NUMOF (3U) +#define TIMER_0_EN 1 +#define TIMER_1_EN 1 +#define TIMER_2_EN 1 + +/* Timer 0 configuration */ +#define TIMER_0_DEV TC0 +#define TIMER_0_CHANNELS 6 +#define TIMER_0_MAX_VALUE (0xffffffff) +#define TIMER_0_ISR1 isr_tc0 +#define TIMER_0_ISR2 isr_tc1 + +/* Timer 1 configuration */ +#define TIMER_1_DEV TC1 +#define TIMER_1_CHANNELS 6 +#define TIMER_1_MAX_VALUE (0xffffffff) +#define TIMER_1_ISR1 isr_tc3 +#define TIMER_1_ISR2 isr_tc4 + +/* Timer 2 configuration */ +#define TIMER_2_DEV TC2 +#define TIMER_2_CHANNELS 6 +#define TIMER_2_MAX_VALUE (0xffffffff) +#define TIMER_2_ISR1 isr_tc6 +#define TIMER_2_ISR2 isr_tc7 +/** @} */ + +/** + * @name UART configuration + * @{ + */ +#define UART_NUMOF (1U) +#define UART_0_EN 1 +#define UART_1_EN 0 +#define UART_2_EN 0 +#define UART_3_EN 0 +#define UART_IRQ_PRIO 1 + +/* UART 0 device configuration */ +#define UART_0_DEV UART +#define UART_0_IRQ UART_IRQn +#define UART_0_ISR isr_uart +/* UART 0 pin configuration */ +#define UART_0_PORT PIOA +#define UART_0_PINS (PIO_PA8 | PIO_PA9) +#define UART_0_PORT_CLKEN() RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOB, ENABLE) +#define UART_0_RX_AFCFG() (GPIO_PinAFConfig(UART_0_PORT, GPIO_PinSource6, GPIO_AF_0)) +#define UART_0_TX_AFCFG() (GPIO_PinAFConfig(UART_0_PORT, GPIO_PinSource7, GPIO_AF_0)) + +/* UART 1 device configuration */ +#define UART_1_DEV USART2 +#define UART_1_CLKEN() RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART2, ENABLE) +#define UART_1_IRQ USART2_IRQn +#define UART_1_ISR isr_usart2 +/* UART 1 pin configuration */ +#define UART_1_PORT GPIOA +#define UART_1_PINS (GPIO_Pin_2 | GPIO_Pin_3) +#define UART_1_PORT_CLKEN() RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOA, ENABLE) +#define UART_1_RX_AFCFG() GPIO_PinAFConfig(UART_1_PORT, GPIO_PinSource2, GPIO_AF_1) +#define UART_1_TX_AFCFG() GPIO_PinAFConfig(UART_1_PORT, GPIO_PinSource3, GPIO_AF_1) +/** @} */ + + +/** + * @brief ADC configuration + */ +#define ADC_NUMOF (0U) +#define ADC_0_EN 0 +#define ADC_1_EN 0 + +/* ADC 0 configuration */ +#define ADC_0_DEV ADC1 /* TODO */ +#define ADC_0_SAMPLE_TIMER +/* ADC 0 channel 0 pin config */ +#define ADC_0_C0_PORT +#define ADC_0_C0_PIN +#define ADC_0_C0_CLKEN() +#define ADC_0_C0_AFCFG() +/* ADC 0 channel 1 pin config */ +#define ADC_0_C1_PORT +#define ADC_0_C1_PIN +#define ADC_0_C1_CLKEN() +#define ADC_0_C1_AFCFG() +/* ADC 0 channel 2 pin config */ +#define ADC_0_C2_PORT +#define ADC_0_C2_PIN +#define ADC_0_C2_CLKEN() +#define ADC_0_C2_AFCFG() +/* ADC 0 channel 3 pin config */ +#define ADC_0_C3_PORT +#define ADC_0_C3_PIN +#define ADC_0_C3_CLKEN() +#define ADC_0_C3_AFCFG() + +/* ADC 0 configuration */ +#define ADC_1_DEV ADC2 /* TODO */ +#define ADC_1_SAMPLE_TIMER +/* ADC 0 channel 0 pin config */ +#define ADC_1_C0_PORT +#define ADC_1_C0_PIN +#define ADC_1_C0_CLKEN() +#define ADC_1_C0_AFCFG() +/* ADC 0 channel 1 pin config */ +#define ADC_1_C1_PORT +#define ADC_1_C1_PIN +#define ADC_1_C1_CLKEN() +#define ADC_1_C1_AFCFG() +/* ADC 0 channel 2 pin config */ +#define ADC_1_C2_PORT +#define ADC_1_C2_PIN +#define ADC_1_C2_CLKEN() +#define ADC_1_C2_AFCFG() +/* ADC 0 channel 3 pin config */ +#define ADC_1_C3_PORT +#define ADC_1_C3_PIN +#define ADC_1_C3_CLKEN() +#define ADC_1_C3_AFCFG() + + +/** + * @brief PWM configuration + */ +#define PWM_NUMOF (0U) /* TODO */ +#define PWM_0_EN 0 +#define PWM_1_EN 0 + +/* PWM 0 device configuration */ +#define PWM_0_DEV TIM1 +#define PWM_0_CHANNELS 4 +/* PWM 0 pin configuration */ +#define PWM_0_PORT +#define PWM_0_PINS +#define PWM_0_PORT_CLKEN() +#define PWM_0_CH1_AFCFG() +#define PWM_0_CH2_AFCFG() +#define PWM_0_CH3_AFCFG() +#define PWM_0_CH4_AFCFG() + +/* PWM 1 device configuration */ +#define PWM_1_DEV TIM3 +#define PWM_1_CHANNELS 4 +/* PWM 1 pin configuration */ +#define PWM_1_PORT +#define PWM_1_PINS +#define PWM_1_PORT_CLKEN() +#define PWM_1_CH1_AFCFG() +#define PWM_1_CH2_AFCFG() +#define PWM_1_CH3_AFCFG() +#define PWM_1_CH4_AFCFG() + + + +/** + * @brief SPI configuration + */ +#define SPI_NUMOF (0U) /* TODO */ +#define SPI_0_EN 0 +#define SPI_1_EN 0 + +/* SPI 0 device config */ +#define SPI_0_DEV SPI1 +#define SPI_0_CLKEN() +#define SPI_0_IRQ SPI1_IRQn +#define SPI_0_IRQ_HANDLER +#define SPI_0_IRQ_PRIO 1 +/* SPI 1 pin configuration */ +#define SPI_0_PORT +#define SPI_0_PINS () +#define SPI_1_PORT_CLKEN() +#define SPI_1_SCK_AFCFG() +#define SPI_1_MISO_AFCFG() +#define SPI_1_MOSI_AFCFG() + +/* SPI 1 device config */ +#define SPI_1_DEV SPI2 +#define SPI_1_CLKEN() +#define SPI_1_IRQ SPI2_IRQn +#define SPI_1_IRQ_HANDLER +#define SPI_1_IRQ_PRIO 1 +/* SPI 1 pin configuration */ +#define SPI_1_PORT +#define SPI_1_PINS () +#define SPI_1_PORT_CLKEN() +#define SPI_1_SCK_AFCFG() +#define SPI_1_MISO_AFCFG() +#define SPI_1_MOSI_AFCFG() + + +/** + * @brief I2C configuration + */ +#define I2C_NUMOF (0U) /* TODO */ +#define I2C_0_EN 0 +#define I2C_0_EN 0 + +/* SPI 0 device configuration */ +#define I2C_0_DEV I2C1 +#define I2C_0_CLKEN() +#define I2C_0_ISR isr_i2c1 +#define I2C_0_IRQ I2C1_IRQn +#define I2C_0_IRQ_PRIO 1 +/* SPI 0 pin configuration */ +#define I2C_0_PORT GPIOB +#define I2C_0_PINS (GPIO_Pin_6 | GPIO_Pin_7) +#define I2C_0_PORT_CLKEN() +#define I2C_0_SCL_AFCFG() +#define I2C_0_SDA_AFCFG() + +/* SPI 1 device configuration */ +#define I2C_1_DEV I2C2 +#define I2C_1_CLKEN() +#define I2C_1_ISR isr_i2c2 +#define I2C_1_IRQ I2C2_IRQn +#define I2C_1_IRQ_PRIO 1 +/* SPI 1 pin configuration */ +#define I2C_1_PORT GPIOF +#define I2C_1_PINS (GPIO_Pin_0 | GPIO_Pin_1) +#define I2C_1_PORT_CLKEN() +#define I2C_1_SCL_AFCFG() +#define I2C_1_SDA_AFCFG() + + +/** + * @brief GPIO configuration + */ +#define GPIO_NUMOF (15U) +#define GPIO_0_EN 1 +#define GPIO_1_EN 1 +#define GPIO_2_EN 1 +#define GPIO_3_EN 1 +#define GPIO_4_EN 1 +#define GPIO_5_EN 1 +#define GPIO_6_EN 1 +#define GPIO_7_EN 1 +#define GPIO_8_EN 1 +#define GPIO_9_EN 1 +#define GPIO_10_EN 1 +#define GPIO_11_EN 1 +#define GPIO_12_EN 1 +#define GPIO_13_EN 1 +#define GPIO_14_EN 1 +#define GPIO_15_EN 1 + +/* IRQ config */ +/* #define GPIO_IRQ_0 GPIO_0 */ +/* #define GPIO_IRQ_1 GPIO_1 */ +/* #define GPIO_IRQ_2 // not configured */ +/* #define GPIO_IRQ_3 // not configured */ +/* #define GPIO_IRQ_4 GPIO_2 */ +/* #define GPIO_IRQ_5 GPIO_3 */ +/* #define GPIO_IRQ_6 GPIO_4 */ +/* #define GPIO_IRQ_7 GPIO_5 */ +/* #define GPIO_IRQ_8 // not configured */ +/* #define GPIO_IRQ_9 // not configured */ +/* #define GPIO_IRQ_10 GPIO_6 */ +/* #define GPIO_IRQ_11 GPIO_7 */ +/* #define GPIO_IRQ_12 GPIO_8 */ +/* #define GPIO_IRQ_13 GPIO_9 */ +/* #define GPIO_IRQ_14 GPIO_10 */ +/* #define GPIO_IRQ_15 GPIO_11 */ + +/* GPIO channel 0 config */ +#define GPIO_0_DEV PIOA +#define GPIO_0_PIN PIO_PA14 +/* GPIO channel 1 config */ +#define GPIO_1_DEV PIOD +#define GPIO_1_PIN PIO_PD0 +/* GPIO channel 2 config */ +#define GPIO_2_DEV PIOD +#define GPIO_2_PIN PIO_PD2 +/* GPIO channel 3 config */ +#define GPIO_3_DEV PIOD +#define GPIO_3_PIN PIO_PD6 +/* GPIO channel 4 config */ +#define GPIO_4_DEV PIOA +#define GPIO_4_PIN PIO_PA7 +/* GPIO channel 5 config */ +#define GPIO_5_DEV PIOC +#define GPIO_5_PIN PIO_PC1 +/* GPIO channel 6 config */ +#define GPIO_6_DEV PIOC +#define GPIO_6_PIN PIO_PC3 +/* GPIO channel 7 config */ +#define GPIO_7_DEV PIOC +#define GPIO_7_PIN PIO_PC5 +/* GPIO channel 8 config */ +#define GPIO_8_DEV PIOC +#define GPIO_8_PIN PIO_PC7 +/* GPIO channel 9 config */ +#define GPIO_9_DEV PIOC +#define GPIO_9_PIN PIO_PC9 +/* GPIO channel 10 config */ +#define GPIO_10_DEV PIOA +#define GPIO_10_PIN PIO_PA20 +/* GPIO channel 11 config */ +#define GPIO_11_DEV PIOC +#define GPIO_11_PIN PIO_PC18 +/* GPIO channel 12 config */ +#define GPIO_12_DEV PIOC +#define GPIO_12_PIN PIO_PC16 +/* GPIO channel 13 config */ +#define GPIO_13_DEV PIOC +#define GPIO_13_PIN PIO_PC14 +/* GPIO channel 14 config */ +#define GPIO_14_DEV PIOC +#define GPIO_14_PIN PIO_PC12 +/* GPIO channel 15 config */ +#define GPIO_15_DEV PIOB +#define GPIO_15_PIN PIO_PB14 + +#endif /* __PERIPH_CONF_H */ diff --git a/boards/arduino-due/system_sam3xa.c b/boards/arduino-due/system_sam3xa.c new file mode 100644 index 0000000000000000000000000000000000000000..9f2e6c5b32a570415c73c5cac7ad823275037242 --- /dev/null +++ b/boards/arduino-due/system_sam3xa.c @@ -0,0 +1,215 @@ +/*! \file ********************************************************************* + * + * \brief Provides the low-level initialization functions that called + * on chip startup. + * + * Copyright (c) 2012, Atmel Corporation + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following condition is 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. + * + * \asf_license_stop + * + * \par Purpose + * + * This file provides basic support for Cortex-M processor based + * microcontrollers. + * + * \author Atmel Corporation: http://www.atmel.com \n + * Support and FAQ: http://support.atmel.no/ + * + ******************************************************************************/ + +#include "sam3x8e.h" + +/* @cond 0 */ +/**INDENT-OFF**/ +#ifdef __cplusplus +extern "C" { +#endif +/**INDENT-ON**/ +/* @endcond */ + +/* Clock settings (84MHz) */ +#define SYS_BOARD_OSCOUNT (CKGR_MOR_MOSCXTST(0x8)) +#define SYS_BOARD_PLLAR (CKGR_PLLAR_ONE \ + | CKGR_PLLAR_MULA(0xdUL) \ + | CKGR_PLLAR_PLLACOUNT(0x3fUL) \ + | CKGR_PLLAR_DIVA(0x1UL)) +#define SYS_BOARD_MCKR (PMC_MCKR_PRES_CLK_2 | PMC_MCKR_CSS_PLLA_CLK) + +/* Clock Definitions */ +#define SYS_UTMIPLL (480000000UL) /* UTMI PLL frequency */ + +#define SYS_CKGR_MOR_KEY_VALUE CKGR_MOR_KEY(0x37) /* Key to unlock MOR register */ + +/* FIXME: should be generated by sock */ +uint32_t SystemCoreClock = CHIP_FREQ_MAINCK_RC_4MHZ; + +/** + * \brief Setup the microcontroller system. + * Initialize the System and update the SystemFrequency variable. + */ +void SystemInit(void) +{ + /* Set FWS according to SYS_BOARD_MCKR configuration */ + EFC0->EEFC_FMR = EEFC_FMR_FWS(4); + EFC1->EEFC_FMR = EEFC_FMR_FWS(4); + + /* Initialize main oscillator */ + if (!(PMC->CKGR_MOR & CKGR_MOR_MOSCSEL)) { + PMC->CKGR_MOR = SYS_CKGR_MOR_KEY_VALUE | SYS_BOARD_OSCOUNT | + CKGR_MOR_MOSCRCEN | CKGR_MOR_MOSCXTEN; + while (!(PMC->PMC_SR & PMC_SR_MOSCXTS)) { + } + } + + /* Switch to 3-20MHz Xtal oscillator */ + PMC->CKGR_MOR = SYS_CKGR_MOR_KEY_VALUE | SYS_BOARD_OSCOUNT | + CKGR_MOR_MOSCRCEN | CKGR_MOR_MOSCXTEN | CKGR_MOR_MOSCSEL; + + while (!(PMC->PMC_SR & PMC_SR_MOSCSELS)) { + } + PMC->PMC_MCKR = (PMC->PMC_MCKR & ~(uint32_t)PMC_MCKR_CSS_Msk) | + PMC_MCKR_CSS_MAIN_CLK; + while (!(PMC->PMC_SR & PMC_SR_MCKRDY)) { + } + + /* Initialize PLLA */ + PMC->CKGR_PLLAR = SYS_BOARD_PLLAR; + while (!(PMC->PMC_SR & PMC_SR_LOCKA)) { + } + + /* Switch to main clock */ + PMC->PMC_MCKR = (SYS_BOARD_MCKR & ~PMC_MCKR_CSS_Msk) | PMC_MCKR_CSS_MAIN_CLK; + while (!(PMC->PMC_SR & PMC_SR_MCKRDY)) { + } + + /* Switch to PLLA */ + PMC->PMC_MCKR = SYS_BOARD_MCKR; + while (!(PMC->PMC_SR & PMC_SR_MCKRDY)) { + } + + SystemCoreClock = CHIP_FREQ_CPU_MAX; +} + +void SystemCoreClockUpdate(void) +{ + /* Determine clock frequency according to clock register values */ + switch (PMC->PMC_MCKR & PMC_MCKR_CSS_Msk) { + case PMC_MCKR_CSS_SLOW_CLK: /* Slow clock */ + if (SUPC->SUPC_SR & SUPC_SR_OSCSEL) { + SystemCoreClock = CHIP_FREQ_XTAL_32K; + } else { + SystemCoreClock = CHIP_FREQ_SLCK_RC; + } + break; + case PMC_MCKR_CSS_MAIN_CLK: /* Main clock */ + if (PMC->CKGR_MOR & CKGR_MOR_MOSCSEL) { + SystemCoreClock = CHIP_FREQ_XTAL_12M; + } else { + SystemCoreClock = CHIP_FREQ_MAINCK_RC_4MHZ; + + switch (PMC->CKGR_MOR & CKGR_MOR_MOSCRCF_Msk) { + case CKGR_MOR_MOSCRCF_4_MHz: + break; + case CKGR_MOR_MOSCRCF_8_MHz: + SystemCoreClock *= 2U; + break; + case CKGR_MOR_MOSCRCF_12_MHz: + SystemCoreClock *= 3U; + break; + default: + break; + } + } + break; + case PMC_MCKR_CSS_PLLA_CLK: /* PLLA clock */ + case PMC_MCKR_CSS_UPLL_CLK: /* UPLL clock */ + if (PMC->CKGR_MOR & CKGR_MOR_MOSCSEL) { + SystemCoreClock = CHIP_FREQ_XTAL_12M; + } else { + SystemCoreClock = CHIP_FREQ_MAINCK_RC_4MHZ; + + switch (PMC->CKGR_MOR & CKGR_MOR_MOSCRCF_Msk) { + case CKGR_MOR_MOSCRCF_4_MHz: + break; + case CKGR_MOR_MOSCRCF_8_MHz: + SystemCoreClock *= 2U; + break; + case CKGR_MOR_MOSCRCF_12_MHz: + SystemCoreClock *= 3U; + break; + default: + break; + } + } + if ((PMC->PMC_MCKR & PMC_MCKR_CSS_Msk) == PMC_MCKR_CSS_PLLA_CLK) { + SystemCoreClock *= ((((PMC->CKGR_PLLAR) & CKGR_PLLAR_MULA_Msk) >> + CKGR_PLLAR_MULA_Pos) + 1U); + SystemCoreClock /= ((((PMC->CKGR_PLLAR) & CKGR_PLLAR_DIVA_Msk) >> + CKGR_PLLAR_DIVA_Pos)); + } else { + SystemCoreClock = SYS_UTMIPLL / 2U; + } + break; + } + + if ((PMC->PMC_MCKR & PMC_MCKR_PRES_Msk) == PMC_MCKR_PRES_CLK_3) { + SystemCoreClock /= 3U; + } else { + SystemCoreClock >>= ((PMC->PMC_MCKR & PMC_MCKR_PRES_Msk) >> + PMC_MCKR_PRES_Pos); + } +} + +/** + * Initialize flash. + */ +void system_init_flash(uint32_t dw_clk) +{ + /* Set FWS for embedded Flash access according to operating frequency */ + if (dw_clk < CHIP_FREQ_FWS_0) { + EFC0->EEFC_FMR = EEFC_FMR_FWS(0); + EFC1->EEFC_FMR = EEFC_FMR_FWS(0); + } else if (dw_clk < CHIP_FREQ_FWS_1) { + EFC0->EEFC_FMR = EEFC_FMR_FWS(1); + EFC1->EEFC_FMR = EEFC_FMR_FWS(1); + } else if (dw_clk < CHIP_FREQ_FWS_2) { + EFC0->EEFC_FMR = EEFC_FMR_FWS(2); + EFC1->EEFC_FMR = EEFC_FMR_FWS(2); + } else if (dw_clk < CHIP_FREQ_FWS_3) { + EFC0->EEFC_FMR = EEFC_FMR_FWS(3); + EFC1->EEFC_FMR = EEFC_FMR_FWS(3); + } else { + EFC0->EEFC_FMR = EEFC_FMR_FWS(4); + EFC1->EEFC_FMR = EEFC_FMR_FWS(4); + } +} + +/* @cond 0 */ +/**INDENT-OFF**/ +#ifdef __cplusplus +} +#endif +/**INDENT-ON**/ +/* @endcond */ diff --git a/cpu/sam3x8e/include/system_sam3xa.h b/cpu/sam3x8e/include/system_sam3xa.h index d79a9867d28b10a1f4942dbf4de6cb6fa93e46ab..89dad6eecbf665b2ec2dc750499782682d135462 100644 --- a/cpu/sam3x8e/include/system_sam3xa.h +++ b/cpu/sam3x8e/include/system_sam3xa.h @@ -3,41 +3,29 @@ * \brief CMSIS Cortex-M# Device Peripheral Access Layer Header File * for SAM3 devices. * - * Copyright (c) 2013-2014 Atmel Corporation. All rights reserved. + * Copyright (c) 2012, Atmel Corporation * - * \asf_license_start - * - * \page License + * All rights reserved. * * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. + * modification, are permitted provided that the following condition is met: * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. + * - Redistributions of source code must retain the above copyright notice, + * this list of conditions and the disclaimer below. * - * 3. The name of Atmel may not be used to endorse or promote products derived - * from this software without specific prior written permission. + * Atmel's name may not be used to endorse or promote products derived from + * this software without specific prior written permission. * - * 4. This software may only be redistributed and used in connection with an - * Atmel microcontroller product. - * - * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED - * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * 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 - * EXPRESSLY AND SPECIFICALLY 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_stop + * 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. * * \par Purpose *