diff --git a/bootloaders/zero/Makefile b/bootloaders/zero/Makefile index d8fb2f349..13de72f2d 100644 --- a/bootloaders/zero/Makefile +++ b/bootloaders/zero/Makefile @@ -1,29 +1,174 @@ -IDE_PATH="../../../../.." -ARM_GCC_PATH=$(IDE_PATH)/hardware/tools/gcc-arm-none-eabi-4.8.3-2014q1/bin -CC=$(ARM_GCC_PATH)/arm-none-eabi-gcc -CFLAGS=-mthumb -mcpu=cortex-m0plus -Wall -c -g -Os -w -std=gnu99 -ffunction-sections -fdata-sections -nostdlib --param max-inline-insns-single=500 -LDFLAGS=-mthumb -mcpu=cortex-m0plus -Wall -Wl,--cref -Wl,--check-sections -Wl,--gc-sections -Wl,--unresolved-symbols=report-all -Wl,--warn-common -Wl,--warn-section-align -Wl,--warn-unresolved-symbols -BLD_EXTA_FLAGS=-D__SAMD21G18A__ +# Copyright (c) 2015 Atmel Corporation/Thibaut VIARD. All right reserved. +# Copyright (c) 2015 Arduino LLC. All right reserved. +# +# This library is free software; you can redistribute it and/or +# modify it under the terms of the GNU Lesser General Public +# License as published by the Free Software Foundation; either +# version 2.1 of the License, or (at your option) any later version. +# +# This library is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. +# See the GNU Lesser General Public License for more details. +# +# You should have received a copy of the GNU Lesser General Public +# License along with this library; if not, write to the Free Software +# Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA + +# ----------------------------------------------------------------------------- +# Paths +ifeq ($(OS),Windows_NT) + + # Are we using mingw/msys/msys2/cygwin? + ifeq ($(TERM),xterm) +# this is the path coming with night build +# T=$(shell cygpath -u $(LOCALAPPDATA)) +# this is the path till 1.6.5 r5 + T=$(shell cygpath -u $(APPDATA)) + MODULE_PATH?=$(T)/Arduino15/packages/arduino + ARM_GCC_PATH?=$(MODULE_PATH)/tools/arm-none-eabi-gcc/4.8.3-2014q1/bin/arm-none-eabi- + RM=rm + SEP=/ + else +# this is the path coming with night build +# MODULE_PATH?=$(LOCALAPPDATA)/Arduino15/packages/arduino +# this is the path till 1.6.5 r5 + MODULE_PATH?=$(APPDATA)/Arduino15/packages/arduino + ARM_GCC_PATH?=$(MODULE_PATH)/tools/arm-none-eabi-gcc/4.8.3-2014q1/bin/arm-none-eabi- + RM=rm + SEP=\\ + endif +else + UNAME_S := $(shell uname -s) + + ifeq ($(UNAME_S),Linux) + MODULE_PATH?=$HOME/.arduino15/packages/arduino + ARM_GCC_PATH?=$(MODULE_PATH)/tools/arm-none-eabi-gcc/4.8.3-2014q1/bin/arm-none-eabi- + RM=rm + SEP=/ + endif + + ifeq ($(UNAME_S),Darwin) + MODULE_PATH?=$HOME/Library/Arduino15/packages/arduino/ + ARM_GCC_PATH?=$(MODULE_PATH)/tools/arm-none-eabi-gcc/4.8.3-2014q1/bin/arm-none-eabi- + RM=rm + SEP=/ + endif +endif + BUILD_PATH=build -INCLUDES=-I$(IDE_PATH)/hardware/tools/CMSIS/CMSIS/Include/ -I$(IDE_PATH)/hardware/tools/CMSIS/Device/ATMEL/ -I./drivers/ -I./utils/ -I./utils/preprocessor/ -I./utils/interrupt -SOURCES=main.c sam_ba_monitor.c startup_samd21.c usart_sam_ba.c drivers/cdc_enumerate.c drivers/uart_driver.c utils/interrupt/interrupt_sam_nvic.c + +# ----------------------------------------------------------------------------- +# Tools +CC=$(ARM_GCC_PATH)gcc +OBJCOPY=$(ARM_GCC_PATH)objcopy +NM=$(ARM_GCC_PATH)nm +SIZE=$(ARM_GCC_PATH)size + +# ----------------------------------------------------------------------------- +# Compiler options +CFLAGS=-mthumb -mcpu=cortex-m0plus -Wall -c -std=gnu99 -ffunction-sections -fdata-sections -nostdlib -nostartfiles --param max-inline-insns-single=500 +ifdef DEBUG +CFLAGS+=-g3 -O1 -DDEBUG=1 +else +CFLAGS+=-Os -DDEBUG=0 +endif +CFLAGS_EXTRA?=-D__SAMD21G18A__ -DUSB_PID_LOW=0x4D -DUSB_PID_HIGH=0x00 +INCLUDES=-I"$(MODULE_PATH)/tools/CMSIS/4.0.0-atmel/CMSIS/Include/" -I"$(MODULE_PATH)/tools/CMSIS/4.0.0-atmel/Device/ATMEL/" + +# ----------------------------------------------------------------------------- +# Linker options +LDFLAGS=-mthumb -mcpu=cortex-m0plus -Wall -Wl,--cref -Wl,--check-sections -Wl,--gc-sections -Wl,--unresolved-symbols=report-all +LDFLAGS+=-Wl,--warn-common -Wl,--warn-section-align -Wl,--warn-unresolved-symbols --specs=nano.specs --specs=nosys.specs + +# ----------------------------------------------------------------------------- +# Source files and objects +SOURCES= \ +board_driver_led.c \ +board_driver_serial.c \ +board_driver_usb.c \ +board_init.c \ +board_startup.c \ +main.c \ +sam_ba_usb.c \ +sam_ba_cdc.c \ +sam_ba_monitor.c \ +sam_ba_serial.c + OBJECTS=$(addprefix $(BUILD_PATH)/, $(SOURCES:.c=.o)) +DEPS=$(addprefix $(BUILD_PATH)/, $(SOURCES:.c=.d)) NAME=samd21_sam_ba -EXECUTABLE=$(NAME).bin +ELF=$(NAME).elf +BIN=$(NAME).bin +HEX=$(NAME).hex -SLASH=/ -BSLASH=$(EMPTY)\$(EMPTY) +ifneq "test$(AVRSTUDIO_EXE_PATH)" "test" +AS_BUILD=copy_for_atmel_studio +AS_CLEAN=clean_for_atmel_studio +else +AS_BUILD= +AS_CLEAN= +endif -all: $(SOURCES) $(EXECUTABLE) - -$(EXECUTABLE): $(OBJECTS) - $(CC) -L$(BUILD_PATH) $(LDFLAGS) -Os -Wl,--gc-sections -save-temps -Tsamd21j18a_flash.ld -Wl,-Map,$(BUILD_PATH)/$(NAME).map --specs=nano.specs --specs=nosys.specs -o $(BUILD_PATH)/$(NAME).elf $(OBJECTS) -Wl,--start-group -lm -Wl,--end-group - $(ARM_GCC_PATH)/arm-none-eabi-objcopy -O binary $(BUILD_PATH)/$(NAME).elf $@ + +all: print_info $(SOURCES) $(BIN) $(HEX) $(AS_BUILD) + +$(ELF): Makefile $(BUILD_PATH) $(OBJECTS) + @echo ---------------------------------------------------------- + @echo Creating ELF binary + "$(CC)" -L. -L$(BUILD_PATH) $(LDFLAGS) -Os -Wl,--gc-sections -save-temps -Tbootloader_samd21x18.ld -Wl,-Map,"$(BUILD_PATH)/$(NAME).map" -o "$(BUILD_PATH)/$(ELF)" -Wl,--start-group $(OBJECTS) -lm -Wl,--end-group + "$(NM)" "$(BUILD_PATH)/$(ELF)" >"$(BUILD_PATH)/$(NAME)_symbols.txt" + "$(SIZE)" --format=sysv -t -x $(BUILD_PATH)/$(ELF) + +$(BIN): $(ELF) + @echo ---------------------------------------------------------- + @echo Creating flash binary + "$(OBJCOPY)" -O binary $(BUILD_PATH)/$< $@ + +$(HEX): $(ELF) + @echo ---------------------------------------------------------- + @echo Creating flash binary + "$(OBJCOPY)" -O ihex $(BUILD_PATH)/$< $@ $(BUILD_PATH)/%.o: %.c - -@mkdir -p $(@D) - $(CC) $(CFLAGS) $(BLD_EXTA_FLAGS) $(INCLUDES) $< -o $@ - -clean: - del $(EXECUTABLE) $(subst /,\,$(OBJECTS)) $(subst /,\,$(BUILD_PATH)/$(NAME).*) + @echo ---------------------------------------------------------- + @echo Compiling $< to $@ + "$(CC)" $(CFLAGS) $(CFLAGS_EXTRA) $(INCLUDES) $< -o $@ + @echo ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ + +$(BUILD_PATH): + @echo ---------------------------------------------------------- + @echo Creating build folder + -mkdir $(BUILD_PATH) + +print_info: + @echo ---------------------------------------------------------- + @echo Compiling bootloader using + @echo BASE PATH = $(MODULE_PATH) + @echo GCC PATH = $(ARM_GCC_PATH) +# @echo OS = $(OS) +# @echo SHELL = $(SHELL) +# @echo TERM = $(TERM) +# "$(CC)" -v +# env + +copy_for_atmel_studio: $(BIN) $(HEX) + @echo ---------------------------------------------------------- + @echo Atmel Studio detected, copying ELF to project root for debug + cp $(BUILD_PATH)/$(ELF) . + +clean_for_atmel_studio: + @echo ---------------------------------------------------------- + @echo Atmel Studio detected, cleaning ELF from project root + -$(RM) ./$(ELF) + +clean: $(AS_CLEAN) + @echo ---------------------------------------------------------- + @echo Cleaning project + -$(RM) $(BIN) + -$(RM) $(HEX) + -$(RM) $(BUILD_PATH)/*.* + -rmdir $(BUILD_PATH) + +.phony: print_info $(BUILD_PATH) diff --git a/bootloaders/zero/README.md b/bootloaders/zero/README.md new file mode 100644 index 000000000..44f4e4e02 --- /dev/null +++ b/bootloaders/zero/README.md @@ -0,0 +1,75 @@ +# Arduino Zero Bootloader + +## 1- Prerequisites + +The project build is based on Makefile system. +Makefile is present at project root and try to handle multi-platform cases. + +Multi-plaform GCC is provided by ARM here: https://launchpad.net/gcc-arm-embedded/+download + +Atmel Studio contains both make and ARM GCC toolchain. You don't need to install them in this specific use case. + +### Windows + +* Native command line +Make binary can be obtained here: http://gnuwin32.sourceforge.net/packages/make.htm + +* Cygwin/MSys/MSys2/Babun/etc... +It is available natively in all distributions. + +* Atmel Studio +An Atmel Studio **7** Makefile-based project is present at project root, just open samd21_sam_ba.atsln file in AS7. + +### Linux + +Make is usually available by default. + +### OS X + +Make is available through XCode package. + + +## 2- Selecting available SAM-BA interfaces + +By default both USB and UART are made available, but this parameter can be modified in sam_ba_monitor.h, line 31: + +Set the define SAM_BA_INTERFACE to +* SAM_BA_UART_ONLY for only UART interface +* SAM_BA_USBCDC_ONLY for only USB CDC interface +* SAM_BA_BOTH_INTERFACES for enabling both the interfaces + +## 3- Behaviour + +This bootloader implements the double-tap on Reset button. +By quickly pressing this button two times, the board will reset and stay in bootloader, waiting for communication on either USB or USART. + +The USB port in use is the USB Native port, close to the Reset button. +The USART in use is the one available on pins D0/D1, labelled respectively RX/TX. Communication parameters are a baudrate at 115200, 8bits of data, no parity and 1 stop bit (8N1). + +## 4- Description + +**Pinmap** + +The following pins are used by the program : +PA25 : input/output (USB DP) +PA24 : input/output (USB DM) +PA11 : input (USART RX) +PA10 : output (USART TX) + +The application board shall avoid driving the PA25, PA24, PB23 and PB22 signals while the boot program is running (after a POR for example). + +**Clock system** + +CPU runs at 48MHz from Generic Clock Generator 0 on DFLL48M. + +Generic Clock Generator 1 is using external 32kHz oscillator and is the source of DFLL48M. + +USB and USART are using Generic Clock Generator 0 also. + +**Memory Mapping** + +Bootloader code will be located at 0x0 and executed before any applicative code. + +Applications compiled to be executed along with the bootloader will start at 0x2000 (see linker script bootloader_samd21x18.ld). + +Before jumping to the application, the bootloader changes the VTOR register to use the interrupt vectors of the application @0x2000.<- not required as application code is taking care of this. diff --git a/bootloaders/zero/board_definitions.h b/bootloaders/zero/board_definitions.h new file mode 100644 index 000000000..458e1b0a7 --- /dev/null +++ b/bootloaders/zero/board_definitions.h @@ -0,0 +1,72 @@ +/* + Copyright (c) 2015 Arduino LLC. All right reserved. + Copyright (c) 2015 Atmel Corporation/Thibaut VIARD. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _BOARD_DEFINITIONS_H_ +#define _BOARD_DEFINITIONS_H_ + +/* + * If BOOT_DOUBLE_TAP_ADDRESS is defined the bootloader is started by + * quickly tapping two times on the reset button. + * BOOT_DOUBLE_TAP_ADDRESS must point to a free SRAM cell that must not + * be touched from the loaded application. + */ +#define BOOT_DOUBLE_TAP_ADDRESS (0x20007FFCul) +#define BOOT_DOUBLE_TAP_DATA (*((volatile uint32_t *) BOOT_DOUBLE_TAP_ADDRESS)) + +/* + * If BOOT_LOAD_PIN is defined the bootloader is started if the selected + * pin is tied LOW. + */ +//#define BOOT_LOAD_PIN PIN_PA21 // Pin 7 +//#define BOOT_LOAD_PIN PIN_PA15 // Pin 5 +#define BOOT_PIN_MASK (1U << (BOOT_LOAD_PIN & 0x1f)) + +#define CPU_FREQUENCY (48000000ul) + +#define BOOT_USART_MODULE SERCOM0 +#define BOOT_USART_BUS_CLOCK_INDEX PM_APBCMASK_SERCOM0 +#define BOOT_USART_PER_CLOCK_INDEX GCLK_ID_SERCOM0_CORE +#define BOOT_USART_PAD_SETTINGS UART_RX_PAD3_TX_PAD2 +#define BOOT_USART_PAD3 PINMUX_PA11C_SERCOM0_PAD3 +#define BOOT_USART_PAD2 PINMUX_PA10C_SERCOM0_PAD2 +#define BOOT_USART_PAD1 PINMUX_UNUSED +#define BOOT_USART_PAD0 PINMUX_UNUSED + +/* Frequency of the board main oscillator */ +#define VARIANT_MAINOSC (32768ul) + +/* Master clock frequency */ +#define VARIANT_MCK CPU_FREQUENCY + +#define NVM_SW_CALIB_DFLL48M_COARSE_VAL (58) +#define NVM_SW_CALIB_DFLL48M_FINE_VAL (64) + +/* + * LEDs definitions + */ +#define BOARD_LED_PORT (0) +#define BOARD_LED_PIN (17) + +#define BOARD_LEDRX_PORT (1) +#define BOARD_LEDRX_PIN (3) + +#define BOARD_LEDTX_PORT (0) +#define BOARD_LEDTX_PIN (27) + +#endif // _BOARD_DEFINITIONS_H_ diff --git a/bootloaders/zero/board_driver_led.c b/bootloaders/zero/board_driver_led.c new file mode 100644 index 000000000..1a2430aff --- /dev/null +++ b/bootloaders/zero/board_driver_led.c @@ -0,0 +1,22 @@ +/* + Copyright (c) 2015 Arduino LLC. All right reserved. + Copyright (c) 2015 Atmel Corporation/Thibaut VIARD. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include "board_driver_led.h" + + diff --git a/bootloaders/zero/board_driver_led.h b/bootloaders/zero/board_driver_led.h new file mode 100644 index 000000000..6f1fd7580 --- /dev/null +++ b/bootloaders/zero/board_driver_led.h @@ -0,0 +1,41 @@ +/* + Copyright (c) 2015 Arduino LLC. All right reserved. + Copyright (c) 2015 Atmel Corporation/Thibaut VIARD. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _BOARD_DRIVER_LED_ +#define _BOARD_DRIVER_LED_ + +#include +#include "board_definitions.h" + +inline void LED_init(void) { PORT->Group[BOARD_LED_PORT].DIRSET.reg = (1<Group[BOARD_LED_PORT].OUTSET.reg = (1<Group[BOARD_LED_PORT].OUTCLR.reg = (1<Group[BOARD_LED_PORT].OUTTGL.reg = (1<Group[BOARD_LEDRX_PORT].DIRSET.reg = (1<Group[BOARD_LEDRX_PORT].OUTSET.reg = (1<Group[BOARD_LEDRX_PORT].OUTCLR.reg = (1<Group[BOARD_LEDRX_PORT].OUTTGL.reg = (1<Group[BOARD_LEDTX_PORT].DIRSET.reg = (1<Group[BOARD_LEDTX_PORT].OUTSET.reg = (1<Group[BOARD_LEDTX_PORT].OUTCLR.reg = (1<Group[BOARD_LEDTX_PORT].OUTTGL.reg = (1<USART.DATA.reg; } while (length--); -} \ No newline at end of file +} diff --git a/bootloaders/zero/drivers/uart_driver.h b/bootloaders/zero/board_driver_serial.h similarity index 51% rename from bootloaders/zero/drivers/uart_driver.h rename to bootloaders/zero/board_driver_serial.h index 84bfe1b1a..c752d977d 100644 --- a/bootloaders/zero/drivers/uart_driver.h +++ b/bootloaders/zero/board_driver_serial.h @@ -1,37 +1,28 @@ -/* ---------------------------------------------------------------------------- - * SAM Software Package License - * ---------------------------------------------------------------------------- - * Copyright (c) 2011-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. - * ---------------------------------------------------------------------------- - */ +/* + Copyright (c) 2015 Arduino LLC. All right reserved. + Copyright (c) 2015 Atmel Corporation/Thibaut VIARD. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ #ifndef UART_DRIVER_H #define UART_DRIVER_H + #include -#include "sam.h" #include +#include #define PINMUX_UNUSED 0xFFFFFFFF #define GCLK_ID_SERCOM0_CORE 0x14 @@ -46,14 +37,6 @@ enum uart_pad_settings { UART_RX_PAD3_TX_PAD2 = SERCOM_USART_CTRLA_RXPO(3) | SERCOM_USART_CTRLA_TXPO(1), }; -/** - * \brief Gets the index of the provided SERCOM instance - * - * \param Pointer to SERCOM instance - * \return Index of the SERCOM module - */ -uint32_t uart_get_sercom_index(Sercom *sercom_instance); - /** * \brief Initializes the UART * @@ -104,4 +87,4 @@ void uart_write_buffer_polled(Sercom *sercom, uint8_t *ptr, uint16_t length); */ void uart_read_buffer_polled(Sercom *sercom, uint8_t *ptr, uint16_t length); -#endif \ No newline at end of file +#endif diff --git a/bootloaders/zero/board_driver_usb.c b/bootloaders/zero/board_driver_usb.c new file mode 100644 index 000000000..6534fa338 --- /dev/null +++ b/bootloaders/zero/board_driver_usb.c @@ -0,0 +1,367 @@ +/* + Copyright (c) 2015 Arduino LLC. All right reserved. + Copyright (c) 2015 Atmel Corporation/Thibaut VIARD. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include "board_driver_usb.h" +#include "sam_ba_usb.h" +#include "sam_ba_cdc.h" + +#define NVM_USB_PAD_TRANSN_POS (45) +#define NVM_USB_PAD_TRANSN_SIZE (5) +#define NVM_USB_PAD_TRANSP_POS (50) +#define NVM_USB_PAD_TRANSP_SIZE (5) +#define NVM_USB_PAD_TRIM_POS (55) +#define NVM_USB_PAD_TRIM_SIZE (3) + +__attribute__((__aligned__(4))) UsbDeviceDescriptor usb_endpoint_table[MAX_EP]; // Initialized to zero in USB_Init +__attribute__((__aligned__(4))) uint8_t udd_ep_out_cache_buffer[2][64]; //1 for CTRL, 1 for BULK +__attribute__((__aligned__(4))) uint8_t udd_ep_in_cache_buffer[2][64]; //1 for CTRL, 1 for BULK + +static volatile bool read_job = false; + +/*---------------------------------------------------------------------------- + * \brief + */ +P_USB_CDC USB_Open(P_USB_CDC pCdc, Usb *pUsb) +{ + pCdc->pUsb = pUsb; + pCdc->currentConfiguration = 0; + pCdc->currentConnection = 0; + pCdc->IsConfigured = USB_IsConfigured; +// pCdc->Write = USB_Write; +// pCdc->Read = USB_Read; + + pCdc->pUsb->HOST.CTRLA.bit.ENABLE = true; + + return pCdc; +} + +/*---------------------------------------------------------------------------- + * \brief Initializes USB + */ +void USB_Init(void) +{ + uint32_t pad_transn, pad_transp, pad_trim; + + /* Enable USB clock */ + PM->APBBMASK.reg |= PM_APBBMASK_USB; + + /* Set up the USB DP/DN pins */ + PORT->Group[0].PINCFG[PIN_PA24G_USB_DM].bit.PMUXEN = 1; + PORT->Group[0].PMUX[PIN_PA24G_USB_DM/2].reg &= ~(0xF << (4 * (PIN_PA24G_USB_DM & 0x01u))); + PORT->Group[0].PMUX[PIN_PA24G_USB_DM/2].reg |= MUX_PA24G_USB_DM << (4 * (PIN_PA24G_USB_DM & 0x01u)); + PORT->Group[0].PINCFG[PIN_PA25G_USB_DP].bit.PMUXEN = 1; + PORT->Group[0].PMUX[PIN_PA25G_USB_DP/2].reg &= ~(0xF << (4 * (PIN_PA25G_USB_DP & 0x01u))); + PORT->Group[0].PMUX[PIN_PA25G_USB_DP/2].reg |= MUX_PA25G_USB_DP << (4 * (PIN_PA25G_USB_DP & 0x01u)); + + /* ---------------------------------------------------------------------------------------------- + * Put Generic Clock Generator 0 as source for Generic Clock Multiplexer 6 (USB reference) + */ + GCLK->CLKCTRL.reg = GCLK_CLKCTRL_ID( 6 ) | // Generic Clock Multiplexer 6 + GCLK_CLKCTRL_GEN_GCLK0 | // Generic Clock Generator 0 is source + GCLK_CLKCTRL_CLKEN ; + + while ( GCLK->STATUS.reg & GCLK_STATUS_SYNCBUSY ) + { + /* Wait for synchronization */ + } + + /* Reset */ + USB->DEVICE.CTRLA.bit.SWRST = 1; + while (USB->DEVICE.SYNCBUSY.bit.SWRST) + { + /* Sync wait */ + } + + /* Load Pad Calibration */ + pad_transn =( *((uint32_t *)(NVMCTRL_OTP4) + + (NVM_USB_PAD_TRANSN_POS / 32)) + >> (NVM_USB_PAD_TRANSN_POS % 32)) + & ((1 << NVM_USB_PAD_TRANSN_SIZE) - 1); + + if (pad_transn == 0x1F) + { + pad_transn = 5; + } + + USB->HOST.PADCAL.bit.TRANSN = pad_transn; + + pad_transp =( *((uint32_t *)(NVMCTRL_OTP4) + + (NVM_USB_PAD_TRANSP_POS / 32)) + >> (NVM_USB_PAD_TRANSP_POS % 32)) + & ((1 << NVM_USB_PAD_TRANSP_SIZE) - 1); + + if (pad_transp == 0x1F) + { + pad_transp = 29; + } + + USB->HOST.PADCAL.bit.TRANSP = pad_transp; + pad_trim =( *((uint32_t *)(NVMCTRL_OTP4) + + (NVM_USB_PAD_TRIM_POS / 32)) + >> (NVM_USB_PAD_TRIM_POS % 32)) + & ((1 << NVM_USB_PAD_TRIM_SIZE) - 1); + + if (pad_trim == 0x7) + { + pad_trim = 3; + } + + USB->HOST.PADCAL.bit.TRIM = pad_trim; + + /* Set the configuration */ + /* Set mode to Device mode */ + USB->HOST.CTRLA.bit.MODE = 0; + /* Enable Run in Standby */ + USB->HOST.CTRLA.bit.RUNSTDBY = true; + /* Set the descriptor address */ + USB->HOST.DESCADD.reg = (uint32_t)(&usb_endpoint_table[0]); + /* Set speed configuration to Full speed */ + USB->DEVICE.CTRLB.bit.SPDCONF = USB_DEVICE_CTRLB_SPDCONF_FS_Val; + /* Attach to the USB host */ + USB->DEVICE.CTRLB.reg &= ~USB_DEVICE_CTRLB_DETACH; + + /* Initialize endpoint table RAM location to a known value 0 */ + memset((uint8_t *)(&usb_endpoint_table[0]), 0, sizeof(usb_endpoint_table)); +} + +uint32_t USB_Write(Usb *pUsb, const char *pData, uint32_t length, uint8_t ep_num) +{ + uint32_t data_address; + uint8_t buf_index; + + /* Set buffer index */ + buf_index = (ep_num == 0) ? 0 : 1; + + /* Check for requirement for multi-packet or auto zlp */ + if (length >= (1 << (usb_endpoint_table[ep_num].DeviceDescBank[1].PCKSIZE.bit.SIZE + 3))) + { + /* Update the EP data address */ + data_address = (uint32_t) pData; + /* Enable auto zlp */ + usb_endpoint_table[ep_num].DeviceDescBank[1].PCKSIZE.bit.AUTO_ZLP = true; + } + else + { + /* Copy to local buffer */ + memcpy(udd_ep_in_cache_buffer[buf_index], pData, length); + /* Update the EP data address */ + data_address = (uint32_t) &udd_ep_in_cache_buffer[buf_index]; + } + + /* Set the buffer address for ep data */ + usb_endpoint_table[ep_num].DeviceDescBank[1].ADDR.reg = data_address; + /* Set the byte count as zero */ + usb_endpoint_table[ep_num].DeviceDescBank[1].PCKSIZE.bit.BYTE_COUNT = length; + /* Set the multi packet size as zero for multi-packet transfers where length > ep size */ + usb_endpoint_table[ep_num].DeviceDescBank[1].PCKSIZE.bit.MULTI_PACKET_SIZE = 0; + /* Clear the transfer complete flag */ + //pUsb->DEVICE.DeviceEndpoint[ep_num].EPINTFLAG.bit.TRCPT1 = true; + pUsb->DEVICE.DeviceEndpoint[ep_num].EPINTFLAG.bit.TRCPT |= (1<<1); + /* Set the bank as ready */ + pUsb->DEVICE.DeviceEndpoint[ep_num].EPSTATUSSET.bit.BK1RDY = true; + + /* Wait for transfer to complete */ + while ( (pUsb->DEVICE.DeviceEndpoint[ep_num].EPINTFLAG.bit.TRCPT & (1<<1)) == 0 ); + + return length; +} + +/*---------------------------------------------------------------------------- + * \brief Read available data from Endpoint OUT + */ +uint32_t USB_Read(Usb *pUsb, char *pData, uint32_t length) +{ + uint32_t packetSize = 0; + + if (!read_job) + { + /* Set the buffer address for ep data */ + usb_endpoint_table[USB_EP_OUT].DeviceDescBank[0].ADDR.reg = (uint32_t)&udd_ep_out_cache_buffer[USB_EP_OUT-1]; + /* Set the byte count as zero */ + usb_endpoint_table[USB_EP_OUT].DeviceDescBank[0].PCKSIZE.bit.BYTE_COUNT = 0; + /* Set the byte count as zero */ + usb_endpoint_table[USB_EP_OUT].DeviceDescBank[0].PCKSIZE.bit.MULTI_PACKET_SIZE = 0; + /* Start the reception by clearing the bank 0 ready bit */ + pUsb->DEVICE.DeviceEndpoint[USB_EP_OUT].EPSTATUSCLR.bit.BK0RDY = true; + /* set the user flag */ + read_job = true; + } + + /* Check for Transfer Complete 0 flag */ + if ( pUsb->DEVICE.DeviceEndpoint[USB_EP_OUT].EPINTFLAG.bit.TRCPT & (1<<0) ) + { + /* Set packet size */ + packetSize = SAM_BA_MIN(usb_endpoint_table[USB_EP_OUT].DeviceDescBank[0].PCKSIZE.bit.BYTE_COUNT, length); + /* Copy read data to user buffer */ + memcpy(pData, udd_ep_out_cache_buffer[USB_EP_OUT-1], packetSize); + /* Clear the Transfer Complete 0 flag */ + //pUsb->DEVICE.DeviceEndpoint[USB_EP_OUT].EPINTFLAG.bit.TRCPT0 = true; + pUsb->DEVICE.DeviceEndpoint[USB_EP_OUT].EPINTFLAG.bit.TRCPT |= (1 << 0); + /* Clear the user flag */ + read_job = false; + } + + return packetSize; +} + +uint32_t USB_Read_blocking(Usb *pUsb, char *pData, uint32_t length) +{ + if (read_job) + { + /* Stop the reception by setting the bank 0 ready bit */ + pUsb->DEVICE.DeviceEndpoint[USB_EP_OUT].EPSTATUSSET.bit.BK0RDY = true; + /* Clear the user flag */ + read_job = false; + } + + /* Set the buffer address for ep data */ + usb_endpoint_table[USB_EP_OUT].DeviceDescBank[0].ADDR.reg = ((uint32_t)pData); + /* Set the byte count as zero */ + usb_endpoint_table[USB_EP_OUT].DeviceDescBank[0].PCKSIZE.bit.BYTE_COUNT = 0; + /* Set the multi packet size as zero for multi-packet transfers where length > ep size */ + usb_endpoint_table[USB_EP_OUT].DeviceDescBank[0].PCKSIZE.bit.MULTI_PACKET_SIZE = length; + /* Clear the bank 0 ready flag */ + pUsb->DEVICE.DeviceEndpoint[USB_EP_OUT].EPSTATUSCLR.bit.BK0RDY = true; + /* Wait for transfer to complete */ + while (!( pUsb->DEVICE.DeviceEndpoint[USB_EP_OUT].EPINTFLAG.bit.TRCPT & (1<<0) )); + /* Clear Transfer complete 0 flag */ + //pUsb->DEVICE.DeviceEndpoint[USB_EP_OUT].EPINTFLAG.bit.TRCPT0 = true; + pUsb->DEVICE.DeviceEndpoint[USB_EP_OUT].EPINTFLAG.bit.TRCPT |= (1 << 0); + + return length; +} + +/*---------------------------------------------------------------------------- + * \brief Test if the device is configured and handle enumeration + */ +uint8_t USB_IsConfigured(P_USB_CDC pCdc) +{ + Usb *pUsb = pCdc->pUsb; + + /* Check for End of Reset flag */ + if (pUsb->DEVICE.INTFLAG.reg & USB_DEVICE_INTFLAG_EORST) + { + /* Clear the flag */ + pUsb->DEVICE.INTFLAG.bit.EORST = true; + /* Set Device address as 0 */ + pUsb->DEVICE.DADD.reg = USB_DEVICE_DADD_ADDEN | 0; + /* Configure endpoint 0 */ + /* Configure Endpoint 0 for Control IN and Control OUT */ + pUsb->DEVICE.DeviceEndpoint[0].EPCFG.reg = USB_DEVICE_EPCFG_EPTYPE0(1) | USB_DEVICE_EPCFG_EPTYPE1(1); + pUsb->DEVICE.DeviceEndpoint[0].EPSTATUSSET.reg = USB_DEVICE_EPSTATUSSET_BK0RDY; + pUsb->DEVICE.DeviceEndpoint[0].EPSTATUSCLR.reg = USB_DEVICE_EPSTATUSCLR_BK1RDY; + /* Configure control OUT Packet size to 64 bytes */ + usb_endpoint_table[0].DeviceDescBank[0].PCKSIZE.bit.SIZE = 3; + /* Configure control IN Packet size to 64 bytes */ + usb_endpoint_table[0].DeviceDescBank[1].PCKSIZE.bit.SIZE = 3; + /* Configure the data buffer address for control OUT */ + usb_endpoint_table[0].DeviceDescBank[0].ADDR.reg = (uint32_t)&udd_ep_out_cache_buffer[0]; + /* Configure the data buffer address for control IN */ + usb_endpoint_table[0].DeviceDescBank[1].ADDR.reg = (uint32_t)&udd_ep_in_cache_buffer[0]; + /* Set Multipacket size to 8 for control OUT and byte count to 0*/ + usb_endpoint_table[0].DeviceDescBank[0].PCKSIZE.bit.MULTI_PACKET_SIZE = 8; + usb_endpoint_table[0].DeviceDescBank[0].PCKSIZE.bit.BYTE_COUNT = 0; + pUsb->DEVICE.DeviceEndpoint[0].EPSTATUSCLR.reg = USB_DEVICE_EPSTATUSCLR_BK0RDY; + + // Reset current configuration value to 0 + pCdc->currentConfiguration = 0; + } + else + { + if (pUsb->DEVICE.DeviceEndpoint[0].EPINTFLAG.reg & USB_DEVICE_EPINTFLAG_RXSTP) + { + sam_ba_usb_CDC_Enumerate(pCdc); + } + } + + return pCdc->currentConfiguration; +} + +/*---------------------------------------------------------------------------- + * \brief Stall the control endpoint + */ +void USB_SendStall(Usb *pUsb, bool direction_in) +{ + /* Check the direction */ + if (direction_in) + { + /* Set STALL request on IN direction */ + //pUsb->DEVICE.DeviceEndpoint[0].EPSTATUSSET.reg = USB_DEVICE_EPSTATUSSET_STALLRQ1; + pUsb->DEVICE.DeviceEndpoint[0].EPSTATUSSET.bit.STALLRQ = (1<<1); + } + else + { + /* Set STALL request on OUT direction */ + //pUsb->DEVICE.DeviceEndpoint[0].EPSTATUSSET.reg = USB_DEVICE_EPSTATUSSET_STALLRQ0; + pUsb->DEVICE.DeviceEndpoint[0].EPSTATUSSET.bit.STALLRQ = (1<<0); + } +} + +/*---------------------------------------------------------------------------- + * \brief Send zero length packet through the control endpoint + */ +void USB_SendZlp(Usb *pUsb) +{ + /* Set the byte count as zero */ + usb_endpoint_table[0].DeviceDescBank[1].PCKSIZE.bit.BYTE_COUNT = 0; + /* Clear the transfer complete flag */ + //pUsb->DEVICE.DeviceEndpoint[0].EPINTFLAG.bit.TRCPT1 = true; + pUsb->DEVICE.DeviceEndpoint[0].EPINTFLAG.bit.TRCPT |= (1 << 1); + /* Set the bank as ready */ + pUsb->DEVICE.DeviceEndpoint[0].EPSTATUSSET.bit.BK1RDY = true; + /* Wait for transfer to complete */ + while (!( pUsb->DEVICE.DeviceEndpoint[0].EPINTFLAG.bit.TRCPT & (1<<1) )); +} + +/*---------------------------------------------------------------------------- + * \brief Set USB device address obtained from host + */ +void USB_SetAddress(Usb *pUsb, uint16_t wValue) +{ + pUsb->DEVICE.DADD.reg = USB_DEVICE_DADD_ADDEN | wValue; +} + +/*---------------------------------------------------------------------------- + * \brief Configure USB device + */ +void USB_Configure(Usb *pUsb) +{ + /* Configure BULK OUT endpoint for CDC Data interface*/ + pUsb->DEVICE.DeviceEndpoint[USB_EP_OUT].EPCFG.reg = USB_DEVICE_EPCFG_EPTYPE0(3); + /* Set maximum packet size as 64 bytes */ + usb_endpoint_table[USB_EP_OUT].DeviceDescBank[0].PCKSIZE.bit.SIZE = 3; + pUsb->DEVICE.DeviceEndpoint[USB_EP_OUT].EPSTATUSSET.reg = USB_DEVICE_EPSTATUSSET_BK0RDY; + /* Configure the data buffer */ + usb_endpoint_table[USB_EP_OUT].DeviceDescBank[0].ADDR.reg = (uint32_t)&udd_ep_out_cache_buffer[1]; + + /* Configure BULK IN endpoint for CDC Data interface */ + pUsb->DEVICE.DeviceEndpoint[USB_EP_IN].EPCFG.reg = USB_DEVICE_EPCFG_EPTYPE1(3); + /* Set maximum packet size as 64 bytes */ + usb_endpoint_table[USB_EP_IN].DeviceDescBank[1].PCKSIZE.bit.SIZE = 3; + pUsb->DEVICE.DeviceEndpoint[USB_EP_IN].EPSTATUSCLR.reg = USB_DEVICE_EPSTATUSCLR_BK1RDY; + /* Configure the data buffer */ + usb_endpoint_table[USB_EP_IN].DeviceDescBank[1].ADDR.reg = (uint32_t)&udd_ep_in_cache_buffer[1]; + + /* Configure INTERRUPT IN endpoint for CDC COMM interface*/ + pUsb->DEVICE.DeviceEndpoint[USB_EP_COMM].EPCFG.reg = USB_DEVICE_EPCFG_EPTYPE1(4); + /* Set maximum packet size as 64 bytes */ + usb_endpoint_table[USB_EP_COMM].DeviceDescBank[1].PCKSIZE.bit.SIZE = 0; + pUsb->DEVICE.DeviceEndpoint[USB_EP_COMM].EPSTATUSCLR.reg = USB_DEVICE_EPSTATUSCLR_BK1RDY; +} diff --git a/bootloaders/zero/board_driver_usb.h b/bootloaders/zero/board_driver_usb.h new file mode 100644 index 000000000..4e71b8c1a --- /dev/null +++ b/bootloaders/zero/board_driver_usb.h @@ -0,0 +1,45 @@ +/* + Copyright (c) 2015 Arduino LLC. All right reserved. + Copyright (c) 2015 Atmel Corporation/Thibaut VIARD. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _BOARD_DRIVER_USB_H_ +#define _BOARD_DRIVER_USB_H_ + +#include "sam_ba_cdc.h" + +extern UsbDeviceDescriptor usb_endpoint_table[MAX_EP]; +extern uint8_t udd_ep_out_cache_buffer[2][64]; //1 for CTRL, 1 for BULK +extern uint8_t udd_ep_in_cache_buffer[2][64]; //1 for CTRL, 1 for BULK + +P_USB_CDC USB_Open(P_USB_CDC pCdc, Usb *pUsb); + +void USB_Init(void); + +uint32_t USB_Write(Usb *pUsb, const char *pData, uint32_t length, uint8_t ep_num); +uint32_t USB_Read(Usb *pUsb, char *pData, uint32_t length); +uint32_t USB_Read_blocking(Usb *pUsb, char *pData, uint32_t length); + +uint8_t USB_IsConfigured(P_USB_CDC pCdc); + +void USB_SendStall(Usb *pUsb, bool direction_in); +void USB_SendZlp(Usb *pUsb); + +void USB_SetAddress(Usb *pUsb, uint16_t wValue); +void USB_Configure(Usb *pUsb); + +#endif // _BOARD_DRIVER_USB_H_ diff --git a/bootloaders/zero/board_init.c b/bootloaders/zero/board_init.c new file mode 100644 index 000000000..c08aedaae --- /dev/null +++ b/bootloaders/zero/board_init.c @@ -0,0 +1,210 @@ +/* + Copyright (c) 2015 Arduino LLC. All right reserved. + Copyright (c) 2015 Atmel Corporation/Thibaut VIARD. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include "board_definitions.h" + +/** + * \brief system_init() configures the needed clocks and according Flash Read Wait States. + * At reset: + * - OSC8M clock source is enabled with a divider by 8 (1MHz). + * - Generic Clock Generator 0 (GCLKMAIN) is using OSC8M as source. + * We need to: + * 1) Enable XOSC32K clock (External on-board 32.768Hz oscillator), will be used as DFLL48M reference. + * 2) Put XOSC32K as source of Generic Clock Generator 1 + * 3) Put Generic Clock Generator 1 as source for Generic Clock Multiplexer 0 (DFLL48M reference) + * 4) Enable DFLL48M clock + * 5) Switch Generic Clock Generator 0 to DFLL48M. CPU will run at 48MHz. + * 6) Modify PRESCaler value of OSCM to have 8MHz + * 7) Put OSC8M as source for Generic Clock Generator 3 + */ +// Constants for Clock generators +#define GENERIC_CLOCK_GENERATOR_MAIN (0u) +#define GENERIC_CLOCK_GENERATOR_XOSC32K (1u) +#define GENERIC_CLOCK_GENERATOR_OSCULP32K (2u) /* Initialized at reset for WDT */ +#define GENERIC_CLOCK_GENERATOR_OSC8M (3u) +// Constants for Clock multiplexers +#define GENERIC_CLOCK_MULTIPLEXER_DFLL48M (0u) + +void board_init(void) +{ + /* Set 1 Flash Wait State for 48MHz, cf tables 20.9 and 35.27 in SAMD21 Datasheet */ + NVMCTRL->CTRLB.bit.RWS = NVMCTRL_CTRLB_RWS_HALF_Val; + + /* Turn on the digital interface clock */ + PM->APBAMASK.reg |= PM_APBAMASK_GCLK; + + /* ---------------------------------------------------------------------------------------------- + * 1) Enable XOSC32K clock (External on-board 32.768Hz oscillator) + */ + SYSCTRL->XOSC32K.reg = SYSCTRL_XOSC32K_STARTUP( 0x6u ) | /* cf table 15.10 of product datasheet in chapter 15.8.6 */ + SYSCTRL_XOSC32K_XTALEN | SYSCTRL_XOSC32K_EN32K; + SYSCTRL->XOSC32K.bit.ENABLE = 1; /* separate call, as described in chapter 15.6.3 */ + + while ( (SYSCTRL->PCLKSR.reg & SYSCTRL_PCLKSR_XOSC32KRDY) == 0 ) + { + /* Wait for oscillator stabilization */ + } + + /* Software reset the module to ensure it is re-initialized correctly */ + /* Note: Due to synchronization, there is a delay from writing CTRL.SWRST until the reset is complete. + * CTRL.SWRST and STATUS.SYNCBUSY will both be cleared when the reset is complete, as described in chapter 13.8.1 + */ + GCLK->CTRL.reg = GCLK_CTRL_SWRST; + + while ( (GCLK->CTRL.reg & GCLK_CTRL_SWRST) && (GCLK->STATUS.reg & GCLK_STATUS_SYNCBUSY) ) + { + /* Wait for reset to complete */ + } + + /* ---------------------------------------------------------------------------------------------- + * 2) Put XOSC32K as source of Generic Clock Generator 1 + */ + GCLK->GENDIV.reg = GCLK_GENDIV_ID( GENERIC_CLOCK_GENERATOR_XOSC32K ); // Generic Clock Generator 1 + + while ( GCLK->STATUS.reg & GCLK_STATUS_SYNCBUSY ) + { + /* Wait for synchronization */ + } + + /* Write Generic Clock Generator 1 configuration */ + GCLK->GENCTRL.reg = GCLK_GENCTRL_ID( GENERIC_CLOCK_GENERATOR_XOSC32K ) | // Generic Clock Generator 1 + GCLK_GENCTRL_SRC_XOSC32K | // Selected source is External 32KHz Oscillator +// GCLK_GENCTRL_OE | // Output clock to a pin for tests + GCLK_GENCTRL_GENEN; + + while ( GCLK->STATUS.reg & GCLK_STATUS_SYNCBUSY ) + { + /* Wait for synchronization */ + } + + /* ---------------------------------------------------------------------------------------------- + * 3) Put Generic Clock Generator 1 as source for Generic Clock Multiplexer 0 (DFLL48M reference) + */ + GCLK->CLKCTRL.reg = GCLK_CLKCTRL_ID( GENERIC_CLOCK_MULTIPLEXER_DFLL48M ) | // Generic Clock Multiplexer 0 + GCLK_CLKCTRL_GEN_GCLK1 | // Generic Clock Generator 1 is source + GCLK_CLKCTRL_CLKEN; + + while ( GCLK->STATUS.reg & GCLK_STATUS_SYNCBUSY ) + { + /* Wait for synchronization */ + } + + /* ---------------------------------------------------------------------------------------------- + * 4) Enable DFLL48M clock + */ + + /* DFLL Configuration in Closed Loop mode, cf product datasheet chapter 15.6.7.1 - Closed-Loop Operation */ + + /* Remove the OnDemand mode, Bug http://avr32.icgroup.norway.atmel.com/bugzilla/show_bug.cgi?id=9905 */ + SYSCTRL->DFLLCTRL.bit.ONDEMAND = 0; + + while ( (SYSCTRL->PCLKSR.reg & SYSCTRL_PCLKSR_DFLLRDY) == 0 ) + { + /* Wait for synchronization */ + } + + SYSCTRL->DFLLMUL.reg = SYSCTRL_DFLLMUL_CSTEP( 31 ) | // Coarse step is 31, half of the max value + SYSCTRL_DFLLMUL_FSTEP( 511 ) | // Fine step is 511, half of the max value + SYSCTRL_DFLLMUL_MUL( (VARIANT_MCK/VARIANT_MAINOSC) ); // External 32KHz is the reference + + while ( (SYSCTRL->PCLKSR.reg & SYSCTRL_PCLKSR_DFLLRDY) == 0 ) + { + /* Wait for synchronization */ + } + + /* Write full configuration to DFLL control register */ + SYSCTRL->DFLLCTRL.reg |= SYSCTRL_DFLLCTRL_MODE | /* Enable the closed loop mode */ + SYSCTRL_DFLLCTRL_WAITLOCK | + SYSCTRL_DFLLCTRL_QLDIS; /* Disable Quick lock */ + + while ( (SYSCTRL->PCLKSR.reg & SYSCTRL_PCLKSR_DFLLRDY) == 0 ) + { + /* Wait for synchronization */ + } + + /* Enable the DFLL */ + SYSCTRL->DFLLCTRL.reg |= SYSCTRL_DFLLCTRL_ENABLE; + + while ( (SYSCTRL->PCLKSR.reg & SYSCTRL_PCLKSR_DFLLLCKC) == 0 || + (SYSCTRL->PCLKSR.reg & SYSCTRL_PCLKSR_DFLLLCKF) == 0 ) + { + /* Wait for locks flags */ + } + + while ( (SYSCTRL->PCLKSR.reg & SYSCTRL_PCLKSR_DFLLRDY) == 0 ) + { + /* Wait for synchronization */ + } + + /* ---------------------------------------------------------------------------------------------- + * 5) Switch Generic Clock Generator 0 to DFLL48M. CPU will run at 48MHz. + */ + GCLK->GENDIV.reg = GCLK_GENDIV_ID( GENERIC_CLOCK_GENERATOR_MAIN ); // Generic Clock Generator 0 + + while ( GCLK->STATUS.reg & GCLK_STATUS_SYNCBUSY ) + { + /* Wait for synchronization */ + } + + /* Write Generic Clock Generator 0 configuration */ + GCLK->GENCTRL.reg = GCLK_GENCTRL_ID( GENERIC_CLOCK_GENERATOR_MAIN ) | // Generic Clock Generator 0 + GCLK_GENCTRL_SRC_DFLL48M | // Selected source is DFLL 48MHz +// GCLK_GENCTRL_OE | // Output clock to a pin for tests + GCLK_GENCTRL_IDC | // Set 50/50 duty cycle + GCLK_GENCTRL_GENEN; + + while ( GCLK->STATUS.reg & GCLK_STATUS_SYNCBUSY ) + { + /* Wait for synchronization */ + } + +#if 0 + /* ---------------------------------------------------------------------------------------------- + * 6) Modify PRESCaler value of OSC8M to have 8MHz + */ + SYSCTRL->OSC8M.bit.PRESC = SYSCTRL_OSC8M_PRESC_1_Val; + SYSCTRL->OSC8M.bit.ONDEMAND = 0; + + /* ---------------------------------------------------------------------------------------------- + * 7) Put OSC8M as source for Generic Clock Generator 3 + */ + GCLK->GENDIV.reg = GCLK_GENDIV_ID( GENERIC_CLOCK_GENERATOR_OSC8M ); // Generic Clock Generator 3 + + /* Write Generic Clock Generator 3 configuration */ + GCLK->GENCTRL.reg = GCLK_GENCTRL_ID( GENERIC_CLOCK_GENERATOR_OSC8M ) | // Generic Clock Generator 3 + GCLK_GENCTRL_SRC_OSC8M | // Selected source is RC OSC 8MHz (already enabled at reset) +// GCLK_GENCTRL_OE | // Output clock to a pin for tests + GCLK_GENCTRL_GENEN; + + while ( GCLK->STATUS.reg & GCLK_STATUS_SYNCBUSY ) + { + /* Wait for synchronization */ + } +#endif //0 + + /* + * Now that all system clocks are configured, we can set CPU and APBx BUS clocks. + * These values are normally the ones present after Reset. + */ + PM->CPUSEL.reg = PM_CPUSEL_CPUDIV_DIV1; + PM->APBASEL.reg = PM_APBASEL_APBADIV_DIV1_Val; + PM->APBBSEL.reg = PM_APBBSEL_APBBDIV_DIV1_Val; + PM->APBCSEL.reg = PM_APBCSEL_APBCDIV_DIV1_Val; +} diff --git a/bootloaders/zero/board_startup.c b/bootloaders/zero/board_startup.c new file mode 100644 index 000000000..aaa5a019f --- /dev/null +++ b/bootloaders/zero/board_startup.c @@ -0,0 +1,147 @@ +/* + Copyright (c) 2015 Arduino LLC. All right reserved. + Copyright (c) 2015 Atmel Corporation/Thibaut VIARD. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include + +struct ConstVectors +{ + /* Stack pointer */ + void* pvStack; + + /* Cortex-M handlers */ + void* pfnReset_Handler; + void* pfnNMI_Handler; + void* pfnHardFault_Handler; + void* pfnReservedM12; + void* pfnReservedM11; + void* pfnReservedM10; + void* pfnReservedM9; + void* pfnReservedM8; + void* pfnReservedM7; + void* pfnReservedM6; + void* pfnSVC_Handler; + void* pfnReservedM4; + void* pfnReservedM3; + void* pfnPendSV_Handler; + void* pfnSysTick_Handler; +}; + +/* Symbols exported from linker script */ +extern uint32_t __etext ; +extern uint32_t __data_start__ ; +extern uint32_t __data_end__ ; +extern uint32_t __bss_start__ ; +extern uint32_t __bss_end__ ; +extern uint32_t __StackTop; + +extern int main(void); +extern void __libc_init_array(void); + +/* Exception Table */ +__attribute__ ((section(".isr_vector"))) +const struct ConstVectors exception_table = +{ + /* Configure Initial Stack Pointer, using linker-generated symbols */ + .pvStack = (void*) (&__StackTop), + + .pfnReset_Handler = (void*) Reset_Handler, + .pfnNMI_Handler = (void*) NMI_Handler, + .pfnHardFault_Handler = (void*) HardFault_Handler, + .pfnReservedM12 = (void*) (0UL), /* Reserved */ + .pfnReservedM11 = (void*) (0UL), /* Reserved */ + .pfnReservedM10 = (void*) (0UL), /* Reserved */ + .pfnReservedM9 = (void*) (0UL), /* Reserved */ + .pfnReservedM8 = (void*) (0UL), /* Reserved */ + .pfnReservedM7 = (void*) (0UL), /* Reserved */ + .pfnReservedM6 = (void*) (0UL), /* Reserved */ + .pfnSVC_Handler = (void*) SVC_Handler, + .pfnReservedM4 = (void*) (0UL), /* Reserved */ + .pfnReservedM3 = (void*) (0UL), /* Reserved */ + .pfnPendSV_Handler = (void*) PendSV_Handler, + .pfnSysTick_Handler = (void*) SysTick_Handler, +}; + +/** + * \brief This is the code that gets called on processor reset. + * Initializes the device and call the main() routine. + */ +void Reset_Handler( void ) +{ + uint32_t *pSrc, *pDest; + + /* Initialize the initialized data section */ + pSrc = &__etext; + pDest = &__data_start__; + + if ( (&__data_start__ != &__data_end__) && (pSrc != pDest) ) + { + for (; pDest < &__data_end__ ; pDest++, pSrc++ ) + { + *pDest = *pSrc ; + } + } + + /* Clear the zero section */ + if ( &__bss_start__ != &__bss_end__ ) + { + for ( pDest = &__bss_start__ ; pDest < &__bss_end__ ; pDest++ ) + { + *pDest = 0ul ; + } + } + +// board_init(); // will be done in main() after app check + + /* Initialize the C library */ +// __libc_init_array(); + + main(); + + while (1); +} + +void NMI_Handler(void) +{ + __BKPT(14); + while (1); +} + +void HardFault_Handler(void) +{ + __BKPT(13); + while (1); +} + +void SVC_Handler(void) +{ + __BKPT(5); + while (1); +} + +void PendSV_Handler(void) +{ + __BKPT(2); + while (1); +} + +void SysTick_Handler(void) +{ + __BKPT(1); + while (1); +} diff --git a/bootloaders/zero/bootloader_samd21x18.ld b/bootloaders/zero/bootloader_samd21x18.ld new file mode 100644 index 000000000..2a8b056d3 --- /dev/null +++ b/bootloaders/zero/bootloader_samd21x18.ld @@ -0,0 +1,221 @@ +/* + Copyright (c) 2014-2015 Arduino LLC. All right reserved. + Copyright (c) 2015 Atmel Corporation/Thibaut VIARD. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +/* Linker script to configure memory regions. + * Need modifying for a specific board. + * FLASH.ORIGIN: starting address of flash + * FLASH.LENGTH: length of flash + * RAM.ORIGIN: starting address of RAM bank 0 + * RAM.LENGTH: length of RAM bank 0 + */ +MEMORY +{ + FLASH (rx) : ORIGIN = 0x00000000, LENGTH = 0x2000 /* First 8KB used by bootloader */ + RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 0x00008000-0x0004 /* 4 bytes used by bootloader to keep data between resets */ +} + +/* Linker script to place sections and symbol values. Should be used together + * with other linker script that defines memory regions FLASH and RAM. + * It references following symbols, which must be defined in code: + * Reset_Handler : Entry of reset handler + * + * It defines following symbols, which code can use without definition: + * __exidx_start + * __exidx_end + * __copy_table_start__ + * __copy_table_end__ + * __zero_table_start__ + * __zero_table_end__ + * __etext + * __data_start__ + * __preinit_array_start + * __preinit_array_end + * __init_array_start + * __init_array_end + * __fini_array_start + * __fini_array_end + * __data_end__ + * __bss_start__ + * __bss_end__ + * __end__ + * end + * __HeapLimit + * __StackLimit + * __StackTop + * __stack + * __sketch_vectors_ptr + */ +ENTRY(Reset_Handler) + +SECTIONS +{ + . = ORIGIN(FLASH); + + .vectors : + { + KEEP(*(.isr_vector)) + } > FLASH + + .text : + { + *(.text*) + + KEEP(*(.init)) + KEEP(*(.fini)) + + /* .ctors */ + *crtbegin.o(.ctors) + *crtbegin?.o(.ctors) + *(EXCLUDE_FILE(*crtend?.o *crtend.o) .ctors) + *(SORT(.ctors.*)) + *(.ctors) + + /* .dtors */ + *crtbegin.o(.dtors) + *crtbegin?.o(.dtors) + *(EXCLUDE_FILE(*crtend?.o *crtend.o) .dtors) + *(SORT(.dtors.*)) + *(.dtors) + + *(.rodata*) + + KEEP(*(.eh_frame*)) + } > FLASH + + .ARM.extab : + { + *(.ARM.extab* .gnu.linkonce.armextab.*) + } > FLASH + + __exidx_start = .; + .ARM.exidx : + { + *(.ARM.exidx* .gnu.linkonce.armexidx.*) + } > FLASH + __exidx_end = .; + + /* To copy multiple ROM to RAM sections, + * uncomment .copy.table section and, + * define __STARTUP_COPY_MULTIPLE in startup_ARMCMx.S */ + /* + .copy.table : + { + . = ALIGN(4); + __copy_table_start__ = .; + LONG (__etext) + LONG (__data_start__) + LONG (__data_end__ - __data_start__) + LONG (__etext2) + LONG (__data2_start__) + LONG (__data2_end__ - __data2_start__) + __copy_table_end__ = .; + } > FLASH + */ + + /* To clear multiple BSS sections, + * uncomment .zero.table section and, + * define __STARTUP_CLEAR_BSS_MULTIPLE in startup_ARMCMx.S */ + /* + .zero.table : + { + . = ALIGN(4); + __zero_table_start__ = .; + LONG (__bss_start__) + LONG (__bss_end__ - __bss_start__) + LONG (__bss2_start__) + LONG (__bss2_end__ - __bss2_start__) + __zero_table_end__ = .; + } > FLASH + */ + + __etext = .; + PROVIDE(__sketch_vectors_ptr = ORIGIN(FLASH) + LENGTH(FLASH)); + + + .data : AT (__etext) + { + __data_start__ = .; + *(vtable) + *(.data*) + + . = ALIGN(4); + /* preinit data */ + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP(*(.preinit_array)) + PROVIDE_HIDDEN (__preinit_array_end = .); + + . = ALIGN(4); + /* init data */ + PROVIDE_HIDDEN (__init_array_start = .); + KEEP(*(SORT(.init_array.*))) + KEEP(*(.init_array)) + PROVIDE_HIDDEN (__init_array_end = .); + + + . = ALIGN(4); + /* finit data */ + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP(*(SORT(.fini_array.*))) + KEEP(*(.fini_array)) + PROVIDE_HIDDEN (__fini_array_end = .); + + KEEP(*(.jcr*)) + . = ALIGN(4); + /* All data end */ + __data_end__ = .; + + } > RAM + + .bss : + { + . = ALIGN(4); + __bss_start__ = .; + *(.bss*) + *(COMMON) + . = ALIGN(4); + __bss_end__ = .; + } > RAM + + .heap (COPY): + { + __end__ = .; + PROVIDE(end = .); + *(.heap*) + __HeapLimit = .; + } > RAM + + /* .stack_dummy section doesn't contains any symbols. It is only + * used for linker to calculate size of stack sections, and assign + * values to stack symbols later */ + .stack_dummy (COPY): + { + *(.stack*) + } > RAM + + /* Set stack top to end of RAM, and stack limit move down by + * size of stack_dummy section */ + __StackTop = ORIGIN(RAM) + LENGTH(RAM); + __StackLimit = __StackTop - SIZEOF(.stack_dummy); + PROVIDE(__stack = __StackTop); + + __ram_end__ = ORIGIN(RAM) + LENGTH(RAM) -1 ; + + /* Check if data + heap + stack exceeds RAM limit */ + ASSERT(__StackLimit >= __HeapLimit, "region RAM overflowed with stack") +} diff --git a/bootloaders/zero/drivers/cdc_enumerate.c b/bootloaders/zero/drivers/cdc_enumerate.c deleted file mode 100644 index bd3873eb2..000000000 --- a/bootloaders/zero/drivers/cdc_enumerate.c +++ /dev/null @@ -1,765 +0,0 @@ -/* ---------------------------------------------------------------------------- - * SAM Software Package License - * ---------------------------------------------------------------------------- - * Copyright (c) 2011-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. - * ---------------------------------------------------------------------------- - */ - -#include "cdc_enumerate.h" -#include -#include -#include - - -#define MIN(a, b) (((a) < (b)) ? (a) : (b)) - -COMPILER_WORD_ALIGNED UsbDeviceDescriptor usb_endpoint_table[MAX_EP] = {0}; -COMPILER_WORD_ALIGNED uint8_t udd_ep_out_cache_buffer[2][64]; //1 for CTRL, 1 for BULK -COMPILER_WORD_ALIGNED uint8_t udd_ep_in_cache_buffer[2][64]; //1 for CTRL, 1 for BULK - -COMPILER_WORD_ALIGNED -const char devDescriptor[] = { - /* Device descriptor */ - 0x12, // bLength - 0x01, // bDescriptorType - 0x10, // bcdUSBL - 0x01, // - 0x02, // bDeviceClass: CDC class code - 0x00, // bDeviceSubclass: CDC class sub code - 0x00, // bDeviceProtocol: CDC Device protocol - 0x40, // bMaxPacketSize0 - 0x41, // idVendorL - 0x23, // - 0x4D, // idProductL - 0x00, // - 0x10, // bcdDeviceL - 0x01, // - 0x00, // iManufacturer // 0x01 - 0x00, // iProduct - 0x00, // SerialNumber - 0x01 // bNumConfigs -}; - -COMPILER_WORD_ALIGNED -char cfgDescriptor[] = { - /* ============== CONFIGURATION 1 =========== */ - /* Configuration 1 descriptor */ - 0x09, // CbLength - 0x02, // CbDescriptorType - 0x43, // CwTotalLength 2 EP + Control - 0x00, - 0x02, // CbNumInterfaces - 0x01, // CbConfigurationValue - 0x00, // CiConfiguration - 0xC0, // CbmAttributes 0xA0 - 0x00, // CMaxPower - - /* Communication Class Interface Descriptor Requirement */ - 0x09, // bLength - 0x04, // bDescriptorType - 0x00, // bInterfaceNumber - 0x00, // bAlternateSetting - 0x01, // bNumEndpoints - 0x02, // bInterfaceClass - 0x02, // bInterfaceSubclass - 0x00, // bInterfaceProtocol - 0x00, // iInterface - - /* Header Functional Descriptor */ - 0x05, // bFunction Length - 0x24, // bDescriptor type: CS_INTERFACE - 0x00, // bDescriptor subtype: Header Func Desc - 0x10, // bcdCDC:1.1 - 0x01, - - /* ACM Functional Descriptor */ - 0x04, // bFunctionLength - 0x24, // bDescriptor Type: CS_INTERFACE - 0x02, // bDescriptor Subtype: ACM Func Desc - 0x00, // bmCapabilities - - /* Union Functional Descriptor */ - 0x05, // bFunctionLength - 0x24, // bDescriptorType: CS_INTERFACE - 0x06, // bDescriptor Subtype: Union Func Desc - 0x00, // bMasterInterface: Communication Class Interface - 0x01, // bSlaveInterface0: Data Class Interface - - /* Call Management Functional Descriptor */ - 0x05, // bFunctionLength - 0x24, // bDescriptor Type: CS_INTERFACE - 0x01, // bDescriptor Subtype: Call Management Func Desc - 0x00, // bmCapabilities: D1 + D0 - 0x01, // bDataInterface: Data Class Interface 1 - - /* Endpoint 1 descriptor */ - 0x07, // bLength - 0x05, // bDescriptorType - 0x83, // bEndpointAddress, Endpoint 03 - IN - 0x03, // bmAttributes INT - 0x08, // wMaxPacketSize - 0x00, - 0xFF, // bInterval - - /* Data Class Interface Descriptor Requirement */ - 0x09, // bLength - 0x04, // bDescriptorType - 0x01, // bInterfaceNumber - 0x00, // bAlternateSetting - 0x02, // bNumEndpoints - 0x0A, // bInterfaceClass - 0x00, // bInterfaceSubclass - 0x00, // bInterfaceProtocol - 0x00, // iInterface - - /* First alternate setting */ - /* Endpoint 1 descriptor */ - 0x07, // bLength - 0x05, // bDescriptorType - 0x81, // bEndpointAddress, Endpoint 01 - IN - 0x02, // bmAttributes BULK - USB_EP_IN_SIZE, // wMaxPacketSize - 0x00, - 0x00, // bInterval - - /* Endpoint 2 descriptor */ - 0x07, // bLength - 0x05, // bDescriptorType - 0x02, // bEndpointAddress, Endpoint 02 - OUT - 0x02, // bmAttributes BULK - USB_EP_OUT_SIZE, // wMaxPacketSize - 0x00, - 0x00 // bInterval -}; - - -static usb_cdc_line_coding_t line_coding = { - 115200, // baudrate - 0, // 1 Stop Bit - 0, // None Parity - 8 // 8 Data bits -}; - -static USB_CDC pCdc; - -/* USB standard request code */ -#define STD_GET_STATUS_ZERO 0x0080 -#define STD_GET_STATUS_INTERFACE 0x0081 -#define STD_GET_STATUS_ENDPOINT 0x0082 - -#define STD_CLEAR_FEATURE_ZERO 0x0100 -#define STD_CLEAR_FEATURE_INTERFACE 0x0101 -#define STD_CLEAR_FEATURE_ENDPOINT 0x0102 - -#define STD_SET_FEATURE_ZERO 0x0300 -#define STD_SET_FEATURE_INTERFACE 0x0301 -#define STD_SET_FEATURE_ENDPOINT 0x0302 - -#define STD_SET_ADDRESS 0x0500 -#define STD_GET_DESCRIPTOR 0x0680 -#define STD_SET_DESCRIPTOR 0x0700 -#define STD_GET_CONFIGURATION 0x0880 -#define STD_SET_CONFIGURATION 0x0900 -#define STD_GET_INTERFACE 0x0A81 -#define STD_SET_INTERFACE 0x0B01 -#define STD_SYNCH_FRAME 0x0C82 - -/* CDC Class Specific Request Code */ -#define GET_LINE_CODING 0x21A1 -#define SET_LINE_CODING 0x2021 -#define SET_CONTROL_LINE_STATE 0x2221 - - -static uint8_t USB_IsConfigured(P_USB_CDC pCdc); -static uint32_t USB_Read(P_USB_CDC pCdc, char *pData, uint32_t length); -static uint32_t USB_Write(P_USB_CDC pCdc, const char *pData, uint32_t length, uint8_t ep_num); -static void AT91F_CDC_Enumerate(P_USB_CDC pCdc); - - -/** - * \fn AT91F_InitUSB - * - * \brief Initializes USB - */ -void AT91F_InitUSB(void) -{ - uint32_t pad_transn, pad_transp, pad_trim; - - /* Enable USB clock */ - PM->APBBMASK.reg |= PM_APBBMASK_USB; - - /* Set up the USB DP/DN pins */ - PORT->Group[0].PINCFG[PIN_PA24G_USB_DM].bit.PMUXEN = 1; - PORT->Group[0].PMUX[PIN_PA24G_USB_DM/2].reg &= ~(0xF << (4 * (PIN_PA24G_USB_DM & 0x01u))); - PORT->Group[0].PMUX[PIN_PA24G_USB_DM/2].reg |= MUX_PA24G_USB_DM << (4 * (PIN_PA24G_USB_DM & 0x01u)); - PORT->Group[0].PINCFG[PIN_PA25G_USB_DP].bit.PMUXEN = 1; - PORT->Group[0].PMUX[PIN_PA25G_USB_DP/2].reg &= ~(0xF << (4 * (PIN_PA25G_USB_DP & 0x01u))); - PORT->Group[0].PMUX[PIN_PA25G_USB_DP/2].reg |= MUX_PA25G_USB_DP << (4 * (PIN_PA25G_USB_DP & 0x01u)); - - /* Setup clock for module */ - GCLK_CLKCTRL_Type clkctrl={0}; - uint16_t temp; - /* GCLK_ID - USB - 0x06 */ - GCLK->CLKCTRL.bit.ID = 0x06; - temp = GCLK->CLKCTRL.reg; - clkctrl.bit.CLKEN = true; - clkctrl.bit.WRTLOCK = false; - clkctrl.bit.GEN = GCLK_CLKCTRL_GEN_GCLK1_Val; - GCLK->CLKCTRL.reg = (clkctrl.reg | temp); - - /* Reset */ - USB->HOST.CTRLA.bit.SWRST = 1; - while (USB->HOST.SYNCBUSY.bit.SWRST) { - /* Sync wait */ - } - - /* Load Pad Calibration */ - pad_transn =( *((uint32_t *)(NVMCTRL_OTP4) - + (NVM_USB_PAD_TRANSN_POS / 32)) - >> (NVM_USB_PAD_TRANSN_POS % 32)) - & ((1 << NVM_USB_PAD_TRANSN_SIZE) - 1); - - if (pad_transn == 0x1F) { - pad_transn = 5; - } - - USB->HOST.PADCAL.bit.TRANSN = pad_transn; - - pad_transp =( *((uint32_t *)(NVMCTRL_OTP4) - + (NVM_USB_PAD_TRANSP_POS / 32)) - >> (NVM_USB_PAD_TRANSP_POS % 32)) - & ((1 << NVM_USB_PAD_TRANSP_SIZE) - 1); - - if (pad_transp == 0x1F) { - pad_transp = 29; - } - - USB->HOST.PADCAL.bit.TRANSP = pad_transp; - pad_trim =( *((uint32_t *)(NVMCTRL_OTP4) - + (NVM_USB_PAD_TRIM_POS / 32)) - >> (NVM_USB_PAD_TRIM_POS % 32)) - & ((1 << NVM_USB_PAD_TRIM_SIZE) - 1); - - if (pad_trim == 0x7) { - pad_trim = 3; - } - - USB->HOST.PADCAL.bit.TRIM = pad_trim; - - /* Set the configuration */ - /* Set mode to Device mode */ - USB->HOST.CTRLA.bit.MODE = 0; - /* Enable Run in Standby */ - USB->HOST.CTRLA.bit.RUNSTDBY = true; - /* Set the descriptor address */ - USB->HOST.DESCADD.reg = (uint32_t)(&usb_endpoint_table[0]); - /* Set speed configuration to Full speed */ - USB->DEVICE.CTRLB.bit.SPDCONF = USB_DEVICE_CTRLB_SPDCONF_FS_Val; - /* Attach to the USB host */ - USB->DEVICE.CTRLB.reg &= ~USB_DEVICE_CTRLB_DETACH; - - /* Initialize endpoint table RAM location to a known value 0 */ - memset((uint8_t *)(&usb_endpoint_table[0]), 0, - sizeof(usb_endpoint_table)); -} - -//*---------------------------------------------------------------------------- -//* \fn AT91F_CDC_Open -//* \brief -//*---------------------------------------------------------------------------- -P_USB_CDC AT91F_CDC_Open(P_USB_CDC pCdc,Usb *pUsb) -{ - pCdc->pUsb = pUsb; - pCdc->currentConfiguration = 0; - pCdc->currentConnection = 0; - pCdc->IsConfigured = USB_IsConfigured; - pCdc->Write = USB_Write; - pCdc->Read = USB_Read; - pCdc->pUsb->HOST.CTRLA.bit.ENABLE = true; - return pCdc; -} - -//*---------------------------------------------------------------------------- -//* \fn USB_IsConfigured -//* \brief Test if the device is configured and handle enumerationDEVICE.DeviceEndpoint[ep_num].EPCFG.bit.EPTYPE1 -//*---------------------------------------------------------------------------- -static uint8_t USB_IsConfigured(P_USB_CDC pCdc) -{ - Usb *pUsb = pCdc->pUsb; - - /* Check for End of Reset flag */ - if (pUsb->DEVICE.INTFLAG.reg & USB_DEVICE_INTFLAG_EORST) { - /* Clear the flag */ - pUsb->DEVICE.INTFLAG.bit.EORST = true; - /* Set Device address as 0 */ - pUsb->DEVICE.DADD.reg = USB_DEVICE_DADD_ADDEN | 0; - /* Configure endpoint 0 */ - /* Configure Endpoint 0 for Control IN and Control OUT */ - pUsb->DEVICE.DeviceEndpoint[0].EPCFG.reg = USB_DEVICE_EPCFG_EPTYPE0(1) | USB_DEVICE_EPCFG_EPTYPE1(1); - pUsb->DEVICE.DeviceEndpoint[0].EPSTATUSSET.reg = USB_DEVICE_EPSTATUSSET_BK0RDY; - pUsb->DEVICE.DeviceEndpoint[0].EPSTATUSCLR.reg = USB_DEVICE_EPSTATUSCLR_BK1RDY; - /* Configure control OUT Packet size to 64 bytes */ - usb_endpoint_table[0].DeviceDescBank[0].PCKSIZE.bit.SIZE = 3; - /* Configure control IN Packet size to 64 bytes */ - usb_endpoint_table[0].DeviceDescBank[1].PCKSIZE.bit.SIZE = 3; - /* Configure the data buffer address for control OUT */ - usb_endpoint_table[0].DeviceDescBank[0].ADDR.reg = (uint32_t)&udd_ep_out_cache_buffer[0]; - /* Configure the data buffer address for control IN */ - usb_endpoint_table[0].DeviceDescBank[1].ADDR.reg = (uint32_t)&udd_ep_in_cache_buffer[0]; - /* Set Multipacket size to 8 for control OUT and byte count to 0*/ - usb_endpoint_table[0].DeviceDescBank[0].PCKSIZE.bit.MULTI_PACKET_SIZE = 8; - usb_endpoint_table[0].DeviceDescBank[0].PCKSIZE.bit.BYTE_COUNT = 0; - pUsb->DEVICE.DeviceEndpoint[0].EPSTATUSCLR.reg = USB_DEVICE_EPSTATUSCLR_BK0RDY; - - // Reset current configuration value to 0 - pCdc->currentConfiguration = 0; - } else if (pUsb->DEVICE.DeviceEndpoint[0].EPINTFLAG.reg & USB_DEVICE_EPINTFLAG_RXSTP) { - AT91F_CDC_Enumerate(pCdc); - } - - return pCdc->currentConfiguration; -} - - -static volatile bool read_job = false; -//*---------------------------------------------------------------------------- -//* \fn USB_Read -//* \brief Read available data from Endpoint OUT -//*---------------------------------------------------------------------------- -static uint32_t USB_Read(P_USB_CDC pCdc, char *pData, uint32_t length) -{ - Usb *pUsb = pCdc->pUsb; - uint32_t packetSize = 0; - - if (!read_job) { - /* Set the buffer address for ep data */ - usb_endpoint_table[USB_EP_OUT].DeviceDescBank[0].ADDR.reg = (uint32_t)&udd_ep_out_cache_buffer[USB_EP_OUT-1]; - /* Set the byte count as zero */ - usb_endpoint_table[USB_EP_OUT].DeviceDescBank[0].PCKSIZE.bit.BYTE_COUNT = 0; - /* Set the byte count as zero */ - usb_endpoint_table[USB_EP_OUT].DeviceDescBank[0].PCKSIZE.bit.MULTI_PACKET_SIZE = 0; - /* Start the reception by clearing the bank 0 ready bit */ - pUsb->DEVICE.DeviceEndpoint[USB_EP_OUT].EPSTATUSCLR.bit.BK0RDY = true; - /* set the user flag */ - read_job = true; - } - - /* Check for Transfer Complete 0 flag */ - if ( pUsb->DEVICE.DeviceEndpoint[USB_EP_OUT].EPINTFLAG.bit.TRCPT & (1<<0) ) { - /* Set packet size */ - packetSize = MIN(usb_endpoint_table[USB_EP_OUT].DeviceDescBank[0].PCKSIZE.bit.BYTE_COUNT, length); - /* Copy read data to user buffer */ - memcpy(pData, udd_ep_out_cache_buffer[USB_EP_OUT-1], packetSize); - /* Clear the Transfer Complete 0 flag */ - //pUsb->DEVICE.DeviceEndpoint[USB_EP_OUT].EPINTFLAG.bit.TRCPT0 = true; - pUsb->DEVICE.DeviceEndpoint[USB_EP_OUT].EPINTFLAG.bit.TRCPT |= (1 << 0); - /* Clear the user flag */ - read_job = false; - } - - return packetSize; -} - -static uint32_t USB_Read_blocking(P_USB_CDC pCdc, char *pData, uint32_t length) -{ - Usb *pUsb = pCdc->pUsb; - - if (read_job) { - /* Stop the reception by setting the bank 0 ready bit */ - pUsb->DEVICE.DeviceEndpoint[USB_EP_OUT].EPSTATUSSET.bit.BK0RDY = true; - /* Clear the user flag */ - read_job = false; - } - - /* Set the buffer address for ep data */ - usb_endpoint_table[USB_EP_OUT].DeviceDescBank[0].ADDR.reg = ((uint32_t)pData); - /* Set the byte count as zero */ - usb_endpoint_table[USB_EP_OUT].DeviceDescBank[0].PCKSIZE.bit.BYTE_COUNT = 0; - /* Set the multi packet size as zero for multi-packet transfers where length > ep size */ - usb_endpoint_table[USB_EP_OUT].DeviceDescBank[0].PCKSIZE.bit.MULTI_PACKET_SIZE = length; - /* Clear the bank 0 ready flag */ - pUsb->DEVICE.DeviceEndpoint[USB_EP_OUT].EPSTATUSCLR.bit.BK0RDY = true; - /* Wait for transfer to complete */ - while (!( pUsb->DEVICE.DeviceEndpoint[USB_EP_OUT].EPINTFLAG.bit.TRCPT & (1<<0) )); - /* Clear Transfer complete 0 flag */ - //pUsb->DEVICE.DeviceEndpoint[USB_EP_OUT].EPINTFLAG.bit.TRCPT0 = true; - pUsb->DEVICE.DeviceEndpoint[USB_EP_OUT].EPINTFLAG.bit.TRCPT |= (1 << 0); - - return length; - -} - - -static uint32_t USB_Write(P_USB_CDC pCdc, const char *pData, uint32_t length, uint8_t ep_num) -{ - Usb *pUsb = pCdc->pUsb; - uint32_t data_address; - uint8_t buf_index; - - /* Set buffer index */ - buf_index = (ep_num == 0) ? 0 : 1; - - /* Check for requirement for multi-packet or auto zlp */ - if (length >= (1 << (usb_endpoint_table[ep_num].DeviceDescBank[1].PCKSIZE.bit.SIZE + 3))) { - /* Update the EP data address */ - data_address = (uint32_t) pData; - /* Enable auto zlp */ - usb_endpoint_table[ep_num].DeviceDescBank[1].PCKSIZE.bit.AUTO_ZLP = true; - } else { - /* Copy to local buffer */ - memcpy(udd_ep_in_cache_buffer[buf_index], pData, length); - /* Update the EP data address */ - data_address = (uint32_t) &udd_ep_in_cache_buffer[buf_index]; - } - - /* Set the buffer address for ep data */ - usb_endpoint_table[ep_num].DeviceDescBank[1].ADDR.reg = data_address; - /* Set the byte count as zero */ - usb_endpoint_table[ep_num].DeviceDescBank[1].PCKSIZE.bit.BYTE_COUNT = length; - /* Set the multi packet size as zero for multi-packet transfers where length > ep size */ - usb_endpoint_table[ep_num].DeviceDescBank[1].PCKSIZE.bit.MULTI_PACKET_SIZE = 0; - /* Clear the transfer complete flag */ - //pUsb->DEVICE.DeviceEndpoint[ep_num].EPINTFLAG.bit.TRCPT1 = true; - pUsb->DEVICE.DeviceEndpoint[ep_num].EPINTFLAG.bit.TRCPT |= (1 << 1); - /* Set the bank as ready */ - pUsb->DEVICE.DeviceEndpoint[ep_num].EPSTATUSSET.bit.BK1RDY = true; - - /* Wait for transfer to complete */ - while (!( pUsb->DEVICE.DeviceEndpoint[ep_num].EPINTFLAG.bit.TRCPT & (1<<1) )); - - return length; -} - -//*---------------------------------------------------------------------------- -//* \fn AT91F_USB_SendData -//* \brief Send Data through the control endpoint -//*---------------------------------------------------------------------------- - -static void AT91F_USB_SendData(P_USB_CDC pCdc, const char *pData, uint32_t length) -{ - USB_Write(pCdc, pData, length, 0); -} - -//*---------------------------------------------------------------------------- -//* \fn AT91F_USB_SendZlp -//* \brief Send zero length packet through the control endpoint -//*---------------------------------------------------------------------------- -void AT91F_USB_SendZlp(Usb *pUsb) -{ - /* Set the byte count as zero */ - usb_endpoint_table[0].DeviceDescBank[1].PCKSIZE.bit.BYTE_COUNT = 0; - /* Clear the transfer complete flag */ - //pUsb->DEVICE.DeviceEndpoint[0].EPINTFLAG.bit.TRCPT1 = true; - pUsb->DEVICE.DeviceEndpoint[0].EPINTFLAG.bit.TRCPT |= (1 << 1); - /* Set the bank as ready */ - pUsb->DEVICE.DeviceEndpoint[0].EPSTATUSSET.bit.BK1RDY = true; - /* Wait for transfer to complete */ - while (!( pUsb->DEVICE.DeviceEndpoint[0].EPINTFLAG.bit.TRCPT & (1<<1) )); -} - -//*---------------------------------------------------------------------------- -//* \fn AT91F_USB_SendStall -//* \brief Stall the control endpoint -//*---------------------------------------------------------------------------- -void AT91F_USB_SendStall(Usb *pUsb, bool direction_in) -{ - /* Check the direction */ - if (direction_in) { - /* Set STALL request on IN direction */ - //pUsb->DEVICE.DeviceEndpoint[0].EPSTATUSSET.reg = USB_DEVICE_EPSTATUSSET_STALLRQ1; - pUsb->DEVICE.DeviceEndpoint[0].EPSTATUSSET.bit.STALLRQ = (1<<1); - } else { - /* Set STALL request on OUT direction */ - //pUsb->DEVICE.DeviceEndpoint[0].EPSTATUSSET.reg = USB_DEVICE_EPSTATUSSET_STALLRQ0; - pUsb->DEVICE.DeviceEndpoint[0].EPSTATUSSET.bit.STALLRQ = (1<<0); - } -} - -//*---------------------------------------------------------------------------- -//* \fn AT91F_CDC_Enumerate -//* \brief This function is a callback invoked when a SETUP packet is received -//*---------------------------------------------------------------------------- -void AT91F_CDC_Enumerate(P_USB_CDC pCdc) -{ - Usb *pUsb = pCdc->pUsb; - static volatile uint8_t bmRequestType, bRequest, dir; - static volatile uint16_t wValue, wIndex, wLength, wStatus; - - /* Clear the Received Setup flag */ - pUsb->DEVICE.DeviceEndpoint[0].EPINTFLAG.bit.RXSTP = true; - - /* Read the USB request parameters */ - bmRequestType = udd_ep_out_cache_buffer[0][0]; - bRequest = udd_ep_out_cache_buffer[0][1]; - wValue = (udd_ep_out_cache_buffer[0][2] & 0xFF); - wValue |= (udd_ep_out_cache_buffer[0][3] << 8); - wIndex = (udd_ep_out_cache_buffer[0][4] & 0xFF); - wIndex |= (udd_ep_out_cache_buffer[0][5] << 8); - wLength = (udd_ep_out_cache_buffer[0][6] & 0xFF); - wLength |= (udd_ep_out_cache_buffer[0][7] << 8); - - /* Clear the Bank 0 ready flag on Control OUT */ - pUsb->DEVICE.DeviceEndpoint[0].EPSTATUSCLR.reg = USB_DEVICE_EPSTATUSCLR_BK0RDY; - - /* Handle supported standard device request Cf Table 9-3 in USB specification Rev 1.1 */ - switch ((bRequest << 8) | bmRequestType) { - case STD_GET_DESCRIPTOR: - if (wValue == 0x100) - /* Return Device Descriptor */ - AT91F_USB_SendData(pCdc, devDescriptor, MIN(sizeof(devDescriptor), wLength)); - else if (wValue == 0x200) - /* Return Configuration Descriptor */ - AT91F_USB_SendData(pCdc, cfgDescriptor, MIN(sizeof(cfgDescriptor), wLength)); - else - /* Stall the request */ - AT91F_USB_SendStall(pUsb, true); - break; - case STD_SET_ADDRESS: - /* Send ZLP */ - AT91F_USB_SendZlp(pUsb); - /* Set device address to the newly received address from host */ - pUsb->DEVICE.DADD.reg = USB_DEVICE_DADD_ADDEN | wValue; - break; - case STD_SET_CONFIGURATION: - /* Store configuration */ - pCdc->currentConfiguration = (uint8_t)wValue; - /* Send ZLP */ - AT91F_USB_SendZlp(pUsb); - /* Configure BULK OUT endpoint for CDC Data interface*/ - pUsb->DEVICE.DeviceEndpoint[USB_EP_OUT].EPCFG.reg = USB_DEVICE_EPCFG_EPTYPE0(3); - /* Set maximum packet size as 64 bytes */ - usb_endpoint_table[USB_EP_OUT].DeviceDescBank[0].PCKSIZE.bit.SIZE = 3; - pUsb->DEVICE.DeviceEndpoint[USB_EP_OUT].EPSTATUSSET.reg = USB_DEVICE_EPSTATUSSET_BK0RDY; - /* Configure the data buffer */ - usb_endpoint_table[USB_EP_OUT].DeviceDescBank[0].ADDR.reg = (uint32_t)&udd_ep_out_cache_buffer[1]; - /* Configure BULK IN endpoint for CDC Data interface */ - pUsb->DEVICE.DeviceEndpoint[USB_EP_IN].EPCFG.reg = USB_DEVICE_EPCFG_EPTYPE1(3); - /* Set maximum packet size as 64 bytes */ - usb_endpoint_table[USB_EP_IN].DeviceDescBank[1].PCKSIZE.bit.SIZE = 3; - pUsb->DEVICE.DeviceEndpoint[USB_EP_IN].EPSTATUSCLR.reg = USB_DEVICE_EPSTATUSCLR_BK1RDY; - /* Configure the data buffer */ - usb_endpoint_table[USB_EP_IN].DeviceDescBank[1].ADDR.reg = (uint32_t)&udd_ep_in_cache_buffer[1]; - /* Configure INTERRUPT IN endpoint for CDC COMM interface*/ - pUsb->DEVICE.DeviceEndpoint[USB_EP_COMM].EPCFG.reg = USB_DEVICE_EPCFG_EPTYPE1(4); - /* Set maximum packet size as 64 bytes */ - usb_endpoint_table[USB_EP_COMM].DeviceDescBank[1].PCKSIZE.bit.SIZE = 0; - pUsb->DEVICE.DeviceEndpoint[USB_EP_COMM].EPSTATUSCLR.reg = USB_DEVICE_EPSTATUSCLR_BK1RDY; - break; - case STD_GET_CONFIGURATION: - /* Return current configuration value */ - AT91F_USB_SendData(pCdc, (char *) &(pCdc->currentConfiguration), sizeof(pCdc->currentConfiguration)); - break; - case STD_GET_STATUS_ZERO: - wStatus = 0; - AT91F_USB_SendData(pCdc, (char *) &wStatus, sizeof(wStatus)); - break; - case STD_GET_STATUS_INTERFACE: - wStatus = 0; - AT91F_USB_SendData(pCdc, (char *) &wStatus, sizeof(wStatus)); - break; - case STD_GET_STATUS_ENDPOINT: - wStatus = 0; - dir = wIndex & 80; - wIndex &= 0x0F; - if (wIndex <= 3) { - if (dir) { - //wStatus = (pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUS.reg & USB_DEVICE_EPSTATUSSET_STALLRQ1) ? 1 : 0; - wStatus = (pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUS.bit.STALLRQ & (1<<1)) ? 1 : 0; - } else { - //wStatus = (pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUS.reg & USB_DEVICE_EPSTATUSSET_STALLRQ0) ? 1 : 0; - wStatus = (pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUS.bit.STALLRQ & (1<<0)) ? 1 : 0; - } - /* Return current status of endpoint */ - AT91F_USB_SendData(pCdc, (char *) &wStatus, sizeof(wStatus)); - } - else - /* Stall the request */ - AT91F_USB_SendStall(pUsb, true); - break; - case STD_SET_FEATURE_ZERO: - /* Stall the request */ - AT91F_USB_SendStall(pUsb, true); - break; - case STD_SET_FEATURE_INTERFACE: - /* Send ZLP */ - AT91F_USB_SendZlp(pUsb); - break; - case STD_SET_FEATURE_ENDPOINT: - dir = wIndex & 0x80; - wIndex &= 0x0F; - if ((wValue == 0) && wIndex && (wIndex <= 3)) { - /* Set STALL request for the endpoint */ - if (dir) { - //pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUSSET.reg = USB_DEVICE_EPSTATUSSET_STALLRQ1; - pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUSSET.bit.STALLRQ = (1<<1); - } else { - //pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUSSET.reg = USB_DEVICE_EPSTATUSSET_STALLRQ0; - pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUSSET.bit.STALLRQ = (1<<0); - } - /* Send ZLP */ - AT91F_USB_SendZlp(pUsb); - } - else - /* Stall the request */ - AT91F_USB_SendStall(pUsb, true); - break; - case STD_CLEAR_FEATURE_ZERO: - /* Stall the request */ - AT91F_USB_SendStall(pUsb, true); - break; - case STD_CLEAR_FEATURE_INTERFACE: - /* Send ZLP */ - AT91F_USB_SendZlp(pUsb); - break; - case STD_CLEAR_FEATURE_ENDPOINT: - dir = wIndex & 0x80; - wIndex &= 0x0F; - if ((wValue == 0) && wIndex && (wIndex <= 3)) { - if (dir) { - if (pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUS.bit.STALLRQ & (1<<1)) { - // Remove stall request - //pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUSCLR.reg = USB_DEVICE_EPSTATUSCLR_STALLRQ1; - pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUSCLR.bit.STALLRQ = (1<<1); - if (pUsb->DEVICE.DeviceEndpoint[wIndex].EPINTFLAG.bit.STALL & (1<<1)) { - pUsb->DEVICE.DeviceEndpoint[wIndex].EPINTFLAG.bit.STALL = (1<<1); - // The Stall has occurred, then reset data toggle - pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUSCLR.reg = USB_DEVICE_EPSTATUSSET_DTGLIN; - } - } - } else { - if (pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUS.bit.STALLRQ & (1<<0)) { - // Remove stall request - //pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUSCLR.reg = USB_DEVICE_EPSTATUSCLR_STALLRQ0; - pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUSCLR.bit.STALLRQ = (1<<0); - if (pUsb->DEVICE.DeviceEndpoint[wIndex].EPINTFLAG.bit.STALL & (1<<0)) { - pUsb->DEVICE.DeviceEndpoint[wIndex].EPINTFLAG.bit.STALL = (1<<0); - // The Stall has occurred, then reset data toggle - pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUSCLR.reg = USB_DEVICE_EPSTATUSSET_DTGLOUT; - } - } - } - /* Send ZLP */ - AT91F_USB_SendZlp(pUsb); - } - else { - AT91F_USB_SendStall(pUsb, true); - } - break; - - // handle CDC class requests - case SET_LINE_CODING: - /* Send ZLP */ - AT91F_USB_SendZlp(pUsb); - break; - case GET_LINE_CODING: - /* Send current line coding */ - AT91F_USB_SendData(pCdc, (char *) &line_coding, MIN(sizeof(usb_cdc_line_coding_t), wLength)); - break; - case SET_CONTROL_LINE_STATE: - /* Store the current connection */ - pCdc->currentConnection = wValue; - /* Send ZLP */ - AT91F_USB_SendZlp(pUsb); - break; - default: - /* Stall the request */ - AT91F_USB_SendStall(pUsb, true); - break; - } -} - -P_USB_CDC usb_init(void) -{ - pCdc.pUsb = USB; - - /* Initialize USB */ - AT91F_InitUSB(); - /* Get the default CDC structure settings */ - AT91F_CDC_Open((P_USB_CDC)&pCdc, pCdc.pUsb); - return &pCdc; -} - -int cdc_putc(int value) -{ - /* Send single byte on USB CDC */ - USB_Write(&pCdc, (const char *)&value, 1, USB_EP_IN); - return 1; -} - -int cdc_getc(void) -{ - uint8_t rx_char; - /* Read singly byte on USB CDC */ - USB_Read(&pCdc, (char *)&rx_char, 1); - return (int)rx_char; -} - -bool cdc_is_rx_ready(void) -{ - /* Check whether the device is configured */ - if ( !USB_IsConfigured(&pCdc) ) - return 0; - - /* Return transfer complete 0 flag status */ - return (pCdc.pUsb->DEVICE.DeviceEndpoint[USB_EP_OUT].EPINTFLAG.bit.TRCPT & (1<<0)); -} - -uint32_t cdc_write_buf(void const* data, uint32_t length) -{ - /* Send the specified number of bytes on USB CDC */ - USB_Write(&pCdc, (const char *)data, length, USB_EP_IN); - return length; -} - -uint32_t cdc_read_buf(void* data, uint32_t length) -{ - /* Check whether the device is configured */ - if ( !USB_IsConfigured(&pCdc) ) - return 0; - - /* Read from USB CDC */ - return USB_Read(&pCdc, (char *)data, length); -} - -uint32_t cdc_read_buf_xmd(void* data, uint32_t length) -{ - /* Check whether the device is configured */ - if ( !USB_IsConfigured(&pCdc) ) - return 0; - - /* Blocking read till specified number of bytes is received */ - // XXX: USB_Read_blocking is not reliable - // return USB_Read_blocking(&pCdc, (char *)data, length); - - char *dst = (char *)data; - uint32_t remaining = length; - while (remaining) { - uint32_t readed = USB_Read(&pCdc, (char *)dst, remaining); - remaining -= readed; - dst += readed; - } - - return length; -} diff --git a/bootloaders/zero/drivers/cdc_enumerate.h b/bootloaders/zero/drivers/cdc_enumerate.h deleted file mode 100644 index 41002626f..000000000 --- a/bootloaders/zero/drivers/cdc_enumerate.h +++ /dev/null @@ -1,126 +0,0 @@ -/* ---------------------------------------------------------------------------- - * SAM Software Package License - * ---------------------------------------------------------------------------- - * Copyright (c) 2011-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. - * ---------------------------------------------------------------------------- - */ - -#ifndef CDC_ENUMERATE_H -#define CDC_ENUMERATE_H - -#include "sam.h" -#include "stdbool.h" - -#define USB_EP_OUT 2 -#define USB_EP_OUT_SIZE 0x40 -#define USB_EP_IN 1 -#define USB_EP_IN_SIZE 0x40 -#define USB_EP_COMM 3 -#define MAX_EP 4 - -#define NVM_USB_PAD_TRANSN_POS 45 -#define NVM_USB_PAD_TRANSN_SIZE 5 -#define NVM_USB_PAD_TRANSP_POS 50 -#define NVM_USB_PAD_TRANSP_SIZE 5 -#define NVM_USB_PAD_TRIM_POS 55 -#define NVM_USB_PAD_TRIM_SIZE 3 - -typedef struct _USB_CDC -{ - // Private members - Usb *pUsb; - uint8_t currentConfiguration; - uint8_t currentConnection; - // Public Methods: - uint8_t (*IsConfigured)(struct _USB_CDC *pCdc); - uint32_t (*Write) (struct _USB_CDC *pCdc, const char *pData, uint32_t length, uint8_t ep_num); - uint32_t (*Read) (struct _USB_CDC *pCdc, char *pData, uint32_t length); -} USB_CDC, *P_USB_CDC; - -typedef struct { - uint32_t dwDTERate; - uint8_t bCharFormat; - uint8_t bParityType; - uint8_t bDataBits; -} usb_cdc_line_coding_t; - -/** - * \brief Initializes the USB module - * - * \return Pointer to the USB CDC structure - */ -P_USB_CDC usb_init(void); - -/** - * \brief Sends a single byte through USB CDC - * - * \param Data to send - * \return number of data sent - */ -int cdc_putc(int value); - -/** - * \brief Reads a single byte through USB CDC - * - * \return Data read through USB - */ -int cdc_getc(void); - -/** - * \brief Checks if a character has been received on USB CDC - * - * \return \c 1 if a byte is ready to be read. - */ -bool cdc_is_rx_ready(void); - -/** - * \brief Sends buffer on USB CDC - * - * \param data pointer - * \param number of data to send - * \return number of data sent - */ -uint32_t cdc_write_buf(void const* data, uint32_t length); - -/** - * \brief Gets data on USB CDC - * - * \param data pointer - * \param number of data to read - * \return number of data read - */ -uint32_t cdc_read_buf(void* data, uint32_t length); - -/** - * \brief Gets specified number of bytes on USB CDC - * - * \param data pointer - * \param number of data to read - * \return number of data read - */ -uint32_t cdc_read_buf_xmd(void* data, uint32_t length); - - -#endif // CDC_ENUMERATE_H diff --git a/bootloaders/zero/main.c b/bootloaders/zero/main.c index 4ad7abd54..3b18872a8 100644 --- a/bootloaders/zero/main.c +++ b/bootloaders/zero/main.c @@ -1,89 +1,37 @@ -/* ---------------------------------------------------------------------------- - * SAM Software Package License - * ---------------------------------------------------------------------------- - * Copyright (c) 2011-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. - * ---------------------------------------------------------------------------- - */ - -/** - * -------------------- - * SAM-BA Implementation on SAMD21 - * -------------------- - * Requirements to use SAM-BA : - * - * Supported communication interfaces : - * -------------------- - * - * SERCOM5 : RX:PB23 TX:PB22 - * Baudrate : 115200 8N1 - * - * USB : D-:PA24 D+:PA25 - * - * Pins Usage - * -------------------- - * The following pins are used by the program : - * PA25 : input/output - * PA24 : input/output - * PB23 : input - * PB22 : output - * PA15 : input - * - * The application board shall avoid driving the PA25,PA24,PB23,PB22 and PA15 signals - * while the boot program is running (after a POR for example) - * - * Clock system - * -------------------- - * CPU clock source (GCLK_GEN_0) - 8MHz internal oscillator (OSC8M) - * SERCOM5 core GCLK source (GCLK_ID_SERCOM5_CORE) - GCLK_GEN_0 (i.e., OSC8M) - * GCLK Generator 1 source (GCLK_GEN_1) - 48MHz DFLL in Clock Recovery mode (DFLL48M) - * USB GCLK source (GCLK_ID_USB) - GCLK_GEN_1 (i.e., DFLL in CRM mode) - * - * Memory Mapping - * -------------------- - * SAM-BA code will be located at 0x0 and executed before any applicative code. - * - * Applications compiled to be executed along with the bootloader will start at - * 0x2000 - * Before jumping to the application, the bootloader changes the VTOR register - * to use the interrupt vectors of the application @0x2000.<- not required as - * application code is taking care of this - * +/* + Copyright (c) 2015 Arduino LLC. All right reserved. + Copyright (c) 2015 Atmel Corporation/Thibaut VIARD. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA */ #include #include -#include "compiler.h" #include "sam_ba_monitor.h" -#include "usart_sam_ba.h" -#include "main.h" -#include "cdc_enumerate.h" +#include "sam_ba_serial.h" +#include "board_definitions.h" +#include "board_driver_led.h" +#include "sam_ba_usb.h" +#include "sam_ba_cdc.h" -#define NVM_SW_CALIB_DFLL48M_COARSE_VAL 58 -#define NVM_SW_CALIB_DFLL48M_FINE_VAL 64 +extern uint32_t __sketch_vectors_ptr; // Exported value from linker script +extern void board_init(void); -static void check_start_application(void); +#if (defined DEBUG) && (DEBUG == 1) +volatile uint32_t* pulSketch_Start_Address; +#endif static volatile bool main_b_cdc_enable = false; @@ -93,156 +41,106 @@ static volatile bool main_b_cdc_enable = false; */ static void check_start_application(void) { - volatile PortGroup *led_port = (volatile PortGroup *)&PORT->Group[1]; - led_port->DIRSET.reg = (1<<30); - led_port->OUTCLR.reg = (1<<30); +// LED_init(); +// LED_off(); #if defined(BOOT_DOUBLE_TAP_ADDRESS) - #define DOUBLE_TAP_MAGIC 0x07738135 - if (PM->RCAUSE.bit.POR) - { - /* On power-on initialize double-tap */ - BOOT_DOUBLE_TAP_DATA = 0; - } - else - { - if (BOOT_DOUBLE_TAP_DATA == DOUBLE_TAP_MAGIC) { - /* Second tap, stay in bootloader */ - BOOT_DOUBLE_TAP_DATA = 0; - return; - } - - /* First tap */ - BOOT_DOUBLE_TAP_DATA = DOUBLE_TAP_MAGIC; - - /* Wait 0.5sec to see if the user tap reset again */ - for (uint32_t i=0; i<125000; i++) /* 500ms */ - /* force compiler to not optimize this... */ - __asm__ __volatile__(""); - - /* Timeout happened, continue boot... */ - BOOT_DOUBLE_TAP_DATA = 0; - } + #define DOUBLE_TAP_MAGIC 0x07738135 + if (PM->RCAUSE.bit.POR) + { + /* On power-on initialize double-tap */ + BOOT_DOUBLE_TAP_DATA = 0; + } + else + { + if (BOOT_DOUBLE_TAP_DATA == DOUBLE_TAP_MAGIC) + { + /* Second tap, stay in bootloader */ + BOOT_DOUBLE_TAP_DATA = 0; + return; + } + + /* First tap */ + BOOT_DOUBLE_TAP_DATA = DOUBLE_TAP_MAGIC; + + /* Wait 0.5sec to see if the user tap reset again. + * The loop value is based on SAMD21 default 1MHz clock @ reset. + */ + for (uint32_t i=0; i<125000; i++) /* 500ms */ + /* force compiler to not optimize this... */ + __asm__ __volatile__(""); + + /* Timeout happened, continue boot... */ + BOOT_DOUBLE_TAP_DATA = 0; + } #endif - uint32_t app_start_address; - - /* Load the Reset Handler address of the application */ - app_start_address = *(uint32_t *)(APP_START_ADDRESS + 4); - - /** - * Test reset vector of application @APP_START_ADDRESS+4 - * Stay in SAM-BA if *(APP_START+0x4) == 0xFFFFFFFF - * Application erased condition - */ - if (app_start_address == 0xFFFFFFFF) { - /* Stay in bootloader */ - return; - } +#if (!defined DEBUG) || ((defined DEBUG) && (DEBUG == 0)) +uint32_t* pulSketch_Start_Address; +#endif + /* + * Test sketch stack pointer @ &__sketch_vectors_ptr + * Stay in SAM-BA if value @ (&__sketch_vectors_ptr) == 0xFFFFFFFF (Erased flash cell value) + */ + if (__sketch_vectors_ptr == 0xFFFFFFFF) + { + /* Stay in bootloader */ + return; + } + + /* + * Load the sketch Reset Handler address + * __sketch_vectors_ptr is exported from linker script and point on first 32b word of sketch vector table + * First 32b word is sketch stack + * Second 32b word is sketch entry point: Reset_Handler() + */ + pulSketch_Start_Address = &__sketch_vectors_ptr ; + pulSketch_Start_Address++ ; + + /* + * Test vector table address of sketch @ &__sketch_vectors_ptr + * Stay in SAM-BA if this function is not aligned enough, ie not valid + */ + if ( ((uint32_t)(&__sketch_vectors_ptr) & ~SCB_VTOR_TBLOFF_Msk) != 0x00) + { + /* Stay in bootloader */ + return; + } + +/* #if defined(BOOT_LOAD_PIN) - volatile PortGroup *boot_port = (volatile PortGroup *)(&(PORT->Group[BOOT_LOAD_PIN / 32])); - volatile bool boot_en; - - /* Enable the input mode in Boot GPIO Pin */ - boot_port->DIRCLR.reg = BOOT_PIN_MASK; - boot_port->PINCFG[BOOT_LOAD_PIN & 0x1F].reg = PORT_PINCFG_INEN | PORT_PINCFG_PULLEN; - boot_port->OUTSET.reg = BOOT_PIN_MASK; - /* Read the BOOT_LOAD_PIN status */ - boot_en = (boot_port->IN.reg) & BOOT_PIN_MASK; - - /* Check the bootloader enable condition */ - if (!boot_en) { - /* Stay in bootloader */ - return; - } + volatile PortGroup *boot_port = (volatile PortGroup *)(&(PORT->Group[BOOT_LOAD_PIN / 32])); + volatile bool boot_en; + + // Enable the input mode in Boot GPIO Pin + boot_port->DIRCLR.reg = BOOT_PIN_MASK; + boot_port->PINCFG[BOOT_LOAD_PIN & 0x1F].reg = PORT_PINCFG_INEN | PORT_PINCFG_PULLEN; + boot_port->OUTSET.reg = BOOT_PIN_MASK; + // Read the BOOT_LOAD_PIN status + boot_en = (boot_port->IN.reg) & BOOT_PIN_MASK; + + // Check the bootloader enable condition + if (!boot_en) + { + // Stay in bootloader + return; + } #endif +*/ - led_port->OUTSET.reg = (1<<30); +// LED_on(); - /* Rebase the Stack Pointer */ - __set_MSP(*(uint32_t *) APP_START_ADDRESS); + /* Rebase the Stack Pointer */ + __set_MSP( (uint32_t)(__sketch_vectors_ptr) ); - /* Rebase the vector table base address */ - SCB->VTOR = ((uint32_t) APP_START_ADDRESS & SCB_VTOR_TBLOFF_Msk); + /* Rebase the vector table base address */ + SCB->VTOR = ((uint32_t)(&__sketch_vectors_ptr) & SCB_VTOR_TBLOFF_Msk); - /* Jump to application Reset Handler in the application */ - asm("bx %0"::"r"(app_start_address)); + /* Jump to application Reset Handler in the application */ + asm("bx %0"::"r"(*pulSketch_Start_Address)); } -void system_init() -{ - /* Configure flash wait states */ - NVMCTRL->CTRLB.bit.RWS = FLASH_WAIT_STATES; - - /* Set OSC8M prescalar to divide by 1 */ - SYSCTRL->OSC8M.bit.PRESC = 0; - - /* Configure OSC8M as source for GCLK_GEN0 */ - GCLK_GENCTRL_Type genctrl={0}; - uint32_t temp_genctrl; - GCLK->GENCTRL.bit.ID = 0; /* GENERATOR_ID - GCLK_GEN_0 */ - while(GCLK->STATUS.reg & GCLK_STATUS_SYNCBUSY); - temp_genctrl = GCLK->GENCTRL.reg; - genctrl.bit.SRC = GCLK_GENCTRL_SRC_OSC8M_Val; - genctrl.bit.GENEN = true; - genctrl.bit.RUNSTDBY = false; - GCLK->GENCTRL.reg = (genctrl.reg | temp_genctrl); - while(GCLK->STATUS.reg & GCLK_STATUS_SYNCBUSY); - -#if SAM_BA_INTERFACE == SAM_BA_USBCDC_ONLY || SAM_BA_INTERFACE == SAM_BA_BOTH_INTERFACES - SYSCTRL_DFLLCTRL_Type dfllctrl_conf = {0}; - SYSCTRL_DFLLVAL_Type dfllval_conf = {0}; - uint32_t coarse =( *((uint32_t *)(NVMCTRL_OTP4) - + (NVM_SW_CALIB_DFLL48M_COARSE_VAL / 32)) - >> (NVM_SW_CALIB_DFLL48M_COARSE_VAL % 32)) - & ((1 << 6) - 1); - if (coarse == 0x3f) { - coarse = 0x1f; - } - uint32_t fine =( *((uint32_t *)(NVMCTRL_OTP4) - + (NVM_SW_CALIB_DFLL48M_FINE_VAL / 32)) - >> (NVM_SW_CALIB_DFLL48M_FINE_VAL % 32)) - & ((1 << 10) - 1); - if (fine == 0x3ff) { - fine = 0x1ff; - } - dfllval_conf.bit.COARSE = coarse; - dfllval_conf.bit.FINE = fine; - dfllctrl_conf.bit.USBCRM = true; - dfllctrl_conf.bit.BPLCKC = false; - dfllctrl_conf.bit.QLDIS = false; - dfllctrl_conf.bit.CCDIS = true; - dfllctrl_conf.bit.ENABLE = true; - - SYSCTRL->DFLLCTRL.bit.ONDEMAND = false; - while (!(SYSCTRL->PCLKSR.reg & SYSCTRL_PCLKSR_DFLLRDY)); - SYSCTRL->DFLLMUL.reg = 48000; - SYSCTRL->DFLLVAL.reg = dfllval_conf.reg; - SYSCTRL->DFLLCTRL.reg = dfllctrl_conf.reg; - - GCLK_CLKCTRL_Type clkctrl={0}; - uint16_t temp; - GCLK->CLKCTRL.bit.ID = 0; /* GCLK_ID - DFLL48M Reference */ - temp = GCLK->CLKCTRL.reg; - clkctrl.bit.CLKEN = true; - clkctrl.bit.WRTLOCK = false; - clkctrl.bit.GEN = GCLK_CLKCTRL_GEN_GCLK0_Val; - GCLK->CLKCTRL.reg = (clkctrl.reg | temp); - - /* Configure DFLL48M as source for GCLK_GEN1 */ - GCLK->GENCTRL.bit.ID = 1; /* GENERATOR_ID - GCLK_GEN_1 */ - while(GCLK->STATUS.reg & GCLK_STATUS_SYNCBUSY); - temp_genctrl = GCLK->GENCTRL.reg; - genctrl.bit.SRC = GCLK_GENCTRL_SRC_DFLL48M_Val; - genctrl.bit.GENEN = true; - genctrl.bit.RUNSTDBY = false; - GCLK->GENCTRL.reg = (genctrl.reg | temp_genctrl); - while(GCLK->STATUS.reg & GCLK_STATUS_SYNCBUSY); -#endif -} - - #if DEBUG_ENABLE # define DEBUG_PIN_HIGH port_pin_set_output_level(BOOT_LED, 1) # define DEBUG_PIN_LOW port_pin_set_output_level(BOOT_LED, 0) @@ -251,61 +149,68 @@ void system_init() # define DEBUG_PIN_LOW do{}while(0) #endif - /** * \brief SAMD21 SAM-BA Main loop. * \return Unused (ANSI-C compatibility). */ int main(void) { -#if SAM_BA_INTERFACE == SAM_BA_USBCDC_ONLY || SAM_BA_INTERFACE == SAM_BA_BOTH_INTERFACES - P_USB_CDC pCdc; +#if SAM_BA_INTERFACE == SAM_BA_USBCDC_ONLY || SAM_BA_INTERFACE == SAM_BA_BOTH_INTERFACES + P_USB_CDC pCdc; #endif - DEBUG_PIN_HIGH; + DEBUG_PIN_HIGH; - /* Jump in application if condition is satisfied */ - check_start_application(); + /* Jump in application if condition is satisfied */ + check_start_application(); - /* We have determined we should stay in the monitor. */ - /* System initialization */ - system_init(); - cpu_irq_enable(); + /* We have determined we should stay in the monitor. */ + /* System initialization */ + board_init(); + __enable_irq(); - #if SAM_BA_INTERFACE == SAM_BA_UART_ONLY || SAM_BA_INTERFACE == SAM_BA_BOTH_INTERFACES - /* UART is enabled in all cases */ - usart_open(); +#if SAM_BA_INTERFACE == SAM_BA_UART_ONLY || SAM_BA_INTERFACE == SAM_BA_BOTH_INTERFACES + /* UART is enabled in all cases */ + serial_open(); #endif #if SAM_BA_INTERFACE == SAM_BA_USBCDC_ONLY || SAM_BA_INTERFACE == SAM_BA_BOTH_INTERFACES - pCdc = (P_USB_CDC)usb_init(); + pCdc = usb_init(); #endif - DEBUG_PIN_LOW; - /* Wait for a complete enum on usb or a '#' char on serial line */ - while (1) { + + DEBUG_PIN_LOW; + + /* Wait for a complete enum on usb or a '#' char on serial line */ + while (1) + { #if SAM_BA_INTERFACE == SAM_BA_USBCDC_ONLY || SAM_BA_INTERFACE == SAM_BA_BOTH_INTERFACES - if (pCdc->IsConfigured(pCdc) != 0) { - main_b_cdc_enable = true; - } - - //Check if a USB enumeration has succeeded - //And com port was opened - if (main_b_cdc_enable) { - sam_ba_monitor_init(SAM_BA_INTERFACE_USBCDC); - //SAM-BA on USB loop - while(1) { - sam_ba_monitor_run(); - } - } + if (pCdc->IsConfigured(pCdc) != 0) + { + main_b_cdc_enable = true; + } + + /* Check if a USB enumeration has succeeded and if comm port has been opened */ + if (main_b_cdc_enable) + { + sam_ba_monitor_init(SAM_BA_INTERFACE_USBCDC); + /* SAM-BA on USB loop */ + while( 1 ) + { + sam_ba_monitor_run(); + } + } #endif + #if SAM_BA_INTERFACE == SAM_BA_UART_ONLY || SAM_BA_INTERFACE == SAM_BA_BOTH_INTERFACES - /* Check if a '#' has been received */ - if (!main_b_cdc_enable && usart_sharp_received()) { - sam_ba_monitor_init(SAM_BA_INTERFACE_USART); - /* SAM-BA on UART loop */ - while(1) { - sam_ba_monitor_run(); - } - } + /* Check if a '#' has been received */ + if (!main_b_cdc_enable && serial_sharp_received()) + { + sam_ba_monitor_init(SAM_BA_INTERFACE_USART); + /* SAM-BA on Serial loop */ + while(1) + { + sam_ba_monitor_run(); + } + } #endif - } + } } diff --git a/bootloaders/zero/main.h b/bootloaders/zero/main.h deleted file mode 100644 index b8c58ec79..000000000 --- a/bootloaders/zero/main.h +++ /dev/null @@ -1,62 +0,0 @@ -/* ---------------------------------------------------------------------------- - * SAM Software Package License - * ---------------------------------------------------------------------------- - * Copyright (c) 2011-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. - * ---------------------------------------------------------------------------- - */ - -#pragma once - -/* - * If BOOT_DOUBLE_TAP_ADDRESS is defined the bootloader is started by - * quickly tapping two times on the reset button. - * BOOT_DOUBLE_TAP_ADDRESS must point to a free SRAM cell that must not - * be touched from the loaded application. - */ -#define BOOT_DOUBLE_TAP_ADDRESS 0x20007FFC -#define BOOT_DOUBLE_TAP_DATA (*((volatile uint32_t *) BOOT_DOUBLE_TAP_ADDRESS)) - -/* - * If BOOT_LOAD_PIN is defined the bootloader is started if the selected - * pin is tied LOW. - */ -//#define BOOT_LOAD_PIN PIN_PA21 // Pin 7 -//#define BOOT_LOAD_PIN PIN_PA15 // Pin 5 -#define BOOT_PIN_MASK (1U << (BOOT_LOAD_PIN & 0x1f)) - -#define CPU_FREQUENCY 8000000 -#define APP_START_ADDRESS 0x00002000 -#define FLASH_WAIT_STATES 1 - -#define BOOT_USART_MODULE SERCOM0 -//#define BOOT_USART_MODULE SERCOM5 -#define BOOT_USART_MUX_SETTINGS UART_RX_PAD3_TX_PAD2 -//#define BOOT_USART_PAD3 PINMUX_PB23D_SERCOM5_PAD3 -//#define BOOT_USART_PAD2 PINMUX_PB22D_SERCOM5_PAD2 -#define BOOT_USART_PAD3 PINMUX_PA11C_SERCOM0_PAD3 -#define BOOT_USART_PAD2 PINMUX_PA10C_SERCOM0_PAD2 -#define BOOT_USART_PAD1 PINMUX_UNUSED -#define BOOT_USART_PAD0 PINMUX_UNUSED - diff --git a/bootloaders/zero/readme.txt b/bootloaders/zero/readme.txt deleted file mode 100644 index 8c760449e..000000000 --- a/bootloaders/zero/readme.txt +++ /dev/null @@ -1,21 +0,0 @@ -1- Prerequisites - -IAR Embedded Workbench for ARM 7.30 - -2- Selecting between USB and UART interface - -Set the define SAM_BA_INTERFACE to -SAM_BA_UART_ONLY for only UART interface -SAM_BA_USBCDC_ONLY for only USB CDC interface -SAM_BA_BOTH_INTERFACES for enabling both the interfaces - -SAM_BA_INTERFACE value should be modified in -Project Options -> C/C++ Compiler -> Preprocessor -> Defined symbols -Project Options -> Assembler -> Preprocessor -> Defined symbols - -3- Start application check - -Bootloader checks for the state of BOOT_LOAD_PIN (configurable by the user from main.h). If BOOT_LOAD_PIN is pulled low, bootloader execution is resumed. -Else, the first location of application is fetched and checked. If it is empty (0xFFFFFFFF), then bootloader execution is resumed. Else it jumps to application and starts execution from there. - -Currently, BOOT_LOAD_PIN is PA15 of SAMD21G18A, pin 5 of Arduino Zero board. diff --git a/bootloaders/zero/sam_ba_cdc.c b/bootloaders/zero/sam_ba_cdc.c new file mode 100644 index 000000000..fc5efe348 --- /dev/null +++ b/bootloaders/zero/sam_ba_cdc.c @@ -0,0 +1,98 @@ +/* + Copyright (c) 2015 Arduino LLC. All right reserved. + Copyright (c) 2015 Atmel Corporation/Thibaut VIARD. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include "sam_ba_cdc.h" +#include "board_driver_usb.h" + +usb_cdc_line_coding_t line_coding= +{ + 115200, // baudrate + 0, // 1 Stop Bit + 0, // None Parity + 8 // 8 Data bits +}; + +#define pCdc (&sam_ba_cdc) + +int cdc_putc(/*P_USB_CDC pCdc,*/ int value) +{ + /* Send single byte on USB CDC */ + USB_Write(pCdc->pUsb, (const char *)&value, 1, USB_EP_IN); + + return 1; +} + +int cdc_getc(/*P_USB_CDC pCdc*/void) +{ + uint8_t rx_char; + + /* Read singly byte on USB CDC */ + USB_Read(pCdc->pUsb, (char *)&rx_char, 1); + + return (int)rx_char; +} + +bool cdc_is_rx_ready(/*P_USB_CDC pCdc*/void) +{ + /* Check whether the device is configured */ + if ( !USB_IsConfigured(pCdc) ) + return 0; + + /* Return transfer complete 0 flag status */ + return (pCdc->pUsb->DEVICE.DeviceEndpoint[USB_EP_OUT].EPINTFLAG.bit.TRCPT & (1<<0)); +} + +uint32_t cdc_write_buf(/*P_USB_CDC pCdc,*/ void const* data, uint32_t length) +{ + /* Send the specified number of bytes on USB CDC */ + USB_Write(pCdc->pUsb, (const char *)data, length, USB_EP_IN); + return length; +} + +uint32_t cdc_read_buf(/*P_USB_CDC pCdc,*/ void* data, uint32_t length) +{ + /* Check whether the device is configured */ + if ( !USB_IsConfigured(pCdc) ) + return 0; + + /* Read from USB CDC */ + return USB_Read(pCdc->pUsb, (char *)data, length); +} + +uint32_t cdc_read_buf_xmd(/*P_USB_CDC pCdc,*/ void* data, uint32_t length) +{ + /* Check whether the device is configured */ + if ( !USB_IsConfigured(pCdc) ) + return 0; + + /* Blocking read till specified number of bytes is received */ + // XXX: USB_Read_blocking is not reliable + // return USB_Read_blocking(pCdc, (char *)data, length); + + char *dst = (char *)data; + uint32_t remaining = length; + while (remaining) + { + uint32_t readed = USB_Read(pCdc->pUsb, (char *)dst, remaining); + remaining -= readed; + dst += readed; + } + + return length; +} diff --git a/bootloaders/zero/sam_ba_cdc.h b/bootloaders/zero/sam_ba_cdc.h new file mode 100644 index 000000000..49b7643cf --- /dev/null +++ b/bootloaders/zero/sam_ba_cdc.h @@ -0,0 +1,91 @@ +/* + Copyright (c) 2015 Arduino LLC. All right reserved. + Copyright (c) 2015 Atmel Corporation/Thibaut VIARD. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _SAM_BA_USB_CDC_H_ +#define _SAM_BA_USB_CDC_H_ + +#include +#include "sam_ba_usb.h" + +typedef struct +{ + uint32_t dwDTERate; + uint8_t bCharFormat; + uint8_t bParityType; + uint8_t bDataBits; +} usb_cdc_line_coding_t; + +/* CDC Class Specific Request Code */ +#define GET_LINE_CODING 0x21A1 +#define SET_LINE_CODING 0x2021 +#define SET_CONTROL_LINE_STATE 0x2221 + +extern usb_cdc_line_coding_t line_coding; + + +/** + * \brief Sends a single byte through USB CDC + * + * \param Data to send + * \return number of data sent + */ +int cdc_putc(/*P_USB_CDC pCdc,*/ int value); + +/** + * \brief Reads a single byte through USB CDC + * + * \return Data read through USB + */ +int cdc_getc(/*P_USB_CDC pCdc*/); + +/** + * \brief Checks if a character has been received on USB CDC + * + * \return \c 1 if a byte is ready to be read. + */ +bool cdc_is_rx_ready(/*P_USB_CDC pCdc*/); + +/** + * \brief Sends buffer on USB CDC + * + * \param data pointer + * \param number of data to send + * \return number of data sent + */ +uint32_t cdc_write_buf(/*P_USB_CDC pCdc,*/ void const* data, uint32_t length); + +/** + * \brief Gets data on USB CDC + * + * \param data pointer + * \param number of data to read + * \return number of data read + */ +uint32_t cdc_read_buf(/*P_USB_CDC pCdc,*/ void* data, uint32_t length); + +/** + * \brief Gets specified number of bytes on USB CDC + * + * \param data pointer + * \param number of data to read + * \return number of data read + */ +uint32_t cdc_read_buf_xmd(/*P_USB_CDC pCdc,*/ void* data, uint32_t length); + +#endif // _SAM_BA_USB_CDC_H_ diff --git a/bootloaders/zero/sam_ba_monitor.c b/bootloaders/zero/sam_ba_monitor.c index 29c9d8566..7daeb3067 100644 --- a/bootloaders/zero/sam_ba_monitor.c +++ b/bootloaders/zero/sam_ba_monitor.c @@ -1,39 +1,30 @@ -/* ---------------------------------------------------------------------------- - * SAM Software Package License - * ---------------------------------------------------------------------------- - * Copyright (c) 2011-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. - * ---------------------------------------------------------------------------- - */ +/* + Copyright (c) 2015 Arduino LLC. All right reserved. + Copyright (c) 2015 Atmel Corporation/Thibaut VIARD. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ #include "sam.h" #include #include "sam_ba_monitor.h" -#include "usart_sam_ba.h" -#include "uart_driver.h" -#include "compiler.h" -#include "cdc_enumerate.h" +#include "sam_ba_serial.h" +#include "board_driver_serial.h" +#include "board_driver_usb.h" +#include "sam_ba_usb.h" +#include "sam_ba_cdc.h" const char RomBOOT_Version[] = SAM_BA_VERSION; const char RomBOOT_ExtendedCapabilities[] = "[Arduino:XYZ]"; @@ -41,35 +32,49 @@ const char RomBOOT_ExtendedCapabilities[] = "[Arduino:XYZ]"; /* Provides one common interface to handle both USART and USB-CDC */ typedef struct { - /* send one byte of data */ - int (*put_c)(int value); - /* Get one byte */ - int (*get_c)(void); - /* Receive buffer not empty */ - bool (*is_rx_ready)(void); - /* Send given data (polling) */ - uint32_t (*putdata)(void const* data, uint32_t length); - /* Get data from comm. device */ - uint32_t (*getdata)(void* data, uint32_t length); - /* Send given data (polling) using xmodem (if necessary) */ - uint32_t (*putdata_xmd)(void const* data, uint32_t length); - /* Get data from comm. device using xmodem (if necessary) */ - uint32_t (*getdata_xmd)(void* data, uint32_t length); + /* send one byte of data */ + int (*put_c)(int value); + /* Get one byte */ + int (*get_c)(void); + /* Receive buffer not empty */ + bool (*is_rx_ready)(void); + /* Send given data (polling) */ + uint32_t (*putdata)(void const* data, uint32_t length); + /* Get data from comm. device */ + uint32_t (*getdata)(void* data, uint32_t length); + /* Send given data (polling) using xmodem (if necessary) */ + uint32_t (*putdata_xmd)(void const* data, uint32_t length); + /* Get data from comm. device using xmodem (if necessary) */ + uint32_t (*getdata_xmd)(void* data, uint32_t length); } t_monitor_if; #if SAM_BA_INTERFACE == SAM_BA_UART_ONLY || SAM_BA_INTERFACE == SAM_BA_BOTH_INTERFACES /* Initialize structures with function pointers from supported interfaces */ const t_monitor_if uart_if = -{ usart_putc, usart_getc, usart_is_rx_ready, usart_putdata, usart_getdata, - usart_putdata_xmd, usart_getdata_xmd }; +{ + .put_c = serial_putc, + .get_c = serial_getc, + .is_rx_ready = serial_is_rx_ready, + .putdata = serial_putdata, + .getdata = serial_getdata, + .putdata_xmd = serial_putdata_xmd, + .getdata_xmd = serial_getdata_xmd +}; #endif #if SAM_BA_INTERFACE == SAM_BA_USBCDC_ONLY || SAM_BA_INTERFACE == SAM_BA_BOTH_INTERFACES //Please note that USB doesn't use Xmodem protocol, since USB already includes flow control and data verification //Data are simply forwarded without further coding. const t_monitor_if usbcdc_if = -{ cdc_putc, cdc_getc, cdc_is_rx_ready, cdc_write_buf, - cdc_read_buf, cdc_write_buf, cdc_read_buf_xmd }; +{ + .put_c = cdc_putc, + .get_c = cdc_getc, + .is_rx_ready = cdc_is_rx_ready, + .putdata = cdc_write_buf, + .getdata = cdc_read_buf, + .putdata_xmd = cdc_write_buf, + .getdata_xmd = cdc_read_buf_xmd +}; #endif /* The pointer to the interface object use by the monitor */ @@ -81,17 +86,19 @@ volatile bool b_sam_ba_interface_usart = false; void sam_ba_monitor_init(uint8_t com_interface) { -#if SAM_BA_INTERFACE == SAM_BA_UART_ONLY || SAM_BA_INTERFACE == SAM_BA_BOTH_INTERFACES - //Selects the requested interface for future actions - if (com_interface == SAM_BA_INTERFACE_USART) { - ptr_monitor_if = (t_monitor_if*) &uart_if; - b_sam_ba_interface_usart = true; - } +#if SAM_BA_INTERFACE == SAM_BA_UART_ONLY || SAM_BA_INTERFACE == SAM_BA_BOTH_INTERFACES + //Selects the requested interface for future actions + if (com_interface == SAM_BA_INTERFACE_USART) + { + ptr_monitor_if = (t_monitor_if*) &uart_if; + b_sam_ba_interface_usart = true; + } #endif -#if SAM_BA_INTERFACE == SAM_BA_USBCDC_ONLY || SAM_BA_INTERFACE == SAM_BA_BOTH_INTERFACES - if (com_interface == SAM_BA_INTERFACE_USBCDC) { - ptr_monitor_if = (t_monitor_if*) &usbcdc_if; - } +#if SAM_BA_INTERFACE == SAM_BA_USBCDC_ONLY || SAM_BA_INTERFACE == SAM_BA_BOTH_INTERFACES + if (com_interface == SAM_BA_INTERFACE_USBCDC) + { + ptr_monitor_if = (t_monitor_if*) &usbcdc_if; + } #endif } @@ -103,64 +110,63 @@ void sam_ba_monitor_init(uint8_t com_interface) */ void sam_ba_putdata_term(uint8_t* data, uint32_t length) { - uint8_t temp, buf[12], *data_ascii; - uint32_t i, int_value; - - if (b_terminal_mode) - { - if (length == 4) - int_value = *(uint32_t *) data; - else if (length == 2) - int_value = *(uint16_t *) data; - else - int_value = *(uint8_t *) data; - - data_ascii = buf + 2; - data_ascii += length * 2 - 1; - - for (i = 0; i < length * 2; i++) - { - temp = (uint8_t) (int_value & 0xf); - - if (temp <= 0x9) - *data_ascii = temp | 0x30; - else - *data_ascii = temp + 0x37; - - int_value >>= 4; - data_ascii--; - } - buf[0] = '0'; - buf[1] = 'x'; - buf[length * 2 + 2] = '\n'; - buf[length * 2 + 3] = '\r'; - ptr_monitor_if->putdata(buf, length * 2 + 4); - } - else - ptr_monitor_if->putdata(data, length); - return; + uint8_t temp, buf[12], *data_ascii; + uint32_t i, int_value; + + if (b_terminal_mode) + { + if (length == 4) + int_value = *(uint32_t *) data; + else if (length == 2) + int_value = *(uint16_t *) data; + else + int_value = *(uint8_t *) data; + + data_ascii = buf + 2; + data_ascii += length * 2 - 1; + + for (i = 0; i < length * 2; i++) + { + temp = (uint8_t) (int_value & 0xf); + + if (temp <= 0x9) + *data_ascii = temp | 0x30; + else + *data_ascii = temp + 0x37; + + int_value >>= 4; + data_ascii--; + } + buf[0] = '0'; + buf[1] = 'x'; + buf[length * 2 + 2] = '\n'; + buf[length * 2 + 3] = '\r'; + ptr_monitor_if->putdata(buf, length * 2 + 4); + } + else + ptr_monitor_if->putdata(data, length); + return; } volatile uint32_t sp; void call_applet(uint32_t address) { - uint32_t app_start_address; + uint32_t app_start_address; - cpu_irq_disable(); + __disable_irq(); - sp = __get_MSP(); + sp = __get_MSP(); - /* Rebase the Stack Pointer */ - __set_MSP(*(uint32_t *) address); + /* Rebase the Stack Pointer */ + __set_MSP(*(uint32_t *) address); - /* Load the Reset Handler address of the application */ - app_start_address = *(uint32_t *)(address + 4); + /* Load the Reset Handler address of the application */ + app_start_address = *(uint32_t *)(address + 4); - /* Jump to application Reset Handler in the application */ - asm("bx %0"::"r"(app_start_address)); + /* Jump to application Reset Handler in the application */ + asm("bx %0"::"r"(app_start_address)); } - uint32_t current_number; uint32_t i, length; uint8_t command, *ptr_data, *ptr, data[SIZEBUFMAX]; @@ -169,286 +175,298 @@ uint32_t u32tmp; uint32_t PAGE_SIZE, PAGES, MAX_FLASH; -/** - * \brief This function starts the SAM-BA monitor. - */ -void sam_ba_monitor_run(void) +// Prints a 32-bit integer in hex. +static void put_uint32(uint32_t n) { - uint32_t pageSizes[] = { 8, 16, 32, 64, 128, 256, 512, 1024 }; - PAGE_SIZE = pageSizes[NVMCTRL->PARAM.bit.PSZ]; - PAGES = NVMCTRL->PARAM.bit.NVMP; - MAX_FLASH = PAGE_SIZE * PAGES; - - ptr_data = NULL; - command = 'z'; - while (1) { - sam_ba_monitor_loop(); - } + char buff[8]; + int i; + for (i=0; i<8; i++) + { + int d = n & 0XF; + n = (n >> 4); + + buff[7-i] = d > 9 ? 'A' + d - 10 : '0' + d; + } + ptr_monitor_if->putdata(buff, 8); } -// Prints a 32-bit integer in hex. -void put_uint32(uint32_t n) { - char buff[8]; - int i; - for (i=0; i<8; i++) { - int d = n & 0XF; - n = (n >> 4); - - buff[7-i] = d > 9 ? 'A' + d - 10 : '0' + d; - } - ptr_monitor_if->putdata(buff, 8); +static void sam_ba_monitor_loop(void) +{ + length = ptr_monitor_if->getdata(data, SIZEBUFMAX); + ptr = data; + + for (i = 0; i < length; i++, ptr++) + { + if (*ptr == 0xff) continue; + + if (*ptr == '#') + { + if (b_terminal_mode) + { + ptr_monitor_if->putdata("\n\r", 2); + } + if (command == 'S') + { + //Check if some data are remaining in the "data" buffer + if(length>i) + { + //Move current indexes to next avail data (currently ptr points to "#") + ptr++; + i++; + + //We need to add first the remaining data of the current buffer already read from usb + //read a maximum of "current_number" bytes + if ((length-i) < current_number) + { + u32tmp=(length-i); + } + else + { + u32tmp=current_number; + } + + memcpy(ptr_data, ptr, u32tmp); + i += u32tmp; + ptr += u32tmp; + j = u32tmp; + } + //update i with the data read from the buffer + i--; + ptr--; + //Do we expect more data ? + if(jgetdata_xmd(ptr_data, current_number-j); + + __asm("nop"); + } + else if (command == 'R') + { + ptr_monitor_if->putdata_xmd(ptr_data, current_number); + } + else if (command == 'O') + { + *ptr_data = (char) current_number; + } + else if (command == 'H') + { + *((uint16_t *) ptr_data) = (uint16_t) current_number; + } + else if (command == 'W') + { + *((int *) ptr_data) = current_number; + } + else if (command == 'o') + { + sam_ba_putdata_term(ptr_data, 1); + } + else if (command == 'h') + { + current_number = *((uint16_t *) ptr_data); + sam_ba_putdata_term((uint8_t*) ¤t_number, 2); + } + else if (command == 'w') + { + current_number = *((uint32_t *) ptr_data); + sam_ba_putdata_term((uint8_t*) ¤t_number, 4); + } + else if (command == 'G') + { + call_applet(current_number); + /* Rebase the Stack Pointer */ + __set_MSP(sp); + __enable_irq(); + if (b_sam_ba_interface_usart) { + ptr_monitor_if->put_c(0x6); + } + } + else if (command == 'T') + { + b_terminal_mode = 1; + ptr_monitor_if->putdata("\n\r", 2); + } + else if (command == 'N') + { + if (b_terminal_mode == 0) + { + ptr_monitor_if->putdata("\n\r", 2); + } + b_terminal_mode = 0; + } + else if (command == 'V') + { + ptr_monitor_if->putdata("v", 1); + ptr_monitor_if->putdata((uint8_t *) RomBOOT_Version, strlen(RomBOOT_Version)); + ptr_monitor_if->putdata(" ", 1); + ptr_monitor_if->putdata((uint8_t *) RomBOOT_ExtendedCapabilities, strlen(RomBOOT_ExtendedCapabilities)); + ptr_monitor_if->putdata(" ", 1); + ptr = (uint8_t*) &(__DATE__); + i = 0; + while (*ptr++ != '\0') + i++; + ptr_monitor_if->putdata((uint8_t *) &(__DATE__), i); + ptr_monitor_if->putdata(" ", 1); + i = 0; + ptr = (uint8_t*) &(__TIME__); + while (*ptr++ != '\0') + i++; + ptr_monitor_if->putdata((uint8_t *) &(__TIME__), i); + ptr_monitor_if->putdata("\n\r", 2); + } + else if (command == 'X') + { + // Syntax: X[ADDR]# + // Erase the flash memory starting from ADDR to the end of flash. + + // Note: the flash memory is erased in ROWS, that is in block of 4 pages. + // Even if the starting address is the last byte of a ROW the entire + // ROW is erased anyway. + + uint32_t dst_addr = current_number; // starting address + + while (dst_addr < MAX_FLASH) + { + // Execute "ER" Erase Row + NVMCTRL->ADDR.reg = dst_addr / 2; + NVMCTRL->CTRLA.reg = NVMCTRL_CTRLA_CMDEX_KEY | NVMCTRL_CTRLA_CMD_ER; + while (NVMCTRL->INTFLAG.bit.READY == 0) + ; + dst_addr += PAGE_SIZE * 4; // Skip a ROW + } + + // Notify command completed + ptr_monitor_if->putdata("X\n\r", 3); + } + else if (command == 'Y') + { + // This command writes the content of a buffer in SRAM into flash memory. + + // Syntax: Y[ADDR],0# + // Set the starting address of the SRAM buffer. + + // Syntax: Y[ROM_ADDR],[SIZE]# + // Write the first SIZE bytes from the SRAM buffer (previously set) into + // flash memory starting from address ROM_ADDR + + static uint32_t *src_buff_addr = NULL; + + if (current_number == 0) + { + // Set buffer address + src_buff_addr = (uint32_t*)ptr_data; + } + else + { + // Write to flash + uint32_t size = current_number/4; + uint32_t *src_addr = src_buff_addr; + uint32_t *dst_addr = (uint32_t*)ptr_data; + + // Set automatic page write + NVMCTRL->CTRLB.bit.MANW = 0; + + // Do writes in pages + while (size) + { + // Execute "PBC" Page Buffer Clear + NVMCTRL->CTRLA.reg = NVMCTRL_CTRLA_CMDEX_KEY | NVMCTRL_CTRLA_CMD_PBC; + while (NVMCTRL->INTFLAG.bit.READY == 0) + ; + + // Fill page buffer + uint32_t i; + for (i=0; i<(PAGE_SIZE/4) && iADDR.reg = ((uint32_t)dst_addr) / 2; + NVMCTRL->CTRLA.reg = NVMCTRL_CTRLA_CMDEX_KEY | NVMCTRL_CTRLA_CMD_WP; + while (NVMCTRL->INTFLAG.bit.READY == 0) + ; + + // Advance to next page + dst_addr += i; + src_addr += i; + size -= i; + } + } + + // Notify command completed + ptr_monitor_if->putdata("Y\n\r", 3); + } + else if (command == 'Z') + { + // This command calculate CRC for a given area of memory. + // It's useful to quickly check if a transfer has been done + // successfully. + + // Syntax: Z[START_ADDR],[SIZE]# + // Returns: Z[CRC]# + + uint8_t *data = (uint8_t *)ptr_data; + uint32_t size = current_number; + uint16_t crc = 0; + uint32_t i = 0; + for (i=0; iputdata("Z", 1); + put_uint32(crc); + ptr_monitor_if->putdata("#\n\r", 3); + } + + command = 'z'; + current_number = 0; + + if (b_terminal_mode) + { + ptr_monitor_if->putdata(">", 1); + } + } + else + { + if (('0' <= *ptr) && (*ptr <= '9')) + { + current_number = (current_number << 4) | (*ptr - '0'); + } + else if (('A' <= *ptr) && (*ptr <= 'F')) + { + current_number = (current_number << 4) | (*ptr - 'A' + 0xa); + } + else if (('a' <= *ptr) && (*ptr <= 'f')) + { + current_number = (current_number << 4) | (*ptr - 'a' + 0xa); + } + else if (*ptr == ',') + { + ptr_data = (uint8_t *) current_number; + current_number = 0; + } + else + { + command = *ptr; + current_number = 0; + } + } + } } -void sam_ba_monitor_loop(void) +/** + * \brief This function starts the SAM-BA monitor. + */ +void sam_ba_monitor_run(void) { - length = ptr_monitor_if->getdata(data, SIZEBUFMAX); - ptr = data; - for (i = 0; i < length; i++, ptr++) - { - if (*ptr == 0xff) continue; - - if (*ptr == '#') - { - if (b_terminal_mode) - { - ptr_monitor_if->putdata("\n\r", 2); - } - if (command == 'S') - { - //Check if some data are remaining in the "data" buffer - if(length>i) - { - //Move current indexes to next avail data (currently ptr points to "#") - ptr++; - i++; - //We need to add first the remaining data of the current buffer already read from usb - //read a maximum of "current_number" bytes - u32tmp=min((length-i),current_number); - memcpy(ptr_data, ptr, u32tmp); - i += u32tmp; - ptr += u32tmp; - j = u32tmp; - } - //update i with the data read from the buffer - i--; - ptr--; - //Do we expect more data ? - if(jgetdata_xmd(ptr_data, current_number-j); - - __asm("nop"); - } - else if (command == 'R') - { - ptr_monitor_if->putdata_xmd(ptr_data, current_number); - } - else if (command == 'O') - { - *ptr_data = (char) current_number; - } - else if (command == 'H') - { - *((uint16_t *) ptr_data) = (uint16_t) current_number; - } - else if (command == 'W') - { - *((int *) ptr_data) = current_number; - } - else if (command == 'o') - { - sam_ba_putdata_term(ptr_data, 1); - } - else if (command == 'h') - { - current_number = *((uint16_t *) ptr_data); - sam_ba_putdata_term((uint8_t*) ¤t_number, 2); - } - else if (command == 'w') - { - current_number = *((uint32_t *) ptr_data); - sam_ba_putdata_term((uint8_t*) ¤t_number, 4); - } - else if (command == 'G') - { - call_applet(current_number); - /* Rebase the Stack Pointer */ - __set_MSP(sp); - cpu_irq_enable(); - if (b_sam_ba_interface_usart) { - ptr_monitor_if->put_c(0x6); - } - } - else if (command == 'T') - { - b_terminal_mode = 1; - ptr_monitor_if->putdata("\n\r", 2); - } - else if (command == 'N') - { - if (b_terminal_mode == 0) - { - ptr_monitor_if->putdata("\n\r", 2); - } - b_terminal_mode = 0; - } - else if (command == 'V') - { - ptr_monitor_if->putdata("v", 1); - ptr_monitor_if->putdata((uint8_t *) RomBOOT_Version, - strlen(RomBOOT_Version)); - ptr_monitor_if->putdata(" ", 1); - ptr_monitor_if->putdata((uint8_t *) RomBOOT_ExtendedCapabilities, - strlen(RomBOOT_ExtendedCapabilities)); - ptr_monitor_if->putdata(" ", 1); - ptr = (uint8_t*) &(__DATE__); - i = 0; - while (*ptr++ != '\0') - i++; - ptr_monitor_if->putdata((uint8_t *) &(__DATE__), i); - ptr_monitor_if->putdata(" ", 1); - i = 0; - ptr = (uint8_t*) &(__TIME__); - while (*ptr++ != '\0') - i++; - ptr_monitor_if->putdata((uint8_t *) &(__TIME__), i); - ptr_monitor_if->putdata("\n\r", 2); - } - else if (command == 'X') - { - // Syntax: X[ADDR]# - // Erase the flash memory starting from ADDR to the end of flash. - - // Note: the flash memory is erased in ROWS, that is in block of 4 pages. - // Even if the starting address is the last byte of a ROW the entire - // ROW is erased anyway. - - uint32_t dst_addr = current_number; // starting address - - while (dst_addr < MAX_FLASH) { - // Execute "ER" Erase Row - NVMCTRL->ADDR.reg = dst_addr / 2; - NVMCTRL->CTRLA.reg = NVMCTRL_CTRLA_CMDEX_KEY | NVMCTRL_CTRLA_CMD_ER; - while (NVMCTRL->INTFLAG.bit.READY == 0) - ; - dst_addr += PAGE_SIZE * 4; // Skip a ROW - } - - // Notify command completed - ptr_monitor_if->putdata("X\n\r", 3); - } - else if (command == 'Y') - { - // This command writes the content of a buffer in SRAM into flash memory. - - // Syntax: Y[ADDR],0# - // Set the starting address of the SRAM buffer. - - // Syntax: Y[ROM_ADDR],[SIZE]# - // Write the first SIZE bytes from the SRAM buffer (previously set) into - // flash memory starting from address ROM_ADDR - - static uint32_t *src_buff_addr = NULL; - - if (current_number == 0) { - // Set buffer address - src_buff_addr = ptr_data; - - } else { - // Write to flash - uint32_t size = current_number/4; - uint32_t *src_addr = src_buff_addr; - uint32_t *dst_addr = ptr_data; - - // Set automatic page write - NVMCTRL->CTRLB.bit.MANW = 0; - - // Do writes in pages - while (size) { - // Execute "PBC" Page Buffer Clear - NVMCTRL->CTRLA.reg = NVMCTRL_CTRLA_CMDEX_KEY | NVMCTRL_CTRLA_CMD_PBC; - while (NVMCTRL->INTFLAG.bit.READY == 0) - ; - - // Fill page buffer - uint32_t i; - for (i=0; i<(PAGE_SIZE/4) && iADDR.reg = ((uint32_t)dst_addr) / 2; - NVMCTRL->CTRLA.reg = NVMCTRL_CTRLA_CMDEX_KEY | NVMCTRL_CTRLA_CMD_WP; - while (NVMCTRL->INTFLAG.bit.READY == 0) - ; - - // Advance to next page - dst_addr += i; - src_addr += i; - size -= i; - } - } - - // Notify command completed - ptr_monitor_if->putdata("Y\n\r", 3); - } - else if (command == 'Z') - { - // This command calculate CRC for a given area of memory. - // It's useful to quickly check if a transfer has been done - // successfully. - - // Syntax: Z[START_ADDR],[SIZE]# - // Returns: Z[CRC]# - - uint8_t *data = (uint8_t *)ptr_data; - uint32_t size = current_number; - uint16_t crc = 0; - uint32_t i = 0; - for (i=0; iputdata("Z", 1); - put_uint32(crc); - ptr_monitor_if->putdata("#\n\r", 3); - } - - command = 'z'; - current_number = 0; - - if (b_terminal_mode) - { - ptr_monitor_if->putdata(">", 1); - } - } - else - { - if (('0' <= *ptr) && (*ptr <= '9')) - { - current_number = (current_number << 4) | (*ptr - '0'); - } - else if (('A' <= *ptr) && (*ptr <= 'F')) - { - current_number = (current_number << 4) | (*ptr - 'A' + 0xa); - } - else if (('a' <= *ptr) && (*ptr <= 'f')) - { - current_number = (current_number << 4) | (*ptr - 'a' + 0xa); - } - else if (*ptr == ',') - { - ptr_data = (uint8_t *) current_number; - current_number = 0; - } - else - { - command = *ptr; - current_number = 0; - } - } - } + uint32_t pageSizes[] = { 8, 16, 32, 64, 128, 256, 512, 1024 }; + PAGE_SIZE = pageSizes[NVMCTRL->PARAM.bit.PSZ]; + PAGES = NVMCTRL->PARAM.bit.NVMP; + MAX_FLASH = PAGE_SIZE * PAGES; + + ptr_data = NULL; + command = 'z'; + while (1) + { + sam_ba_monitor_loop(); + } } - - - - diff --git a/bootloaders/zero/sam_ba_monitor.h b/bootloaders/zero/sam_ba_monitor.h index c70ddb187..e72582bcf 100644 --- a/bootloaders/zero/sam_ba_monitor.h +++ b/bootloaders/zero/sam_ba_monitor.h @@ -1,36 +1,26 @@ -/* ---------------------------------------------------------------------------- - * SAM Software Package License - * ---------------------------------------------------------------------------- - * Copyright (c) 2011-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. - * ---------------------------------------------------------------------------- - */ +/* + Copyright (c) 2015 Arduino LLC. All right reserved. + Copyright (c) 2015 Atmel Corporation/Thibaut VIARD. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ #ifndef _MONITOR_SAM_BA_H_ #define _MONITOR_SAM_BA_H_ -#define SAM_BA_VERSION "1.1" +#define SAM_BA_VERSION "2.0" /* Enable the interfaces to save code size */ #define SAM_BA_BOTH_INTERFACES 0 @@ -41,11 +31,10 @@ #define SAM_BA_INTERFACE SAM_BA_BOTH_INTERFACES #endif -/* Selects USART as the communication interface of the monitor */ -#define SAM_BA_INTERFACE_USART 1 /* Selects USB as the communication interface of the monitor */ #define SAM_BA_INTERFACE_USBCDC 0 - +/* Selects USART as the communication interface of the monitor */ +#define SAM_BA_INTERFACE_USART 1 /* Selects USB as the communication interface of the monitor */ #define SIZEBUFMAX 64 diff --git a/bootloaders/zero/usart_sam_ba.c b/bootloaders/zero/sam_ba_serial.c similarity index 61% rename from bootloaders/zero/usart_sam_ba.c rename to bootloaders/zero/sam_ba_serial.c index 645e725e9..a06de01dc 100644 --- a/bootloaders/zero/usart_sam_ba.c +++ b/bootloaders/zero/sam_ba_serial.c @@ -1,38 +1,26 @@ -/* ---------------------------------------------------------------------------- - * SAM Software Package License - * ---------------------------------------------------------------------------- - * Copyright (c) 2011-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. - * ---------------------------------------------------------------------------- - */ - -//#include -#include "usart_sam_ba.h" -#include "main.h" -#include "uart_driver.h" -#include "compiler.h" -#include "sam.h" +/* + Copyright (c) 2015 Arduino LLC. All right reserved. + Copyright (c) 2015 Atmel Corporation/Thibaut VIARD. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include "board_definitions.h" +#include "sam_ba_serial.h" +#include "board_driver_serial.h" /* Local reference to current Usart instance in use with this driver */ //struct usart_module usart_sam_ba; @@ -61,22 +49,24 @@ uint8_t mode_of_transfer; /** * \brief Open the given USART */ -void usart_open() +void serial_open(void) { - uint32_t inst; uint32_t port; - uint8_t pin; + uint32_t pin; /* Configure the port pins for SERCOM_USART */ - if (BOOT_USART_PAD0 != PINMUX_UNUSED) { + if (BOOT_USART_PAD0 != PINMUX_UNUSED) + { /* Mask 6th bit in pin number to check whether it is greater than 32 i.e., PORTB pin */ port = (BOOT_USART_PAD0 & 0x200000) >> 21; - pin = BOOT_USART_PAD0 >> 16; + pin = (BOOT_USART_PAD0 >> 16); PORT->Group[port].PINCFG[(pin - (port*32))].bit.PMUXEN = 1; PORT->Group[port].PMUX[(pin - (port*32))/2].reg &= ~(0xF << (4 * (pin & 0x01u))); PORT->Group[port].PMUX[(pin - (port*32))/2].reg |= (BOOT_USART_PAD0 & 0xFF) << (4 * (pin & 0x01u)); } - if (BOOT_USART_PAD1 != PINMUX_UNUSED) { + + if (BOOT_USART_PAD1 != PINMUX_UNUSED) + { /* Mask 6th bit in pin number to check whether it is greater than 32 i.e., PORTB pin */ port = (BOOT_USART_PAD1 & 0x200000) >> 21; pin = BOOT_USART_PAD1 >> 16; @@ -84,7 +74,9 @@ void usart_open() PORT->Group[port].PMUX[(pin - (port*32))/2].reg &= ~(0xF << (4 * (pin & 0x01u))); PORT->Group[port].PMUX[(pin - (port*32))/2].reg |= (BOOT_USART_PAD1 & 0xFF) << (4 * (pin & 0x01u)); } - if (BOOT_USART_PAD2 != PINMUX_UNUSED) { + + if (BOOT_USART_PAD2 != PINMUX_UNUSED) + { /* Mask 6th bit in pin number to check whether it is greater than 32 i.e., PORTB pin */ port = (BOOT_USART_PAD2 & 0x200000) >> 21; pin = BOOT_USART_PAD2 >> 16; @@ -92,7 +84,9 @@ void usart_open() PORT->Group[port].PMUX[(pin - (port*32))/2].reg &= ~(0xF << (4 * (pin & 0x01u))); PORT->Group[port].PMUX[(pin - (port*32))/2].reg |= (BOOT_USART_PAD2 & 0xFF) << (4 * (pin & 0x01u)); } - if (BOOT_USART_PAD3 != PINMUX_UNUSED) { + + if (BOOT_USART_PAD3 != PINMUX_UNUSED) + { /* Mask 6th bit in pin number to check whether it is greater than 32 i.e., PORTB pin */ port = (BOOT_USART_PAD3 & 0x200000) >> 21; pin = BOOT_USART_PAD3 >> 16; @@ -101,23 +95,21 @@ void usart_open() PORT->Group[port].PMUX[(pin - (port*32))/2].reg |= (BOOT_USART_PAD3 & 0xFF) << (4 * (pin & 0x01u)); } - inst = uart_get_sercom_index(BOOT_USART_MODULE); - /* Enable clock for BOOT_USART_MODULE */ - PM->APBCMASK.reg |= (1u << (inst + PM_APBCMASK_SERCOM0_Pos)); + PM->APBCMASK.reg |= BOOT_USART_BUS_CLOCK_INDEX ; /* Set GCLK_GEN0 as source for GCLK_ID_SERCOMx_CORE */ - GCLK_CLKCTRL_Type clkctrl={0}; - uint16_t temp; - GCLK->CLKCTRL.bit.ID = inst + GCLK_ID_SERCOM0_CORE; - temp = GCLK->CLKCTRL.reg; - clkctrl.bit.CLKEN = true; - clkctrl.bit.WRTLOCK = false; - clkctrl.bit.GEN = GCLK_CLKCTRL_GEN_GCLK0_Val; - GCLK->CLKCTRL.reg = (clkctrl.reg | temp); + GCLK->CLKCTRL.reg = GCLK_CLKCTRL_ID( BOOT_USART_PER_CLOCK_INDEX ) | // Generic Clock 0 (SERCOMx) + GCLK_CLKCTRL_GEN_GCLK0 | // Generic Clock Generator 0 is source + GCLK_CLKCTRL_CLKEN ; + + while ( GCLK->STATUS.reg & GCLK_STATUS_SYNCBUSY ) + { + /* Wait for synchronization */ + } /* Baud rate 115200 - clock 8MHz -> BAUD value-50436 */ - uart_basic_init(BOOT_USART_MODULE, 50436, BOOT_USART_MUX_SETTINGS); + uart_basic_init(BOOT_USART_MODULE, 50436, BOOT_USART_PAD_SETTINGS); //Initialize flag b_sharp_received = false; @@ -130,10 +122,9 @@ void usart_open() } /** - * \brief Configures communication line - * + * \brief Close communication line */ -void usart_close(void) +void serial_close(void) { uart_disable(BOOT_USART_MODULE); } @@ -146,37 +137,40 @@ void usart_close(void) * * \return \c 1 if function was successfully done, otherwise \c 0. */ -int usart_putc(int value) +int serial_putc(int value) { uart_write_byte(BOOT_USART_MODULE, (uint8_t)value); return 1; } - - -int usart_getc(void) { +int serial_getc(void) +{ uint16_t retval; //Wait until input buffer is filled - while(!(usart_is_rx_ready())); + while(!(serial_is_rx_ready())); retval = (uint16_t)uart_read_byte(BOOT_USART_MODULE); //usart_read_wait(&usart_sam_ba, &retval); return (int)retval; } -int usart_sharp_received(void) { - if (usart_is_rx_ready()) { - if (usart_getc() == SHARP_CHARACTER) +int serial_sharp_received(void) +{ + if (serial_is_rx_ready()) + { + if (serial_getc() == SHARP_CHARACTER) return (true); } return (false); } -bool usart_is_rx_ready(void) { +bool serial_is_rx_ready(void) +{ return (BOOT_USART_MODULE->USART.INTFLAG.reg & SERCOM_USART_INTFLAG_RXC); } -int usart_readc(void) { +int serial_readc(void) +{ int retval; retval = buffer_rx_usart[idx_rx_read]; idx_rx_read = (idx_rx_read + 1) & (USART_BUFFER_SIZE - 1); @@ -184,26 +178,30 @@ int usart_readc(void) { } //Send given data (polling) -uint32_t usart_putdata(void const* data, uint32_t length) { +uint32_t serial_putdata(void const* data, uint32_t length) +{ uint32_t i; uint8_t* ptrdata; ptrdata = (uint8_t*) data; - for (i = 0; i < length; i++) { - usart_putc(*ptrdata); + for (i = 0; i < length; i++) + { + serial_putc(*ptrdata); ptrdata++; } return (i); } //Get data from comm. device -uint32_t usart_getdata(void* data, uint32_t length) { +uint32_t serial_getdata(void* data, uint32_t length) +{ uint8_t* ptrdata; ptrdata = (uint8_t*) data; - *ptrdata = usart_getc(); + *ptrdata = serial_getc(); return (1); } -static const uint16_t crc16Table[256] = { +static const uint16_t crc16Table[256]= +{ 0x0000,0x1021,0x2042,0x3063,0x4084,0x50a5,0x60c6,0x70e7, 0x8108,0x9129,0xa14a,0xb16b,0xc18c,0xd1ad,0xe1ce,0xf1ef, 0x1231,0x0210,0x3273,0x2252,0x52b5,0x4294,0x72f7,0x62d6, @@ -239,29 +237,31 @@ static const uint16_t crc16Table[256] = { }; //*---------------------------------------------------------------------------- -//* \fn add_crc //* \brief Compute the CRC //*---------------------------------------------------------------------------- -unsigned short add_crc(char ptr, unsigned short crc) { +unsigned short serial_add_crc(char ptr, unsigned short crc) +{ return (crc << 8) ^ crc16Table[((crc >> 8) ^ ptr) & 0xff]; } //*---------------------------------------------------------------------------- -//* \fn getbytes //* \brief //*---------------------------------------------------------------------------- -static uint16_t getbytes(uint8_t *ptr_data, uint16_t length) { +static uint16_t getbytes(uint8_t *ptr_data, uint16_t length) +{ uint16_t crc = 0; uint16_t cpt; uint8_t c; - for (cpt = 0; cpt < length; ++cpt) { - c = usart_getc(); + for (cpt = 0; cpt < length; ++cpt) + { + c = serial_getc(); if (error_timeout) return 1; - crc = add_crc(c, crc); + crc = serial_add_crc(c, crc); //crc = (crc << 8) ^ xcrc16tab[(crc>>8) ^ c]; - if (size_of_data || mode_of_transfer) { + if (size_of_data || mode_of_transfer) + { *ptr_data++ = c; if (length == PKTLEN_128) size_of_data--; @@ -272,90 +272,65 @@ static uint16_t getbytes(uint8_t *ptr_data, uint16_t length) { } //*---------------------------------------------------------------------------- -//* \fn putPacket //* \brief Used by Xup to send packets. //*---------------------------------------------------------------------------- -static int putPacket(uint8_t *tmppkt, uint8_t sno) { +static int putPacket(uint8_t *tmppkt, uint8_t sno) +{ uint32_t i; uint16_t chksm; uint8_t data; chksm = 0; - usart_putc(SOH); + serial_putc(SOH); - usart_putc(sno); - usart_putc((uint8_t) ~(sno)); + serial_putc(sno); + serial_putc((uint8_t) ~(sno)); - for (i = 0; i < PKTLEN_128; i++) { - if (size_of_data || mode_of_transfer) { + for (i = 0; i < PKTLEN_128; i++) + { + if (size_of_data || mode_of_transfer) + { data = *tmppkt++; size_of_data--; - } else + } + else data = 0x00; - usart_putc(data); + serial_putc(data); //chksm = (chksm<<8) ^ xcrc16tab[(chksm>>8)^data]; - chksm = add_crc(data, chksm); + chksm = serial_add_crc(data, chksm); } /* An "endian independent way to extract the CRC bytes. */ - usart_putc((uint8_t) (chksm >> 8)); - usart_putc((uint8_t) chksm); - - return (usart_getc()); /* Wait for ack */ -} - -//*---------------------------------------------------------------------------- -//* \fn getPacket -//* \brief Used by Xdown to retrieve packets. -//*---------------------------------------------------------------------------- -uint8_t getPacket(uint8_t *ptr_data, uint8_t sno) { - uint8_t seq[2]; - uint16_t crc, xcrc; - - getbytes(seq, 2); - xcrc = getbytes(ptr_data, PKTLEN_128); - if (error_timeout) - return (false); - - /* An "endian independent way to combine the CRC bytes. */ - crc = (uint16_t) usart_getc() << 8; - crc += (uint16_t) usart_getc(); - - if (error_timeout == 1) - return (false); - - if ((crc != xcrc) || (seq[0] != sno) || (seq[1] != (uint8_t) (~sno))) { - usart_putc(CAN); - return (false); - } + serial_putc((uint8_t) (chksm >> 8)); + serial_putc((uint8_t) chksm); - usart_putc(ACK); - return (true); + return (serial_getc()); /* Wait for ack */ } //*---------------------------------------------------------------------------- -//* \fn Xup //* \brief Called when a transfer from target to host is being made (considered //* an upload). //*---------------------------------------------------------------------------- -//static void Xup(char *ptr_data, uint16_t length) //Send given data (polling) using xmodem (if necessary) -uint32_t usart_putdata_xmd(void const* data, uint32_t length) { +uint32_t serial_putdata_xmd(void const* data, uint32_t length) +{ uint8_t c, sno = 1; uint8_t done; uint8_t * ptr_data = (uint8_t *) data; error_timeout = 0; if (!length) mode_of_transfer = 1; - else { + else + { size_of_data = length; mode_of_transfer = 0; } - if (length & (PKTLEN_128 - 1)) { + if (length & (PKTLEN_128 - 1)) + { length += PKTLEN_128; length &= ~(PKTLEN_128 - 1); } @@ -364,58 +339,68 @@ uint32_t usart_putdata_xmd(void const* data, uint32_t length) { /* Wait to receive a NAK or 'C' from receiver. */ done = 0; while (!done) { - c = (uint8_t) usart_getc(); - if (error_timeout) { // Test for timeout in usart_getc + c = (uint8_t) serial_getc(); + if (error_timeout) + { // Test for timeout in serial_getc error_timeout = 0; - c = (uint8_t) usart_getc(); - if (error_timeout) { + c = (uint8_t) serial_getc(); + if (error_timeout) + { error_timeout = 0; return (0); } } - switch (c) { - case NAK: - done = 1; - // ("CSM"); + switch (c) + { + case NAK: + done = 1; + // ("CSM"); break; - case 'C': - done = 1; - // ("CRC"); + case 'C': + done = 1; + // ("CRC"); break; - case 'q': /* ELS addition, not part of XMODEM spec. */ - return (0); - default: + case 'q': /* ELS addition, not part of XMODEM spec. */ + return (0); + default: break; } } done = 0; sno = 1; - while (!done) { + while (!done) + { c = (uint8_t) putPacket((uint8_t *) ptr_data, sno); - if (error_timeout) { // Test for timeout in usart_getc + if (error_timeout) + { // Test for timeout in serial_getc error_timeout = 0; return (0); } - switch (c) { - case ACK: - ++sno; - length -= PKTLEN_128; - ptr_data += PKTLEN_128; - // ("A"); + switch (c) + { + case ACK: + ++sno; + length -= PKTLEN_128; + ptr_data += PKTLEN_128; + // ("A"); break; - case NAK: - // ("N"); + + case NAK: + // ("N"); break; - case CAN: - case EOT: - default: - done = 0; + + case CAN: + case EOT: + default: + done = 0; break; } - if (!length) { - usart_putc(EOT); - usart_getc(); /* Flush the ACK */ + + if (!length) + { + serial_putc(EOT); + serial_getc(); /* Flush the ACK */ break; } // ("!"); @@ -427,14 +412,43 @@ uint32_t usart_putdata_xmd(void const* data, uint32_t length) { // return(0); } +/*---------------------------------------------------------------------------- + * \brief Used by serial_getdata_xmd to retrieve packets. + */ +static uint8_t getPacket(uint8_t *ptr_data, uint8_t sno) +{ + uint8_t seq[2]; + uint16_t crc, xcrc; + + getbytes(seq, 2); + xcrc = getbytes(ptr_data, PKTLEN_128); + if (error_timeout) + return (false); + + /* An "endian independent way to combine the CRC bytes. */ + crc = (uint16_t) serial_getc() << 8; + crc += (uint16_t) serial_getc(); + + if (error_timeout == 1) + return (false); + + if ((crc != xcrc) || (seq[0] != sno) || (seq[1] != (uint8_t) (~sno))) + { + serial_putc(CAN); + return (false); + } + + serial_putc(ACK); + return (true); +} + //*---------------------------------------------------------------------------- -//* \fn Xdown //* \brief Called when a transfer from host to target is being made (considered //* an download). //*---------------------------------------------------------------------------- -//static void Xdown(char *ptr_data, uint16_t length) //Get data from comm. device using xmodem (if necessary) -uint32_t usart_getdata_xmd(void* data, uint32_t length) { +uint32_t serial_getdata_xmd(void* data, uint32_t length) +{ uint32_t timeout; char c; uint8_t * ptr_data = (uint8_t *) data; @@ -443,13 +457,14 @@ uint32_t usart_getdata_xmd(void* data, uint32_t length) { uint32_t data_transfered = 0; //Copied from legacy source code ... might need some tweaking - uint32_t loops_per_second = CPU_FREQUENCY/10; /* system_clock_source_get_hz(BOOT_USART_GCLK_GEN_SOURCE) / 10; */ + uint32_t loops_per_second = CPU_FREQUENCY/60; error_timeout = 0; if (length == 0) mode_of_transfer = 1; - else { + else + { size_of_data = length; mode_of_transfer = 0; } @@ -457,10 +472,11 @@ uint32_t usart_getdata_xmd(void* data, uint32_t length) { /* Startup synchronization... */ /* Continuously send NAK or 'C' until sender responds. */ // ("Xdown"); - while (1) { - usart_putc('C'); + while (1) + { + serial_putc('C'); timeout = loops_per_second; - while (!(usart_is_rx_ready()) && timeout) + while (!(serial_is_rx_ready()) && timeout) timeout--; if (timeout) break; @@ -472,36 +488,41 @@ uint32_t usart_getdata_xmd(void* data, uint32_t length) { b_run = true; // ("Got response"); - while (b_run != false) { - c = (char) usart_getc(); - if (error_timeout) { // Test for timeout in usart_getc + while (b_run != false) + { + c = (char) serial_getc(); + if (error_timeout) + { // Test for timeout in serial_getc error_timeout = 0; return (0); // return (-1); } - switch (c) { - case SOH: /* 128-byte incoming packet */ - // ("O"); - b_run = getPacket(ptr_data, sno); - if (error_timeout) { // Test for timeout in usart_getc - error_timeout = 0; - return (0); -// return (-1); - } - if (b_run == true) { - ++sno; - ptr_data += PKTLEN_128; - data_transfered += PKTLEN_128; - } + switch (c) + { + case SOH: /* 128-byte incoming packet */ + // ("O"); + b_run = getPacket(ptr_data, sno); + if (error_timeout) + { // Test for timeout in serial_getc + error_timeout = 0; + return (0); + // return (-1); + } + if (b_run == true) + { + ++sno; + ptr_data += PKTLEN_128; + data_transfered += PKTLEN_128; + } break; - case EOT: // ("E"); - usart_putc(ACK); - b_run = false; + case EOT: // ("E"); + serial_putc(ACK); + b_run = false; break; - case CAN: // ("C"); - case ESC: /* "X" User-invoked abort */ - default: - b_run = false; + case CAN: // ("C"); + case ESC: /* "X" User-invoked abort */ + default: + b_run = false; break; } // ("!"); diff --git a/bootloaders/zero/sam_ba_serial.h b/bootloaders/zero/sam_ba_serial.h new file mode 100644 index 000000000..cb69f459e --- /dev/null +++ b/bootloaders/zero/sam_ba_serial.h @@ -0,0 +1,143 @@ +/* + Copyright (c) 2015 Arduino LLC. All right reserved. + Copyright (c) 2015 Atmel Corporation/Thibaut VIARD. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef _SAM_BA_SERIAL_H_ +#define _SAM_BA_SERIAL_H_ + +#include +#include + + +/* USART buffer size (must be a power of two) */ +#define USART_BUFFER_SIZE (128) + +/* Define the default time-out value for USART. */ +#define USART_DEFAULT_TIMEOUT (1000) + +/* Xmodem related defines */ +/* CRC16 polynomial */ +#define CRC16POLY (0x1021) + +#define SHARP_CHARACTER '#' + +/* X/Ymodem protocol: */ +#define SOH (0x01) +//#define STX (0x02) +#define EOT (0x04) +#define ACK (0x06) +#define NAK (0x15) +#define CAN (0x18) +#define ESC (0x1b) + +#define PKTLEN_128 (128) + + +/** + * \brief Open the given USART + */ +void serial_open(void); + +/** + * \brief Stops the USART + */ +void serial_close(void); + +/** + * \brief Puts a byte on usart line + * + * \param value Value to put + * + * \return \c 1 if function was successfully done, otherwise \c 0. + */ +int serial_putc(int value); + +/** + * \brief Waits and gets a value on usart line + * + * \return value read on usart line + */ +int serial_getc(void); + +/** + * \brief Returns true if the SAM-BA Uart received the sharp char + * + * \return Returns true if the SAM-BA Uart received the sharp char + */ +int serial_sharp_received(void); + +/** + * \brief This function checks if a character has been received on the usart line + * + * \return \c 1 if a byte is ready to be read. + */ +bool serial_is_rx_ready(void); + +/** + * \brief Gets a value on usart line + * + * \return value read on usart line + */ +int serial_readc(void); + +/** + * \brief Send buffer on usart line + * + * \param data pointer + * \param number of data to send + * \return number of data sent + */ +uint32_t serial_putdata(void const* data, uint32_t length); //Send given data (polling) + +/** + * \brief Gets data from usart line + * + * \param data pointer + * \param number of data to get + * \return value read on usart line + */ +uint32_t serial_getdata(void* data, uint32_t length); //Get data from comm. device + +/** + * \brief Send buffer on usart line using Xmodem protocol + * + * \param data pointer + * \param number of data to send + * \return number of data sent + */ +uint32_t serial_putdata_xmd(void const* data, uint32_t length); //Send given data (polling) using xmodem (if necessary) + +/** + * \brief Gets data from usart line using Xmodem protocol + * + * \param data pointer + * \param number of data to get + * \return value read on usart line + */ +uint32_t serial_getdata_xmd(void* data, uint32_t length); //Get data from comm. device using xmodem (if necessary) + +/** + * \brief Compute the CRC + * + * \param Char to add to CRC + * \param Previous CRC + * \return The new computed CRC + */ +unsigned short serial_add_crc(char c, unsigned short crc); + +#endif // _SAM_BA_SERIAL_H_ diff --git a/bootloaders/zero/sam_ba_usb.c b/bootloaders/zero/sam_ba_usb.c new file mode 100644 index 000000000..090375c7f --- /dev/null +++ b/bootloaders/zero/sam_ba_usb.c @@ -0,0 +1,456 @@ +/* + Copyright (c) 2015 Arduino LLC. All right reserved. + Copyright (c) 2015 Atmel Corporation/Thibaut VIARD. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include +#include +#include "sam_ba_usb.h" +#include "board_driver_usb.h" +#include "sam_ba_cdc.h" + +/* This data array will be copied into SRAM as its length is inferior to 64 bytes, + * and so can stay in flash. + */ +static __attribute__((__aligned__(4))) +const char devDescriptor[] = +{ + /* Device descriptor */ + 0x12, // bLength + 0x01, // bDescriptorType + 0x00, // bcdUSB L + 0x02, // bcdUSB H + 0x02, // bDeviceClass: CDC class code + 0x00, // bDeviceSubclass: CDC class sub code + 0x00, // bDeviceProtocol: CDC Device protocol + 0x40, // bMaxPacketSize0 + 0x41, // idVendor L + 0x23, // idVendor H + USB_PID_LOW, // idProduct L + USB_PID_HIGH, // idProduct H + 0x00, // bcdDevice L, here matching SAM-BA version + 0x02, // bcdDevice H +#if 0 // TODO: pending validation + STRING_INDEX_MANUFACTURER, // iManufacturer + STRING_INDEX_PRODUCT, // iProduct +#else + 0x00, // iManufacturer + 0x00, // iProduct +#endif // 0 + 0x00, // SerialNumber, should be based on product unique ID + 0x01 // bNumConfigs +}; + +/* This data array will be consumed directly by USB_Write() and must be in SRAM. + * We cannot send data from product internal flash. + */ +static __attribute__((__aligned__(4))) +char cfgDescriptor[] = +{ + /* ============== CONFIGURATION 1 =========== */ + /* Configuration 1 descriptor */ + 0x09, // CbLength + 0x02, // CbDescriptorType + 0x43, // CwTotalLength 2 EP + Control + 0x00, + 0x02, // CbNumInterfaces + 0x01, // CbConfigurationValue + 0x00, // CiConfiguration + 0x80, // CbmAttributes Bus powered without remote wakeup: 0x80, Self powered without remote wakeup: 0xc0 + 0x32, // CMaxPower, report using 100mA, enough for a bootloader + + /* Communication Class Interface Descriptor Requirement */ + 0x09, // bLength + 0x04, // bDescriptorType + 0x00, // bInterfaceNumber + 0x00, // bAlternateSetting + 0x01, // bNumEndpoints + 0x02, // bInterfaceClass + 0x02, // bInterfaceSubclass + 0x00, // bInterfaceProtocol + 0x00, // iInterface + + /* Header Functional Descriptor */ + 0x05, // bFunction Length + 0x24, // bDescriptor type: CS_INTERFACE + 0x00, // bDescriptor subtype: Header Func Desc + 0x10, // bcdCDC:1.1 + 0x01, + + /* ACM Functional Descriptor */ + 0x04, // bFunctionLength + 0x24, // bDescriptor Type: CS_INTERFACE + 0x02, // bDescriptor Subtype: ACM Func Desc + 0x00, // bmCapabilities + + /* Union Functional Descriptor */ + 0x05, // bFunctionLength + 0x24, // bDescriptorType: CS_INTERFACE + 0x06, // bDescriptor Subtype: Union Func Desc + 0x00, // bMasterInterface: Communication Class Interface + 0x01, // bSlaveInterface0: Data Class Interface + + /* Call Management Functional Descriptor */ + 0x05, // bFunctionLength + 0x24, // bDescriptor Type: CS_INTERFACE + 0x01, // bDescriptor Subtype: Call Management Func Desc + 0x00, // bmCapabilities: D1 + D0 + 0x01, // bDataInterface: Data Class Interface 1 + + /* Endpoint 1 descriptor */ + 0x07, // bLength + 0x05, // bDescriptorType + 0x83, // bEndpointAddress, Endpoint 03 - IN + 0x03, // bmAttributes INT + 0x08, // wMaxPacketSize + 0x00, + 0xFF, // bInterval + + /* Data Class Interface Descriptor Requirement */ + 0x09, // bLength + 0x04, // bDescriptorType + 0x01, // bInterfaceNumber + 0x00, // bAlternateSetting + 0x02, // bNumEndpoints + 0x0A, // bInterfaceClass + 0x00, // bInterfaceSubclass + 0x00, // bInterfaceProtocol + 0x00, // iInterface + + /* First alternate setting */ + /* Endpoint 1 descriptor */ + 0x07, // bLength + 0x05, // bDescriptorType + 0x81, // bEndpointAddress, Endpoint 01 - IN + 0x02, // bmAttributes BULK + USB_EP_IN_SIZE, // wMaxPacketSize + 0x00, + 0x00, // bInterval + + /* Endpoint 2 descriptor */ + 0x07, // bLength + 0x05, // bDescriptorType + 0x02, // bEndpointAddress, Endpoint 02 - OUT + 0x02, // bmAttributes BULK + USB_EP_OUT_SIZE, // wMaxPacketSize + 0x00, + 0x00 // bInterval +}; + +#ifndef STRING_MANUFACTURER +# define STRING_MANUFACTURER "Arduino LLC" +#endif + +#ifndef STRING_PRODUCT +# define STRING_PRODUCT "Arduino Zero" +#endif + +USB_CDC sam_ba_cdc; + +/*---------------------------------------------------------------------------- + * \brief This function is a callback invoked when a SETUP packet is received + */ +void sam_ba_usb_CDC_Enumerate(P_USB_CDC pCdc) +{ + Usb *pUsb = pCdc->pUsb; + static volatile uint8_t bmRequestType, bRequest, dir; + static volatile uint16_t wValue, wIndex, wLength, wStatus; + + /* Clear the Received Setup flag */ + pUsb->DEVICE.DeviceEndpoint[0].EPINTFLAG.bit.RXSTP = true; + + /* Read the USB request parameters */ + bmRequestType = udd_ep_out_cache_buffer[0][0]; + bRequest = udd_ep_out_cache_buffer[0][1]; + wValue = (udd_ep_out_cache_buffer[0][2] & 0xFF); + wValue |= (udd_ep_out_cache_buffer[0][3] << 8); + wIndex = (udd_ep_out_cache_buffer[0][4] & 0xFF); + wIndex |= (udd_ep_out_cache_buffer[0][5] << 8); + wLength = (udd_ep_out_cache_buffer[0][6] & 0xFF); + wLength |= (udd_ep_out_cache_buffer[0][7] << 8); + + /* Clear the Bank 0 ready flag on Control OUT */ + pUsb->DEVICE.DeviceEndpoint[0].EPSTATUSCLR.reg = USB_DEVICE_EPSTATUSCLR_BK0RDY; + + /* Handle supported standard device request Cf Table 9-3 in USB specification Rev 1.1 */ + switch ((bRequest << 8) | bmRequestType) + { + case STD_GET_DESCRIPTOR: + if (wValue>>8 == STD_GET_DESCRIPTOR_DEVICE) + { + /* Return Device Descriptor */ + USB_Write(pCdc->pUsb, devDescriptor, SAM_BA_MIN(sizeof(devDescriptor), wLength), USB_EP_CTRL); + } + else + { + if (wValue>>8 == STD_GET_DESCRIPTOR_CONFIGURATION) + { + /* Return Configuration Descriptor */ + USB_Write(pCdc->pUsb, cfgDescriptor, SAM_BA_MIN(sizeof(cfgDescriptor), wLength), USB_EP_CTRL); + } + else + { +#if 0 // TODO: pending validation + if (wValue>>8 == STD_GET_DESCRIPTOR_STRING) + { + switch ( wValue & 0xff ) + { + case STRING_INDEX_LANGUAGES: + uint16_t STRING_LANGUAGE[2] = { (STD_GET_DESCRIPTOR_STRING<<8) | 4, 0x0409 }; + + USB_Write(pCdc->pUsb, (const char*)STRING_LANGUAGE, SAM_BA_MIN(sizeof(STRING_LANGUAGE), wLength), USB_EP_CTRL); + break; + + case STRING_INDEX_MANUFACTURER: + USB_SendString(pCdc->pUsb, STRING_MANUFACTURER, strlen(STRING_MANUFACTURER), wLength ); + break; + + case STRING_INDEX_PRODUCT: + USB_SendString(pCdc->pUsb, STRING_PRODUCT, strlen(STRING_PRODUCT), wLength ); + break; + default: + /* Stall the request */ + USB_SendStall(pUsb, true); + break; + } + } + else +#endif // 0 + { + /* Stall the request */ + USB_SendStall(pUsb, true); + } + } + } + break; + + case STD_SET_ADDRESS: + /* Send ZLP */ + USB_SendZlp(pUsb); + /* Set device address to the newly received address from host */ + USB_SetAddress(pCdc->pUsb, wValue); + break; + + case STD_SET_CONFIGURATION: + /* Store configuration */ + pCdc->currentConfiguration = (uint8_t)wValue; + + /* Send ZLP */ + USB_SendZlp(pUsb); + + /* Configure the 3 needed endpoints */ + USB_Configure(pUsb); + break; + + case STD_GET_CONFIGURATION: + /* Return current configuration value */ + USB_Write(pCdc->pUsb, (char *) &(pCdc->currentConfiguration), sizeof(pCdc->currentConfiguration), USB_EP_CTRL); + break; + + case STD_GET_STATUS_ZERO: + wStatus = 0; + USB_Write(pCdc->pUsb, (char *) &wStatus, sizeof(wStatus), USB_EP_CTRL); + break; + + case STD_GET_STATUS_INTERFACE: + wStatus = 0; + USB_Write(pCdc->pUsb, (char *) &wStatus, sizeof(wStatus), USB_EP_CTRL); + break; + + case STD_GET_STATUS_ENDPOINT: + wStatus = 0; + dir = wIndex & 80; + wIndex &= 0x0F; + if (wIndex <= 3) + { + if (dir) + { + //wStatus = (pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUS.reg & USB_DEVICE_EPSTATUSSET_STALLRQ1) ? 1 : 0; + wStatus = (pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUS.bit.STALLRQ & (1<<1)) ? 1 : 0; + } + else + { + //wStatus = (pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUS.reg & USB_DEVICE_EPSTATUSSET_STALLRQ0) ? 1 : 0; + wStatus = (pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUS.bit.STALLRQ & (1<<0)) ? 1 : 0; + } + /* Return current status of endpoint */ + USB_Write(pCdc->pUsb, (char *) &wStatus, sizeof(wStatus), USB_EP_CTRL); + } + else + { + /* Stall the request */ + USB_SendStall(pUsb, true); + } + break; + + case STD_SET_FEATURE_ZERO: + /* Stall the request */ + USB_SendStall(pUsb, true); + break; + + case STD_SET_FEATURE_INTERFACE: + /* Send ZLP */ + USB_SendZlp(pUsb); + break; + + case STD_SET_FEATURE_ENDPOINT: + dir = wIndex & 0x80; + wIndex &= 0x0F; + if ((wValue == 0) && wIndex && (wIndex <= 3)) + { + /* Set STALL request for the endpoint */ + if (dir) + { + //pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUSSET.reg = USB_DEVICE_EPSTATUSSET_STALLRQ1; + pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUSSET.bit.STALLRQ = (1<<1); + } + else + { + //pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUSSET.reg = USB_DEVICE_EPSTATUSSET_STALLRQ0; + pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUSSET.bit.STALLRQ = (1<<0); + } + + /* Send ZLP */ + USB_SendZlp(pUsb); + } + else + { + /* Stall the request */ + USB_SendStall(pUsb, true); + } + break; + + case STD_SET_INTERFACE: + case STD_CLEAR_FEATURE_ZERO: + /* Stall the request */ + USB_SendStall(pUsb, true); + break; + + case STD_CLEAR_FEATURE_INTERFACE: + /* Send ZLP */ + USB_SendZlp(pUsb); + break; + + case STD_CLEAR_FEATURE_ENDPOINT: + dir = wIndex & 0x80; + wIndex &= 0x0F; + + if ((wValue == 0) && wIndex && (wIndex <= 3)) + { + if (dir) + { + if (pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUS.bit.STALLRQ & (1<<1)) + { + // Remove stall request + //pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUSCLR.reg = USB_DEVICE_EPSTATUSCLR_STALLRQ1; + pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUSCLR.bit.STALLRQ = (1<<1); + if (pUsb->DEVICE.DeviceEndpoint[wIndex].EPINTFLAG.bit.STALL & (1<<1)) + { + pUsb->DEVICE.DeviceEndpoint[wIndex].EPINTFLAG.bit.STALL = (1<<1); + // The Stall has occurred, then reset data toggle + pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUSCLR.reg = USB_DEVICE_EPSTATUSSET_DTGLIN; + } + } + } + else + { + if (pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUS.bit.STALLRQ & (1<<0)) + { + // Remove stall request + //pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUSCLR.reg = USB_DEVICE_EPSTATUSCLR_STALLRQ0; + pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUSCLR.bit.STALLRQ = (1<<0); + if (pUsb->DEVICE.DeviceEndpoint[wIndex].EPINTFLAG.bit.STALL & (1<<0)) + { + pUsb->DEVICE.DeviceEndpoint[wIndex].EPINTFLAG.bit.STALL = (1<<0); + // The Stall has occurred, then reset data toggle + pUsb->DEVICE.DeviceEndpoint[wIndex].EPSTATUSCLR.reg = USB_DEVICE_EPSTATUSSET_DTGLOUT; + } + } + } + /* Send ZLP */ + USB_SendZlp(pUsb); + } + else + { + USB_SendStall(pUsb, true); + } + break; + + // handle CDC class requests + case SET_LINE_CODING: + /* Send ZLP */ + USB_SendZlp(pUsb); + break; + + case GET_LINE_CODING: + /* Send current line coding */ + USB_Write(pCdc->pUsb, (char *) &line_coding, SAM_BA_MIN(sizeof(usb_cdc_line_coding_t), wLength), USB_EP_CTRL); + break; + + case SET_CONTROL_LINE_STATE: + /* Store the current connection */ + pCdc->currentConnection = wValue; + /* Send ZLP */ + USB_SendZlp(pUsb); + break; + + default: + /* Stall the request */ + USB_SendStall(pUsb, true); + break; + } +} + +/*---------------------------------------------------------------------------- + * \brief + */ +P_USB_CDC usb_init(void) +{ + sam_ba_cdc.pUsb = USB; + + /* Initialize USB */ + USB_Init(); + /* Get the default CDC structure settings */ + USB_Open(&sam_ba_cdc, sam_ba_cdc.pUsb); + + return &sam_ba_cdc; +} + +#if 0 // TODO: pending validation +/*---------------------------------------------------------------------------- + * \brief Send a USB descriptor string. + * + * The input string is plain ASCII but is sent out as UTF-16 with the correct 2-byte prefix. + */ +uint32_t USB_SendString(Usb *pUsb, const char* ascii_string, uint8_t length, uint8_t maxLength) +{ + uint8_t string_descriptor[255]; // Max USB-allowed string length + uint16_t* unicode_string=(uint16_t*)(string_descriptor+2); // point on 3 bytes of descriptor + + int resulting_length = 1; + + for ( ; *ascii_string && (length>=0) && (resulting_length<(maxLength>>1)) ; ascii_string++, length--, resulting_length++ ) + { + *unicode_string++ = (uint16_t)(*ascii_string); + } + + string_descriptor[0] = (resulting_length<<1); + string_descriptor[1] = STD_GET_DESCRIPTOR_STRING; + + return USB_Write(pUsb, (const char*)unicode_string, resulting_length, USB_EP_CTRL); +} +#endif // 0 diff --git a/bootloaders/zero/sam_ba_usb.h b/bootloaders/zero/sam_ba_usb.h new file mode 100644 index 000000000..42c0d608f --- /dev/null +++ b/bootloaders/zero/sam_ba_usb.h @@ -0,0 +1,107 @@ +/* + Copyright (c) 2015 Arduino LLC. All right reserved. + Copyright (c) 2015 Atmel Corporation/Thibaut VIARD. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef CDC_ENUMERATE_H +#define CDC_ENUMERATE_H + +#include +#include + +#define USB_EP_CTRL (0u) +#define USB_EP_OUT (2u) +#define USB_EP_OUT_SIZE (0x40u) +#define USB_EP_IN (1u) +#define USB_EP_IN_SIZE (0x40u) +#define USB_EP_COMM (3u) +#define MAX_EP (4u) + +/* USB standard request code */ +#define STD_GET_STATUS_ZERO (0x0080u) +#define STD_GET_STATUS_INTERFACE (0x0081u) +#define STD_GET_STATUS_ENDPOINT (0x0082u) + +#define STD_CLEAR_FEATURE_ZERO (0x0100u) +#define STD_CLEAR_FEATURE_INTERFACE (0x0101u) +#define STD_CLEAR_FEATURE_ENDPOINT (0x0102u) + +#define STD_SET_FEATURE_ZERO (0x0300u) +#define STD_SET_FEATURE_INTERFACE (0x0301u) +#define STD_SET_FEATURE_ENDPOINT (0x0302u) + +#define STD_SET_ADDRESS (0x0500u) +#define STD_GET_DESCRIPTOR (0x0680u) +#define STD_SET_DESCRIPTOR (0x0700u) +#define STD_GET_CONFIGURATION (0x0880u) +#define STD_SET_CONFIGURATION (0x0900u) +#define STD_GET_INTERFACE (0x0A81u) +#define STD_SET_INTERFACE (0x0B01u) +#define STD_SYNCH_FRAME (0x0C82u) + +#define STD_GET_DESCRIPTOR_DEVICE (1u) +#define STD_GET_DESCRIPTOR_CONFIGURATION (2u) +#define STD_GET_DESCRIPTOR_STRING (3u) +#define STD_GET_DESCRIPTOR_INTERFACE (4u) +#define STD_GET_DESCRIPTOR_ENDPOINT (5u) +#define STD_GET_DESCRIPTOR_DEVICE_QUALIFIER (6u) +#define STD_GET_DESCRIPTOR_OTHER_SPEED_CONFIGURATION (7u) +#define STD_GET_DESCRIPTOR_INTERFACE_POWER1 (8u) + +#define FEATURE_ENDPOINT_HALT (0u) +#define FEATURE_DEVICE_REMOTE_WAKEUP (1u) +#define FEATURE_TEST_MODE (2u) + +#if 0 // TODO: pending validation +#define STRING_INDEX_LANGUAGES (0x00u) +#define STRING_INDEX_MANUFACTURER (0x01u) +#define STRING_INDEX_PRODUCT (0x02u) +#endif // 0 + +#define SAM_BA_MIN(a, b) (((a) < (b)) ? (a) : (b)) + + +typedef struct _USB_CDC +{ + // Private members + Usb *pUsb; + uint8_t currentConfiguration; + uint8_t currentConnection; + // Public Methods: + uint8_t (*IsConfigured)(struct _USB_CDC *pCdc); +// uint32_t (*Write) (Usb *pUsb, const char *pData, uint32_t length, uint8_t ep_num); +// uint32_t (*Read) (Usb *pUsb, char *pData, uint32_t length); +} USB_CDC, *P_USB_CDC; + +/** + * \brief Initializes the USB module + * + * \return Pointer to the USB CDC structure + */ +P_USB_CDC usb_init(void); + +void sam_ba_usb_CDC_Enumerate(P_USB_CDC pCdc); + +#if 0 // TODO: pending validation +uint32_t USB_SendString(Usb *pUsb, const char* ascii_string, uint8_t length, uint8_t maxLength); +#endif // 0 + +extern USB_CDC sam_ba_cdc; + + + +#endif // CDC_ENUMERATE_H diff --git a/bootloaders/zero/samd21_sam_ba.atsln b/bootloaders/zero/samd21_sam_ba.atsln new file mode 100644 index 000000000..cf1043181 --- /dev/null +++ b/bootloaders/zero/samd21_sam_ba.atsln @@ -0,0 +1,22 @@ + +Microsoft Visual Studio Solution File, Format Version 12.00 +# Atmel Studio Solution File, Format Version 11.00 +VisualStudioVersion = 14.0.23107.0 +MinimumVisualStudioVersion = 10.0.40219.1 +Project("{54F91283-7BC4-4236-8FF9-10F437C3AD48}") = "samd21_sam_ba", "samd21_sam_ba.cproj", "{DCE6C7E3-EE26-4D79-826B-08594B9AD897}" +EndProject +Global + GlobalSection(SolutionConfigurationPlatforms) = preSolution + Debug|ARM = Debug|ARM + Release|ARM = Release|ARM + EndGlobalSection + GlobalSection(ProjectConfigurationPlatforms) = postSolution + {DCE6C7E3-EE26-4D79-826B-08594B9AD897}.Debug|ARM.ActiveCfg = Debug|ARM + {DCE6C7E3-EE26-4D79-826B-08594B9AD897}.Debug|ARM.Build.0 = Debug|ARM + {DCE6C7E3-EE26-4D79-826B-08594B9AD897}.Release|ARM.ActiveCfg = Release|ARM + {DCE6C7E3-EE26-4D79-826B-08594B9AD897}.Release|ARM.Build.0 = Release|ARM + EndGlobalSection + GlobalSection(SolutionProperties) = preSolution + HideSolutionNode = FALSE + EndGlobalSection +EndGlobal diff --git a/bootloaders/zero/samd21_sam_ba.bin b/bootloaders/zero/samd21_sam_ba.bin index 08f40f425..d727d0707 100644 Binary files a/bootloaders/zero/samd21_sam_ba.bin and b/bootloaders/zero/samd21_sam_ba.bin differ diff --git a/bootloaders/zero/samd21_sam_ba.cproj b/bootloaders/zero/samd21_sam_ba.cproj new file mode 100644 index 000000000..70ee7e93a --- /dev/null +++ b/bootloaders/zero/samd21_sam_ba.cproj @@ -0,0 +1,218 @@ + + + + 2.0 + 7.0 + com.Atmel.ARMGCC.C + dce6c7e3-ee26-4d79-826b-08594b9ad897 + ATSAMD21G18A + none + Executable + C + $(MSBuildProjectName) + .elf + $(MSBuildProjectDirectory)\$(Configuration) + samd21_sam_ba + samd21_sam_ba + samd21_sam_ba + Native + true + false + true + true + 0x20000000 + + true + exception_table + 2 + 0 + + + + + + + + + + + + + + com.atmel.avrdbg.tool.atmelice + J41800001895 + 0x10010000 + SWD + + + + 2000000 + + SWD + + com.atmel.avrdbg.tool.atmelice + J41800001895 + Atmel-ICE + + 2000000 + + + + + SWD + + com.atmel.avrdbg.tool.edbg + ATML2320040200000259 + EDBG + + + + + + True + True + True + True + True + + + NDEBUG + + + Optimize for size (-Os) + True + True + + + libm + + + True + -Tsamd21j18a_flash.ld + + + + + + + True + True + True + True + True + + + DEBUG + + + Optimize (-O1) + True + Maximum (-g3) + True + + + libm + + + True + -Tsamd21j18a_flash.ld + Default (-g) + Default (-Wa,-g) + + + True + + DEBUG=1 all + clean + Makefile + + + + compile + board_definitions.h + + + compile + board_driver_led.c + + + compile + board_driver_led.h + + + compile + board_driver_serial.c + + + compile + board_driver_serial.h + + + compile + board_driver_usb.c + + + compile + board_driver_usb.h + + + compile + board_init.c + + + compile + board_startup.c + + + compile + main.c + + + compile + sam_ba_cdc.c + + + compile + sam_ba_cdc.h + + + compile + sam_ba_monitor.c + + + compile + sam_ba_monitor.h + + + compile + sam_ba_serial.c + + + compile + sam_ba_serial.h + + + compile + sam_ba_usb.c + + + compile + sam_ba_usb.h + + + + + compile + Makefile + + + compile + README.md + + + compile + bootloader_samd21x18.ld + + + + \ No newline at end of file diff --git a/bootloaders/zero/samd21_sam_ba.elf b/bootloaders/zero/samd21_sam_ba.elf new file mode 100644 index 000000000..edee94811 Binary files /dev/null and b/bootloaders/zero/samd21_sam_ba.elf differ diff --git a/bootloaders/zero/samd21_sam_ba.hex b/bootloaders/zero/samd21_sam_ba.hex new file mode 100644 index 000000000..1fde99e8a --- /dev/null +++ b/bootloaders/zero/samd21_sam_ba.hex @@ -0,0 +1,376 @@ +:10000000FC7F0020E9050000D5050000D9050000AF +:1000100000000000000000000000000000000000E0 +:10002000000000000000000000000000DD050000EE +:100030000000000000000000E1050000E5050000F0 +:1000400010B5064C2378002B07D1054B002B02D0AE +:10005000044800E000BF0123237010BD58000020B9 +:1000600000000000F816000008B5084B002B03D074 +:100070000748084900E000BF07480368002B03D089 +:10008000064B002B00D0984708BDC046000000007A +:10009000F81600005C000020540000200000000062 +:1000A00010B5C3699C07FCD403680224A343036012 +:1000B000C46901231C42FBD1046823430360036825 +:1000C000DC07FCD4C46901231C42FBD1C469DC40B9 +:1000D0001C42F7D1084B1A430260C3695A07FCD48B +:1000E000C0239B0243608181C3699C07FCD40368E1 +:1000F00002221343036010BD04000040037EDA07B0 +:10010000FCD5018570470000027E01235107FBD515 +:10011000428B1A4207D1428BDA401A4203D1428BFA +:1001200092081A4202D0034B01221A70008DC0B20D +:100130007047C0467400002070B50368041C988B9B +:100140001A1C0821FF32084228D0988B174D014312 +:10015000802099839872112353704021144B917120 +:1001600050715E68C0202E40800506435E605E6967 +:100170003540284358610F4818600F4818615D6882 +:100180000E4828408025AD02284358605868800BEF +:100190008003586000235171237105E0137ADA0659 +:1001A00002D5201C00F0A0FA207970BDFFFFFF8F60 +:1001B0008C0100208C0000200C010020FF3F00F08B +:1001C000002303714371044B016083600B780222AA +:1001D00013430B707047C0463901000038B5364BE9 +:1001E0002021DA6901200A43DA61344B06241A78A7 +:1001F00002431A70324B0F22197891431970197803 +:10020000214319702F490C782043087019780A404F +:100210001A701A7860210A431A702B4B2B4A5A80A5 +:100220005A7852B2002AFBDB294B01211A780A4383 +:100230001A709A78D107FCD426480268510B1F2205 +:100240001140914200D1052111408C011D8D2249A0 +:100250002940214319850468A10C0A401F2A00D1B6 +:100260001D221C8D1F210A408C4322431A850268DF +:100270000721D20D0A408A4200D103220A40188D7C +:100280001103164A02400A431A8519787F220A4050 +:100290001A701A78042112480A431A7058621A898F +:1002A0000C218A431A811A8901218A431A8100216B +:1002B000802201F0B6F838BD0004004058440041E7 +:1002C0003C44004159440041000C004006400000FD +:1002D00000500041246080003FF8FFFFFF8FFFFFC8 +:1002E0008C010020F7B5141C234A5F0101971D1CE7 +:1002F000D319061C5869271C4000400F03301033E7 +:10030000C74006D00F1C8022596812060A435A6063 +:1003100009E02F1C7B1E9F41184BBF01FF18381CA2 +:10032000221C01F075F8019913480835421817612D +:10033000131C5269A104920B890C92030A435A615F +:1003400059690F4A02200A405A616B01F318D979A2 +:10035000032211400143D8799043021C0A43DA7109 +:100360005979802252420A435A716B01F318DB79A2 +:100370009A07FAD5201CFEBD8C0100200C0100203C +:10038000FF3F00F0F8B51E4E041C3378151C002BFF +:1003900012D11C4B1C4A1A645A6C920B92035A6479 +:1003A000586C1A4A02405A64A2235B00E25C402067 +:1003B0000243E254012333704827FF37E25D0123F3 +:1003C00013401AD00F4B5A6C9204920CAA4202D2DC +:1003D0005D6CAD04AD0C081C2A1C0B4901F018F82B +:1003E000E25D03231A4001210A43E15D99430B1C9E +:1003F0001343E3550023337000E01D1C281CF8BD97 +:10040000750000208C010020CC000020FF3F00F090 +:10041000FF30827930239A43131C2022002900D117 +:1004200010221343837170470C4BFF305A6902212D +:10043000920B92035A61027A03231A400A43017A0B +:1004400099430B1C13430372827980235B4213434D +:100450008371037A9A07FCD57047C0468C0100204F +:1004600080235B421943C9B28172704770B5A023E3 +:1004700003225B00C254134B134A5C6CC02114402E +:1004800089050C4346255C64FF35402444550F4DD7 +:1004900030261D6490256D0046555D6B154029433F +:1004A000922559636D0080214155094D1D63B0258A +:1004B0006D0044555C6F22405A67B2235B00C15403 +:1004C00070BDC0468C010020FFFFFF8FCC000020D4 +:1004D0004C01002030B5364A1E235168082099434C +:1004E00002231943516033498A6902438A613248C1 +:1004F000324A9082908A03439382D3689807FCD54E +:100500002F4B012018701878C40704D52C48407868 +:1005100040B20028F7DB01209860587840B20028EC +:10052000FBDB284C26484460587840B20028FBDBAF +:1005300082242348E4014480587840B20028FBDB41 +:10054000908C8024A0439084D068C506FCD51E4CB6 +:100550001A48C462D4681948E506FBD5848C1B4D43 +:100560002C438484D4681548E506FBD5848C022589 +:100570002C438484D0680406FCD51048C068450626 +:10058000F8D5D068C406FCD500229A605A7852B2D9 +:10059000002AFBDB0E480A4A50605A7852B2002A01 +:1005A000FBDB00230B724B728B72CB7230BDC046EB +:1005B00000400041000400400C060000000800401C +:1005C000000C004001050100B805FF7D040A000091 +:1005D000000703000EBEFEE70DBEFEE705BEFEE708 +:1005E00002BEFEE701BEFEE70E4A0F4838B5824262 +:1005F00004D10E4A0E4B93420ED10AE00D4C9442A8 +:10060000F7D00023D1188842F3D9E55804330D60A0 +:10061000F8E700F011F804E09342FAD2002102C397 +:10062000FAE7FEE7000000205800002098030020B1 +:1006300058000020FC16000010B5244B0022197849 +:1006400001231940224B0AD11868224A904201D155 +:10065000196014E01A60204A013A002AFCD11A609D +:100660001E4B1968181C4A1C09D0FF22134206D1E0 +:1006700081F3088893431A4A936043681847FFF749 +:1006800029FF62B600F0F2FC00F0C8F9041CA36870 +:10069000201C9847134B002801D001221A701A78A9 +:1006A000002A05D0002000F035FA00F091FAFCE7AE +:1006B0001B78002BEBD100F04DFD0028E7D0012086 +:1006C00000F028FA00F084FAFCE7C0463804004045 +:1006D000FC7F00203581730748E8010000200000FE +:1006E00000ED00E076000020F8B50468051C201C31 +:1006F000FF30037AB64A10210B430372B54F1378CB +:10070000B5493B705378B54E0B7093783380D178F0 +:10071000338809020B4333801179B14B1980517929 +:100720001F8809020F431F809779AE490F80D27945 +:100730000F8812023A430A8040224271A648A54F10 +:1007400002783878A84F12020243181CBA4200D12E +:1007500099E01EDC802149008A4200D158E107DC83 +:10076000812A6AD0822A6ED0802A00D050E164E0CB +:1007700081235B009A4200D1AFE000DA23E1C0237D +:100780009B009A4200D143E1984B9A4200D11AE172 +:100790003EE190231B019A4242D015DCD023DB00BE +:1007A0009A4222D088231B019A4242D0A023DB0028 +:1007B0009A4200D02CE1201CFFF736FE31882868D1 +:1007C00089B2FFF74DFE27E1894B9A4200D1FAE04A +:1007D00000DC1DE1874B9A4200D1E8E0864B9A424B +:1007E00000D015E133886B71EDE033881B0A012BD3 +:1007F00008D10B8812222868934201D80A8892B245 +:100800007E49DCE033881B0A022B00D000E10B8814 +:1008100043222868934201D80A8892B27849CEE0F0 +:100820003388201C2B71FFF7FFFD201CFFF71EFEF5 +:10083000F2E0291C01C90122C1E0724900230B80AA +:1008400028680222BCE06F4900220A8018885022E2 +:1008500010406D4A10701E880F2030401880188894 +:10086000032800D9D4E012781B8808335B01E41810 +:10087000A379002A01D09B0600E0DB06DB0F0B808A +:10088000286802229BE019887F2291435E4AC9B200 +:10089000117018880F21014019803188002900D07B +:1008A000B6E01988002900D1B2E01988032900D9DF +:1008B000AEE012781B8808335B01E318002A05D0EC +:1008C0005A7930218A4320210A4304E05A793021A1 +:1008D0008A43102002435A7175E002887F239A43AD +:1008E000494BD2B21A7001880F220A400280328826 +:1008F000002A00D08CE00288002A00D188E002881B +:10090000032A00D984E01B78002B27D00388083302 +:100910005B01E3189B79990655D50388302108338C +:100920005B01E3181A798A4320210A431A7103886C +:1009300008335B01E318DB795A0644D5038860214C +:1009400008335B01E318DA798A4340210A43DA71FC +:100950000388022208335B01E31826E0038808338A +:100960005B01E3189B79DF062DD50388302108331E +:100970005B01E3181A798A4310210A431A7103882C +:1009800008335B01E318DB7999061CD503886021E5 +:1009900008335B01E318DA798A4320210A43DA71CC +:1009A0000388012208335B01E3181A710BE00B88FE +:1009B00008222868934201D80A8892B2134900237A +:1009C000FFF790FC28E0201CFFF72EFD24E0C04636 +:1009D0008C0000208100002077000020780000209B +:1009E0007C0000207E0000200203000001030000C4 +:1009F00021200000A1210000212200004C14000051 +:100A0000000000207A000020800000204400002028 +:100A1000201C0121FFF7FCFCF8BDC04610B5054BBA +:100A2000054C2360FFF7DAFB201C2168FFF7C8FBA9 +:100A3000201C10BD005000410C02002007B5054BE2 +:100A40000122019001A91868131CFFF74BFC01203B +:100A50000EBDC0460C02002013B5054B6C46073492 +:100A60001868211C0122FFF78DFC207816BDC046B6 +:100A70000C02002010B5074C201CFFF75DFB031C87 +:100A80000020834205D022684823FF33D05C012335 +:100A9000184010BD0C02002010B5054A0C1C031CA8 +:100AA000191C10680123221CFFF71CFC201C10BD20 +:100AB0000C02002070B5084C061C201C0D1CFFF712 +:100AC0003BFB0023984205D02068311C2A1CFFF70D +:100AD00059FC031C181C70BD0C020020F8B50C4C0E +:100AE000051C201C0E1CFFF727FB0023271C341CB1 +:100AF00098420AD0002C07D0291C221C3868FFF726 +:100B000041FC241A2D18F5E7331C181CF8BDC0460B +:100B10000C020020012805D1054B064A1A60064B3D +:100B2000187004E0002802D1044A014B1A60704793 +:100B30007C0200208014000089000020CC140000FA +:100B400030B51A4B85B01B78002B29D0042901D170 +:100B5000026804E0022901D1028800E0027849001D +:100B600004A843180B3B5C1AA3420BD00F20104083 +:100B7000092802D83025284300E0373018701209C0 +:100B8000013BF1E701A830230370782343700A2268 +:100B900043189A700D22DA70054B04311B6801E08E +:100BA000034B1B68DB68984705B030BD8800002008 +:100BB0007C02002072B6EFF30883044A13600368D6 +:100BC00083F30888436818477047C04680020020B6 +:100BD000F0B58FB006A9CD4A0B1C31CA31C351CA3A +:100BE00051C360CA60C3CA4CCA48A3687A255B0374 +:100BF0005B0F9B005B58C8490360A26892B25343E5 +:100C00000A60C649C64A0B6000231360C54B1D70BD +:100C1000C54BC64D1B68281C1B6940219847C44B17 +:100C200000221860C34B1D60C34BC34DC04F1A60F8 +:100C3000286839688842EBD2BE4B1B681A78FF2AB5 +:100C400000D1F7E1232A00D0CEE1BC4E3378002B4F +:100C500005D0B54BBA481B680221DB689847B14BF9 +:100C60001B78532B38D13B682A6893421ED9B14870 +:100C700001322A609A1AB34B01681B680131016086 +:100C8000B14E9A4201D2326000E03360A44832682B +:100C90000068029000F0BCFB336829685A182A608B +:100CA000A44A1668F1181160A84A13702B68013B1A +:100CB0002B60A04B1A68013A1A60A44BA14A1B781A +:100CC00011688B4206D2984A954812680068C91A82 +:100CD00092699047C04676E1522B07D1904A924BD9 +:100CE00010681B68974A5B6911686BE14F2B05D14F +:100CF0008B4B944A1B6812681A7064E1482B05D12B +:100D0000874B904A1B6812681A805CE1572B05D10B +:100D1000834B8C4A1B6812681A6054E16F2B03D115 +:100D20007F4B0121186807E0682B08D17C4B854870 +:100D30001B6802211B880360FFF702FF43E1772B4A +:100D400006D1774B7F481B6804211B680360F3E7DB +:100D5000472B13D17B4B1868FFF72CFF7C4B1B688C +:100D600083F3088862B67B4B1B78002B00D12AE105 +:100D70006D4B06201B681B68984724E1542B04D157 +:100D800001233370684B1B685CE04E2B0BD133782A +:100D9000002B05D1644B6A481B680221DB68984729 +:100DA000002333700FE1562B50D15F4D01212B688A +:100DB0006948DB6898472B680321DB6867489847D8 +:100DC000674E2B68301CDB68012198472B680D218A +:100DD000DB68644898472B68301CDB680121984722 +:100DE000544F614B544E3B60002333603A1C311C1E +:100DF0001368581C10601B780393002B03D00B68FA +:100E000001330B60F4E72B683168DB68564898477C +:100E10002B685348DB68012198470398306053489A +:100E20003860444A1368591C11601A78424B002AF2 +:100E300003D01A6801321A60F3E72A681968D36888 +:100E400098472B68DB683E480221BBE03D4A582B9F +:100E500015D1304E314D366813682A68B10093427F +:100E600008D25808E06142482080207DC507FCD5A3 +:100E70005B18F4E72C4B3F481B68DB68A1E0592B5B +:100E800033D11268264B3C49002A02D11B680B6003 +:100E900026E00868196863688025AB4392086360A0 +:100EA000002A1DD0354B2380237DDE07FCD500238F +:100EB000184D2D680095AD08AB4202D3304D25800A +:100EC00006E09342FAD09D00465901334E51EFE7B8 +:100ED000257DEE07FCD59D0049194019D21ADFE7A0 +:100EE000114B28481B68DB686BE05A2B6BD10C4B0D +:100EF00017681D680026EF19BD4245D02878311CBF +:100F000000F04AF90135061CF6E7C04660140000FF +:100F100000400041340200202C0200202802002062 +:100F200078020020240200207C02002038020020E9 +:100F30001C02002020020020300200208800002037 +:100F4000C014000084020020880200201802002043 +:100F500080020020890000209C140000C5140000BD +:100F60009E140000E8140000A0140000AC1400005F +:100F700002A5FFFFB51400008400002044A5FFFF78 +:100F800004A5FFFFB91400002E4D2F482B68012146 +:100F9000DB68984707230F223240111C3609303195 +:100FA000092A00DD07311020C0186A468154013B30 +:100FB000F1D22B6804A8DB68082198472B682348E6 +:100FC000DB6803219847224D7A232B70214B0022A6 +:100FD0001A60214B1B7893422CD01A4B01211B68BD +:100FE0001E48DB68984725E0111C3039C8B2194B00 +:100FF000092804D81E683201114319601AE0111C37 +:101000004139052903D81868373A010106E0111C57 +:101010006139052904D81D68573A29010A4308E0B7 +:101020002C2A03D10E4A1E68166001E008490A7096 +:1010300000221A600B4B1A6801321A600A4B1A68B8 +:101040000132F2E57C020020BD140000BF14000054 +:10105000240200208402002088000020C314000025 +:1010600078020020300200202002002010B51C4B26 +:1010700001201A78022402431A701A4B0F221978A1 +:101080009143197019782143197017490C7820433E +:10109000087019780A401A701A7820210A431A70C9 +:1010A000124B04211A6A0A431A62114B114A5A80E0 +:1010B0005A7852B2002AFBDBC4220F480F49920330 +:1010C000FEF7EEFF0E4A002313700E4A13700E4A0D +:1010D00013700E4A13700E4A13700E4A137010BD2F +:1010E0004A440041354400414B4400410004004063 +:1010F000000C0040144000000008004204C500003D +:101100008C020020130300208D020020900200209A +:10111000140300201103002008B5C1B20248FEF7F5 +:10112000EDFF012008BDC04600080042024B187EBA +:101130004007C00F7047C0460008004208B5FFF7DF +:10114000F5FF0028FBD00248FEF7DEFF08BDC046D1 +:101150000008004208B5FFF7E9FF0023984205D0D8 +:10116000FFF7ECFF031C233B5A425341181C08BDF8 +:1011700070B5041C0D1C4618B44204D02078FFF74B +:10118000CBFF0134F8E7281C70BD10B5041CFFF735 +:10119000D5FF2070012010BD0B0A5840034B4000C2 +:1011A000C05A0902484080B27047C046F614000099 +:1011B000F7B50024051C0F1C261CBC4220D0FFF7ED +:1011C000BDFF114BC0B21B780190002B1AD1311C0E +:1011D000FFF7E2FF0D4B061C1A88002A04D10C4AC7 +:1011E00011782A1C002907D001996A1C2970802FC8 +:1011F00002D11988013919800134A4B2151CDCE729 +:10120000301C00E00120FEBD110300208E020020F2 +:1012100012030020F0B53E4E85B0002203900C1C56 +:1012200032703C4B914201D1012201E03A490C80DD +:101230001A707F231C4201D080349C43FFF77EFF4D +:101240003378C0B2002B07D000253570FFF776FF4A +:101250003378C0B2AB4236D1432803D0712853D083 +:101260001528EBD1012300930120FFF755FF0098CB +:10127000FFF752FF00998025C843C0B2FFF74CFF2B +:10128000039B00270293244A1388002B1DD1214978 +:1012900001930978002918D10198FFF73DFF391C07 +:1012A0000198FFF779FF013D071C002DEBD1000AE3 +:1012B000C0B2FFF731FFF8B2FFF72EFFFFF73EFF96 +:1012C0003378002B0AD035701FE00299013B097872 +:1012D0001380029B019101330293DDE7C0B206281F +:1012E00007D1009B03990133DBB280310093803C2E +:1012F0000391002CB8D10420FFF70EFFFFF71EFF6B +:10130000044B01251C7000E00025281C05B0F0BD31 +:1013100011030020120300208E020020F0B5384C8B +:1013200087B0002301902370994201D1012301E08D +:10133000344A1180344A642613704320FFF7ECFED0 +:10134000324FFFF7F3FE002803D1002F03D0013FF7 +:10135000F7E7002F03D1013E002EEED14DE001252D +:10136000FFF7ECFE2378002B38D1C0B202900128A1 +:1013700005D004283DD10620FFF7CEFE39E005AEAA +:101380000221301CFFF714FF01988021FFF710FFA6 +:1013900023780390002B18D1FFF7D0FE0702FFF748 +:1013A000CDFEBFB223783F18BFB2012B0DD0039BF7 +:1013B0009F4207D13378AB4204D1EB437278DBB262 +:1013C0009A4204D01820FFF7A7FE002303E006206E +:1013D000FFF7A2FE029B2278002A02D00026267088 +:1013E0000BE0012B05D1019A6B1C8032DDB201921A +:1013F000B6E7054A002313700126301C07B0F0BD84 +:10140000110300208E0200201203002000350C0082 +:1014100010B50023934203D0CC5CC4540133F9E7E8 +:1014200010BD031C8218934202D019700133FAE7F1 +:1014300070470000F8B5C046F8BC08BC9E4670472F +:10144000F8B5C046F8BC08BC9E46704712010002C1 +:101450000200004041234D00000200000001000096 +:101460000800000010000000200000004000000004 +:1014700080000000000100000002000000040000E5 +:10148000191100003D1100002D1100007111000024 +:101490008B110000151200001D13000076002000C3 +:1014A0004F637420313020323031350031353A35D8 +:1014B000373A343500580A0D00590A0D005A0023F6 +:1014C0000A0D003E00322E30000000003D0A0000F0 +:1014D000590A0000750A0000990A0000B50A0000C8 +:1014E000990A0000DD0A00005B41726475696E6F45 +:1014F0003A58595A5D000000211042206330844060 +:10150000A550C660E770088129914AA16BB18CC1D2 +:10151000ADD1CEE1EFF13112100273325222B55249 +:101520009442F772D662399318837BB35AA3BDD322 +:101530009CC3FFF3DEE36224433420040114E66419 +:10154000C774A44485546AA54BB528850995EEE572 +:10155000CFF5ACC58DD55336722611163006D77629 +:10156000F6669556B4465BB77AA719973887DFF7C2 +:10157000FEE79DD7BCC7C448E5588668A7784008F1 +:10158000611802282338CCC9EDD98EE9AFF9488912 +:1015900069990AA92BB9F55AD44AB77A966A711A89 +:1015A000500A333A122AFDDBDCCBBFFB9EEB799B62 +:1015B000588B3BBB1AABA66C877CE44CC55C222CD9 +:1015C000033C600C411CAEED8FFDECCDCDDD2AADB2 +:1015D0000BBD688D499D977EB66ED55EF44E133E69 +:1015E000322E511E700E9FFFBEEFDDDFFCCF1BBF02 +:1015F0003AAF599F788F8891A981CAB1EBA10CD1DC +:101600002DC14EF16FE18010A100C230E3200450E3 +:10161000254046706760B9839893FBA3DAB33DC356 +:101620001CD37FE35EF3B1029012F322D232354233 +:10163000145277625672EAB5CBA5A89589856EF5E6 +:101640004FE52CD50DC5E234C324A0148104667483 +:10165000476424540544DBA7FAB79987B8975FE736 +:101660007EF71DC73CD7D326F2369106B0165766D3 +:101670007676154634564CD96DC90EF92FE9C899BE +:10168000E9898AB9ABA94458654806782768C01823 +:10169000E1088238A3287DCB5CDB3FEB1EFBF98B96 +:1016A000D89BBBAB9ABB754A545A376A167AF10A73 +:1016B000D01AB32A923A2EFD0FED6CDD4DCDAABDA6 +:1016C0008BADE89DC98D267C076C645C454CA23CC3 +:1016D000832CE01CC10C1FEF3EFF5DCF7CDF9BAF76 +:1016E000BABFD98FF89F176E367E554E745E932E13 +:0C16F000B23ED10EF01E00000000000011 +:1016FC0009024300020100803209040000010202C9 +:10170C000000052400100104240200052406000139 +:10171C000524010001070583030800FF09040100EB +:10172C00020A0000000705810240000007050202C2 +:10173C004000000000C20100000008006900000029 +:08174C00410000000000000054 +:04000003000005E90B +:00000001FF diff --git a/bootloaders/zero/samd21j18a_flash.ld b/bootloaders/zero/samd21j18a_flash.ld deleted file mode 100644 index c9385c487..000000000 --- a/bootloaders/zero/samd21j18a_flash.ld +++ /dev/null @@ -1,157 +0,0 @@ -/** - * \file - * - * \brief Linker script for running in internal FLASH on the SAMD21J18A - * - * Copyright (c) 2013-2014 Atmel Corporation. All rights reserved. - * - * \asf_license_start - * - * \page License - * - * 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. - * - * 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. - * - * 3. The name of Atmel 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 - * 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 - * - */ - - -OUTPUT_FORMAT("elf32-littlearm", "elf32-littlearm", "elf32-littlearm") -OUTPUT_ARCH(arm) -SEARCH_DIR(.) - -/* Memory Spaces Definitions */ -MEMORY -{ - rom (rx) : ORIGIN = 0x00000000, LENGTH = 0x00040000 - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 0x00008000-0x0004 /* 4 bytes used by bootloader to keep data between resets */ -} - -/* The stack size used by the application. NOTE: you need to adjust according to your application. */ -STACK_SIZE = DEFINED(STACK_SIZE) ? STACK_SIZE : DEFINED(__stack_size__) ? __stack_size__ : 0x2000; - -/* 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(4); - 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); - _sstack = .; - . = . + STACK_SIZE; - . = ALIGN(8); - _estack = .; - } > ram - - . = ALIGN(4); - _end = . ; -} diff --git a/bootloaders/zero/startup_samd21.c b/bootloaders/zero/startup_samd21.c deleted file mode 100644 index 0f45ae3f9..000000000 --- a/bootloaders/zero/startup_samd21.c +++ /dev/null @@ -1,201 +0,0 @@ -/** - * \file - * - * \brief gcc starttup file for SAMD21 - * - * Copyright (c) 2013-2014 Atmel Corporation. All rights reserved. - * - * \asf_license_start - * - * \page License - * - * 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. - * - * 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. - * - * 3. The name of Atmel 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 - * 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 - * - */ - -#include "sam.h" - -/* 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; -extern uint32_t _sstack; -extern uint32_t _estack; - -/** \cond DOXYGEN_SHOULD_SKIP_THIS */ -int main(void); -/** \endcond */ - -void __libc_init_array(void); - -/* Default empty handler */ -void Dummy_Handler(void); - -/* Cortex-M0+ core handlers */ -void NMI_Handler ( void ) __attribute__ ((weak, alias("Dummy_Handler"))); -void HardFault_Handler ( void ) __attribute__ ((weak, alias("Dummy_Handler"))); -void SVC_Handler ( void ) __attribute__ ((weak, alias("Dummy_Handler"))); -void PendSV_Handler ( void ) __attribute__ ((weak, alias("Dummy_Handler"))); -void SysTick_Handler ( void ) __attribute__ ((weak, alias("Dummy_Handler"))); - -/* Peripherals handlers */ -void PM_Handler ( void ) __attribute__ ((weak, alias("Dummy_Handler"))); -void SYSCTRL_Handler ( void ) __attribute__ ((weak, alias("Dummy_Handler"))); -void WDT_Handler ( void ) __attribute__ ((weak, alias("Dummy_Handler"))); -void RTC_Handler ( void ) __attribute__ ((weak, alias("Dummy_Handler"))); -void EIC_Handler ( void ) __attribute__ ((weak, alias("Dummy_Handler"))); -void NVMCTRL_Handler ( void ) __attribute__ ((weak, alias("Dummy_Handler"))); -void DMAC_Handler ( void ) __attribute__ ((weak, alias("Dummy_Handler"))); -void USB_Handler ( void ) __attribute__ ((weak, alias("Dummy_Handler"))); -void EVSYS_Handler ( void ) __attribute__ ((weak, alias("Dummy_Handler"))); -void SERCOM0_Handler ( void ) __attribute__ ((weak, alias("Dummy_Handler"))); -void SERCOM1_Handler ( void ) __attribute__ ((weak, alias("Dummy_Handler"))); -void SERCOM2_Handler ( void ) __attribute__ ((weak, alias("Dummy_Handler"))); -void SERCOM3_Handler ( void ) __attribute__ ((weak, alias("Dummy_Handler"))); -void SERCOM4_Handler ( void ) __attribute__ ((weak, alias("Dummy_Handler"))); -void SERCOM5_Handler ( void ) __attribute__ ((weak, alias("Dummy_Handler"))); -void TCC0_Handler ( void ) __attribute__ ((weak, alias("Dummy_Handler"))); -void TCC1_Handler ( void ) __attribute__ ((weak, alias("Dummy_Handler"))); -void TCC2_Handler ( void ) __attribute__ ((weak, alias("Dummy_Handler"))); -void TC3_Handler ( void ) __attribute__ ((weak, alias("Dummy_Handler"))); -void TC4_Handler ( void ) __attribute__ ((weak, alias("Dummy_Handler"))); -void TC5_Handler ( void ) __attribute__ ((weak, alias("Dummy_Handler"))); -void TC6_Handler ( void ) __attribute__ ((weak, alias("Dummy_Handler"))); -void TC7_Handler ( void ) __attribute__ ((weak, alias("Dummy_Handler"))); -void ADC_Handler ( void ) __attribute__ ((weak, alias("Dummy_Handler"))); -void AC_Handler ( void ) __attribute__ ((weak, alias("Dummy_Handler"))); -void DAC_Handler ( void ) __attribute__ ((weak, alias("Dummy_Handler"))); -void PTC_Handler ( void ) __attribute__ ((weak, alias("Dummy_Handler"))); -void I2S_Handler ( void ) __attribute__ ((weak, alias("Dummy_Handler"))); - -/* Exception Table */ -__attribute__ ((section(".vectors"))) -const DeviceVectors exception_table = { - - /* Configure Initial Stack Pointer, using linker-generated symbols */ - (void*) (&_estack), - - (void*) Reset_Handler, - (void*) NMI_Handler, - (void*) HardFault_Handler, - (void*) (0UL), /* Reserved */ - (void*) (0UL), /* Reserved */ - (void*) (0UL), /* Reserved */ - (void*) (0UL), /* Reserved */ - (void*) (0UL), /* Reserved */ - (void*) (0UL), /* Reserved */ - (void*) (0UL), /* Reserved */ - (void*) SVC_Handler, - (void*) (0UL), /* Reserved */ - (void*) (0UL), /* Reserved */ - (void*) PendSV_Handler, - (void*) SysTick_Handler, - - /* Configurable interrupts */ - (void*) PM_Handler, /* 0 Power Manager */ - (void*) SYSCTRL_Handler, /* 1 System Control */ - (void*) WDT_Handler, /* 2 Watchdog Timer */ - (void*) RTC_Handler, /* 3 Real-Time Counter */ - (void*) EIC_Handler, /* 4 External Interrupt Controller */ - (void*) NVMCTRL_Handler, /* 5 Non-Volatile Memory Controller */ - (void*) DMAC_Handler, /* 6 Direct Memory Access Controller */ - (void*) USB_Handler, /* 7 Universal Serial Bus */ - (void*) EVSYS_Handler, /* 8 Event System Interface */ - (void*) SERCOM0_Handler, /* 9 Serial Communication Interface 0 */ - (void*) SERCOM1_Handler, /* 10 Serial Communication Interface 1 */ - (void*) SERCOM2_Handler, /* 11 Serial Communication Interface 2 */ - (void*) SERCOM3_Handler, /* 12 Serial Communication Interface 3 */ - (void*) SERCOM4_Handler, /* 13 Serial Communication Interface 4 */ - (void*) SERCOM5_Handler, /* 14 Serial Communication Interface 5 */ - (void*) TCC0_Handler, /* 15 Timer Counter Control 0 */ - (void*) TCC1_Handler, /* 16 Timer Counter Control 1 */ - (void*) TCC2_Handler, /* 17 Timer Counter Control 2 */ - (void*) TC3_Handler, /* 18 Basic Timer Counter 0 */ - (void*) TC4_Handler, /* 19 Basic Timer Counter 1 */ - (void*) TC5_Handler, /* 20 Basic Timer Counter 2 */ - (void*) TC6_Handler, /* 21 Basic Timer Counter 3 */ - (void*) TC7_Handler, /* 22 Basic Timer Counter 4 */ - (void*) ADC_Handler, /* 23 Analog Digital Converter */ - (void*) AC_Handler, /* 24 Analog Comparators */ - (void*) DAC_Handler, /* 25 Digital Analog Converter */ - (void*) PTC_Handler, /* 26 Peripheral Touch Controller */ - (void*) I2S_Handler /* 27 Inter-IC Sound Interface */ -}; - -/** - * \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; - - /* 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); - - /* Initialize the C library */ - __libc_init_array(); - - /* Branch to main function */ - main(); - - /* Infinite loop */ - while (1); -} - -/** - * \brief Default interrupt handler for unused IRQs. - */ -void Dummy_Handler(void) -{ - while (1) { - } -} diff --git a/bootloaders/zero/usart_sam_ba.h b/bootloaders/zero/usart_sam_ba.h deleted file mode 100644 index d498dc791..000000000 --- a/bootloaders/zero/usart_sam_ba.h +++ /dev/null @@ -1,155 +0,0 @@ -/* ---------------------------------------------------------------------------- - * SAM Software Package License - * ---------------------------------------------------------------------------- - * Copyright (c) 2011-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. - * ---------------------------------------------------------------------------- - */ - -#ifndef _USART_SAM_BA_H_ -#define _USART_SAM_BA_H_ - -#include "stdint.h" -#include "stdbool.h" - - -/* USART buffer size (must be a power of two) */ -#define USART_BUFFER_SIZE 128 - -/* Define the default time-out value for USART. */ -#define USART_DEFAULT_TIMEOUT 1000 - -/* Xmodem related defines */ -/* CRC16 polynomial */ -#define CRC16POLY 0x1021 - -#define SHARP_CHARACTER '#' - -/* X/Ymodem protocol: */ -#define SOH 0x01 -//#define STX 0x02 -#define EOT 0x04 -#define ACK 0x06 -#define NAK 0x15 -#define CAN 0x18 -#define ESC 0x1b - -#define PKTLEN_128 128 - - -/** - * \brief Open the given USART - */ -void usart_open(void); - -/** - * \brief Stops the USART - */ -void usart_close(void); - -/** - * \brief Puts a byte on usart line - * - * \param value Value to put - * - * \return \c 1 if function was successfully done, otherwise \c 0. - */ -int usart_putc(int value); - -/** - * \brief Waits and gets a value on usart line - * - * \return value read on usart line - */ -int usart_getc(void); - -/** - * \brief Returns true if the SAM-BA Uart received the sharp char - * - * \return Returns true if the SAM-BA Uart received the sharp char - */ -int usart_sharp_received(void); - -/** - * \brief This function checks if a character has been received on the usart line - * - * \return \c 1 if a byte is ready to be read. - */ -bool usart_is_rx_ready(void); - -/** - * \brief Gets a value on usart line - * - * \return value read on usart line - */ -int usart_readc(void); - -/** - * \brief Send buffer on usart line - * - * \param data pointer - * \param number of data to send - * \return number of data sent - */ -uint32_t usart_putdata(void const* data, uint32_t length); //Send given data (polling) - -/** - * \brief Gets data from usart line - * - * \param data pointer - * \param number of data to get - * \return value read on usart line - */ -uint32_t usart_getdata(void* data, uint32_t length); //Get data from comm. device - -/** - * \brief Send buffer on usart line using Xmodem protocol - * - * \param data pointer - * \param number of data to send - * \return number of data sent - */ -uint32_t usart_putdata_xmd(void const* data, uint32_t length); //Send given data (polling) using xmodem (if necessary) - -/** - * \brief Gets data from usart line using Xmodem protocol - * - * \param data pointer - * \param number of data to get - * \return value read on usart line - */ -uint32_t usart_getdata_xmd(void* data, uint32_t length); //Get data from comm. device using xmodem (if necessary) - -/** - * \brief Compute the CRC - * - * \param Char to add to CRC - * \param Previous CRC - * \return The new computed CRC - */ -unsigned short add_crc(char c, unsigned short crc); - -uint8_t getPacket(uint8_t *pData, uint8_t sno); - -#endif // _USART_SAM_BA_H_ diff --git a/bootloaders/zero/utils/compiler.h b/bootloaders/zero/utils/compiler.h deleted file mode 100644 index e31d7dba4..000000000 --- a/bootloaders/zero/utils/compiler.h +++ /dev/null @@ -1,1157 +0,0 @@ -/* ---------------------------------------------------------------------------- - * SAM Software Package License - * ---------------------------------------------------------------------------- - * Copyright (c) 2011-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. - * ---------------------------------------------------------------------------- - */ - -#ifndef UTILS_COMPILER_H_INCLUDED -#define UTILS_COMPILER_H_INCLUDED - -/** - * \defgroup group_sam0_utils Compiler abstraction layer and code utilities - * - * Compiler abstraction layer and code utilities for Cortex-M0+ based Atmel SAM devices. - * This module provides various abstraction layers and utilities to make code compatible between different compilers. - * - * @{ - */ - -#if (defined __ICCARM__) -# include -#endif - -#include -//#include -#include -#include -#include - -#ifndef __ASSEMBLY__ - -#include -#include -#include -#include - -/** - * \def UNUSED - * \brief Marking \a v as a unused parameter or value. - */ -#define UNUSED(v) (void)(v) - -/** - * \def barrier - * \brief Memory barrier - */ -#ifdef __GNUC__ -# define barrier() asm volatile("" ::: "memory") -#else -# define barrier() asm ("") -#endif - -/** - * \brief Emit the compiler pragma \a arg. - * - * \param[in] arg The pragma directive as it would appear after \e \#pragma - * (i.e. not stringified). - */ -#define COMPILER_PRAGMA(arg) _Pragma(#arg) - -/** - * \def COMPILER_PACK_SET(alignment) - * \brief Set maximum alignment for subsequent struct and union definitions to \a alignment. - */ -#define COMPILER_PACK_SET(alignment) COMPILER_PRAGMA(pack(alignment)) - -/** - * \def COMPILER_PACK_RESET() - * \brief Set default alignment for subsequent struct and union definitions. - */ -#define COMPILER_PACK_RESET() COMPILER_PRAGMA(pack()) - - -/** - * \brief Set aligned boundary. - */ -#if (defined __GNUC__) || (defined __CC_ARM) -# define COMPILER_ALIGNED(a) __attribute__((__aligned__(a))) -#elif (defined __ICCARM__) -# define COMPILER_ALIGNED(a) COMPILER_PRAGMA(data_alignment = a) -#endif - -/** - * \brief Set word-aligned boundary. - */ -#if (defined __GNUC__) || defined(__CC_ARM) -#define COMPILER_WORD_ALIGNED __attribute__((__aligned__(4))) -#elif (defined __ICCARM__) -#define COMPILER_WORD_ALIGNED COMPILER_PRAGMA(data_alignment = 4) -#endif - -/** - * \def __always_inline - * \brief The function should always be inlined. - * - * This annotation instructs the compiler to ignore its inlining - * heuristics and inline the function no matter how big it thinks it - * becomes. - */ -#if defined(__CC_ARM) -# define __always_inline __forceinline -#elif (defined __GNUC__) -# define __always_inline __attribute__((__always_inline__)) -#elif (defined __ICCARM__) -# define __always_inline _Pragma("inline=forced") -#endif - -/** - * \def __no_inline - * \brief The function should never be inlined - * - * This annotation instructs the compiler to ignore its inlining - * heuristics and not inline the function no matter how small it thinks it - * becomes. - */ -#if defined(__CC_ARM) -# define __no_inline __attribute__((noinline)) -#elif (defined __GNUC__) -# define __no_inline __attribute__((noinline)) -#elif (defined __ICCARM__) -# define __no_inline _Pragma("inline=never") -#endif - - -/** \brief This macro is used to test fatal errors. - * - * The macro tests if the expression is false. If it is, a fatal error is - * detected and the application hangs up. If \c TEST_SUITE_DEFINE_ASSERT_MACRO - * is defined, a unit test version of the macro is used, to allow execution - * of further tests after a false expression. - * - * \param[in] expr Expression to evaluate and supposed to be nonzero. - */ -#if defined(_ASSERT_ENABLE_) -# if defined(TEST_SUITE_DEFINE_ASSERT_MACRO) -# include "unit_test/suite.h" -# else -# undef TEST_SUITE_DEFINE_ASSERT_MACRO -# define Assert(expr) \ - {\ - if (!(expr)) asm("BKPT #0");\ - } -# endif -#else -# define Assert(expr) ((void) 0) -#endif - -/* Define WEAK attribute */ -#if defined ( __CC_ARM ) -# define WEAK __attribute__ ((weak)) -#elif defined ( __ICCARM__ ) -# define WEAK __weak -#elif defined ( __GNUC__ ) -# define WEAK __attribute__ ((weak)) -#endif - -/* Define NO_INIT attribute */ -#if defined ( __CC_ARM ) -# define NO_INIT __attribute__((zero_init)) -#elif defined ( __ICCARM__ ) -# define NO_INIT __no_init -#elif defined ( __GNUC__ ) -# define NO_INIT __attribute__((section(".no_init"))) -#endif - -#include "interrupt.h" - -/** \name Usual Types - * @{ */ -#ifndef __cplusplus -# if !defined(__bool_true_false_are_defined) -typedef unsigned char bool; -# endif -#endif -typedef uint16_t le16_t; -typedef uint16_t be16_t; -typedef uint32_t le32_t; -typedef uint32_t be32_t; -typedef uint32_t iram_size_t; -/** @} */ - -/** \name Aliasing Aggregate Types - * @{ */ - -/** 16-bit union. */ -typedef union -{ - int16_t s16; - uint16_t u16; - int8_t s8[2]; - uint8_t u8[2]; -} Union16; - -/** 32-bit union. */ -typedef union -{ - int32_t s32; - uint32_t u32; - int16_t s16[2]; - uint16_t u16[2]; - int8_t s8[4]; - uint8_t u8[4]; -} Union32; - -/** 64-bit union. */ -typedef union -{ - int64_t s64; - uint64_t u64; - int32_t s32[2]; - uint32_t u32[2]; - int16_t s16[4]; - uint16_t u16[4]; - int8_t s8[8]; - uint8_t u8[8]; -} Union64; - -/** Union of pointers to 64-, 32-, 16- and 8-bit unsigned integers. */ -typedef union -{ - int64_t *s64ptr; - uint64_t *u64ptr; - int32_t *s32ptr; - uint32_t *u32ptr; - int16_t *s16ptr; - uint16_t *u16ptr; - int8_t *s8ptr; - uint8_t *u8ptr; -} UnionPtr; - -/** Union of pointers to volatile 64-, 32-, 16- and 8-bit unsigned integers. */ -typedef union -{ - volatile int64_t *s64ptr; - volatile uint64_t *u64ptr; - volatile int32_t *s32ptr; - volatile uint32_t *u32ptr; - volatile int16_t *s16ptr; - volatile uint16_t *u16ptr; - volatile int8_t *s8ptr; - volatile uint8_t *u8ptr; -} UnionVPtr; - -/** Union of pointers to constant 64-, 32-, 16- and 8-bit unsigned integers. */ -typedef union -{ - const int64_t *s64ptr; - const uint64_t *u64ptr; - const int32_t *s32ptr; - const uint32_t *u32ptr; - const int16_t *s16ptr; - const uint16_t *u16ptr; - const int8_t *s8ptr; - const uint8_t *u8ptr; -} UnionCPtr; - -/** Union of pointers to constant volatile 64-, 32-, 16- and 8-bit unsigned integers. */ -typedef union -{ - const volatile int64_t *s64ptr; - const volatile uint64_t *u64ptr; - const volatile int32_t *s32ptr; - const volatile uint32_t *u32ptr; - const volatile int16_t *s16ptr; - const volatile uint16_t *u16ptr; - const volatile int8_t *s8ptr; - const volatile uint8_t *u8ptr; -} UnionCVPtr; - -/** Structure of pointers to 64-, 32-, 16- and 8-bit unsigned integers. */ -typedef struct -{ - int64_t *s64ptr; - uint64_t *u64ptr; - int32_t *s32ptr; - uint32_t *u32ptr; - int16_t *s16ptr; - uint16_t *u16ptr; - int8_t *s8ptr; - uint8_t *u8ptr; -} StructPtr; - -/** Structure of pointers to volatile 64-, 32-, 16- and 8-bit unsigned integers. */ -typedef struct -{ - volatile int64_t *s64ptr; - volatile uint64_t *u64ptr; - volatile int32_t *s32ptr; - volatile uint32_t *u32ptr; - volatile int16_t *s16ptr; - volatile uint16_t *u16ptr; - volatile int8_t *s8ptr; - volatile uint8_t *u8ptr; -} StructVPtr; - -/** Structure of pointers to constant 64-, 32-, 16- and 8-bit unsigned integers. */ -typedef struct -{ - const int64_t *s64ptr; - const uint64_t *u64ptr; - const int32_t *s32ptr; - const uint32_t *u32ptr; - const int16_t *s16ptr; - const uint16_t *u16ptr; - const int8_t *s8ptr; - const uint8_t *u8ptr; -} StructCPtr; - -/** Structure of pointers to constant volatile 64-, 32-, 16- and 8-bit unsigned integers. */ -typedef struct -{ - const volatile int64_t *s64ptr; - const volatile uint64_t *u64ptr; - const volatile int32_t *s32ptr; - const volatile uint32_t *u32ptr; - const volatile int16_t *s16ptr; - const volatile uint16_t *u16ptr; - const volatile int8_t *s8ptr; - const volatile uint8_t *u8ptr; -} StructCVPtr; - -/** @} */ - -#endif /* #ifndef __ASSEMBLY__ */ - -/** \name Usual Constants - * @{ */ -#define DISABLE 0 -//#define ENABLE 1 - -#ifndef __cplusplus -# if !defined(__bool_true_false_are_defined) -# define false 0 -# define true 1 -# endif -#endif -/** @} */ - -#ifndef __ASSEMBLY__ - -/** \name Optimization Control - * @{ */ - -/** - * \def likely(exp) - * \brief The expression \a exp is likely to be true - */ -#if !defined(likely) || defined(__DOXYGEN__) -# define likely(exp) (exp) -#endif - -/** - * \def unlikely(exp) - * \brief The expression \a exp is unlikely to be true - */ -#if !defined(unlikely) || defined(__DOXYGEN__) -# define unlikely(exp) (exp) -#endif - -/** - * \def is_constant(exp) - * \brief Determine if an expression evaluates to a constant value. - * - * \param[in] exp Any expression - * - * \return true if \a exp is constant, false otherwise. - */ -#if (defined __GNUC__) || (defined __CC_ARM) -# define is_constant(exp) __builtin_constant_p(exp) -#else -# define is_constant(exp) (0) -#endif - -/** @} */ - -/** \name Bit-Field Handling - * @{ */ - -/** \brief Reads the bits of a value specified by a given bit-mask. - * - * \param[in] value Value to read bits from. - * \param[in] mask Bit-mask indicating bits to read. - * - * \return Read bits. - */ -#define Rd_bits( value, mask) ((value) & (mask)) - -/** \brief Writes the bits of a C lvalue specified by a given bit-mask. - * - * \param[in] lvalue C lvalue to write bits to. - * \param[in] mask Bit-mask indicating bits to write. - * \param[in] bits Bits to write. - * - * \return Resulting value with written bits. - */ -#define Wr_bits(lvalue, mask, bits) ((lvalue) = ((lvalue) & ~(mask)) |\ - ((bits ) & (mask))) - -/** \brief Tests the bits of a value specified by a given bit-mask. - * - * \param[in] value Value of which to test bits. - * \param[in] mask Bit-mask indicating bits to test. - * - * \return \c 1 if at least one of the tested bits is set, else \c 0. - */ -#define Tst_bits( value, mask) (Rd_bits(value, mask) != 0) - -/** \brief Clears the bits of a C lvalue specified by a given bit-mask. - * - * \param[in] lvalue C lvalue of which to clear bits. - * \param[in] mask Bit-mask indicating bits to clear. - * - * \return Resulting value with cleared bits. - */ -#define Clr_bits(lvalue, mask) ((lvalue) &= ~(mask)) - -/** \brief Sets the bits of a C lvalue specified by a given bit-mask. - * - * \param[in] lvalue C lvalue of which to set bits. - * \param[in] mask Bit-mask indicating bits to set. - * - * \return Resulting value with set bits. - */ -#define Set_bits(lvalue, mask) ((lvalue) |= (mask)) - -/** \brief Toggles the bits of a C lvalue specified by a given bit-mask. - * - * \param[in] lvalue C lvalue of which to toggle bits. - * \param[in] mask Bit-mask indicating bits to toggle. - * - * \return Resulting value with toggled bits. - */ -#define Tgl_bits(lvalue, mask) ((lvalue) ^= (mask)) - -/** \brief Reads the bit-field of a value specified by a given bit-mask. - * - * \param[in] value Value to read a bit-field from. - * \param[in] mask Bit-mask indicating the bit-field to read. - * - * \return Read bit-field. - */ -#define Rd_bitfield( value, mask) (Rd_bits( value, mask) >> ctz(mask)) - -/** \brief Writes the bit-field of a C lvalue specified by a given bit-mask. - * - * \param[in] lvalue C lvalue to write a bit-field to. - * \param[in] mask Bit-mask indicating the bit-field to write. - * \param[in] bitfield Bit-field to write. - * - * \return Resulting value with written bit-field. - */ -#define Wr_bitfield(lvalue, mask, bitfield) (Wr_bits(lvalue, mask, (uint32_t)(bitfield) << ctz(mask))) - -/** @} */ - - -/** \name Zero-Bit Counting - * - * Under GCC, __builtin_clz and __builtin_ctz behave like macros when - * applied to constant expressions (values known at compile time), so they are - * more optimized than the use of the corresponding assembly instructions and - * they can be used as constant expressions e.g. to initialize objects having - * static storage duration, and like the corresponding assembly instructions - * when applied to non-constant expressions (values unknown at compile time), so - * they are more optimized than an assembly periphrasis. Hence, clz and ctz - * ensure a possible and optimized behavior for both constant and non-constant - * expressions. - * - * @{ */ - -/** \brief Counts the leading zero bits of the given value considered as a 32-bit integer. - * - * \param[in] u Value of which to count the leading zero bits. - * - * \return The count of leading zero bits in \a u. - */ -#if (defined __GNUC__) || (defined __CC_ARM) -# define clz(u) __builtin_clz(u) -#else -# define clz(u) (((u) == 0) ? 32 : \ - ((u) & (1ul << 31)) ? 0 : \ - ((u) & (1ul << 30)) ? 1 : \ - ((u) & (1ul << 29)) ? 2 : \ - ((u) & (1ul << 28)) ? 3 : \ - ((u) & (1ul << 27)) ? 4 : \ - ((u) & (1ul << 26)) ? 5 : \ - ((u) & (1ul << 25)) ? 6 : \ - ((u) & (1ul << 24)) ? 7 : \ - ((u) & (1ul << 23)) ? 8 : \ - ((u) & (1ul << 22)) ? 9 : \ - ((u) & (1ul << 21)) ? 10 : \ - ((u) & (1ul << 20)) ? 11 : \ - ((u) & (1ul << 19)) ? 12 : \ - ((u) & (1ul << 18)) ? 13 : \ - ((u) & (1ul << 17)) ? 14 : \ - ((u) & (1ul << 16)) ? 15 : \ - ((u) & (1ul << 15)) ? 16 : \ - ((u) & (1ul << 14)) ? 17 : \ - ((u) & (1ul << 13)) ? 18 : \ - ((u) & (1ul << 12)) ? 19 : \ - ((u) & (1ul << 11)) ? 20 : \ - ((u) & (1ul << 10)) ? 21 : \ - ((u) & (1ul << 9)) ? 22 : \ - ((u) & (1ul << 8)) ? 23 : \ - ((u) & (1ul << 7)) ? 24 : \ - ((u) & (1ul << 6)) ? 25 : \ - ((u) & (1ul << 5)) ? 26 : \ - ((u) & (1ul << 4)) ? 27 : \ - ((u) & (1ul << 3)) ? 28 : \ - ((u) & (1ul << 2)) ? 29 : \ - ((u) & (1ul << 1)) ? 30 : \ - 31) -#endif - -/** \brief Counts the trailing zero bits of the given value considered as a 32-bit integer. - * - * \param[in] u Value of which to count the trailing zero bits. - * - * \return The count of trailing zero bits in \a u. - */ -#if (defined __GNUC__) || (defined __CC_ARM) -# define ctz(u) __builtin_ctz(u) -#else -# define ctz(u) ((u) & (1ul << 0) ? 0 : \ - (u) & (1ul << 1) ? 1 : \ - (u) & (1ul << 2) ? 2 : \ - (u) & (1ul << 3) ? 3 : \ - (u) & (1ul << 4) ? 4 : \ - (u) & (1ul << 5) ? 5 : \ - (u) & (1ul << 6) ? 6 : \ - (u) & (1ul << 7) ? 7 : \ - (u) & (1ul << 8) ? 8 : \ - (u) & (1ul << 9) ? 9 : \ - (u) & (1ul << 10) ? 10 : \ - (u) & (1ul << 11) ? 11 : \ - (u) & (1ul << 12) ? 12 : \ - (u) & (1ul << 13) ? 13 : \ - (u) & (1ul << 14) ? 14 : \ - (u) & (1ul << 15) ? 15 : \ - (u) & (1ul << 16) ? 16 : \ - (u) & (1ul << 17) ? 17 : \ - (u) & (1ul << 18) ? 18 : \ - (u) & (1ul << 19) ? 19 : \ - (u) & (1ul << 20) ? 20 : \ - (u) & (1ul << 21) ? 21 : \ - (u) & (1ul << 22) ? 22 : \ - (u) & (1ul << 23) ? 23 : \ - (u) & (1ul << 24) ? 24 : \ - (u) & (1ul << 25) ? 25 : \ - (u) & (1ul << 26) ? 26 : \ - (u) & (1ul << 27) ? 27 : \ - (u) & (1ul << 28) ? 28 : \ - (u) & (1ul << 29) ? 29 : \ - (u) & (1ul << 30) ? 30 : \ - (u) & (1ul << 31) ? 31 : \ - 32) -#endif - -/** @} */ - - -/** \name Bit Reversing - * @{ */ - -/** \brief Reverses the bits of \a u8. - * - * \param[in] u8 U8 of which to reverse the bits. - * - * \return Value resulting from \a u8 with reversed bits. - */ -#define bit_reverse8(u8) ((U8)(bit_reverse32((U8)(u8)) >> 24)) - -/** \brief Reverses the bits of \a u16. - * - * \param[in] u16 U16 of which to reverse the bits. - * - * \return Value resulting from \a u16 with reversed bits. - */ -#define bit_reverse16(u16) ((uint16_t)(bit_reverse32((uint16_t)(u16)) >> 16)) - -/** \brief Reverses the bits of \a u32. - * - * \param[in] u32 U32 of which to reverse the bits. - * - * \return Value resulting from \a u32 with reversed bits. - */ -#define bit_reverse32(u32) __RBIT(u32) - -/** \brief Reverses the bits of \a u64. - * - * \param[in] u64 U64 of which to reverse the bits. - * - * \return Value resulting from \a u64 with reversed bits. - */ -#define bit_reverse64(u64) ((uint64_t)(((uint64_t)bit_reverse32((uint64_t)(u64) >> 32)) |\ - ((uint64_t)bit_reverse32((uint64_t)(u64)) << 32))) - -/** @} */ - - -/** \name Alignment - * @{ */ - -/** \brief Tests alignment of the number \a val with the \a n boundary. - * - * \param[in] val Input value. - * \param[in] n Boundary. - * - * \return \c 1 if the number \a val is aligned with the \a n boundary, else \c 0. - */ -#define Test_align(val, n) (!Tst_bits( val, (n) - 1 ) ) - -/** \brief Gets alignment of the number \a val with respect to the \a n boundary. - * - * \param[in] val Input value. - * \param[in] n Boundary. - * - * \return Alignment of the number \a val with respect to the \a n boundary. - */ -#define Get_align(val, n) ( Rd_bits( val, (n) - 1 ) ) - -/** \brief Sets alignment of the lvalue number \a lval to \a alg with respect to the \a n boundary. - * - * \param[in] lval Input/output lvalue. - * \param[in] n Boundary. - * \param[in] alg Alignment. - * - * \return New value of \a lval resulting from its alignment set to \a alg with respect to the \a n boundary. - */ -#define Set_align(lval, n, alg) ( Wr_bits(lval, (n) - 1, alg) ) - -/** \brief Aligns the number \a val with the upper \a n boundary. - * - * \param[in] val Input value. - * \param[in] n Boundary. - * - * \return Value resulting from the number \a val aligned with the upper \a n boundary. - */ -#define Align_up( val, n) (((val) + ((n) - 1)) & ~((n) - 1)) - -/** \brief Aligns the number \a val with the lower \a n boundary. - * - * \param[in] val Input value. - * \param[in] n Boundary. - * - * \return Value resulting from the number \a val aligned with the lower \a n boundary. - */ -#define Align_down(val, n) ( (val) & ~((n) - 1)) - -/** @} */ - - -/** \name Mathematics - * - * The same considerations as for clz and ctz apply here but GCC does not - * provide built-in functions to access the assembly instructions abs, min and - * max and it does not produce them by itself in most cases, so two sets of - * macros are defined here: - * - Abs, Min and Max to apply to constant expressions (values known at - * compile time); - * - abs, min and max to apply to non-constant expressions (values unknown at - * compile time), abs is found in stdlib.h. - * - * @{ */ - -/** \brief Takes the absolute value of \a a. - * - * \param[in] a Input value. - * - * \return Absolute value of \a a. - * - * \note More optimized if only used with values known at compile time. - */ -#define Abs(a) (((a) < 0 ) ? -(a) : (a)) - -/** \brief Takes the minimal value of \a a and \a b. - * - * \param[in] a Input value. - * \param[in] b Input value. - * - * \return Minimal value of \a a and \a b. - * - * \note More optimized if only used with values known at compile time. - */ -#define Min(a, b) (((a) < (b)) ? (a) : (b)) - -/** \brief Takes the maximal value of \a a and \a b. - * - * \param[in] a Input value. - * \param[in] b Input value. - * - * \return Maximal value of \a a and \a b. - * - * \note More optimized if only used with values known at compile time. - */ -#define Max(a, b) (((a) > (b)) ? (a) : (b)) - -/** \brief Takes the minimal value of \a a and \a b. - * - * \param[in] a Input value. - * \param[in] b Input value. - * - * \return Minimal value of \a a and \a b. - * - * \note More optimized if only used with values unknown at compile time. - */ -#define min(a, b) Min(a, b) - -/** \brief Takes the maximal value of \a a and \a b. - * - * \param[in] a Input value. - * \param[in] b Input value. - * - * \return Maximal value of \a a and \a b. - * - * \note More optimized if only used with values unknown at compile time. - */ -#define max(a, b) Max(a, b) - -/** @} */ - - -/** \brief Calls the routine at address \a addr. - * - * It generates a long call opcode. - * - * For example, `Long_call(0x80000000)' generates a software reset on a UC3 if - * it is invoked from the CPU supervisor mode. - * - * \param[in] addr Address of the routine to call. - * - * \note It may be used as a long jump opcode in some special cases. - */ -#define Long_call(addr) ((*(void (*)(void))(addr))()) - - -/** \name MCU Endianism Handling - * ARM is MCU little endian. - * - * @{ */ -#define BE16(x) Swap16(x) -#define LE16(x) (x) - -#define le16_to_cpu(x) (x) -#define cpu_to_le16(x) (x) -#define LE16_TO_CPU(x) (x) -#define CPU_TO_LE16(x) (x) - -#define be16_to_cpu(x) Swap16(x) -#define cpu_to_be16(x) Swap16(x) -#define BE16_TO_CPU(x) Swap16(x) -#define CPU_TO_BE16(x) Swap16(x) - -#define le32_to_cpu(x) (x) -#define cpu_to_le32(x) (x) -#define LE32_TO_CPU(x) (x) -#define CPU_TO_LE32(x) (x) - -#define be32_to_cpu(x) swap32(x) -#define cpu_to_be32(x) swap32(x) -#define BE32_TO_CPU(x) swap32(x) -#define CPU_TO_BE32(x) swap32(x) -/** @} */ - - -/** \name Endianism Conversion - * - * The same considerations as for clz and ctz apply here but GCC's - * __builtin_bswap_32 and __builtin_bswap_64 do not behave like macros when - * applied to constant expressions, so two sets of macros are defined here: - * - Swap16, Swap32 and Swap64 to apply to constant expressions (values known - * at compile time); - * - swap16, swap32 and swap64 to apply to non-constant expressions (values - * unknown at compile time). - * - * @{ */ - -/** \brief Toggles the endianism of \a u16 (by swapping its bytes). - * - * \param[in] u16 U16 of which to toggle the endianism. - * - * \return Value resulting from \a u16 with toggled endianism. - * - * \note More optimized if only used with values known at compile time. - */ -#define Swap16(u16) ((uint16_t)(((uint16_t)(u16) >> 8) |\ - ((uint16_t)(u16) << 8))) - -/** \brief Toggles the endianism of \a u32 (by swapping its bytes). - * - * \param[in] u32 U32 of which to toggle the endianism. - * - * \return Value resulting from \a u32 with toggled endianism. - * - * \note More optimized if only used with values known at compile time. - */ -#define Swap32(u32) ((uint32_t)(((uint32_t)Swap16((uint32_t)(u32) >> 16)) |\ - ((uint32_t)Swap16((uint32_t)(u32)) << 16))) - -/** \brief Toggles the endianism of \a u64 (by swapping its bytes). - * - * \param[in] u64 U64 of which to toggle the endianism. - * - * \return Value resulting from \a u64 with toggled endianism. - * - * \note More optimized if only used with values known at compile time. - */ -#define Swap64(u64) ((uint64_t)(((uint64_t)Swap32((uint64_t)(u64) >> 32)) |\ - ((uint64_t)Swap32((uint64_t)(u64)) << 32))) - -/** \brief Toggles the endianism of \a u16 (by swapping its bytes). - * - * \param[in] u16 U16 of which to toggle the endianism. - * - * \return Value resulting from \a u16 with toggled endianism. - * - * \note More optimized if only used with values unknown at compile time. - */ -#define swap16(u16) Swap16(u16) - -/** \brief Toggles the endianism of \a u32 (by swapping its bytes). - * - * \param[in] u32 U32 of which to toggle the endianism. - * - * \return Value resulting from \a u32 with toggled endianism. - * - * \note More optimized if only used with values unknown at compile time. - */ -#if (defined __GNUC__) -# define swap32(u32) ((uint32_t)__builtin_bswap32((uint32_t)(u32))) -#else -# define swap32(u32) Swap32(u32) -#endif - -/** \brief Toggles the endianism of \a u64 (by swapping its bytes). - * - * \param[in] u64 U64 of which to toggle the endianism. - * - * \return Value resulting from \a u64 with toggled endianism. - * - * \note More optimized if only used with values unknown at compile time. - */ -#if (defined __GNUC__) -# define swap64(u64) ((uint64_t)__builtin_bswap64((uint64_t)(u64))) -#else -# define swap64(u64) ((uint64_t)(((uint64_t)swap32((uint64_t)(u64) >> 32)) |\ - ((uint64_t)swap32((uint64_t)(u64)) << 32))) -#endif - -/** @} */ - - -/** \name Target Abstraction - * - * @{ */ - -#define _GLOBEXT_ extern /**< extern storage-class specifier. */ -#define _CONST_TYPE_ const /**< const type qualifier. */ -#define _MEM_TYPE_SLOW_ /**< Slow memory type. */ -#define _MEM_TYPE_MEDFAST_ /**< Fairly fast memory type. */ -#define _MEM_TYPE_FAST_ /**< Fast memory type. */ - -#define memcmp_ram2ram memcmp /**< Target-specific memcmp of RAM to RAM. */ -#define memcmp_code2ram memcmp /**< Target-specific memcmp of RAM to NVRAM. */ -#define memcpy_ram2ram memcpy /**< Target-specific memcpy from RAM to RAM. */ -#define memcpy_code2ram memcpy /**< Target-specific memcpy from NVRAM to RAM. */ - -/** @} */ - -/** - * \brief Calculate \f$ \left\lceil \frac{a}{b} \right\rceil \f$ using - * integer arithmetic. - * - * \param[in] a An integer - * \param[in] b Another integer - * - * \return (\a a / \a b) rounded up to the nearest integer. - */ -#define div_ceil(a, b) (((a) + (b) - 1) / (b)) - -#endif /* #ifndef __ASSEMBLY__ */ -#ifdef __ICCARM__ -/** \name Compiler Keywords - * - * Port of some keywords from GCC to IAR Embedded Workbench. - * - * @{ */ - -#define __asm__ asm -#define __inline__ inline -#define __volatile__ - -/** @} */ - -#endif - -#define FUNC_PTR void * -/** - * \def unused - * \brief Marking \a v as a unused parameter or value. - */ -#define unused(v) do { (void)(v); } while(0) - -/* Define RAMFUNC attribute */ -#if defined ( __CC_ARM ) /* Keil uVision 4 */ -# define RAMFUNC __attribute__ ((section(".ramfunc"))) -#elif defined ( __ICCARM__ ) /* IAR Ewarm 5.41+ */ -# define RAMFUNC __ramfunc -#elif defined ( __GNUC__ ) /* GCC CS3 2009q3-68 */ -# define RAMFUNC __attribute__ ((section(".ramfunc"))) -#endif - -/* Define OPTIMIZE_HIGH attribute */ -#if defined ( __CC_ARM ) /* Keil uVision 4 */ -# define OPTIMIZE_HIGH _Pragma("O3") -#elif defined ( __ICCARM__ ) /* IAR Ewarm 5.41+ */ -# define OPTIMIZE_HIGH _Pragma("optimize=high") -#elif defined ( __GNUC__ ) /* GCC CS3 2009q3-68 */ -# define OPTIMIZE_HIGH __attribute__((optimize(s))) -#endif -#define PASS 0 -#define FAIL 1 -#define LOW 0 -#define HIGH 1 - -typedef int8_t S8 ; //!< 8-bit signed integer. -typedef uint8_t U8 ; //!< 8-bit unsigned integer. -typedef int16_t S16; //!< 16-bit signed integer. -typedef uint16_t U16; //!< 16-bit unsigned integer. -typedef int32_t S32; //!< 32-bit signed integer. -typedef uint32_t U32; //!< 32-bit unsigned integer. -typedef int64_t S64; //!< 64-bit signed integer. -typedef uint64_t U64; //!< 64-bit unsigned integer. -typedef float F32; //!< 32-bit floating-point number. -typedef double F64; //!< 64-bit floating-point number. - -#define MSB(u16) (((U8 *)&(u16))[1]) //!< Most significant byte of \a u16. -#define LSB(u16) (((U8 *)&(u16))[0]) //!< Least significant byte of \a u16. - -#define MSH(u32) (((U16 *)&(u32))[1]) //!< Most significant half-word of \a u32. -#define LSH(u32) (((U16 *)&(u32))[0]) //!< Least significant half-word of \a u32. -#define MSB0W(u32) (((U8 *)&(u32))[3]) //!< Most significant byte of 1st rank of \a u32. -#define MSB1W(u32) (((U8 *)&(u32))[2]) //!< Most significant byte of 2nd rank of \a u32. -#define MSB2W(u32) (((U8 *)&(u32))[1]) //!< Most significant byte of 3rd rank of \a u32. -#define MSB3W(u32) (((U8 *)&(u32))[0]) //!< Most significant byte of 4th rank of \a u32. -#define LSB3W(u32) MSB0W(u32) //!< Least significant byte of 4th rank of \a u32. -#define LSB2W(u32) MSB1W(u32) //!< Least significant byte of 3rd rank of \a u32. -#define LSB1W(u32) MSB2W(u32) //!< Least significant byte of 2nd rank of \a u32. -#define LSB0W(u32) MSB3W(u32) //!< Least significant byte of 1st rank of \a u32. - -#define MSW(u64) (((U32 *)&(u64))[1]) //!< Most significant word of \a u64. -#define LSW(u64) (((U32 *)&(u64))[0]) //!< Least significant word of \a u64. -#define MSH0(u64) (((U16 *)&(u64))[3]) //!< Most significant half-word of 1st rank of \a u64. -#define MSH1(u64) (((U16 *)&(u64))[2]) //!< Most significant half-word of 2nd rank of \a u64. -#define MSH2(u64) (((U16 *)&(u64))[1]) //!< Most significant half-word of 3rd rank of \a u64. -#define MSH3(u64) (((U16 *)&(u64))[0]) //!< Most significant half-word of 4th rank of \a u64. -#define LSH3(u64) MSH0(u64) //!< Least significant half-word of 4th rank of \a u64. -#define LSH2(u64) MSH1(u64) //!< Least significant half-word of 3rd rank of \a u64. -#define LSH1(u64) MSH2(u64) //!< Least significant half-word of 2nd rank of \a u64. -#define LSH0(u64) MSH3(u64) //!< Least significant half-word of 1st rank of \a u64. -#define MSB0D(u64) (((U8 *)&(u64))[7]) //!< Most significant byte of 1st rank of \a u64. -#define MSB1D(u64) (((U8 *)&(u64))[6]) //!< Most significant byte of 2nd rank of \a u64. -#define MSB2D(u64) (((U8 *)&(u64))[5]) //!< Most significant byte of 3rd rank of \a u64. -#define MSB3D(u64) (((U8 *)&(u64))[4]) //!< Most significant byte of 4th rank of \a u64. -#define MSB4D(u64) (((U8 *)&(u64))[3]) //!< Most significant byte of 5th rank of \a u64. -#define MSB5D(u64) (((U8 *)&(u64))[2]) //!< Most significant byte of 6th rank of \a u64. -#define MSB6D(u64) (((U8 *)&(u64))[1]) //!< Most significant byte of 7th rank of \a u64. -#define MSB7D(u64) (((U8 *)&(u64))[0]) //!< Most significant byte of 8th rank of \a u64. -#define LSB7D(u64) MSB0D(u64) //!< Least significant byte of 8th rank of \a u64. -#define LSB6D(u64) MSB1D(u64) //!< Least significant byte of 7th rank of \a u64. -#define LSB5D(u64) MSB2D(u64) //!< Least significant byte of 6th rank of \a u64. -#define LSB4D(u64) MSB3D(u64) //!< Least significant byte of 5th rank of \a u64. -#define LSB3D(u64) MSB4D(u64) //!< Least significant byte of 4th rank of \a u64. -#define LSB2D(u64) MSB5D(u64) //!< Least significant byte of 3rd rank of \a u64. -#define LSB1D(u64) MSB6D(u64) //!< Least significant byte of 2nd rank of \a u64. -#define LSB0D(u64) MSB7D(u64) //!< Least significant byte of 1st rank of \a u64. - -#define LSB0(u32) LSB0W(u32) //!< Least significant byte of 1st rank of \a u32. -#define LSB1(u32) LSB1W(u32) //!< Least significant byte of 2nd rank of \a u32. -#define LSB2(u32) LSB2W(u32) //!< Least significant byte of 3rd rank of \a u32. -#define LSB3(u32) LSB3W(u32) //!< Least significant byte of 4th rank of \a u32. -#define MSB3(u32) MSB3W(u32) //!< Most significant byte of 4th rank of \a u32. -#define MSB2(u32) MSB2W(u32) //!< Most significant byte of 3rd rank of \a u32. -#define MSB1(u32) MSB1W(u32) //!< Most significant byte of 2nd rank of \a u32. -#define MSB0(u32) MSB0W(u32) //!< Most significant byte of 1st rank of \a u32. - -#if defined(__ICCARM__) -#define SHORTENUM __packed -#elif defined(__GNUC__) -#define SHORTENUM __attribute__((packed)) -#endif - -/* No operation */ -#if defined(__ICCARM__) -#define nop() __no_operation() -#elif defined(__GNUC__) -#define nop() (__NOP()) -#endif - -#define FLASH_DECLARE(x) const x -#define FLASH_EXTERN(x) extern const x -#define PGM_READ_BYTE(x) *(x) -#define PGM_READ_WORD(x) *(x) -#define MEMCPY_ENDIAN memcpy -#define PGM_READ_BLOCK(dst, src, len) memcpy((dst), (src), (len)) - -/*Defines the Flash Storage for the request and response of MAC*/ -#define CMD_ID_OCTET (0) - -/* Converting of values from CPU endian to little endian. */ -#define CPU_ENDIAN_TO_LE16(x) (x) -#define CPU_ENDIAN_TO_LE32(x) (x) -#define CPU_ENDIAN_TO_LE64(x) (x) - -/* Converting of values from little endian to CPU endian. */ -#define LE16_TO_CPU_ENDIAN(x) (x) -#define LE32_TO_CPU_ENDIAN(x) (x) -#define LE64_TO_CPU_ENDIAN(x) (x) - -/* Converting of constants from little endian to CPU endian. */ -#define CLE16_TO_CPU_ENDIAN(x) (x) -#define CLE32_TO_CPU_ENDIAN(x) (x) -#define CLE64_TO_CPU_ENDIAN(x) (x) - -/* Converting of constants from CPU endian to little endian. */ -#define CCPU_ENDIAN_TO_LE16(x) (x) -#define CCPU_ENDIAN_TO_LE32(x) (x) -#define CCPU_ENDIAN_TO_LE64(x) (x) - -#define ADDR_COPY_DST_SRC_16(dst, src) ((dst) = (src)) -#define ADDR_COPY_DST_SRC_64(dst, src) ((dst) = (src)) - -/** - * @brief Converts a 64-Bit value into a 8 Byte array - * - * @param[in] value 64-Bit value - * @param[out] data Pointer to the 8 Byte array to be updated with 64-Bit value - * @ingroup apiPalApi - */ -static inline void convert_64_bit_to_byte_array(uint64_t value, uint8_t *data) -{ - uint8_t index = 0; - - while (index < 8) - { - data[index++] = value & 0xFF; - value = value >> 8; - } -} - -/** - * @brief Converts a 16-Bit value into a 2 Byte array - * - * @param[in] value 16-Bit value - * @param[out] data Pointer to the 2 Byte array to be updated with 16-Bit value - * @ingroup apiPalApi - */ -static inline void convert_16_bit_to_byte_array(uint16_t value, uint8_t *data) -{ - data[0] = value & 0xFF; - data[1] = (value >> 8) & 0xFF; -} - -/* Converts a 16-Bit value into a 2 Byte array */ -static inline void convert_spec_16_bit_to_byte_array(uint16_t value, uint8_t *data) -{ - data[0] = value & 0xFF; - data[1] = (value >> 8) & 0xFF; -} - -/* Converts a 16-Bit value into a 2 Byte array */ -static inline void convert_16_bit_to_byte_address(uint16_t value, uint8_t *data) -{ - data[0] = value & 0xFF; - data[1] = (value >> 8) & 0xFF; -} - -/* - * @brief Converts a 2 Byte array into a 16-Bit value - * - * @param data Specifies the pointer to the 2 Byte array - * - * @return 16-Bit value - * @ingroup apiPalApi - */ -static inline uint16_t convert_byte_array_to_16_bit(uint8_t *data) -{ - return (data[0] | ((uint16_t)data[1] << 8)); -} - -/* Converts a 4 Byte array into a 32-Bit value */ -static inline uint32_t convert_byte_array_to_32_bit(uint8_t *data) -{ - union - { - uint32_t u32; - uint8_t u8[4]; - }long_addr; - uint8_t index; - for (index = 0; index < 4; index++) - { - long_addr.u8[index] = *data++; - } - return long_addr.u32; -} - -/** - * @brief Converts a 8 Byte array into a 64-Bit value - * - * @param data Specifies the pointer to the 8 Byte array - * - * @return 64-Bit value - * @ingroup apiPalApi - */ -static inline uint64_t convert_byte_array_to_64_bit(uint8_t *data) -{ - union - { - uint64_t u64; - uint8_t u8[8]; - } long_addr; - - uint8_t index; - - for (index = 0; index < 8; index++) - { - long_addr.u8[index] = *data++; - } - - return long_addr.u64; -} - -/** @} */ - -#endif /* UTILS_COMPILER_H_INCLUDED */ diff --git a/bootloaders/zero/utils/interrupt.h b/bootloaders/zero/utils/interrupt.h deleted file mode 100644 index fa4878ee8..000000000 --- a/bootloaders/zero/utils/interrupt.h +++ /dev/null @@ -1,117 +0,0 @@ -/* ---------------------------------------------------------------------------- - * SAM Software Package License - * ---------------------------------------------------------------------------- - * Copyright (c) 2011-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. - * ---------------------------------------------------------------------------- - */ -#ifndef UTILS_INTERRUPT_H -#define UTILS_INTERRUPT_H - -//#include - -#include "interrupt/interrupt_sam_nvic.h" - -/** - * \defgroup interrupt_group Global interrupt management - * - * This is a driver for global enabling and disabling of interrupts. - * - * @{ - */ - -#if defined(__DOXYGEN__) -/** - * \def CONFIG_INTERRUPT_FORCE_INTC - * \brief Force usage of the ASF INTC driver - * - * Predefine this symbol when preprocessing to force the use of the ASF INTC driver. - * This is useful to ensure compatibility across compilers and shall be used only when required - * by the application needs. - */ -# define CONFIG_INTERRUPT_FORCE_INTC -#endif - -//! \name Global interrupt flags -//@{ -/** - * \typedef irqflags_t - * \brief Type used for holding state of interrupt flag - */ - -/** - * \def cpu_irq_enable - * \brief Enable interrupts globally - */ - -/** - * \def cpu_irq_disable - * \brief Disable interrupts globally - */ - -/** - * \fn irqflags_t cpu_irq_save(void) - * \brief Get and clear the global interrupt flags - * - * Use in conjunction with \ref cpu_irq_restore. - * - * \return Current state of interrupt flags. - * - * \note This function leaves interrupts disabled. - */ - -/** - * \fn void cpu_irq_restore(irqflags_t flags) - * \brief Restore global interrupt flags - * - * Use in conjunction with \ref cpu_irq_save. - * - * \param flags State to set interrupt flag to. - */ - -/** - * \fn bool cpu_irq_is_enabled_flags(irqflags_t flags) - * \brief Check if interrupts are globally enabled in supplied flags - * - * \param flags Currents state of interrupt flags. - * - * \return True if interrupts are enabled. - */ - -/** - * \def cpu_irq_is_enabled - * \brief Check if interrupts are globally enabled - * - * \return True if interrupts are enabled. - */ -//@} - -//! @} - -/** - * \ingroup interrupt_group - * \defgroup interrupt_deprecated_group Deprecated interrupt definitions - */ - -#endif /* UTILS_INTERRUPT_H */ diff --git a/bootloaders/zero/utils/interrupt/interrupt_sam_nvic.c b/bootloaders/zero/utils/interrupt/interrupt_sam_nvic.c deleted file mode 100644 index d8134852e..000000000 --- a/bootloaders/zero/utils/interrupt/interrupt_sam_nvic.c +++ /dev/null @@ -1,69 +0,0 @@ -/* ---------------------------------------------------------------------------- - * SAM Software Package License - * ---------------------------------------------------------------------------- - * Copyright (c) 2011-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. - * ---------------------------------------------------------------------------- - */ - -#include "interrupt_sam_nvic.h" - -#if !defined(__DOXYGEN__) -/* Deprecated - global flag to determine the global interrupt state. Required by - * QTouch library, however new applications should use cpu_irq_is_enabled() - * which probes the true global interrupt state from the CPU special registers. - */ -volatile bool g_interrupt_enabled = true; -#endif - -void cpu_irq_enter_critical(void) -{ - if (cpu_irq_critical_section_counter == 0) { - if (cpu_irq_is_enabled()) { - cpu_irq_disable(); - cpu_irq_prev_interrupt_state = true; - } else { - /* Make sure the to save the prev state as false */ - cpu_irq_prev_interrupt_state = false; - } - - } - - cpu_irq_critical_section_counter++; -} - -void cpu_irq_leave_critical(void) -{ - /* Check if the user is trying to leave a critical section when not in a critical section */ - Assert(cpu_irq_critical_section_counter > 0); - - cpu_irq_critical_section_counter--; - - /* Only enable global interrupts when the counter reaches 0 and the state of the global interrupt flag - was enabled when entering critical state */ - if ((cpu_irq_critical_section_counter == 0) && (cpu_irq_prev_interrupt_state)) { - cpu_irq_enable(); - } -} - diff --git a/bootloaders/zero/utils/interrupt/interrupt_sam_nvic.h b/bootloaders/zero/utils/interrupt/interrupt_sam_nvic.h deleted file mode 100644 index 9b5645b63..000000000 --- a/bootloaders/zero/utils/interrupt/interrupt_sam_nvic.h +++ /dev/null @@ -1,172 +0,0 @@ -/* ---------------------------------------------------------------------------- - * SAM Software Package License - * ---------------------------------------------------------------------------- - * Copyright (c) 2011-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. - * ---------------------------------------------------------------------------- - */ - -#ifndef UTILS_INTERRUPT_INTERRUPT_H -#define UTILS_INTERRUPT_INTERRUPT_H - -#include -//#include - -#ifdef __cplusplus -extern "C" { -#endif - -/** - * \weakgroup interrupt_group - * - * @{ - */ - -/** - * \name Interrupt Service Routine definition - * - * @{ - */ - -/** - * \brief Define service routine - * - * \note For NVIC devices the interrupt service routines are predefined to - * add to vector table in binary generation, so there is no service - * register at run time. The routine collections are in exceptions.h. - * - * Usage: - * \code - ISR(foo_irq_handler) - { - // Function definition - ... - } -\endcode - * - * \param func Name for the function. - */ -# define ISR(func) \ - void func (void) - -/** - * \brief Initialize interrupt vectors - * - * For NVIC the interrupt vectors are put in vector table. So nothing - * to do to initialize them, except defined the vector function with - * right name. - * - * This must be called prior to \ref irq_register_handler. - */ -# define irq_initialize_vectors() \ - do { \ - } while(0) - -/** - * \brief Register handler for interrupt - * - * For NVIC the interrupt vectors are put in vector table. So nothing - * to do to register them, except defined the vector function with - * right name. - * - * Usage: - * \code - irq_initialize_vectors(); - irq_register_handler(foo_irq_handler); -\endcode - * - * \note The function \a func must be defined with the \ref ISR macro. - * \note The functions prototypes can be found in the device exception header - * files (exceptions.h). - */ -# define irq_register_handler(int_num, int_prio) \ - NVIC_ClearPendingIRQ( (IRQn_Type)int_num); \ - NVIC_SetPriority( (IRQn_Type)int_num, int_prio); \ - NVIC_EnableIRQ( (IRQn_Type)int_num); \ - -//@} - -# define cpu_irq_enable() \ - do { \ - g_interrupt_enabled = true; \ - __DMB(); \ - __enable_irq(); \ - } while (0) -# define cpu_irq_disable() \ - do { \ - __disable_irq(); \ - __DMB(); \ - g_interrupt_enabled = false; \ - } while (0) - -typedef uint32_t irqflags_t; - -#if !defined(__DOXYGEN__) -extern volatile bool g_interrupt_enabled; -#endif - -#define cpu_irq_is_enabled() (__get_PRIMASK() == 0) - -static volatile uint32_t cpu_irq_critical_section_counter; -static volatile bool cpu_irq_prev_interrupt_state; - -static inline irqflags_t cpu_irq_save(void) -{ - irqflags_t flags = cpu_irq_is_enabled(); - cpu_irq_disable(); - return flags; -} - -static inline bool cpu_irq_is_enabled_flags(irqflags_t flags) -{ - return (flags); -} - -static inline void cpu_irq_restore(irqflags_t flags) -{ - if (cpu_irq_is_enabled_flags(flags)) - cpu_irq_enable(); -} - -void cpu_irq_enter_critical(void); -void cpu_irq_leave_critical(void); - -/** - * \weakgroup interrupt_deprecated_group - * @{ - */ - -#define Enable_global_interrupt() cpu_irq_enable() -#define Disable_global_interrupt() cpu_irq_disable() -#define Is_global_interrupt_enabled() cpu_irq_is_enabled() - -//@} - -//@} - -#ifdef __cplusplus -} -#endif - -#endif /* UTILS_INTERRUPT_INTERRUPT_H */ diff --git a/bootloaders/zero/utils/preprocessor/mrecursion.h b/bootloaders/zero/utils/preprocessor/mrecursion.h deleted file mode 100644 index 444792727..000000000 --- a/bootloaders/zero/utils/preprocessor/mrecursion.h +++ /dev/null @@ -1,581 +0,0 @@ -/* ---------------------------------------------------------------------------- - * SAM Software Package License - * ---------------------------------------------------------------------------- - * Copyright (c) 2011-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. - * ---------------------------------------------------------------------------- - */ - -#ifndef _MRECURSION_H_ -#define _MRECURSION_H_ - -/** - * \defgroup group_sam0_utils_mrecursion Preprocessor - Macro Recursion - * - * \ingroup group_sam0_utils - * - * @{ - */ - -#include "preprocessor.h" - -#define DEC_256 255 -#define DEC_255 254 -#define DEC_254 253 -#define DEC_253 252 -#define DEC_252 251 -#define DEC_251 250 -#define DEC_250 249 -#define DEC_249 248 -#define DEC_248 247 -#define DEC_247 246 -#define DEC_246 245 -#define DEC_245 244 -#define DEC_244 243 -#define DEC_243 242 -#define DEC_242 241 -#define DEC_241 240 -#define DEC_240 239 -#define DEC_239 238 -#define DEC_238 237 -#define DEC_237 236 -#define DEC_236 235 -#define DEC_235 234 -#define DEC_234 233 -#define DEC_233 232 -#define DEC_232 231 -#define DEC_231 230 -#define DEC_230 229 -#define DEC_229 228 -#define DEC_228 227 -#define DEC_227 226 -#define DEC_226 225 -#define DEC_225 224 -#define DEC_224 223 -#define DEC_223 222 -#define DEC_222 221 -#define DEC_221 220 -#define DEC_220 219 -#define DEC_219 218 -#define DEC_218 217 -#define DEC_217 216 -#define DEC_216 215 -#define DEC_215 214 -#define DEC_214 213 -#define DEC_213 212 -#define DEC_212 211 -#define DEC_211 210 -#define DEC_210 209 -#define DEC_209 208 -#define DEC_208 207 -#define DEC_207 206 -#define DEC_206 205 -#define DEC_205 204 -#define DEC_204 203 -#define DEC_203 202 -#define DEC_202 201 -#define DEC_201 200 -#define DEC_200 199 -#define DEC_199 198 -#define DEC_198 197 -#define DEC_197 196 -#define DEC_196 195 -#define DEC_195 194 -#define DEC_194 193 -#define DEC_193 192 -#define DEC_192 191 -#define DEC_191 190 -#define DEC_190 189 -#define DEC_189 188 -#define DEC_188 187 -#define DEC_187 186 -#define DEC_186 185 -#define DEC_185 184 -#define DEC_184 183 -#define DEC_183 182 -#define DEC_182 181 -#define DEC_181 180 -#define DEC_180 179 -#define DEC_179 178 -#define DEC_178 177 -#define DEC_177 176 -#define DEC_176 175 -#define DEC_175 174 -#define DEC_174 173 -#define DEC_173 172 -#define DEC_172 171 -#define DEC_171 170 -#define DEC_170 169 -#define DEC_169 168 -#define DEC_168 167 -#define DEC_167 166 -#define DEC_166 165 -#define DEC_165 164 -#define DEC_164 163 -#define DEC_163 162 -#define DEC_162 161 -#define DEC_161 160 -#define DEC_160 159 -#define DEC_159 158 -#define DEC_158 157 -#define DEC_157 156 -#define DEC_156 155 -#define DEC_155 154 -#define DEC_154 153 -#define DEC_153 152 -#define DEC_152 151 -#define DEC_151 150 -#define DEC_150 149 -#define DEC_149 148 -#define DEC_148 147 -#define DEC_147 146 -#define DEC_146 145 -#define DEC_145 144 -#define DEC_144 143 -#define DEC_143 142 -#define DEC_142 141 -#define DEC_141 140 -#define DEC_140 139 -#define DEC_139 138 -#define DEC_138 137 -#define DEC_137 136 -#define DEC_136 135 -#define DEC_135 134 -#define DEC_134 133 -#define DEC_133 132 -#define DEC_132 131 -#define DEC_131 130 -#define DEC_130 129 -#define DEC_129 128 -#define DEC_128 127 -#define DEC_127 126 -#define DEC_126 125 -#define DEC_125 124 -#define DEC_124 123 -#define DEC_123 122 -#define DEC_122 121 -#define DEC_121 120 -#define DEC_120 119 -#define DEC_119 118 -#define DEC_118 117 -#define DEC_117 116 -#define DEC_116 115 -#define DEC_115 114 -#define DEC_114 113 -#define DEC_113 112 -#define DEC_112 111 -#define DEC_111 110 -#define DEC_110 109 -#define DEC_109 108 -#define DEC_108 107 -#define DEC_107 106 -#define DEC_106 105 -#define DEC_105 104 -#define DEC_104 103 -#define DEC_103 102 -#define DEC_102 101 -#define DEC_101 100 -#define DEC_100 99 -#define DEC_99 98 -#define DEC_98 97 -#define DEC_97 96 -#define DEC_96 95 -#define DEC_95 94 -#define DEC_94 93 -#define DEC_93 92 -#define DEC_92 91 -#define DEC_91 90 -#define DEC_90 89 -#define DEC_89 88 -#define DEC_88 87 -#define DEC_87 86 -#define DEC_86 85 -#define DEC_85 84 -#define DEC_84 83 -#define DEC_83 82 -#define DEC_82 81 -#define DEC_81 80 -#define DEC_80 79 -#define DEC_79 78 -#define DEC_78 77 -#define DEC_77 76 -#define DEC_76 75 -#define DEC_75 74 -#define DEC_74 73 -#define DEC_73 72 -#define DEC_72 71 -#define DEC_71 70 -#define DEC_70 69 -#define DEC_69 68 -#define DEC_68 67 -#define DEC_67 66 -#define DEC_66 65 -#define DEC_65 64 -#define DEC_64 63 -#define DEC_63 62 -#define DEC_62 61 -#define DEC_61 60 -#define DEC_60 59 -#define DEC_59 58 -#define DEC_58 57 -#define DEC_57 56 -#define DEC_56 55 -#define DEC_55 54 -#define DEC_54 53 -#define DEC_53 52 -#define DEC_52 51 -#define DEC_51 50 -#define DEC_50 49 -#define DEC_49 48 -#define DEC_48 47 -#define DEC_47 46 -#define DEC_46 45 -#define DEC_45 44 -#define DEC_44 43 -#define DEC_43 42 -#define DEC_42 41 -#define DEC_41 40 -#define DEC_40 39 -#define DEC_39 38 -#define DEC_38 37 -#define DEC_37 36 -#define DEC_36 35 -#define DEC_35 34 -#define DEC_34 33 -#define DEC_33 32 -#define DEC_32 31 -#define DEC_31 30 -#define DEC_30 29 -#define DEC_29 28 -#define DEC_28 27 -#define DEC_27 26 -#define DEC_26 25 -#define DEC_25 24 -#define DEC_24 23 -#define DEC_23 22 -#define DEC_22 21 -#define DEC_21 20 -#define DEC_20 19 -#define DEC_19 18 -#define DEC_18 17 -#define DEC_17 16 -#define DEC_16 15 -#define DEC_15 14 -#define DEC_14 13 -#define DEC_13 12 -#define DEC_12 11 -#define DEC_11 10 -#define DEC_10 9 -#define DEC_9 8 -#define DEC_8 7 -#define DEC_7 6 -#define DEC_6 5 -#define DEC_5 4 -#define DEC_4 3 -#define DEC_3 2 -#define DEC_2 1 -#define DEC_1 0 -#define DEC_(n) DEC_##n - - -/** Maximal number of repetitions supported by MRECURSION. */ -#define MRECURSION_LIMIT 256 - -/** \brief Macro recursion. - * - * This macro represents a horizontal repetition construct. - * - * \param[in] count The number of repetitious calls to macro. Valid values - * range from 0 to MRECURSION_LIMIT. - * \param[in] macro A binary operation of the form macro(data, n). This macro - * is expanded by MRECURSION with the current repetition number - * and the auxiliary data argument. - * \param[in] data A recursive threshold, building on this to decline by times - * defined with param count. - * - * \return macro(data-count+1,0) macro(data-count+2,1)...macro(data,count-1) - */ -#define MRECURSION(count, macro, data) TPASTE2(MRECURSION, count) (macro, data) - -#define MRECURSION0( macro, data) -#define MRECURSION1( macro, data) MRECURSION0( macro, DEC_(data)) macro(data, 0) -#define MRECURSION2( macro, data) MRECURSION1( macro, DEC_(data)) macro(data, 1) -#define MRECURSION3( macro, data) MRECURSION2( macro, DEC_(data)) macro(data, 2) -#define MRECURSION4( macro, data) MRECURSION3( macro, DEC_(data)) macro(data, 3) -#define MRECURSION5( macro, data) MRECURSION4( macro, DEC_(data)) macro(data, 4) -#define MRECURSION6( macro, data) MRECURSION5( macro, DEC_(data)) macro(data, 5) -#define MRECURSION7( macro, data) MRECURSION6( macro, DEC_(data)) macro(data, 6) -#define MRECURSION8( macro, data) MRECURSION7( macro, DEC_(data)) macro(data, 7) -#define MRECURSION9( macro, data) MRECURSION8( macro, DEC_(data)) macro(data, 8) -#define MRECURSION10( macro, data) MRECURSION9( macro, DEC_(data)) macro(data, 9) -#define MRECURSION11( macro, data) MRECURSION10( macro, DEC_(data)) macro(data, 10) -#define MRECURSION12( macro, data) MRECURSION11( macro, DEC_(data)) macro(data, 11) -#define MRECURSION13( macro, data) MRECURSION12( macro, DEC_(data)) macro(data, 12) -#define MRECURSION14( macro, data) MRECURSION13( macro, DEC_(data)) macro(data, 13) -#define MRECURSION15( macro, data) MRECURSION14( macro, DEC_(data)) macro(data, 14) -#define MRECURSION16( macro, data) MRECURSION15( macro, DEC_(data)) macro(data, 15) -#define MRECURSION17( macro, data) MRECURSION16( macro, DEC_(data)) macro(data, 16) -#define MRECURSION18( macro, data) MRECURSION17( macro, DEC_(data)) macro(data, 17) -#define MRECURSION19( macro, data) MRECURSION18( macro, DEC_(data)) macro(data, 18) -#define MRECURSION20( macro, data) MRECURSION19( macro, DEC_(data)) macro(data, 19) -#define MRECURSION21( macro, data) MRECURSION20( macro, DEC_(data)) macro(data, 20) -#define MRECURSION22( macro, data) MRECURSION21( macro, DEC_(data)) macro(data, 21) -#define MRECURSION23( macro, data) MRECURSION22( macro, DEC_(data)) macro(data, 22) -#define MRECURSION24( macro, data) MRECURSION23( macro, DEC_(data)) macro(data, 23) -#define MRECURSION25( macro, data) MRECURSION24( macro, DEC_(data)) macro(data, 24) -#define MRECURSION26( macro, data) MRECURSION25( macro, DEC_(data)) macro(data, 25) -#define MRECURSION27( macro, data) MRECURSION26( macro, DEC_(data)) macro(data, 26) -#define MRECURSION28( macro, data) MRECURSION27( macro, DEC_(data)) macro(data, 27) -#define MRECURSION29( macro, data) MRECURSION28( macro, DEC_(data)) macro(data, 28) -#define MRECURSION30( macro, data) MRECURSION29( macro, DEC_(data)) macro(data, 29) -#define MRECURSION31( macro, data) MRECURSION30( macro, DEC_(data)) macro(data, 30) -#define MRECURSION32( macro, data) MRECURSION31( macro, DEC_(data)) macro(data, 31) -#define MRECURSION33( macro, data) MRECURSION32( macro, DEC_(data)) macro(data, 32) -#define MRECURSION34( macro, data) MRECURSION33( macro, DEC_(data)) macro(data, 33) -#define MRECURSION35( macro, data) MRECURSION34( macro, DEC_(data)) macro(data, 34) -#define MRECURSION36( macro, data) MRECURSION35( macro, DEC_(data)) macro(data, 35) -#define MRECURSION37( macro, data) MRECURSION36( macro, DEC_(data)) macro(data, 36) -#define MRECURSION38( macro, data) MRECURSION37( macro, DEC_(data)) macro(data, 37) -#define MRECURSION39( macro, data) MRECURSION38( macro, DEC_(data)) macro(data, 38) -#define MRECURSION40( macro, data) MRECURSION39( macro, DEC_(data)) macro(data, 39) -#define MRECURSION41( macro, data) MRECURSION40( macro, DEC_(data)) macro(data, 40) -#define MRECURSION42( macro, data) MRECURSION41( macro, DEC_(data)) macro(data, 41) -#define MRECURSION43( macro, data) MRECURSION42( macro, DEC_(data)) macro(data, 42) -#define MRECURSION44( macro, data) MRECURSION43( macro, DEC_(data)) macro(data, 43) -#define MRECURSION45( macro, data) MRECURSION44( macro, DEC_(data)) macro(data, 44) -#define MRECURSION46( macro, data) MRECURSION45( macro, DEC_(data)) macro(data, 45) -#define MRECURSION47( macro, data) MRECURSION46( macro, DEC_(data)) macro(data, 46) -#define MRECURSION48( macro, data) MRECURSION47( macro, DEC_(data)) macro(data, 47) -#define MRECURSION49( macro, data) MRECURSION48( macro, DEC_(data)) macro(data, 48) -#define MRECURSION50( macro, data) MRECURSION49( macro, DEC_(data)) macro(data, 49) -#define MRECURSION51( macro, data) MRECURSION50( macro, DEC_(data)) macro(data, 50) -#define MRECURSION52( macro, data) MRECURSION51( macro, DEC_(data)) macro(data, 51) -#define MRECURSION53( macro, data) MRECURSION52( macro, DEC_(data)) macro(data, 52) -#define MRECURSION54( macro, data) MRECURSION53( macro, DEC_(data)) macro(data, 53) -#define MRECURSION55( macro, data) MRECURSION54( macro, DEC_(data)) macro(data, 54) -#define MRECURSION56( macro, data) MRECURSION55( macro, DEC_(data)) macro(data, 55) -#define MRECURSION57( macro, data) MRECURSION56( macro, DEC_(data)) macro(data, 56) -#define MRECURSION58( macro, data) MRECURSION57( macro, DEC_(data)) macro(data, 57) -#define MRECURSION59( macro, data) MRECURSION58( macro, DEC_(data)) macro(data, 58) -#define MRECURSION60( macro, data) MRECURSION59( macro, DEC_(data)) macro(data, 59) -#define MRECURSION61( macro, data) MRECURSION60( macro, DEC_(data)) macro(data, 60) -#define MRECURSION62( macro, data) MRECURSION61( macro, DEC_(data)) macro(data, 61) -#define MRECURSION63( macro, data) MRECURSION62( macro, DEC_(data)) macro(data, 62) -#define MRECURSION64( macro, data) MRECURSION63( macro, DEC_(data)) macro(data, 63) -#define MRECURSION65( macro, data) MRECURSION64( macro, DEC_(data)) macro(data, 64) -#define MRECURSION66( macro, data) MRECURSION65( macro, DEC_(data)) macro(data, 65) -#define MRECURSION67( macro, data) MRECURSION66( macro, DEC_(data)) macro(data, 66) -#define MRECURSION68( macro, data) MRECURSION67( macro, DEC_(data)) macro(data, 67) -#define MRECURSION69( macro, data) MRECURSION68( macro, DEC_(data)) macro(data, 68) -#define MRECURSION70( macro, data) MRECURSION69( macro, DEC_(data)) macro(data, 69) -#define MRECURSION71( macro, data) MRECURSION70( macro, DEC_(data)) macro(data, 70) -#define MRECURSION72( macro, data) MRECURSION71( macro, DEC_(data)) macro(data, 71) -#define MRECURSION73( macro, data) MRECURSION72( macro, DEC_(data)) macro(data, 72) -#define MRECURSION74( macro, data) MRECURSION73( macro, DEC_(data)) macro(data, 73) -#define MRECURSION75( macro, data) MRECURSION74( macro, DEC_(data)) macro(data, 74) -#define MRECURSION76( macro, data) MRECURSION75( macro, DEC_(data)) macro(data, 75) -#define MRECURSION77( macro, data) MRECURSION76( macro, DEC_(data)) macro(data, 76) -#define MRECURSION78( macro, data) MRECURSION77( macro, DEC_(data)) macro(data, 77) -#define MRECURSION79( macro, data) MRECURSION78( macro, DEC_(data)) macro(data, 78) -#define MRECURSION80( macro, data) MRECURSION79( macro, DEC_(data)) macro(data, 79) -#define MRECURSION81( macro, data) MRECURSION80( macro, DEC_(data)) macro(data, 80) -#define MRECURSION82( macro, data) MRECURSION81( macro, DEC_(data)) macro(data, 81) -#define MRECURSION83( macro, data) MRECURSION82( macro, DEC_(data)) macro(data, 82) -#define MRECURSION84( macro, data) MRECURSION83( macro, DEC_(data)) macro(data, 83) -#define MRECURSION85( macro, data) MRECURSION84( macro, DEC_(data)) macro(data, 84) -#define MRECURSION86( macro, data) MRECURSION85( macro, DEC_(data)) macro(data, 85) -#define MRECURSION87( macro, data) MRECURSION86( macro, DEC_(data)) macro(data, 86) -#define MRECURSION88( macro, data) MRECURSION87( macro, DEC_(data)) macro(data, 87) -#define MRECURSION89( macro, data) MRECURSION88( macro, DEC_(data)) macro(data, 88) -#define MRECURSION90( macro, data) MRECURSION89( macro, DEC_(data)) macro(data, 89) -#define MRECURSION91( macro, data) MRECURSION90( macro, DEC_(data)) macro(data, 90) -#define MRECURSION92( macro, data) MRECURSION91( macro, DEC_(data)) macro(data, 91) -#define MRECURSION93( macro, data) MRECURSION92( macro, DEC_(data)) macro(data, 92) -#define MRECURSION94( macro, data) MRECURSION93( macro, DEC_(data)) macro(data, 93) -#define MRECURSION95( macro, data) MRECURSION94( macro, DEC_(data)) macro(data, 94) -#define MRECURSION96( macro, data) MRECURSION95( macro, DEC_(data)) macro(data, 95) -#define MRECURSION97( macro, data) MRECURSION96( macro, DEC_(data)) macro(data, 96) -#define MRECURSION98( macro, data) MRECURSION97( macro, DEC_(data)) macro(data, 97) -#define MRECURSION99( macro, data) MRECURSION98( macro, DEC_(data)) macro(data, 98) -#define MRECURSION100(macro, data) MRECURSION99( macro, DEC_(data)) macro(data, 99) -#define MRECURSION101(macro, data) MRECURSION100( macro, DEC_(data)) macro(data, 100) -#define MRECURSION102(macro, data) MRECURSION101( macro, DEC_(data)) macro(data, 101) -#define MRECURSION103(macro, data) MRECURSION102( macro, DEC_(data)) macro(data, 102) -#define MRECURSION104(macro, data) MRECURSION103( macro, DEC_(data)) macro(data, 103) -#define MRECURSION105(macro, data) MRECURSION104( macro, DEC_(data)) macro(data, 104) -#define MRECURSION106(macro, data) MRECURSION105( macro, DEC_(data)) macro(data, 105) -#define MRECURSION107(macro, data) MRECURSION106( macro, DEC_(data)) macro(data, 106) -#define MRECURSION108(macro, data) MRECURSION107( macro, DEC_(data)) macro(data, 107) -#define MRECURSION109(macro, data) MRECURSION108( macro, DEC_(data)) macro(data, 108) -#define MRECURSION110(macro, data) MRECURSION109( macro, DEC_(data)) macro(data, 109) -#define MRECURSION111(macro, data) MRECURSION110( macro, DEC_(data)) macro(data, 110) -#define MRECURSION112(macro, data) MRECURSION111( macro, DEC_(data)) macro(data, 111) -#define MRECURSION113(macro, data) MRECURSION112( macro, DEC_(data)) macro(data, 112) -#define MRECURSION114(macro, data) MRECURSION113( macro, DEC_(data)) macro(data, 113) -#define MRECURSION115(macro, data) MRECURSION114( macro, DEC_(data)) macro(data, 114) -#define MRECURSION116(macro, data) MRECURSION115( macro, DEC_(data)) macro(data, 115) -#define MRECURSION117(macro, data) MRECURSION116( macro, DEC_(data)) macro(data, 116) -#define MRECURSION118(macro, data) MRECURSION117( macro, DEC_(data)) macro(data, 117) -#define MRECURSION119(macro, data) MRECURSION118( macro, DEC_(data)) macro(data, 118) -#define MRECURSION120(macro, data) MRECURSION119( macro, DEC_(data)) macro(data, 119) -#define MRECURSION121(macro, data) MRECURSION120( macro, DEC_(data)) macro(data, 120) -#define MRECURSION122(macro, data) MRECURSION121( macro, DEC_(data)) macro(data, 121) -#define MRECURSION123(macro, data) MRECURSION122( macro, DEC_(data)) macro(data, 122) -#define MRECURSION124(macro, data) MRECURSION123( macro, DEC_(data)) macro(data, 123) -#define MRECURSION125(macro, data) MRECURSION124( macro, DEC_(data)) macro(data, 124) -#define MRECURSION126(macro, data) MRECURSION125( macro, DEC_(data)) macro(data, 125) -#define MRECURSION127(macro, data) MRECURSION126( macro, DEC_(data)) macro(data, 126) -#define MRECURSION128(macro, data) MRECURSION127( macro, DEC_(data)) macro(data, 127) -#define MRECURSION129(macro, data) MRECURSION128( macro, DEC_(data)) macro(data, 128) -#define MRECURSION130(macro, data) MRECURSION129( macro, DEC_(data)) macro(data, 129) -#define MRECURSION131(macro, data) MRECURSION130( macro, DEC_(data)) macro(data, 130) -#define MRECURSION132(macro, data) MRECURSION131( macro, DEC_(data)) macro(data, 131) -#define MRECURSION133(macro, data) MRECURSION132( macro, DEC_(data)) macro(data, 132) -#define MRECURSION134(macro, data) MRECURSION133( macro, DEC_(data)) macro(data, 133) -#define MRECURSION135(macro, data) MRECURSION134( macro, DEC_(data)) macro(data, 134) -#define MRECURSION136(macro, data) MRECURSION135( macro, DEC_(data)) macro(data, 135) -#define MRECURSION137(macro, data) MRECURSION136( macro, DEC_(data)) macro(data, 136) -#define MRECURSION138(macro, data) MRECURSION137( macro, DEC_(data)) macro(data, 137) -#define MRECURSION139(macro, data) MRECURSION138( macro, DEC_(data)) macro(data, 138) -#define MRECURSION140(macro, data) MRECURSION139( macro, DEC_(data)) macro(data, 139) -#define MRECURSION141(macro, data) MRECURSION140( macro, DEC_(data)) macro(data, 140) -#define MRECURSION142(macro, data) MRECURSION141( macro, DEC_(data)) macro(data, 141) -#define MRECURSION143(macro, data) MRECURSION142( macro, DEC_(data)) macro(data, 142) -#define MRECURSION144(macro, data) MRECURSION143( macro, DEC_(data)) macro(data, 143) -#define MRECURSION145(macro, data) MRECURSION144( macro, DEC_(data)) macro(data, 144) -#define MRECURSION146(macro, data) MRECURSION145( macro, DEC_(data)) macro(data, 145) -#define MRECURSION147(macro, data) MRECURSION146( macro, DEC_(data)) macro(data, 146) -#define MRECURSION148(macro, data) MRECURSION147( macro, DEC_(data)) macro(data, 147) -#define MRECURSION149(macro, data) MRECURSION148( macro, DEC_(data)) macro(data, 148) -#define MRECURSION150(macro, data) MRECURSION149( macro, DEC_(data)) macro(data, 149) -#define MRECURSION151(macro, data) MRECURSION150( macro, DEC_(data)) macro(data, 150) -#define MRECURSION152(macro, data) MRECURSION151( macro, DEC_(data)) macro(data, 151) -#define MRECURSION153(macro, data) MRECURSION152( macro, DEC_(data)) macro(data, 152) -#define MRECURSION154(macro, data) MRECURSION153( macro, DEC_(data)) macro(data, 153) -#define MRECURSION155(macro, data) MRECURSION154( macro, DEC_(data)) macro(data, 154) -#define MRECURSION156(macro, data) MRECURSION155( macro, DEC_(data)) macro(data, 155) -#define MRECURSION157(macro, data) MRECURSION156( macro, DEC_(data)) macro(data, 156) -#define MRECURSION158(macro, data) MRECURSION157( macro, DEC_(data)) macro(data, 157) -#define MRECURSION159(macro, data) MRECURSION158( macro, DEC_(data)) macro(data, 158) -#define MRECURSION160(macro, data) MRECURSION159( macro, DEC_(data)) macro(data, 159) -#define MRECURSION161(macro, data) MRECURSION160( macro, DEC_(data)) macro(data, 160) -#define MRECURSION162(macro, data) MRECURSION161( macro, DEC_(data)) macro(data, 161) -#define MRECURSION163(macro, data) MRECURSION162( macro, DEC_(data)) macro(data, 162) -#define MRECURSION164(macro, data) MRECURSION163( macro, DEC_(data)) macro(data, 163) -#define MRECURSION165(macro, data) MRECURSION164( macro, DEC_(data)) macro(data, 164) -#define MRECURSION166(macro, data) MRECURSION165( macro, DEC_(data)) macro(data, 165) -#define MRECURSION167(macro, data) MRECURSION166( macro, DEC_(data)) macro(data, 166) -#define MRECURSION168(macro, data) MRECURSION167( macro, DEC_(data)) macro(data, 167) -#define MRECURSION169(macro, data) MRECURSION168( macro, DEC_(data)) macro(data, 168) -#define MRECURSION170(macro, data) MRECURSION169( macro, DEC_(data)) macro(data, 169) -#define MRECURSION171(macro, data) MRECURSION170( macro, DEC_(data)) macro(data, 170) -#define MRECURSION172(macro, data) MRECURSION171( macro, DEC_(data)) macro(data, 171) -#define MRECURSION173(macro, data) MRECURSION172( macro, DEC_(data)) macro(data, 172) -#define MRECURSION174(macro, data) MRECURSION173( macro, DEC_(data)) macro(data, 173) -#define MRECURSION175(macro, data) MRECURSION174( macro, DEC_(data)) macro(data, 174) -#define MRECURSION176(macro, data) MRECURSION175( macro, DEC_(data)) macro(data, 175) -#define MRECURSION177(macro, data) MRECURSION176( macro, DEC_(data)) macro(data, 176) -#define MRECURSION178(macro, data) MRECURSION177( macro, DEC_(data)) macro(data, 177) -#define MRECURSION179(macro, data) MRECURSION178( macro, DEC_(data)) macro(data, 178) -#define MRECURSION180(macro, data) MRECURSION179( macro, DEC_(data)) macro(data, 179) -#define MRECURSION181(macro, data) MRECURSION180( macro, DEC_(data)) macro(data, 180) -#define MRECURSION182(macro, data) MRECURSION181( macro, DEC_(data)) macro(data, 181) -#define MRECURSION183(macro, data) MRECURSION182( macro, DEC_(data)) macro(data, 182) -#define MRECURSION184(macro, data) MRECURSION183( macro, DEC_(data)) macro(data, 183) -#define MRECURSION185(macro, data) MRECURSION184( macro, DEC_(data)) macro(data, 184) -#define MRECURSION186(macro, data) MRECURSION185( macro, DEC_(data)) macro(data, 185) -#define MRECURSION187(macro, data) MRECURSION186( macro, DEC_(data)) macro(data, 186) -#define MRECURSION188(macro, data) MRECURSION187( macro, DEC_(data)) macro(data, 187) -#define MRECURSION189(macro, data) MRECURSION188( macro, DEC_(data)) macro(data, 188) -#define MRECURSION190(macro, data) MRECURSION189( macro, DEC_(data)) macro(data, 189) -#define MRECURSION191(macro, data) MRECURSION190( macro, DEC_(data)) macro(data, 190) -#define MRECURSION192(macro, data) MRECURSION191( macro, DEC_(data)) macro(data, 191) -#define MRECURSION193(macro, data) MRECURSION192( macro, DEC_(data)) macro(data, 192) -#define MRECURSION194(macro, data) MRECURSION193( macro, DEC_(data)) macro(data, 193) -#define MRECURSION195(macro, data) MRECURSION194( macro, DEC_(data)) macro(data, 194) -#define MRECURSION196(macro, data) MRECURSION195( macro, DEC_(data)) macro(data, 195) -#define MRECURSION197(macro, data) MRECURSION196( macro, DEC_(data)) macro(data, 196) -#define MRECURSION198(macro, data) MRECURSION197( macro, DEC_(data)) macro(data, 197) -#define MRECURSION199(macro, data) MRECURSION198( macro, DEC_(data)) macro(data, 198) -#define MRECURSION200(macro, data) MRECURSION199( macro, DEC_(data)) macro(data, 199) -#define MRECURSION201(macro, data) MRECURSION200( macro, DEC_(data)) macro(data, 200) -#define MRECURSION202(macro, data) MRECURSION201( macro, DEC_(data)) macro(data, 201) -#define MRECURSION203(macro, data) MRECURSION202( macro, DEC_(data)) macro(data, 202) -#define MRECURSION204(macro, data) MRECURSION203( macro, DEC_(data)) macro(data, 203) -#define MRECURSION205(macro, data) MRECURSION204( macro, DEC_(data)) macro(data, 204) -#define MRECURSION206(macro, data) MRECURSION205( macro, DEC_(data)) macro(data, 205) -#define MRECURSION207(macro, data) MRECURSION206( macro, DEC_(data)) macro(data, 206) -#define MRECURSION208(macro, data) MRECURSION207( macro, DEC_(data)) macro(data, 207) -#define MRECURSION209(macro, data) MRECURSION208( macro, DEC_(data)) macro(data, 208) -#define MRECURSION210(macro, data) MRECURSION209( macro, DEC_(data)) macro(data, 209) -#define MRECURSION211(macro, data) MRECURSION210( macro, DEC_(data)) macro(data, 210) -#define MRECURSION212(macro, data) MRECURSION211( macro, DEC_(data)) macro(data, 211) -#define MRECURSION213(macro, data) MRECURSION212( macro, DEC_(data)) macro(data, 212) -#define MRECURSION214(macro, data) MRECURSION213( macro, DEC_(data)) macro(data, 213) -#define MRECURSION215(macro, data) MRECURSION214( macro, DEC_(data)) macro(data, 214) -#define MRECURSION216(macro, data) MRECURSION215( macro, DEC_(data)) macro(data, 215) -#define MRECURSION217(macro, data) MRECURSION216( macro, DEC_(data)) macro(data, 216) -#define MRECURSION218(macro, data) MRECURSION217( macro, DEC_(data)) macro(data, 217) -#define MRECURSION219(macro, data) MRECURSION218( macro, DEC_(data)) macro(data, 218) -#define MRECURSION220(macro, data) MRECURSION219( macro, DEC_(data)) macro(data, 219) -#define MRECURSION221(macro, data) MRECURSION220( macro, DEC_(data)) macro(data, 220) -#define MRECURSION222(macro, data) MRECURSION221( macro, DEC_(data)) macro(data, 221) -#define MRECURSION223(macro, data) MRECURSION222( macro, DEC_(data)) macro(data, 222) -#define MRECURSION224(macro, data) MRECURSION223( macro, DEC_(data)) macro(data, 223) -#define MRECURSION225(macro, data) MRECURSION224( macro, DEC_(data)) macro(data, 224) -#define MRECURSION226(macro, data) MRECURSION225( macro, DEC_(data)) macro(data, 225) -#define MRECURSION227(macro, data) MRECURSION226( macro, DEC_(data)) macro(data, 226) -#define MRECURSION228(macro, data) MRECURSION227( macro, DEC_(data)) macro(data, 227) -#define MRECURSION229(macro, data) MRECURSION228( macro, DEC_(data)) macro(data, 228) -#define MRECURSION230(macro, data) MRECURSION229( macro, DEC_(data)) macro(data, 229) -#define MRECURSION231(macro, data) MRECURSION230( macro, DEC_(data)) macro(data, 230) -#define MRECURSION232(macro, data) MRECURSION231( macro, DEC_(data)) macro(data, 231) -#define MRECURSION233(macro, data) MRECURSION232( macro, DEC_(data)) macro(data, 232) -#define MRECURSION234(macro, data) MRECURSION233( macro, DEC_(data)) macro(data, 233) -#define MRECURSION235(macro, data) MRECURSION234( macro, DEC_(data)) macro(data, 234) -#define MRECURSION236(macro, data) MRECURSION235( macro, DEC_(data)) macro(data, 235) -#define MRECURSION237(macro, data) MRECURSION236( macro, DEC_(data)) macro(data, 236) -#define MRECURSION238(macro, data) MRECURSION237( macro, DEC_(data)) macro(data, 237) -#define MRECURSION239(macro, data) MRECURSION238( macro, DEC_(data)) macro(data, 238) -#define MRECURSION240(macro, data) MRECURSION239( macro, DEC_(data)) macro(data, 239) -#define MRECURSION241(macro, data) MRECURSION240( macro, DEC_(data)) macro(data, 240) -#define MRECURSION242(macro, data) MRECURSION241( macro, DEC_(data)) macro(data, 241) -#define MRECURSION243(macro, data) MRECURSION242( macro, DEC_(data)) macro(data, 242) -#define MRECURSION244(macro, data) MRECURSION243( macro, DEC_(data)) macro(data, 243) -#define MRECURSION245(macro, data) MRECURSION244( macro, DEC_(data)) macro(data, 244) -#define MRECURSION246(macro, data) MRECURSION245( macro, DEC_(data)) macro(data, 245) -#define MRECURSION247(macro, data) MRECURSION246( macro, DEC_(data)) macro(data, 246) -#define MRECURSION248(macro, data) MRECURSION247( macro, DEC_(data)) macro(data, 247) -#define MRECURSION249(macro, data) MRECURSION248( macro, DEC_(data)) macro(data, 248) -#define MRECURSION250(macro, data) MRECURSION249( macro, DEC_(data)) macro(data, 249) -#define MRECURSION251(macro, data) MRECURSION250( macro, DEC_(data)) macro(data, 250) -#define MRECURSION252(macro, data) MRECURSION251( macro, DEC_(data)) macro(data, 251) -#define MRECURSION253(macro, data) MRECURSION252( macro, DEC_(data)) macro(data, 252) -#define MRECURSION254(macro, data) MRECURSION253( macro, DEC_(data)) macro(data, 253) -#define MRECURSION255(macro, data) MRECURSION254( macro, DEC_(data)) macro(data, 254) -#define MRECURSION256(macro, data) MRECURSION255( macro, DEC_(data)) macro(data, 255) - -/** @} */ - -#endif /* _MRECURSION_H_ */ diff --git a/bootloaders/zero/utils/preprocessor/mrepeat.h b/bootloaders/zero/utils/preprocessor/mrepeat.h deleted file mode 100644 index fb820d5bd..000000000 --- a/bootloaders/zero/utils/preprocessor/mrepeat.h +++ /dev/null @@ -1,321 +0,0 @@ -/* ---------------------------------------------------------------------------- - * SAM Software Package License - * ---------------------------------------------------------------------------- - * Copyright (c) 2011-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. - * ---------------------------------------------------------------------------- - */ - -#ifndef _MREPEAT_H_ -#define _MREPEAT_H_ - -/** - * \defgroup group_sam0_utils_mrepeat Preprocessor - Macro Repeat - * - * \ingroup group_sam0_utils - * - * @{ - */ - -#include "preprocessor.h" - -/** Maximal number of repetitions supported by MREPEAT. */ -#define MREPEAT_LIMIT 256 - -/** \brief Macro repeat. - * - * This macro represents a horizontal repetition construct. - * - * \param[in] count The number of repetitious calls to macro. Valid values - * range from 0 to MREPEAT_LIMIT. - * \param[in] macro A binary operation of the form macro(n, data). This macro - * is expanded by MREPEAT with the current repetition number - * and the auxiliary data argument. - * \param[in] data Auxiliary data passed to macro. - * - * \return macro(0, data) macro(1, data) ... macro(count - 1, data) - */ -#define MREPEAT(count, macro, data) TPASTE2(MREPEAT, count) (macro, data) - -#define MREPEAT0( macro, data) -#define MREPEAT1( macro, data) MREPEAT0( macro, data) macro( 0, data) -#define MREPEAT2( macro, data) MREPEAT1( macro, data) macro( 1, data) -#define MREPEAT3( macro, data) MREPEAT2( macro, data) macro( 2, data) -#define MREPEAT4( macro, data) MREPEAT3( macro, data) macro( 3, data) -#define MREPEAT5( macro, data) MREPEAT4( macro, data) macro( 4, data) -#define MREPEAT6( macro, data) MREPEAT5( macro, data) macro( 5, data) -#define MREPEAT7( macro, data) MREPEAT6( macro, data) macro( 6, data) -#define MREPEAT8( macro, data) MREPEAT7( macro, data) macro( 7, data) -#define MREPEAT9( macro, data) MREPEAT8( macro, data) macro( 8, data) -#define MREPEAT10( macro, data) MREPEAT9( macro, data) macro( 9, data) -#define MREPEAT11( macro, data) MREPEAT10( macro, data) macro( 10, data) -#define MREPEAT12( macro, data) MREPEAT11( macro, data) macro( 11, data) -#define MREPEAT13( macro, data) MREPEAT12( macro, data) macro( 12, data) -#define MREPEAT14( macro, data) MREPEAT13( macro, data) macro( 13, data) -#define MREPEAT15( macro, data) MREPEAT14( macro, data) macro( 14, data) -#define MREPEAT16( macro, data) MREPEAT15( macro, data) macro( 15, data) -#define MREPEAT17( macro, data) MREPEAT16( macro, data) macro( 16, data) -#define MREPEAT18( macro, data) MREPEAT17( macro, data) macro( 17, data) -#define MREPEAT19( macro, data) MREPEAT18( macro, data) macro( 18, data) -#define MREPEAT20( macro, data) MREPEAT19( macro, data) macro( 19, data) -#define MREPEAT21( macro, data) MREPEAT20( macro, data) macro( 20, data) -#define MREPEAT22( macro, data) MREPEAT21( macro, data) macro( 21, data) -#define MREPEAT23( macro, data) MREPEAT22( macro, data) macro( 22, data) -#define MREPEAT24( macro, data) MREPEAT23( macro, data) macro( 23, data) -#define MREPEAT25( macro, data) MREPEAT24( macro, data) macro( 24, data) -#define MREPEAT26( macro, data) MREPEAT25( macro, data) macro( 25, data) -#define MREPEAT27( macro, data) MREPEAT26( macro, data) macro( 26, data) -#define MREPEAT28( macro, data) MREPEAT27( macro, data) macro( 27, data) -#define MREPEAT29( macro, data) MREPEAT28( macro, data) macro( 28, data) -#define MREPEAT30( macro, data) MREPEAT29( macro, data) macro( 29, data) -#define MREPEAT31( macro, data) MREPEAT30( macro, data) macro( 30, data) -#define MREPEAT32( macro, data) MREPEAT31( macro, data) macro( 31, data) -#define MREPEAT33( macro, data) MREPEAT32( macro, data) macro( 32, data) -#define MREPEAT34( macro, data) MREPEAT33( macro, data) macro( 33, data) -#define MREPEAT35( macro, data) MREPEAT34( macro, data) macro( 34, data) -#define MREPEAT36( macro, data) MREPEAT35( macro, data) macro( 35, data) -#define MREPEAT37( macro, data) MREPEAT36( macro, data) macro( 36, data) -#define MREPEAT38( macro, data) MREPEAT37( macro, data) macro( 37, data) -#define MREPEAT39( macro, data) MREPEAT38( macro, data) macro( 38, data) -#define MREPEAT40( macro, data) MREPEAT39( macro, data) macro( 39, data) -#define MREPEAT41( macro, data) MREPEAT40( macro, data) macro( 40, data) -#define MREPEAT42( macro, data) MREPEAT41( macro, data) macro( 41, data) -#define MREPEAT43( macro, data) MREPEAT42( macro, data) macro( 42, data) -#define MREPEAT44( macro, data) MREPEAT43( macro, data) macro( 43, data) -#define MREPEAT45( macro, data) MREPEAT44( macro, data) macro( 44, data) -#define MREPEAT46( macro, data) MREPEAT45( macro, data) macro( 45, data) -#define MREPEAT47( macro, data) MREPEAT46( macro, data) macro( 46, data) -#define MREPEAT48( macro, data) MREPEAT47( macro, data) macro( 47, data) -#define MREPEAT49( macro, data) MREPEAT48( macro, data) macro( 48, data) -#define MREPEAT50( macro, data) MREPEAT49( macro, data) macro( 49, data) -#define MREPEAT51( macro, data) MREPEAT50( macro, data) macro( 50, data) -#define MREPEAT52( macro, data) MREPEAT51( macro, data) macro( 51, data) -#define MREPEAT53( macro, data) MREPEAT52( macro, data) macro( 52, data) -#define MREPEAT54( macro, data) MREPEAT53( macro, data) macro( 53, data) -#define MREPEAT55( macro, data) MREPEAT54( macro, data) macro( 54, data) -#define MREPEAT56( macro, data) MREPEAT55( macro, data) macro( 55, data) -#define MREPEAT57( macro, data) MREPEAT56( macro, data) macro( 56, data) -#define MREPEAT58( macro, data) MREPEAT57( macro, data) macro( 57, data) -#define MREPEAT59( macro, data) MREPEAT58( macro, data) macro( 58, data) -#define MREPEAT60( macro, data) MREPEAT59( macro, data) macro( 59, data) -#define MREPEAT61( macro, data) MREPEAT60( macro, data) macro( 60, data) -#define MREPEAT62( macro, data) MREPEAT61( macro, data) macro( 61, data) -#define MREPEAT63( macro, data) MREPEAT62( macro, data) macro( 62, data) -#define MREPEAT64( macro, data) MREPEAT63( macro, data) macro( 63, data) -#define MREPEAT65( macro, data) MREPEAT64( macro, data) macro( 64, data) -#define MREPEAT66( macro, data) MREPEAT65( macro, data) macro( 65, data) -#define MREPEAT67( macro, data) MREPEAT66( macro, data) macro( 66, data) -#define MREPEAT68( macro, data) MREPEAT67( macro, data) macro( 67, data) -#define MREPEAT69( macro, data) MREPEAT68( macro, data) macro( 68, data) -#define MREPEAT70( macro, data) MREPEAT69( macro, data) macro( 69, data) -#define MREPEAT71( macro, data) MREPEAT70( macro, data) macro( 70, data) -#define MREPEAT72( macro, data) MREPEAT71( macro, data) macro( 71, data) -#define MREPEAT73( macro, data) MREPEAT72( macro, data) macro( 72, data) -#define MREPEAT74( macro, data) MREPEAT73( macro, data) macro( 73, data) -#define MREPEAT75( macro, data) MREPEAT74( macro, data) macro( 74, data) -#define MREPEAT76( macro, data) MREPEAT75( macro, data) macro( 75, data) -#define MREPEAT77( macro, data) MREPEAT76( macro, data) macro( 76, data) -#define MREPEAT78( macro, data) MREPEAT77( macro, data) macro( 77, data) -#define MREPEAT79( macro, data) MREPEAT78( macro, data) macro( 78, data) -#define MREPEAT80( macro, data) MREPEAT79( macro, data) macro( 79, data) -#define MREPEAT81( macro, data) MREPEAT80( macro, data) macro( 80, data) -#define MREPEAT82( macro, data) MREPEAT81( macro, data) macro( 81, data) -#define MREPEAT83( macro, data) MREPEAT82( macro, data) macro( 82, data) -#define MREPEAT84( macro, data) MREPEAT83( macro, data) macro( 83, data) -#define MREPEAT85( macro, data) MREPEAT84( macro, data) macro( 84, data) -#define MREPEAT86( macro, data) MREPEAT85( macro, data) macro( 85, data) -#define MREPEAT87( macro, data) MREPEAT86( macro, data) macro( 86, data) -#define MREPEAT88( macro, data) MREPEAT87( macro, data) macro( 87, data) -#define MREPEAT89( macro, data) MREPEAT88( macro, data) macro( 88, data) -#define MREPEAT90( macro, data) MREPEAT89( macro, data) macro( 89, data) -#define MREPEAT91( macro, data) MREPEAT90( macro, data) macro( 90, data) -#define MREPEAT92( macro, data) MREPEAT91( macro, data) macro( 91, data) -#define MREPEAT93( macro, data) MREPEAT92( macro, data) macro( 92, data) -#define MREPEAT94( macro, data) MREPEAT93( macro, data) macro( 93, data) -#define MREPEAT95( macro, data) MREPEAT94( macro, data) macro( 94, data) -#define MREPEAT96( macro, data) MREPEAT95( macro, data) macro( 95, data) -#define MREPEAT97( macro, data) MREPEAT96( macro, data) macro( 96, data) -#define MREPEAT98( macro, data) MREPEAT97( macro, data) macro( 97, data) -#define MREPEAT99( macro, data) MREPEAT98( macro, data) macro( 98, data) -#define MREPEAT100(macro, data) MREPEAT99( macro, data) macro( 99, data) -#define MREPEAT101(macro, data) MREPEAT100(macro, data) macro(100, data) -#define MREPEAT102(macro, data) MREPEAT101(macro, data) macro(101, data) -#define MREPEAT103(macro, data) MREPEAT102(macro, data) macro(102, data) -#define MREPEAT104(macro, data) MREPEAT103(macro, data) macro(103, data) -#define MREPEAT105(macro, data) MREPEAT104(macro, data) macro(104, data) -#define MREPEAT106(macro, data) MREPEAT105(macro, data) macro(105, data) -#define MREPEAT107(macro, data) MREPEAT106(macro, data) macro(106, data) -#define MREPEAT108(macro, data) MREPEAT107(macro, data) macro(107, data) -#define MREPEAT109(macro, data) MREPEAT108(macro, data) macro(108, data) -#define MREPEAT110(macro, data) MREPEAT109(macro, data) macro(109, data) -#define MREPEAT111(macro, data) MREPEAT110(macro, data) macro(110, data) -#define MREPEAT112(macro, data) MREPEAT111(macro, data) macro(111, data) -#define MREPEAT113(macro, data) MREPEAT112(macro, data) macro(112, data) -#define MREPEAT114(macro, data) MREPEAT113(macro, data) macro(113, data) -#define MREPEAT115(macro, data) MREPEAT114(macro, data) macro(114, data) -#define MREPEAT116(macro, data) MREPEAT115(macro, data) macro(115, data) -#define MREPEAT117(macro, data) MREPEAT116(macro, data) macro(116, data) -#define MREPEAT118(macro, data) MREPEAT117(macro, data) macro(117, data) -#define MREPEAT119(macro, data) MREPEAT118(macro, data) macro(118, data) -#define MREPEAT120(macro, data) MREPEAT119(macro, data) macro(119, data) -#define MREPEAT121(macro, data) MREPEAT120(macro, data) macro(120, data) -#define MREPEAT122(macro, data) MREPEAT121(macro, data) macro(121, data) -#define MREPEAT123(macro, data) MREPEAT122(macro, data) macro(122, data) -#define MREPEAT124(macro, data) MREPEAT123(macro, data) macro(123, data) -#define MREPEAT125(macro, data) MREPEAT124(macro, data) macro(124, data) -#define MREPEAT126(macro, data) MREPEAT125(macro, data) macro(125, data) -#define MREPEAT127(macro, data) MREPEAT126(macro, data) macro(126, data) -#define MREPEAT128(macro, data) MREPEAT127(macro, data) macro(127, data) -#define MREPEAT129(macro, data) MREPEAT128(macro, data) macro(128, data) -#define MREPEAT130(macro, data) MREPEAT129(macro, data) macro(129, data) -#define MREPEAT131(macro, data) MREPEAT130(macro, data) macro(130, data) -#define MREPEAT132(macro, data) MREPEAT131(macro, data) macro(131, data) -#define MREPEAT133(macro, data) MREPEAT132(macro, data) macro(132, data) -#define MREPEAT134(macro, data) MREPEAT133(macro, data) macro(133, data) -#define MREPEAT135(macro, data) MREPEAT134(macro, data) macro(134, data) -#define MREPEAT136(macro, data) MREPEAT135(macro, data) macro(135, data) -#define MREPEAT137(macro, data) MREPEAT136(macro, data) macro(136, data) -#define MREPEAT138(macro, data) MREPEAT137(macro, data) macro(137, data) -#define MREPEAT139(macro, data) MREPEAT138(macro, data) macro(138, data) -#define MREPEAT140(macro, data) MREPEAT139(macro, data) macro(139, data) -#define MREPEAT141(macro, data) MREPEAT140(macro, data) macro(140, data) -#define MREPEAT142(macro, data) MREPEAT141(macro, data) macro(141, data) -#define MREPEAT143(macro, data) MREPEAT142(macro, data) macro(142, data) -#define MREPEAT144(macro, data) MREPEAT143(macro, data) macro(143, data) -#define MREPEAT145(macro, data) MREPEAT144(macro, data) macro(144, data) -#define MREPEAT146(macro, data) MREPEAT145(macro, data) macro(145, data) -#define MREPEAT147(macro, data) MREPEAT146(macro, data) macro(146, data) -#define MREPEAT148(macro, data) MREPEAT147(macro, data) macro(147, data) -#define MREPEAT149(macro, data) MREPEAT148(macro, data) macro(148, data) -#define MREPEAT150(macro, data) MREPEAT149(macro, data) macro(149, data) -#define MREPEAT151(macro, data) MREPEAT150(macro, data) macro(150, data) -#define MREPEAT152(macro, data) MREPEAT151(macro, data) macro(151, data) -#define MREPEAT153(macro, data) MREPEAT152(macro, data) macro(152, data) -#define MREPEAT154(macro, data) MREPEAT153(macro, data) macro(153, data) -#define MREPEAT155(macro, data) MREPEAT154(macro, data) macro(154, data) -#define MREPEAT156(macro, data) MREPEAT155(macro, data) macro(155, data) -#define MREPEAT157(macro, data) MREPEAT156(macro, data) macro(156, data) -#define MREPEAT158(macro, data) MREPEAT157(macro, data) macro(157, data) -#define MREPEAT159(macro, data) MREPEAT158(macro, data) macro(158, data) -#define MREPEAT160(macro, data) MREPEAT159(macro, data) macro(159, data) -#define MREPEAT161(macro, data) MREPEAT160(macro, data) macro(160, data) -#define MREPEAT162(macro, data) MREPEAT161(macro, data) macro(161, data) -#define MREPEAT163(macro, data) MREPEAT162(macro, data) macro(162, data) -#define MREPEAT164(macro, data) MREPEAT163(macro, data) macro(163, data) -#define MREPEAT165(macro, data) MREPEAT164(macro, data) macro(164, data) -#define MREPEAT166(macro, data) MREPEAT165(macro, data) macro(165, data) -#define MREPEAT167(macro, data) MREPEAT166(macro, data) macro(166, data) -#define MREPEAT168(macro, data) MREPEAT167(macro, data) macro(167, data) -#define MREPEAT169(macro, data) MREPEAT168(macro, data) macro(168, data) -#define MREPEAT170(macro, data) MREPEAT169(macro, data) macro(169, data) -#define MREPEAT171(macro, data) MREPEAT170(macro, data) macro(170, data) -#define MREPEAT172(macro, data) MREPEAT171(macro, data) macro(171, data) -#define MREPEAT173(macro, data) MREPEAT172(macro, data) macro(172, data) -#define MREPEAT174(macro, data) MREPEAT173(macro, data) macro(173, data) -#define MREPEAT175(macro, data) MREPEAT174(macro, data) macro(174, data) -#define MREPEAT176(macro, data) MREPEAT175(macro, data) macro(175, data) -#define MREPEAT177(macro, data) MREPEAT176(macro, data) macro(176, data) -#define MREPEAT178(macro, data) MREPEAT177(macro, data) macro(177, data) -#define MREPEAT179(macro, data) MREPEAT178(macro, data) macro(178, data) -#define MREPEAT180(macro, data) MREPEAT179(macro, data) macro(179, data) -#define MREPEAT181(macro, data) MREPEAT180(macro, data) macro(180, data) -#define MREPEAT182(macro, data) MREPEAT181(macro, data) macro(181, data) -#define MREPEAT183(macro, data) MREPEAT182(macro, data) macro(182, data) -#define MREPEAT184(macro, data) MREPEAT183(macro, data) macro(183, data) -#define MREPEAT185(macro, data) MREPEAT184(macro, data) macro(184, data) -#define MREPEAT186(macro, data) MREPEAT185(macro, data) macro(185, data) -#define MREPEAT187(macro, data) MREPEAT186(macro, data) macro(186, data) -#define MREPEAT188(macro, data) MREPEAT187(macro, data) macro(187, data) -#define MREPEAT189(macro, data) MREPEAT188(macro, data) macro(188, data) -#define MREPEAT190(macro, data) MREPEAT189(macro, data) macro(189, data) -#define MREPEAT191(macro, data) MREPEAT190(macro, data) macro(190, data) -#define MREPEAT192(macro, data) MREPEAT191(macro, data) macro(191, data) -#define MREPEAT193(macro, data) MREPEAT192(macro, data) macro(192, data) -#define MREPEAT194(macro, data) MREPEAT193(macro, data) macro(193, data) -#define MREPEAT195(macro, data) MREPEAT194(macro, data) macro(194, data) -#define MREPEAT196(macro, data) MREPEAT195(macro, data) macro(195, data) -#define MREPEAT197(macro, data) MREPEAT196(macro, data) macro(196, data) -#define MREPEAT198(macro, data) MREPEAT197(macro, data) macro(197, data) -#define MREPEAT199(macro, data) MREPEAT198(macro, data) macro(198, data) -#define MREPEAT200(macro, data) MREPEAT199(macro, data) macro(199, data) -#define MREPEAT201(macro, data) MREPEAT200(macro, data) macro(200, data) -#define MREPEAT202(macro, data) MREPEAT201(macro, data) macro(201, data) -#define MREPEAT203(macro, data) MREPEAT202(macro, data) macro(202, data) -#define MREPEAT204(macro, data) MREPEAT203(macro, data) macro(203, data) -#define MREPEAT205(macro, data) MREPEAT204(macro, data) macro(204, data) -#define MREPEAT206(macro, data) MREPEAT205(macro, data) macro(205, data) -#define MREPEAT207(macro, data) MREPEAT206(macro, data) macro(206, data) -#define MREPEAT208(macro, data) MREPEAT207(macro, data) macro(207, data) -#define MREPEAT209(macro, data) MREPEAT208(macro, data) macro(208, data) -#define MREPEAT210(macro, data) MREPEAT209(macro, data) macro(209, data) -#define MREPEAT211(macro, data) MREPEAT210(macro, data) macro(210, data) -#define MREPEAT212(macro, data) MREPEAT211(macro, data) macro(211, data) -#define MREPEAT213(macro, data) MREPEAT212(macro, data) macro(212, data) -#define MREPEAT214(macro, data) MREPEAT213(macro, data) macro(213, data) -#define MREPEAT215(macro, data) MREPEAT214(macro, data) macro(214, data) -#define MREPEAT216(macro, data) MREPEAT215(macro, data) macro(215, data) -#define MREPEAT217(macro, data) MREPEAT216(macro, data) macro(216, data) -#define MREPEAT218(macro, data) MREPEAT217(macro, data) macro(217, data) -#define MREPEAT219(macro, data) MREPEAT218(macro, data) macro(218, data) -#define MREPEAT220(macro, data) MREPEAT219(macro, data) macro(219, data) -#define MREPEAT221(macro, data) MREPEAT220(macro, data) macro(220, data) -#define MREPEAT222(macro, data) MREPEAT221(macro, data) macro(221, data) -#define MREPEAT223(macro, data) MREPEAT222(macro, data) macro(222, data) -#define MREPEAT224(macro, data) MREPEAT223(macro, data) macro(223, data) -#define MREPEAT225(macro, data) MREPEAT224(macro, data) macro(224, data) -#define MREPEAT226(macro, data) MREPEAT225(macro, data) macro(225, data) -#define MREPEAT227(macro, data) MREPEAT226(macro, data) macro(226, data) -#define MREPEAT228(macro, data) MREPEAT227(macro, data) macro(227, data) -#define MREPEAT229(macro, data) MREPEAT228(macro, data) macro(228, data) -#define MREPEAT230(macro, data) MREPEAT229(macro, data) macro(229, data) -#define MREPEAT231(macro, data) MREPEAT230(macro, data) macro(230, data) -#define MREPEAT232(macro, data) MREPEAT231(macro, data) macro(231, data) -#define MREPEAT233(macro, data) MREPEAT232(macro, data) macro(232, data) -#define MREPEAT234(macro, data) MREPEAT233(macro, data) macro(233, data) -#define MREPEAT235(macro, data) MREPEAT234(macro, data) macro(234, data) -#define MREPEAT236(macro, data) MREPEAT235(macro, data) macro(235, data) -#define MREPEAT237(macro, data) MREPEAT236(macro, data) macro(236, data) -#define MREPEAT238(macro, data) MREPEAT237(macro, data) macro(237, data) -#define MREPEAT239(macro, data) MREPEAT238(macro, data) macro(238, data) -#define MREPEAT240(macro, data) MREPEAT239(macro, data) macro(239, data) -#define MREPEAT241(macro, data) MREPEAT240(macro, data) macro(240, data) -#define MREPEAT242(macro, data) MREPEAT241(macro, data) macro(241, data) -#define MREPEAT243(macro, data) MREPEAT242(macro, data) macro(242, data) -#define MREPEAT244(macro, data) MREPEAT243(macro, data) macro(243, data) -#define MREPEAT245(macro, data) MREPEAT244(macro, data) macro(244, data) -#define MREPEAT246(macro, data) MREPEAT245(macro, data) macro(245, data) -#define MREPEAT247(macro, data) MREPEAT246(macro, data) macro(246, data) -#define MREPEAT248(macro, data) MREPEAT247(macro, data) macro(247, data) -#define MREPEAT249(macro, data) MREPEAT248(macro, data) macro(248, data) -#define MREPEAT250(macro, data) MREPEAT249(macro, data) macro(249, data) -#define MREPEAT251(macro, data) MREPEAT250(macro, data) macro(250, data) -#define MREPEAT252(macro, data) MREPEAT251(macro, data) macro(251, data) -#define MREPEAT253(macro, data) MREPEAT252(macro, data) macro(252, data) -#define MREPEAT254(macro, data) MREPEAT253(macro, data) macro(253, data) -#define MREPEAT255(macro, data) MREPEAT254(macro, data) macro(254, data) -#define MREPEAT256(macro, data) MREPEAT255(macro, data) macro(255, data) - -/** @} */ - -#endif /* _MREPEAT_H_ */ diff --git a/bootloaders/zero/utils/preprocessor/preprocessor.h b/bootloaders/zero/utils/preprocessor/preprocessor.h deleted file mode 100644 index 7f67d8adf..000000000 --- a/bootloaders/zero/utils/preprocessor/preprocessor.h +++ /dev/null @@ -1,38 +0,0 @@ -/* ---------------------------------------------------------------------------- - * SAM Software Package License - * ---------------------------------------------------------------------------- - * Copyright (c) 2011-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. - * ---------------------------------------------------------------------------- - */ - -#ifndef _PREPROCESSOR_H_ -#define _PREPROCESSOR_H_ - -#include "tpaste.h" -#include "stringz.h" -#include "mrepeat.h" -#include "mrecursion.h" - -#endif // _PREPROCESSOR_H_ diff --git a/bootloaders/zero/utils/preprocessor/stringz.h b/bootloaders/zero/utils/preprocessor/stringz.h deleted file mode 100644 index 70937c434..000000000 --- a/bootloaders/zero/utils/preprocessor/stringz.h +++ /dev/null @@ -1,67 +0,0 @@ -/* ---------------------------------------------------------------------------- - * SAM Software Package License - * ---------------------------------------------------------------------------- - * Copyright (c) 2011-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. - * ---------------------------------------------------------------------------- - */ - -#ifndef _STRINGZ_H_ -#define _STRINGZ_H_ - -/** - * \defgroup group_sam0_utils_stringz Preprocessor - Stringize - * - * \ingroup group_sam0_utils - * - * @{ - */ - -/** \brief Stringize. - * - * Stringize a preprocessing token, this token being allowed to be \#defined. - * - * May be used only within macros with the token passed as an argument if the - * token is \#defined. - * - * For example, writing STRINGZ(PIN) within a macro \#defined by PIN_NAME(PIN) - * and invoked as PIN_NAME(PIN0) with PIN0 \#defined as A0 is equivalent to - * writing "A0". - */ -#define STRINGZ(x) #x - -/** \brief Absolute stringize. - * - * Stringize a preprocessing token, this token being allowed to be \#defined. - * - * No restriction of use if the token is \#defined. - * - * For example, writing ASTRINGZ(PIN0) anywhere with PIN0 \#defined as A0 is - * equivalent to writing "A0". - */ -#define ASTRINGZ(x) STRINGZ(x) - -/** @} */ - -#endif // _STRINGZ_H_ diff --git a/bootloaders/zero/utils/preprocessor/tpaste.h b/bootloaders/zero/utils/preprocessor/tpaste.h deleted file mode 100644 index 910818347..000000000 --- a/bootloaders/zero/utils/preprocessor/tpaste.h +++ /dev/null @@ -1,85 +0,0 @@ -/* ---------------------------------------------------------------------------- - * SAM Software Package License - * ---------------------------------------------------------------------------- - * Copyright (c) 2011-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. - * ---------------------------------------------------------------------------- - */ -#ifndef _TPASTE_H_ -#define _TPASTE_H_ - -/** - * \defgroup group_sam0_utils_tpaste Preprocessor - Token Paste - * - * \ingroup group_sam0_utils - * - * @{ - */ - -/** \name Token Paste - * - * Paste N preprocessing tokens together, these tokens being allowed to be \#defined. - * - * May be used only within macros with the tokens passed as arguments if the tokens are \#defined. - * - * For example, writing TPASTE2(U, WIDTH) within a macro \#defined by - * UTYPE(WIDTH) and invoked as UTYPE(UL_WIDTH) with UL_WIDTH \#defined as 32 is - * equivalent to writing U32. - * - * @{ */ -#define TPASTE2( a, b) a##b -#define TPASTE3( a, b, c) a##b##c -#define TPASTE4( a, b, c, d) a##b##c##d -#define TPASTE5( a, b, c, d, e) a##b##c##d##e -#define TPASTE6( a, b, c, d, e, f) a##b##c##d##e##f -#define TPASTE7( a, b, c, d, e, f, g) a##b##c##d##e##f##g -#define TPASTE8( a, b, c, d, e, f, g, h) a##b##c##d##e##f##g##h -#define TPASTE9( a, b, c, d, e, f, g, h, i) a##b##c##d##e##f##g##h##i -#define TPASTE10(a, b, c, d, e, f, g, h, i, j) a##b##c##d##e##f##g##h##i##j -/** @} */ - -/** \name Absolute Token Paste - * - * Paste N preprocessing tokens together, these tokens being allowed to be \#defined. - * - * No restriction of use if the tokens are \#defined. - * - * For example, writing ATPASTE2(U, UL_WIDTH) anywhere with UL_WIDTH \#defined - * as 32 is equivalent to writing U32. - * - * @{ */ -#define ATPASTE2( a, b) TPASTE2( a, b) -#define ATPASTE3( a, b, c) TPASTE3( a, b, c) -#define ATPASTE4( a, b, c, d) TPASTE4( a, b, c, d) -#define ATPASTE5( a, b, c, d, e) TPASTE5( a, b, c, d, e) -#define ATPASTE6( a, b, c, d, e, f) TPASTE6( a, b, c, d, e, f) -#define ATPASTE7( a, b, c, d, e, f, g) TPASTE7( a, b, c, d, e, f, g) -#define ATPASTE8( a, b, c, d, e, f, g, h) TPASTE8( a, b, c, d, e, f, g, h) -#define ATPASTE9( a, b, c, d, e, f, g, h, i) TPASTE9( a, b, c, d, e, f, g, h, i) -#define ATPASTE10(a, b, c, d, e, f, g, h, i, j) TPASTE10(a, b, c, d, e, f, g, h, i, j) -/** @} */ - -/** @} */ - -#endif // _TPASTE_H_ diff --git a/bootloaders/zero/utils/status_codes.h b/bootloaders/zero/utils/status_codes.h deleted file mode 100644 index 29bbf4166..000000000 --- a/bootloaders/zero/utils/status_codes.h +++ /dev/null @@ -1,138 +0,0 @@ -/* ---------------------------------------------------------------------------- - * SAM Software Package License - * ---------------------------------------------------------------------------- - * Copyright (c) 2011-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. - * ---------------------------------------------------------------------------- - */ - -#ifndef STATUS_CODES_H_INCLUDED -#define STATUS_CODES_H_INCLUDED - -#include - -/** - * \defgroup group_sam0_utils_status_codes Status Codes - * - * \ingroup group_sam0_utils - * - * @{ - */ - -/** Mask to retrieve the error category of a status code. */ -#define STATUS_CATEGORY_MASK 0xF0 - -/** Mask to retrieve the error code within the category of a status code. */ -#define STATUS_ERROR_MASK 0x0F - -/** Status code error categories. */ -enum status_categories { - STATUS_CATEGORY_OK = 0x00, - STATUS_CATEGORY_COMMON = 0x10, - STATUS_CATEGORY_ANALOG = 0x30, - STATUS_CATEGORY_COM = 0x40, - STATUS_CATEGORY_IO = 0x50, -}; - -/** - * Status code that may be returned by shell commands and protocol - * implementations. - * - * \note Any change to these status codes and the corresponding - * message strings is strictly forbidden. New codes can be added, - * however, but make sure that any message string tables are updated - * at the same time. - */ -enum status_code { - STATUS_OK = STATUS_CATEGORY_OK | 0x00, - STATUS_VALID_DATA = STATUS_CATEGORY_OK | 0x01, - STATUS_NO_CHANGE = STATUS_CATEGORY_OK | 0x02, - STATUS_ABORTED = STATUS_CATEGORY_OK | 0x04, - STATUS_BUSY = STATUS_CATEGORY_OK | 0x05, - STATUS_SUSPEND = STATUS_CATEGORY_OK | 0x06, - - STATUS_ERR_IO = STATUS_CATEGORY_COMMON | 0x00, - STATUS_ERR_REQ_FLUSHED = STATUS_CATEGORY_COMMON | 0x01, - STATUS_ERR_TIMEOUT = STATUS_CATEGORY_COMMON | 0x02, - STATUS_ERR_BAD_DATA = STATUS_CATEGORY_COMMON | 0x03, - STATUS_ERR_NOT_FOUND = STATUS_CATEGORY_COMMON | 0x04, - STATUS_ERR_UNSUPPORTED_DEV = STATUS_CATEGORY_COMMON | 0x05, - STATUS_ERR_NO_MEMORY = STATUS_CATEGORY_COMMON | 0x06, - STATUS_ERR_INVALID_ARG = STATUS_CATEGORY_COMMON | 0x07, - STATUS_ERR_BAD_ADDRESS = STATUS_CATEGORY_COMMON | 0x08, - STATUS_ERR_BAD_FORMAT = STATUS_CATEGORY_COMMON | 0x0A, - STATUS_ERR_BAD_FRQ = STATUS_CATEGORY_COMMON | 0x0B, - STATUS_ERR_DENIED = STATUS_CATEGORY_COMMON | 0x0c, - STATUS_ERR_ALREADY_INITIALIZED = STATUS_CATEGORY_COMMON | 0x0d, - STATUS_ERR_OVERFLOW = STATUS_CATEGORY_COMMON | 0x0e, - STATUS_ERR_NOT_INITIALIZED = STATUS_CATEGORY_COMMON | 0x0f, - - STATUS_ERR_SAMPLERATE_UNAVAILABLE = STATUS_CATEGORY_ANALOG | 0x00, - STATUS_ERR_RESOLUTION_UNAVAILABLE = STATUS_CATEGORY_ANALOG | 0x01, - - STATUS_ERR_BAUDRATE_UNAVAILABLE = STATUS_CATEGORY_COM | 0x00, - STATUS_ERR_PACKET_COLLISION = STATUS_CATEGORY_COM | 0x01, - STATUS_ERR_PROTOCOL = STATUS_CATEGORY_COM | 0x02, - - STATUS_ERR_PIN_MUX_INVALID = STATUS_CATEGORY_IO | 0x00, -}; -typedef enum status_code status_code_genare_t; - -/** - Status codes used by MAC stack. - */ -enum status_code_wireless { - //STATUS_OK = 0, //!< Success - ERR_IO_ERROR = -1, //!< I/O error - ERR_FLUSHED = -2, //!< Request flushed from queue - ERR_TIMEOUT = -3, //!< Operation timed out - ERR_BAD_DATA = -4, //!< Data integrity check failed - ERR_PROTOCOL = -5, //!< Protocol error - ERR_UNSUPPORTED_DEV = -6, //!< Unsupported device - ERR_NO_MEMORY = -7, //!< Insufficient memory - ERR_INVALID_ARG = -8, //!< Invalid argument - ERR_BAD_ADDRESS = -9, //!< Bad address - ERR_BUSY = -10, //!< Resource is busy - ERR_BAD_FORMAT = -11, //!< Data format not recognized - ERR_NO_TIMER = -12, //!< No timer available - ERR_TIMER_ALREADY_RUNNING = -13, //!< Timer already running - ERR_TIMER_NOT_RUNNING = -14, //!< Timer not running - - /** - * \brief Operation in progress - * - * This status code is for driver-internal use when an operation - * is currently being performed. - * - * \note Drivers should never return this status code to any - * callers. It is strictly for internal use. - */ - OPERATION_IN_PROGRESS = -128, -}; - -typedef enum status_code_wireless status_code_t; - -/** @} */ - -#endif /* STATUS_CODES_H_INCLUDED */