diff --git a/boards.txt b/boards.txt index 174a561e0..0fd495234 100644 --- a/boards.txt +++ b/boards.txt @@ -14,77 +14,58 @@ # License along with this library; if not, write to the Free Software # Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA -# Arduino/Genuino Zero (Prorgamming Port) -# --------------------------------------- -arduino_zero_edbg.name=Arduino/Genuino Zero (Programming Port) -arduino_zero_edbg.vid.0=0x03eb -arduino_zero_edbg.pid.0=0x2157 -arduino_zero_edbg.upload.tool=openocd -arduino_zero_edbg.upload.protocol=sam-ba -arduino_zero_edbg.upload.maximum_size=262144 -arduino_zero_edbg.upload.use_1200bps_touch=false -arduino_zero_edbg.upload.wait_for_upload_port=false -arduino_zero_edbg.upload.native_usb=false -arduino_zero_edbg.build.mcu=cortex-m0plus -arduino_zero_edbg.build.f_cpu=48000000L -arduino_zero_edbg.build.usb_product="Arduino Zero" -arduino_zero_edbg.build.usb_manufacturer="Arduino LLC" -arduino_zero_edbg.build.board=SAMD_ZERO -arduino_zero_edbg.build.core=arduino -arduino_zero_edbg.build.extra_flags=-D__SAMD21G18A__ {build.usb_flags} -arduino_zero_edbg.build.ldscript=linker_scripts/gcc/flash_with_bootloader.ld -arduino_zero_edbg.build.openocdscript=openocd_scripts/arduino_zero.cfg -arduino_zero_edbg.build.variant=arduino_zero -arduino_zero_edbg.build.variant_system_lib= -arduino_zero_edbg.build.vid=0x2341 -arduino_zero_edbg.build.pid=0x804d -arduino_zero_edbg.bootloader.tool=openocd -arduino_zero_edbg.bootloader.file=zero/samd21_sam_ba.bin +adafruit_feather_m0.name=Adafruit Feather M0 (Native USB Port) +adafruit_feather_m0.vid.0=0x239A +adafruit_feather_m0.pid.0=0x800B +adafruit_feather_m0.vid.1=0x239A +adafruit_feather_m0.pid.1=0x000B +adafruit_feather_m0.upload.tool=bossac +adafruit_feather_m0.upload.protocol=sam-ba +adafruit_feather_m0.upload.maximum_size=262144 +adafruit_feather_m0.upload.use_1200bps_touch=true +adafruit_feather_m0.upload.wait_for_upload_port=true +adafruit_feather_m0.upload.native_usb=true +adafruit_feather_m0.build.mcu=cortex-m0plus +adafruit_feather_m0.build.f_cpu=48000000L +adafruit_feather_m0.build.usb_product="Feather M0" +adafruit_feather_m0.build.usb_manufacturer="Adafruit" +adafruit_feather_m0.build.board=SAMD_FEATHER_M0 +adafruit_feather_m0.build.core=arduino +adafruit_feather_m0.build.extra_flags=-DARDUINO_SAMD_ZERO -D__SAMD21G18A__ {build.usb_flags} +adafruit_feather_m0.build.ldscript=linker_scripts/gcc/flash_with_bootloader.ld +adafruit_feather_m0.build.openocdscript=openocd_scripts/arduino_zero.cfg +adafruit_feather_m0.build.variant=arduino_zero +adafruit_feather_m0.build.variant_system_lib= +adafruit_feather_m0.build.vid=0x239A +adafruit_feather_m0.build.pid=0x800B +adafruit_feather_m0.bootloader.tool=openocd +adafruit_feather_m0.bootloader.file=feather/samd21_sam_ba.bin -# Arduino/Genuino Zero (Native USB Port) -# --------------------------------------- -arduino_zero_native.name=Arduino/Genuino Zero (Native USB Port) -arduino_zero_native.vid.0=0x2341 -arduino_zero_native.pid.0=0x804d -arduino_zero_native.vid.1=0x2341 -arduino_zero_native.pid.1=0x004d - -arduino_zero_native.vid.2=0x2341 -arduino_zero_native.pid.2=0x824d -# If the board is a 2341:824d use 2341:824d for build and set other parameters as well -arduino_zero_native.vid.2.build.vid=0x2341 -arduino_zero_native.vid.2.build.pid=0x824d -arduino_zero_native.vid.2.build.usb_product="Genuino Zero" -arduino_zero_native.vid.2.bootloader.file=zero/samd21_sam_ba_genuino.bin - -arduino_zero_native.vid.3=0x2341 -arduino_zero_native.pid.3=0x024d -# If the board is a 2341:024d use 2341:824d for build and set other parameters as well -arduino_zero_native.vid.3.build.vid=0x2341 -arduino_zero_native.vid.3.build.pid=0x824d -arduino_zero_native.vid.3.build.usb_product="Genuino Zero" -arduino_zero_native.vid.3.bootloader.file=zero/samd21_sam_ba_genuino.bin - -arduino_zero_native.upload.tool=bossac -arduino_zero_native.upload.protocol=sam-ba -arduino_zero_native.upload.maximum_size=262144 -arduino_zero_native.upload.use_1200bps_touch=true -arduino_zero_native.upload.wait_for_upload_port=true -arduino_zero_native.upload.native_usb=true -arduino_zero_native.build.mcu=cortex-m0plus -arduino_zero_native.build.f_cpu=48000000L -arduino_zero_native.build.usb_product="Arduino Zero" -arduino_zero_native.build.usb_manufacturer="Arduino LLC" -arduino_zero_native.build.board=SAMD_ZERO -arduino_zero_native.build.core=arduino -arduino_zero_native.build.extra_flags=-D__SAMD21G18A__ {build.usb_flags} -arduino_zero_native.build.ldscript=linker_scripts/gcc/flash_with_bootloader.ld -arduino_zero_native.build.openocdscript=openocd_scripts/arduino_zero.cfg -arduino_zero_native.build.variant=arduino_zero -arduino_zero_native.build.variant_system_lib= -arduino_zero_native.build.vid=0x2341 -arduino_zero_native.build.pid=0x804d -arduino_zero_native.bootloader.tool=openocd -arduino_zero_native.bootloader.file=zero/samd21_sam_ba.bin +adafruit_metro_m0.name=Adafruit Metro M0 (Native USB Port) +adafruit_metro_m0.vid.0=0x239A +adafruit_metro_m0.pid.0=0x8013 +adafruit_metro_m0.vid.1=0x239A +adafruit_metro_m0.pid.1=0x0013 +adafruit_metro_m0.upload.tool=bossac +adafruit_metro_m0.upload.protocol=sam-ba +adafruit_metro_m0.upload.maximum_size=262144 +adafruit_metro_m0.upload.use_1200bps_touch=true +adafruit_metro_m0.upload.wait_for_upload_port=true +adafruit_metro_m0.upload.native_usb=true +adafruit_metro_m0.build.mcu=cortex-m0plus +adafruit_metro_m0.build.f_cpu=48000000L +adafruit_metro_m0.build.usb_product="Metro M0" +adafruit_metro_m0.build.usb_manufacturer="Adafruit" +adafruit_metro_m0.build.board=SAMD_ZERO +adafruit_metro_m0.build.core=arduino +adafruit_metro_m0.build.extra_flags=-D__SAMD21G18A__ {build.usb_flags} +adafruit_metro_m0.build.ldscript=linker_scripts/gcc/flash_with_bootloader.ld +adafruit_metro_m0.build.openocdscript=openocd_scripts/arduino_zero.cfg +adafruit_metro_m0.build.variant=arduino_zero +adafruit_metro_m0.build.variant_system_lib= +adafruit_metro_m0.build.vid=0x239A +adafruit_metro_m0.build.pid=0x8013 +adafruit_metro_m0.bootloader.tool=openocd +adafruit_metro_m0.bootloader.file=metro/samd21_sam_ba.bin diff --git a/bootloaders/feather/Makefile b/bootloaders/feather/Makefile new file mode 100644 index 000000000..dc10c59b9 --- /dev/null +++ b/bootloaders/feather/Makefile @@ -0,0 +1,178 @@ +# 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) + T=$(shell cygpath -u $(LOCALAPPDATA)) + 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 + MODULE_PATH?=$(LOCALAPPDATA)/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 + +# ----------------------------------------------------------------------------- +# 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_HIGH=0x00 -DUSB_PID_LOW=0x0B -DUSB_VID_LOW=0x9A -DUSB_VID_HIGH=0x23 +# Arduino Zero (PID == 0x004D) +# CFLAGS_EXTRA?=-D__SAMD21G18A__ -DUSB_PID_HIGH=0x00 -DUSB_PID_LOW=0x4D -DUSB_VID_LOW=0x41 -DUSB_VID_HIGH=0x23 +# Genuino Zero (PID == 0x024D) +# CFLAGS_EXTRA?=-D__SAMD21G18A__ -DUSB_PID_HIGH=0x02 -DUSB_PID_LOW=0x4D -DUSB_VID_LOW=0x41 -DUSB_VID_HIGH=0x23 +# Arduino MKR1000 (PID == 0x004E) +# CFLAGS_EXTRA?=-D__SAMD21G18A__ -DUSB_PID_HIGH=0x00 -DUSB_PID_LOW=0x4E -DUSB_VID_LOW=0x41 -DUSB_VID_HIGH=0x23 +# Genuino MKR1000 (PID == 0x024E) +# CFLAGS_EXTRA?=-D__SAMD21G18A__ -DUSB_PID_HIGH=0x02 -DUSB_PID_LOW=0x4E -DUSB_VID_LOW=0x41 -DUSB_VID_HIGH=0x23 + +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 +ELF=$(NAME).elf +BIN=$(NAME).bin +HEX=$(NAME).hex + +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: 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 + @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/feather/README.md b/bootloaders/feather/README.md new file mode 100644 index 000000000..44f4e4e02 --- /dev/null +++ b/bootloaders/feather/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/feather/board_definitions.h b/bootloaders/feather/board_definitions.h new file mode 100644 index 000000000..458e1b0a7 --- /dev/null +++ b/bootloaders/feather/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/feather/board_driver_led.c b/bootloaders/feather/board_driver_led.c new file mode 100644 index 000000000..1a2430aff --- /dev/null +++ b/bootloaders/feather/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/feather/board_driver_led.h b/bootloaders/feather/board_driver_led.h new file mode 100644 index 000000000..6f1fd7580 --- /dev/null +++ b/bootloaders/feather/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.SYNCBUSY.bit.ENABLE); + /* Disable the SERCOM UART module */ + sercom->USART.CTRLA.bit.ENABLE = 0; + /* Wait for synchronization */ + while(sercom->USART.SYNCBUSY.bit.SWRST); + /* Perform a software reset */ + sercom->USART.CTRLA.bit.SWRST = 1; + /* Wait for synchronization */ + while(sercom->USART.CTRLA.bit.SWRST); + /* Wait for synchronization */ + while(sercom->USART.SYNCBUSY.bit.SWRST || sercom->USART.SYNCBUSY.bit.ENABLE); + /* Update the UART pad settings, mode and data order settings */ + sercom->USART.CTRLA.reg = pad_conf | SERCOM_USART_CTRLA_MODE(1) | SERCOM_USART_CTRLA_DORD; + /* Wait for synchronization */ + while(sercom->USART.SYNCBUSY.bit.CTRLB); + /* Enable transmit and receive and set data size to 8 bits */ + sercom->USART.CTRLB.reg = SERCOM_USART_CTRLB_RXEN | SERCOM_USART_CTRLB_TXEN | SERCOM_USART_CTRLB_CHSIZE(0); + /* Load the baud value */ + sercom->USART.BAUD.reg = baud_val; + /* Wait for synchronization */ + while(sercom->USART.SYNCBUSY.bit.ENABLE); + /* Enable SERCOM UART */ + sercom->USART.CTRLA.bit.ENABLE = 1; +} + +void uart_disable(Sercom *sercom) +{ + /* Wait for synchronization */ + while(sercom->USART.SYNCBUSY.bit.ENABLE); + /* Disable SERCOM UART */ + sercom->USART.CTRLA.bit.ENABLE = 0; +} + +void uart_write_byte(Sercom *sercom, uint8_t data) +{ + /* Wait for Data Register Empty flag */ + while(!sercom->USART.INTFLAG.bit.DRE); + /* Write the data to DATA register */ + sercom->USART.DATA.reg = (uint16_t)data; +} + +uint8_t uart_read_byte(Sercom *sercom) +{ + /* Wait for Receive Complete flag */ + while(!sercom->USART.INTFLAG.bit.RXC); + /* Check for errors */ + if (sercom->USART.STATUS.bit.PERR || sercom->USART.STATUS.bit.FERR || sercom->USART.STATUS.bit.BUFOVF) + /* Set the error flag */ + uart_drv_error_flag = true; + /* Return the read data */ + return((uint8_t)sercom->USART.DATA.reg); +} + +void uart_write_buffer_polled(Sercom *sercom, uint8_t *ptr, uint16_t length) +{ + /* Do the following for specified length */ + do { + /* Wait for Data Register Empty flag */ + while(!sercom->USART.INTFLAG.bit.DRE); + /* Send data from the buffer */ + sercom->USART.DATA.reg = (uint16_t)*ptr++; + } while (length--); +} + +void uart_read_buffer_polled(Sercom *sercom, uint8_t *ptr, uint16_t length) +{ + /* Do the following for specified length */ + do { + /* Wait for Receive Complete flag */ + while(!sercom->USART.INTFLAG.bit.RXC); + /* Check for errors */ + if (sercom->USART.STATUS.bit.PERR || sercom->USART.STATUS.bit.FERR || sercom->USART.STATUS.bit.BUFOVF) + /* Set the error flag */ + uart_drv_error_flag = true; + /* Store the read data to the buffer */ + *ptr++ = (uint8_t)sercom->USART.DATA.reg; + } while (length--); +} diff --git a/bootloaders/feather/board_driver_serial.h b/bootloaders/feather/board_driver_serial.h new file mode 100644 index 000000000..c752d977d --- /dev/null +++ b/bootloaders/feather/board_driver_serial.h @@ -0,0 +1,90 @@ +/* + 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 +#include + +#define PINMUX_UNUSED 0xFFFFFFFF +#define GCLK_ID_SERCOM0_CORE 0x14 + +/* SERCOM UART available pad settings */ +enum uart_pad_settings { + UART_RX_PAD0_TX_PAD2 = SERCOM_USART_CTRLA_RXPO(0) | SERCOM_USART_CTRLA_TXPO(1), + UART_RX_PAD1_TX_PAD2 = SERCOM_USART_CTRLA_RXPO(1) | SERCOM_USART_CTRLA_TXPO(1), + UART_RX_PAD2_TX_PAD0 = SERCOM_USART_CTRLA_RXPO(2), + UART_RX_PAD3_TX_PAD0 = SERCOM_USART_CTRLA_RXPO(3), + UART_RX_PAD1_TX_PAD0 = SERCOM_USART_CTRLA_RXPO(1), + UART_RX_PAD3_TX_PAD2 = SERCOM_USART_CTRLA_RXPO(3) | SERCOM_USART_CTRLA_TXPO(1), +}; + +/** + * \brief Initializes the UART + * + * \param Pointer to SERCOM instance + * \param Baud value corresponding to the desired baudrate + * \param SERCOM pad settings + */ +void uart_basic_init(Sercom *sercom, uint16_t baud_val, enum uart_pad_settings pad_conf); + +/** + * \brief Disables UART interface + * + * \param Pointer to SERCOM instance + */ +void uart_disable(Sercom *sercom); + +/** + * \brief Sends a single byte through UART interface + * + * \param Pointer to SERCOM instance + * \param Data to send + */ +void uart_write_byte(Sercom *sercom, uint8_t data); + +/** + * \brief Reads a single character from UART interface + * + * \param Pointer to SERCOM instance + * \return Data byte read + */ +uint8_t uart_read_byte(Sercom *sercom); + +/** + * \brief Sends buffer on UART interface + * + * \param Pointer to SERCOM instance + * \param Pointer to data to send + * \param Number of bytes to send + */ +void uart_write_buffer_polled(Sercom *sercom, uint8_t *ptr, uint16_t length); + +/** + * \brief Reads data on UART interface + * + * \param Pointer to SERCOM instance + * \param Pointer to store read data + * \param Number of bytes to read + */ +void uart_read_buffer_polled(Sercom *sercom, uint8_t *ptr, uint16_t length); + +#endif diff --git a/bootloaders/feather/board_driver_usb.c b/bootloaders/feather/board_driver_usb.c new file mode 100644 index 000000000..6534fa338 --- /dev/null +++ b/bootloaders/feather/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/feather/board_driver_usb.h b/bootloaders/feather/board_driver_usb.h new file mode 100644 index 000000000..4e71b8c1a --- /dev/null +++ b/bootloaders/feather/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/feather/board_init.c b/bootloaders/feather/board_init.c new file mode 100644 index 000000000..c08aedaae --- /dev/null +++ b/bootloaders/feather/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/feather/board_startup.c b/bootloaders/feather/board_startup.c new file mode 100644 index 000000000..aaa5a019f --- /dev/null +++ b/bootloaders/feather/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/feather/bootloader_samd21x18.ld b/bootloaders/feather/bootloader_samd21x18.ld new file mode 100644 index 000000000..2a8b056d3 --- /dev/null +++ b/bootloaders/feather/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/feather/main.c b/bootloaders/feather/main.c new file mode 100644 index 000000000..b490596b4 --- /dev/null +++ b/bootloaders/feather/main.c @@ -0,0 +1,247 @@ +/* + 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_monitor.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" + +extern uint32_t __sketch_vectors_ptr; // Exported value from linker script +extern void board_init(void); + +#if (defined DEBUG) && (DEBUG == 1) +volatile uint32_t* pulSketch_Start_Address; +#endif + +static volatile bool main_b_cdc_enable = false; + +/** + * \brief Check the application startup condition + * + */ +static void check_start_application(void) +{ + 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. + * 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 + +#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; + } +#endif +*/ + + LED_on(); + + /* Rebase the Stack Pointer */ + __set_MSP( (uint32_t)(__sketch_vectors_ptr) ); + + /* 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"(*pulSketch_Start_Address)); +} + +#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) +#else +# define DEBUG_PIN_HIGH do{}while(0) +# 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; +#endif + DEBUG_PIN_HIGH; + + /* Jump in application if condition is satisfied */ + check_start_application(); + + /* 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 */ + serial_open(); +#endif + +#if SAM_BA_INTERFACE == SAM_BA_USBCDC_ONLY || SAM_BA_INTERFACE == SAM_BA_BOTH_INTERFACES + pCdc = usb_init(); +#endif + + DEBUG_PIN_LOW; + + LED_on(); + + /* Wait for a complete enum on usb or a '#' char on serial line */ + while (1) + { + pulse_led(3); // while we're waiting, blink the D13 + +#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 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 && serial_sharp_received()) + { + sam_ba_monitor_init(SAM_BA_INTERFACE_USART); + /* SAM-BA on Serial loop */ + while(1) + { + sam_ba_monitor_run(); + } + } +#endif + } +} + + +// We'll have the D13 LED slowly pulse on and off with bitbang PWM +// for a nice 'hey we're in bootload mode' indication! -ada +static uint16_t pulse_tick=0; +#define BOOT_PULSE_MAX 1000 +static int8_t pulse_dir=1; +static int16_t pulse_pwm; +void pulse_led(int8_t speed) { + // blink D13 + pulse_tick++; + if (pulse_tick==BOOT_PULSE_MAX) { + pulse_tick = 0; + pulse_pwm += pulse_dir * speed; + if (pulse_pwm > 255) { + pulse_pwm = 255; + pulse_dir = -1; + } + if (pulse_pwm < 0) { + pulse_pwm = 0; + pulse_dir = +1; + } + LED_on(); + } + if (pulse_tick==pulse_pwm) + LED_off(); +} diff --git a/bootloaders/feather/sam_ba_cdc.c b/bootloaders/feather/sam_ba_cdc.c new file mode 100644 index 000000000..fc5efe348 --- /dev/null +++ b/bootloaders/feather/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/feather/sam_ba_cdc.h b/bootloaders/feather/sam_ba_cdc.h new file mode 100644 index 000000000..49b7643cf --- /dev/null +++ b/bootloaders/feather/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/feather/sam_ba_monitor.c b/bootloaders/feather/sam_ba_monitor.c new file mode 100644 index 000000000..ddf7b9773 --- /dev/null +++ b/bootloaders/feather/sam_ba_monitor.c @@ -0,0 +1,474 @@ +/* + 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 "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]"; + +/* 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); +} 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 = +{ + .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 = +{ + .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 */ +t_monitor_if * ptr_monitor_if; + +/* b_terminal_mode mode (ascii) or hex mode */ +volatile bool b_terminal_mode = false; +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; + } +#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; + } +#endif +} + +/** + * \brief This function allows data rx by USART + * + * \param *data Data pointer + * \param length Length of the data + */ +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; +} + +volatile uint32_t sp; +void call_applet(uint32_t address) +{ + uint32_t app_start_address; + + __disable_irq(); + + sp = __get_MSP(); + + /* Rebase the Stack Pointer */ + __set_MSP(*(uint32_t *) address); + + /* 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)); +} + +uint32_t current_number; +uint32_t i, length; +uint8_t command, *ptr_data, *ptr, data[SIZEBUFMAX]; +uint8_t j; +uint32_t u32tmp; + +uint32_t PAGE_SIZE, PAGES, MAX_FLASH; + +// Prints a 32-bit integer in hex. +static 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) +{ + pulse_led(3); + + 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; + } + } + } +} + +/** + * \brief This function starts the SAM-BA monitor. + */ +void sam_ba_monitor_run(void) +{ + 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/feather/sam_ba_monitor.h b/bootloaders/feather/sam_ba_monitor.h new file mode 100644 index 000000000..e72582bcf --- /dev/null +++ b/bootloaders/feather/sam_ba_monitor.h @@ -0,0 +1,66 @@ +/* + 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 "2.0" + +/* Enable the interfaces to save code size */ +#define SAM_BA_BOTH_INTERFACES 0 +#define SAM_BA_UART_ONLY 1 +#define SAM_BA_USBCDC_ONLY 2 + +#ifndef SAM_BA_INTERFACE +#define SAM_BA_INTERFACE SAM_BA_BOTH_INTERFACES +#endif + +/* 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 + +/** + * \brief Initialize the monitor + * + */ +void sam_ba_monitor_init(uint8_t com_interface); + +/** + * \brief Main function of the SAM-BA Monitor + * + */ +void sam_ba_monitor_run(void); + +/** + * \brief + * + */ +void sam_ba_putdata_term(uint8_t* data, uint32_t length); + +/** + * \brief + * + */ +void call_applet(uint32_t address); + +#endif // _MONITOR_SAM_BA_H_ diff --git a/bootloaders/feather/sam_ba_serial.c b/bootloaders/feather/sam_ba_serial.c new file mode 100644 index 000000000..09607ecf6 --- /dev/null +++ b/bootloaders/feather/sam_ba_serial.c @@ -0,0 +1,534 @@ +/* + 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; + +/* Variable to let the main task select the appropriate communication interface */ +volatile uint8_t b_sharp_received; + +/* RX and TX Buffers + rw pointers for each buffer */ +volatile uint8_t buffer_rx_usart[USART_BUFFER_SIZE]; + +volatile uint8_t idx_rx_read; +volatile uint8_t idx_rx_write; + +volatile uint8_t buffer_tx_usart[USART_BUFFER_SIZE]; + +volatile uint8_t idx_tx_read; +volatile uint8_t idx_tx_write; + +/* Test for timeout in AT91F_GetChar */ +uint8_t error_timeout; +uint16_t size_of_data; +uint8_t mode_of_transfer; + +#define BOOT_USART_PAD(n) BOOT_USART_PAD##n + +/** + * \brief Open the given USART + */ +void serial_open(void) +{ + uint32_t port; + uint32_t pin; + + /* Configure the port pins for SERCOM_USART */ + 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); + 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) + { + /* 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; + 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_PAD1 & 0xFF) << (4 * (pin & 0x01u)); + } + + 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; + 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_PAD2 & 0xFF) << (4 * (pin & 0x01u)); + } + + 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; + 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_PAD3 & 0xFF) << (4 * (pin & 0x01u)); + } + + /* Enable clock for BOOT_USART_MODULE */ + PM->APBCMASK.reg |= BOOT_USART_BUS_CLOCK_INDEX ; + + /* Set GCLK_GEN0 as source for GCLK_ID_SERCOMx_CORE */ + 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 48MHz -> BAUD value-63018 */ + uart_basic_init(BOOT_USART_MODULE, 63018, BOOT_USART_PAD_SETTINGS); + + //Initialize flag + b_sharp_received = false; + idx_rx_read = 0; + idx_rx_write = 0; + idx_tx_read = 0; + idx_tx_write = 0; + + error_timeout = 0; +} + +/** + * \brief Close communication line + */ +void serial_close(void) +{ + uart_disable(BOOT_USART_MODULE); +} + +/** + * \brief Puts a byte on usart line + * The type int is used to support printf redirection from compiler LIB. + * + * \param value Value to put + * + * \return \c 1 if function was successfully done, otherwise \c 0. + */ +int serial_putc(int value) +{ + uart_write_byte(BOOT_USART_MODULE, (uint8_t)value); + return 1; +} + +int serial_getc(void) +{ + uint16_t retval; + //Wait until input buffer is filled + 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 serial_sharp_received(void) +{ + if (serial_is_rx_ready()) + { + if (serial_getc() == SHARP_CHARACTER) + return (true); + } + return (false); +} + +bool serial_is_rx_ready(void) +{ + return (BOOT_USART_MODULE->USART.INTFLAG.reg & SERCOM_USART_INTFLAG_RXC); +} + +int serial_readc(void) +{ + int retval; + retval = buffer_rx_usart[idx_rx_read]; + idx_rx_read = (idx_rx_read + 1) & (USART_BUFFER_SIZE - 1); + return (retval); +} + +//Send given data (polling) +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++) + { + serial_putc(*ptrdata); + ptrdata++; + } + return (i); +} + +//Get data from comm. device +uint32_t serial_getdata(void* data, uint32_t length) +{ + uint8_t* ptrdata; + ptrdata = (uint8_t*) data; + *ptrdata = serial_getc(); + return (1); +} + +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, + 0x9339,0x8318,0xb37b,0xa35a,0xd3bd,0xc39c,0xf3ff,0xe3de, + 0x2462,0x3443,0x0420,0x1401,0x64e6,0x74c7,0x44a4,0x5485, + 0xa56a,0xb54b,0x8528,0x9509,0xe5ee,0xf5cf,0xc5ac,0xd58d, + 0x3653,0x2672,0x1611,0x0630,0x76d7,0x66f6,0x5695,0x46b4, + 0xb75b,0xa77a,0x9719,0x8738,0xf7df,0xe7fe,0xd79d,0xc7bc, + 0x48c4,0x58e5,0x6886,0x78a7,0x0840,0x1861,0x2802,0x3823, + 0xc9cc,0xd9ed,0xe98e,0xf9af,0x8948,0x9969,0xa90a,0xb92b, + 0x5af5,0x4ad4,0x7ab7,0x6a96,0x1a71,0x0a50,0x3a33,0x2a12, + 0xdbfd,0xcbdc,0xfbbf,0xeb9e,0x9b79,0x8b58,0xbb3b,0xab1a, + 0x6ca6,0x7c87,0x4ce4,0x5cc5,0x2c22,0x3c03,0x0c60,0x1c41, + 0xedae,0xfd8f,0xcdec,0xddcd,0xad2a,0xbd0b,0x8d68,0x9d49, + 0x7e97,0x6eb6,0x5ed5,0x4ef4,0x3e13,0x2e32,0x1e51,0x0e70, + 0xff9f,0xefbe,0xdfdd,0xcffc,0xbf1b,0xaf3a,0x9f59,0x8f78, + 0x9188,0x81a9,0xb1ca,0xa1eb,0xd10c,0xc12d,0xf14e,0xe16f, + 0x1080,0x00a1,0x30c2,0x20e3,0x5004,0x4025,0x7046,0x6067, + 0x83b9,0x9398,0xa3fb,0xb3da,0xc33d,0xd31c,0xe37f,0xf35e, + 0x02b1,0x1290,0x22f3,0x32d2,0x4235,0x5214,0x6277,0x7256, + 0xb5ea,0xa5cb,0x95a8,0x8589,0xf56e,0xe54f,0xd52c,0xc50d, + 0x34e2,0x24c3,0x14a0,0x0481,0x7466,0x6447,0x5424,0x4405, + 0xa7db,0xb7fa,0x8799,0x97b8,0xe75f,0xf77e,0xc71d,0xd73c, + 0x26d3,0x36f2,0x0691,0x16b0,0x6657,0x7676,0x4615,0x5634, + 0xd94c,0xc96d,0xf90e,0xe92f,0x99c8,0x89e9,0xb98a,0xa9ab, + 0x5844,0x4865,0x7806,0x6827,0x18c0,0x08e1,0x3882,0x28a3, + 0xcb7d,0xdb5c,0xeb3f,0xfb1e,0x8bf9,0x9bd8,0xabbb,0xbb9a, + 0x4a75,0x5a54,0x6a37,0x7a16,0x0af1,0x1ad0,0x2ab3,0x3a92, + 0xfd2e,0xed0f,0xdd6c,0xcd4d,0xbdaa,0xad8b,0x9de8,0x8dc9, + 0x7c26,0x6c07,0x5c64,0x4c45,0x3ca2,0x2c83,0x1ce0,0x0cc1, + 0xef1f,0xff3e,0xcf5d,0xdf7c,0xaf9b,0xbfba,0x8fd9,0x9ff8, + 0x6e17,0x7e36,0x4e55,0x5e74,0x2e93,0x3eb2,0x0ed1,0x1ef0 +}; + +//*---------------------------------------------------------------------------- +//* \brief Compute the CRC +//*---------------------------------------------------------------------------- +unsigned short serial_add_crc(char ptr, unsigned short crc) +{ + return (crc << 8) ^ crc16Table[((crc >> 8) ^ ptr) & 0xff]; +} + +//*---------------------------------------------------------------------------- +//* \brief +//*---------------------------------------------------------------------------- +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 = serial_getc(); + if (error_timeout) + return 1; + crc = serial_add_crc(c, crc); + //crc = (crc << 8) ^ xcrc16tab[(crc>>8) ^ c]; + if (size_of_data || mode_of_transfer) + { + *ptr_data++ = c; + if (length == PKTLEN_128) + size_of_data--; + } + } + + return crc; +} + +//*---------------------------------------------------------------------------- +//* \brief Used by Xup to send packets. +//*---------------------------------------------------------------------------- +static int putPacket(uint8_t *tmppkt, uint8_t sno) +{ + uint32_t i; + uint16_t chksm; + uint8_t data; + + chksm = 0; + + serial_putc(SOH); + + serial_putc(sno); + serial_putc((uint8_t) ~(sno)); + + for (i = 0; i < PKTLEN_128; i++) + { + if (size_of_data || mode_of_transfer) + { + data = *tmppkt++; + size_of_data--; + } + else + data = 0x00; + + serial_putc(data); + + //chksm = (chksm<<8) ^ xcrc16tab[(chksm>>8)^data]; + chksm = serial_add_crc(data, chksm); + } + + /* An "endian independent way to extract the CRC bytes. */ + serial_putc((uint8_t) (chksm >> 8)); + serial_putc((uint8_t) chksm); + + return (serial_getc()); /* Wait for ack */ +} + +//*---------------------------------------------------------------------------- +//* \brief Called when a transfer from target to host is being made (considered +//* an upload). +//*---------------------------------------------------------------------------- +//Send given data (polling) using xmodem (if necessary) +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 + { + size_of_data = length; + mode_of_transfer = 0; + } + + if (length & (PKTLEN_128 - 1)) + { + length += PKTLEN_128; + length &= ~(PKTLEN_128 - 1); + } + + /* Startup synchronization... */ + /* Wait to receive a NAK or 'C' from receiver. */ + done = 0; + while (!done) { + c = (uint8_t) serial_getc(); + if (error_timeout) + { // Test for timeout in serial_getc + error_timeout = 0; + c = (uint8_t) serial_getc(); + if (error_timeout) + { + error_timeout = 0; + return (0); + } + } + switch (c) + { + case NAK: + done = 1; + // ("CSM"); + break; + case 'C': + done = 1; + // ("CRC"); + break; + case 'q': /* ELS addition, not part of XMODEM spec. */ + return (0); + default: + break; + } + } + + done = 0; + sno = 1; + while (!done) + { + c = (uint8_t) putPacket((uint8_t *) ptr_data, sno); + 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"); + break; + + case NAK: + // ("N"); + break; + + case CAN: + case EOT: + default: + done = 0; + break; + } + + if (!length) + { + serial_putc(EOT); + serial_getc(); /* Flush the ACK */ + break; + } + // ("!"); + } + + mode_of_transfer = 0; + // ("Xup_done."); + return (1); + // 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); +} + +//*---------------------------------------------------------------------------- +//* \brief Called when a transfer from host to target is being made (considered +//* an download). +//*---------------------------------------------------------------------------- +//Get data from comm. device using xmodem (if necessary) +uint32_t serial_getdata_xmd(void* data, uint32_t length) +{ + uint32_t timeout; + char c; + uint8_t * ptr_data = (uint8_t *) data; + uint32_t b_run, nbr_of_timeout = 100; + uint8_t sno = 0x01; + uint32_t data_transfered = 0; + + //Copied from legacy source code ... might need some tweaking + uint32_t loops_per_second = CPU_FREQUENCY/60; + + error_timeout = 0; + + if (length == 0) + mode_of_transfer = 1; + else + { + size_of_data = length; + mode_of_transfer = 0; + } + + /* Startup synchronization... */ + /* Continuously send NAK or 'C' until sender responds. */ + // ("Xdown"); + while (1) + { + serial_putc('C'); + timeout = loops_per_second; + while (!(serial_is_rx_ready()) && timeout) + timeout--; + if (timeout) + break; + + if (!(--nbr_of_timeout)) + return (0); +// return -1; + } + + b_run = true; + // ("Got response"); + 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 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"); + serial_putc(ACK); + b_run = false; + break; + case CAN: // ("C"); + case ESC: /* "X" User-invoked abort */ + default: + b_run = false; + break; + } + // ("!"); + } + mode_of_transfer = 0; + return (true); +// return(b_run); +} + diff --git a/bootloaders/feather/sam_ba_serial.h b/bootloaders/feather/sam_ba_serial.h new file mode 100644 index 000000000..cb69f459e --- /dev/null +++ b/bootloaders/feather/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/feather/sam_ba_usb.c b/bootloaders/feather/sam_ba_usb.c new file mode 100644 index 000000000..687e065e9 --- /dev/null +++ b/bootloaders/feather/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 + USB_VID_LOW, // idVendor L + USB_VID_HIGH, // 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/feather/sam_ba_usb.h b/bootloaders/feather/sam_ba_usb.h new file mode 100644 index 000000000..42c0d608f --- /dev/null +++ b/bootloaders/feather/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/feather/samd21_sam_ba.atsln b/bootloaders/feather/samd21_sam_ba.atsln new file mode 100644 index 000000000..cf1043181 --- /dev/null +++ b/bootloaders/feather/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/feather/samd21_sam_ba.bin b/bootloaders/feather/samd21_sam_ba.bin new file mode 100644 index 000000000..331adde78 Binary files /dev/null and b/bootloaders/feather/samd21_sam_ba.bin differ diff --git a/bootloaders/feather/samd21_sam_ba.cproj b/bootloaders/feather/samd21_sam_ba.cproj new file mode 100644 index 000000000..70ee7e93a --- /dev/null +++ b/bootloaders/feather/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/feather/samd21_sam_ba.elf b/bootloaders/feather/samd21_sam_ba.elf new file mode 100644 index 000000000..edee94811 Binary files /dev/null and b/bootloaders/feather/samd21_sam_ba.elf differ diff --git a/bootloaders/feather/samd21_sam_ba.hex b/bootloaders/feather/samd21_sam_ba.hex new file mode 100644 index 000000000..5ae649d9d --- /dev/null +++ b/bootloaders/feather/samd21_sam_ba.hex @@ -0,0 +1,386 @@ +:10000000FC7F0020E9050000D5050000D9050000AF +:1000100000000000000000000000000000000000E0 +:10002000000000000000000000000000DD050000EE +:100030000000000000000000E1050000E5050000F0 +:1000400010B5064C2378002B07D1054B002B02D0AE +:10005000044800E000BF0123237010BD5C000020B5 +:10006000000000009817000008B5084B002B03D0D3 +:100070000748084900E000BF07480368002B03D089 +:10008000064B002B00D0984708BDC046000000007A +:1000900098170000600000205800002000000000B9 +:1000A00010B5C3699C07FCD403680224A343036012 +:1000B000C46901231C42FBD1046823430360036825 +:1000C000DC07FCD4C46901231C42FBD1C469DC40B9 +:1000D0001C42F7D1084B1A430260C3695A07FCD48B +:1000E000C0239B0243608181C3699C07FCD40368E1 +:1000F00002221343036010BD04000040037EDA07B0 +:10010000FCD5018570470000027E01235107FBD515 +:10011000428B1A4207D1428BDA401A4203D1428BFA +:1001200092081A4202D0034B01221A70008DC0B20D +:100130007047C0467800002070B50368041C988B97 +:100140001A1C0821FF32084228D0988B174D014312 +:10015000802099839872112353704021144B917120 +:1001600050715E68C0202E40800506435E605E6967 +:100170003540284358610F4818600F4818615D6882 +:100180000E4828408025AD02284358605868800BEF +:100190008003586000235171237105E0137ADA0659 +:1001A00002D5201C00F0EEFA207970BDFFFFFF8F12 +:1001B000940100209400002014010020FF3F00F073 +:1001C000002303714371044B016083600B780222AA +:1001D00013430B707047C0463901000038B5364BE9 +:1001E0002021DA6901200A43DA61344B06241A78A7 +:1001F00002431A70324B0F22197891431970197803 +:10020000214319702F490C782043087019780A404F +:100210001A701A7860210A431A702B4B2B4A5A80A5 +:100220005A7852B2002AFBDB294B01211A780A4383 +:100230001A709A78D107FCD426480268510B1F2205 +:100240001140914200D1052111408C011D8D2249A0 +:100250002940214319850468A10C0A401F2A00D1B6 +:100260001D221C8D1F210A408C4322431A850268DF +:100270000721D20D0A408A4200D103220A40188D7C +:100280001103164A02400A431A8519787F220A4050 +:100290001A701A78042112480A431A7058621A898F +:1002A0000C218A431A811A8901218A431A8100216B +:1002B000802201F006F938BD000400405844004196 +:1002C0003C44004159440041000C004006400000FD +:1002D00000500041246080003FF8FFFFFF8FFFFFC8 +:1002E00094010020F7B5141C234A5F0101971D1CDF +:1002F000D319061C5869271C4000400F03301033E7 +:10030000C74006D00F1C8022596812060A435A6063 +:1003100009E02F1C7B1E9F41184BBF01FF18381CA2 +:10032000221C01F0C5F801991348083542181761DD +:10033000131C5269A104920B890C92030A435A615F +:1003400059690F4A02200A405A616B01F318D979A2 +:10035000032211400143D8799043021C0A43DA7109 +:100360005979802252420A435A716B01F318DB79A2 +:100370009A07FAD5201CFEBD94010020140100202C +:10038000FF3F00F0F8B51E4E041C3378151C002BFF +:1003900012D11C4B1C4A1A645A6C920B92035A6479 +:1003A000586C1A4A02405A64A2235B00E25C402067 +:1003B0000243E254012333704827FF37E25D0123F3 +:1003C00013401AD00F4B5A6C9204920CAA4202D2DC +:1003D0005D6CAD04AD0C081C2A1C0B4901F068F8DB +:1003E000E25D03231A4001210A43E15D99430B1C9E +:1003F0001343E3550023337000E01D1C281CF8BD97 +:100400007900002094010020D4000020FF3F00F07C +:10041000FF30827930239A43131C2022002900D117 +:1004200010221343837170470C4BFF305A6902212D +:10043000920B92035A61027A03231A400A43017A0B +:1004400099430B1C13430372827980235B4213434D +:100450008371037A9A07FCD57047C0469401002047 +:1004600080235B421943C9B28172704770B5A023E3 +:1004700003225B00C254134B134A5C6CC02114402E +:1004800089050C4346255C64FF35402444550F4DD7 +:1004900030261D6490256D0046555D6B154029433F +:1004A000922559636D0080214155094D1D63B0258A +:1004B0006D0044555C6F22405A67B2235B00C15403 +:1004C00070BDC04694010020FFFFFF8FD4000020C4 +:1004D0005401002030B5364A1E2351680820994344 +:1004E00002231943516033498A6902438A613248C1 +:1004F000324A9082908A03439382D3689807FCD54E +:100500002F4B012018701878C40704D52C48407868 +:1005100040B20028F7DB01209860587840B20028EC +:10052000FBDB284C26484460587840B20028FBDBAF +:1005300082242348E4014480587840B20028FBDB41 +:10054000908C8024A0439084D068C506FCD51E4CB6 +:100550001A48C462D4681948E506FBD5848C1B4D43 +:100560002C438484D4681548E506FBD5848C022589 +:100570002C438484D0680406FCD51048C068450626 +:10058000F8D5D068C406FCD500229A605A7852B2D9 +:10059000002AFBDB0E480A4A50605A7852B2002A01 +:1005A000FBDB00230B724B728B72CB7230BDC046EB +:1005B00000400041000400400C060000000800401C +:1005C000000C004001050100B805FF7D040A000091 +:1005D000000703000EBEFEE70DBEFEE705BEFEE708 +:1005E00002BEFEE701BEFEE70E4A0F4838B5824262 +:1005F00004D10E4A0E4B93420ED10AE00D4C9442A8 +:10060000F7D00023D1188842F3D9E55804330D60A0 +:10061000F8E700F04DF804E09342FAD2002102C35B +:10062000FAE7FEE7000000205C000020A0030020A5 +:100630005C0000209C170000194A10B51188FA24AC +:10064000013189B2174BA400A14201D011801CE0F6 +:1006500000211180144900240C5760431C880019A4 +:1006600080B204B2FF2C01DC188002E0FF20188069 +:1006700008700024185F002803DA00201880012089 +:1006800008708020094980028861128800215B5E21 +:100690009A4203D18022054B92025A6110BDC04696 +:1006A0007A0000207C00002000000020004400416F +:1006B00038B580222B4B92029A605A612A4A1C1C40 +:1006C000117801221140294B002200290AD1186813 +:1006D000274A904201D1196018E01A60254A013A70 +:1006E000002AFCD11A60244B1A68191C501C0DD02A +:1006F000D8B200280AD180208002A06182F3088845 +:10070000FF2293431D4A93604B681847FFF7E2FEB0 +:1007100062B600F0FBFC00F0CFF980239B02051CC1 +:10072000A3610320FFF788FFAB68281C9847144B90 +:10073000002801D001221A701A78002A05D0002062 +:1007400000F036FA00F092FAFCE71B78002BE8D1B3 +:1007500000F050FD0028E4D0012000F029FA00F05C +:1007600085FAFCE70044004138040040FC7F00208B +:100770003581730748E801000020000000ED00E02B +:100780007E000020F8B50468051C201CFF30037AA9 +:10079000B64A10210B430372B54F1378B5493B702D +:1007A0005378B54E0B7093783380D1783388090233 +:1007B0000B4333801179B14B198051791F8809029D +:1007C0000F431F809779AE490F80D2790F881202AC +:1007D0003A430A8040224271A648A54F02783878F1 +:1007E000A84F12020243181CBA4200D199E01EDC45 +:1007F000802149008A4200D158E107DC812A6AD071 +:10080000822A6ED0802A00D050E164E081235B0010 +:100810009A4200D1AFE000DA23E1C0239B009A4264 +:1008200000D143E1984B9A4200D11AE13EE1902376 +:100830001B019A4242D015DCD023DB009A4222D021 +:1008400088231B019A4242D0A023DB009A4200D0A9 +:100850002CE1201CFFF7E8FD3188286889B2FFF7FA +:10086000FFFD27E1894B9A4200D1FAE000DC1DE14F +:10087000874B9A4200D1E8E0864B9A4200D015E1BE +:1008800033886B71EDE033881B0A012B08D10B888C +:1008900012222868934201D80A8892B27E49DCE08D +:1008A00033881B0A022B00D000E10B884322286802 +:1008B000934201D80A8892B27849CEE03388201C4E +:1008C0002B71FFF7B1FD201CFFF7D0FDF2E0291CD2 +:1008D00001C90122C1E0724900230B80286802226D +:1008E000BCE06F4900220A801888502210406D4AEF +:1008F00010701E880F20304018801888032800D9F7 +:10090000D4E012781B8808335B01E418A379002A2D +:1009100001D09B0600E0DB06DB0F0B80286802227B +:100920009BE019887F2291435E4AC9B211701888F2 +:100930000F21014019803188002900D0B6E01988C4 +:10094000002900D1B2E01988032900D9AEE012785D +:100950001B8808335B01E318002A05D05A7930213F +:100960008A4320210A4304E05A7930218A43102027 +:1009700002435A7175E002887F239A43494BD2B2F1 +:100980001A7001880F220A4002803288002A00D0A3 +:100990008CE00288002A00D188E00288032A00D96E +:1009A00084E01B78002B27D0038808335B01E31811 +:1009B0009B79990655D50388302108335B01E318EC +:1009C0001A798A4320210A431A71038808335B018C +:1009D000E318DB795A0644D50388602108335B01AC +:1009E000E318DA798A4340210A43DA710388022244 +:1009F00008335B01E31826E0038808335B01E31842 +:100A00009B79DF062DD50388302108335B01E3187D +:100A10001A798A4310210A431A71038808335B014B +:100A2000E318DB7999061CD50388602108335B0144 +:100A3000E318DA798A4320210A43DA710388012214 +:100A400008335B01E3181A710BE00B880822286851 +:100A5000934201D80A8892B213490023FFF742FC5F +:100A600028E0201CFFF7E0FC24E0C04694000020B2 +:100A7000890000207F0000208000002084000020EA +:100A80008600002002030000010300002120000076 +:100A9000A121000021220000EC140000040000202D +:100AA000820000208800002048000020201C012136 +:100AB000FFF7AEFCF8BDC04610B5054B054C2360F2 +:100AC000FFF78CFB201C2168FFF77AFB201C10BD70 +:100AD000005000411402002007B5054B012201908F +:100AE00001A91868131CFFF7FDFB01200EBDC046CD +:100AF0001402002013B5054B6C4607341868211CFE +:100B00000122FFF73FFC207816BDC04614020020EA +:100B100010B5074C201CFFF70FFB031C002083427D +:100B200005D022684823FF33D05C0123184010BD54 +:100B30001402002010B5054A0C1C031C191C106877 +:100B40000123221CFFF7CEFB201C10BD1402002045 +:100B500070B5084C061C201C0D1CFFF7EDFA002395 +:100B6000984205D02068311C2A1CFFF70BFC031C9F +:100B7000181C70BD14020020F8B50C4C051C201C7C +:100B80000E1CFFF7D9FA0023271C341C98420AD008 +:100B9000002C07D0291C221C3868FFF7F3FB241A0D +:100BA0002D18F5E7331C181CF8BDC04614020020B0 +:100BB000012805D1054B064A1A60064B187004E05F +:100BC000002802D1044A014B1A60704784020020B9 +:100BD00020150000910000206C15000030B51A4B64 +:100BE00085B01B78002B29D0042901D1026804E0CC +:100BF000022901D1028800E00278490004A84318C4 +:100C00000B3B5C1AA3420BD00F201040092802D8DE +:100C10003025284300E0373018701209013BF1E716 +:100C200001A830230370782343700A2243189A7076 +:100C30000D22DA70054B04311B6801E0034B1B6881 +:100C4000DB68984705B030BD90000020840200208A +:100C500072B6EFF30883044A1360036883F30888CD +:100C6000436818477047C04688020020F0B58FB02F +:100C700006A9CE4A0B1C31CA31C351CA51C360CA3E +:100C800060C3CB4CCB48A3687A255B035B0F9B000A +:100C90005B58C9490360A26892B253430A60C749CE +:100CA000C74A0B6000231360C64B1D700320FFF77B +:100CB000C3FCC54BC54D1B68281C1B6940219847C8 +:100CC000C34B00221860C34B1D60C34BC24DC04FC5 +:100CD0001A60286839688842E8D2BE4B1B681A78C7 +:100CE000FF2A00D1F6E1232A00D0CDE1BB4E3378B4 +:100CF000002B05D0B44BBA481B680221DB6898472B +:100D0000B04B1B78532B38D13B682A6893421ED9CD +:100D1000B04801322A609A1AB24B01681B6801314F +:100D20000160B14E9A4201D2326000E03360A448C3 +:100D300032680068029000F0BBFB336829685A18DB +:100D40002A60A44A1668F1181160A84A13702B682B +:100D5000013B2B609F4B1A68013A1A60A34BA14AD2 +:100D60001B7811688B4206D2974A95481268006832 +:100D7000C91A92699047C04675E1522B07D1904A33 +:100D8000914B10681B68974A5B6911686AE14F2BA9 +:100D900005D18B4B934A1B6812681A7063E1482B8C +:100DA00005D1874B8F4A1B6812681A805BE1572B6D +:100DB00005D1834B8B4A1B6812681A6053E16F2B75 +:100DC00003D17F4B0121186807E0682B08D17C4BC9 +:100DD00084481B6802211B880360FFF7FFFE42E185 +:100DE000772B06D1764B7F481B6804211B68036074 +:100DF000F3E7472B13D17B4B1868FFF729FF7C4B98 +:100E00001B6883F3088862B67A4B1B78002B00D1ED +:100E100029E16D4B06201B681B68984723E1542B82 +:100E200004D101233370684B1B685CE04E2B0BD15F +:100E30003378002B05D1644B69481B680221DB68BD +:100E40009847002333700EE1562B50D15E4D01219F +:100E50002B686948DB6898472B680321DB68674883 +:100E60009847674E2B68301CDB68012198472B6838 +:100E70000D21DB68634898472B68301CDB68012133 +:100E80009847544F604B544E3B60002333603A1CEC +:100E9000311C1368581C10601B780393002B03D07F +:100EA0000B6801330B60F4E72B683168DB68564848 +:100EB00098472B685248DB680121984703983060B7 +:100EC00052483860434A1368591C11601A78424BE3 +:100ED000002A03D01A6801321A60F3E72A681968F9 +:100EE000D36898472B68DB683D480221BAE03D4A49 +:100EF000582B15D12F4E314D366813682A68B10032 +:100F0000934208D25808E06141482080207DC507FF +:100F1000FCD55B18F4E72C4B3E481B68DB68A0E06F +:100F2000592B33D11268264B3B49002A02D11B684A +:100F30000B6026E00868196863688025AB43920857 +:100F40006360002A1DD0354B2380237DDE07FCD54E +:100F50000023184D2D680095AD08AB4202D3304DEB +:100F6000258006E09342FAD09D00465901334E5148 +:100F7000EFE7257DEE07FCD59D0049194019D21AEF +:100F8000DFE7114B27481B68DB686AE05A2B6AD100 +:100F90000B4B17681D680026EF19BD4244D0287816 +:100FA000311C00F049F90135061CF6E70015000078 +:100FB000004000413C0200203402002030020020AA +:100FC000800200202C020020840200204002002029 +:100FD0002402002028020020380200209000002077 +:100FE000601500008C0200209002002020020020EA +:100FF00088020020910000203C15000065150000CB +:101000003E15000088150000401500004C1500003A +:1010100002A5FFFF551500008C00002044A5FFFF2E +:1010200004A5FFFF591500002E4D2F482B68012104 +:10103000DB68984707230F223240111C36093031F4 +:10104000092A00DD07311020C0186A468154013B8F +:10105000F1D22B6804A8DB68082198472B68234845 +:10106000DB6803219847224D7A232B70214B002205 +:101070001A60214B1B7893422CD01A4B01211B681C +:101080001E48DB68984725E0111C3039C8B2194B5F +:10109000092804D81E683201114319601AE0111C96 +:1010A0004139052903D81868373A010106E0111CB7 +:1010B0006139052904D81D68573A29010A4308E017 +:1010C0002C2A03D10E4A1E68166001E008490A70F6 +:1010D00000221A600B4B1A6801321A600A4B1A6818 +:1010E0000132F3E5840200205D1500005F15000069 +:1010F0002C0200208C0200209000002063150000CC +:1011000080020020380200202802002010B51C4B6D +:1011100001201A78022402431A701A4B0F22197800 +:101120009143197019782143197017490C7820439D +:10113000087019780A401A701A7820210A431A7028 +:10114000124B04211A6A0A431A62114B114A5A803F +:101150005A7852B2002AFBDBC4220F480F4992038F +:10116000FEF79EFF0E4A002313700E4A13700E4ABC +:1011700013700E4A13700E4A13700E4A137010BD8E +:101180004A440041354400414B44004100040040C2 +:10119000000C004014400000000800422AF6000045 +:1011A000940200201B0300209502002098020020DA +:1011B0001C0300201903002008B5C1B20248FEF745 +:1011C0009DFF012008BDC04600080042024B187E6A +:1011D0004007C00F7047C0460008004208B5FFF73F +:1011E000F5FF0028FBD00248FEF78EFF08BDC04681 +:1011F0000008004208B5FFF7E9FF0023984205D038 +:10120000FFF7ECFF031C233B5A425341181C08BD57 +:1012100070B5041C0D1C4618B44204D02078FFF7AA +:10122000CBFF0134F8E7281C70BD10B5041CFFF794 +:10123000D5FF2070012010BD0B0A5840034B400021 +:10124000C05A0902484080B27047C0469615000057 +:10125000F7B50024051C0F1C261CBC4220D0FFF74C +:10126000BDFF114BC0B21B780190002B1AD1311C6D +:10127000FFF7E2FF0D4B061C1A88002A04D10C4A26 +:1012800011782A1C002907D001996A1C2970802F27 +:1012900002D11988013919800134A4B2151CDCE788 +:1012A000301C00E00120FEBD190300209602002042 +:1012B0001A030020F0B53E4E85B0002203900C1CAE +:1012C00032703C4B914201D1012201E03A490C803D +:1012D0001A707F231C4201D080349C43FFF77EFFAD +:1012E0003378C0B2002B07D000253570FFF776FFAA +:1012F0003378C0B2AB4236D1432803D0712853D0E3 +:101300001528EBD1012300930120FFF755FF00982A +:10131000FFF752FF00998025C843C0B2FFF74CFF8A +:10132000039B00270293244A1388002B1DD12149D7 +:1013300001930978002918D10198FFF73DFF391C66 +:101340000198FFF779FF013D071C002DEBD1000A42 +:10135000C0B2FFF731FFF8B2FFF72EFFFFF73EFFF5 +:101360003378002B0AD035701FE00299013B0978D1 +:101370001380029B019101330293DDE7C0B206287E +:1013800007D1009B03990133DBB280310093803C8D +:101390000391002CB8D10420FFF70EFFFFF71EFFCA +:1013A000044B01251C7000E00025281C05B0F0BD91 +:1013B000190300201A03002096020020F0B5384CD3 +:1013C00087B0002301902370994201D1012301E0ED +:1013D000344A1180344A642613704320FFF7ECFE30 +:1013E000324FFFF7F3FE002803D1002F03D0013F57 +:1013F000F7E7002F03D1013E002EEED14DE001258D +:10140000FFF7ECFE2378002B38D1C0B20290012800 +:1014100005D004283DD10620FFF7CEFE39E005AE09 +:101420000221301CFFF714FF01988021FFF710FF05 +:1014300023780390002B18D1FFF7D0FE0702FFF7A7 +:10144000CDFEBFB223783F18BFB2012B0DD0039B56 +:101450009F4207D13378AB4204D1EB437278DBB2C1 +:101460009A4204D01820FFF7A7FE002303E00620CD +:10147000FFF7A2FE029B2278002A02D000262670E7 +:101480000BE0012B05D1019A6B1C8032DDB2019279 +:10149000B6E7054A002313700126301C07B0F0BDE3 +:1014A00019030020960200201A03002000350C00CA +:1014B00010B50023934203D0CC5CC4540133F9E748 +:1014C00010BD031C8218934202D019700133FAE751 +:1014D00070470000F8B5C046F8BC08BC9E4670478F +:1014E000F8B5C046F8BC08BC9E4670471201000221 +:1014F000020000409A230B000002000000010000DF +:101500000800000010000000200000004000000063 +:101510008000000000010000000200000004000044 +:10152000B9110000DD110000CD1100001112000002 +:101530002B120000B5120000BD1300007600200041 +:101540004D617220203520323031360032313A324E +:10155000383A333400580A0D00590A0D005A002356 +:101560000A0D003E00322E3000000000D90A0000B3 +:10157000F50A0000110B0000350B0000510B0000B4 +:10158000350B0000790B00005B41726475696E6F6A +:101590003A58595A5D0000002110422063308440BF +:1015A000A550C660E770088129914AA16BB18CC132 +:1015B000ADD1CEE1EFF13112100273325222B552A9 +:1015C0009442F772D662399318837BB35AA3BDD382 +:1015D0009CC3FFF3DEE36224433420040114E66479 +:1015E000C774A44485546AA54BB528850995EEE5D2 +:1015F000CFF5ACC58DD55336722611163006D77689 +:10160000F6669556B4465BB77AA719973887DFF721 +:10161000FEE79DD7BCC7C448E5588668A778400850 +:10162000611802282338CCC9EDD98EE9AFF9488971 +:1016300069990AA92BB9F55AD44AB77A966A711AE8 +:10164000500A333A122AFDDBDCCBBFFB9EEB799BC1 +:10165000588B3BBB1AABA66C877CE44CC55C222C38 +:10166000033C600C411CAEED8FFDECCDCDDD2AAD11 +:101670000BBD688D499D977EB66ED55EF44E133EC8 +:10168000322E511E700E9FFFBEEFDDDFFCCF1BBF61 +:101690003AAF599F788F8891A981CAB1EBA10CD13B +:1016A0002DC14EF16FE18010A100C230E320045043 +:1016B000254046706760B9839893FBA3DAB33DC3B6 +:1016C0001CD37FE35EF3B1029012F322D232354293 +:1016D000145277625672EAB5CBA5A89589856EF546 +:1016E0004FE52CD50DC5E234C324A01481046674E3 +:1016F000476424540544DBA7FAB79987B8975FE796 +:101700007EF71DC73CD7D326F2369106B016576632 +:101710007676154634564CD96DC90EF92FE9C8991D +:10172000E9898AB9ABA94458654806782768C01882 +:10173000E1088238A3287DCB5CDB3FEB1EFBF98BF5 +:10174000D89BBBAB9ABB754A545A376A167AF10AD2 +:10175000D01AB32A923A2EFD0FED6CDD4DCDAABD05 +:101760008BADE89DC98D267C076C645C454CA23C22 +:10177000832CE01CC10C1FEF3EFF5DCF7CDF9BAFD5 +:10178000BABFD98FF89F176E367E554E745E932E72 +:0C179000B23ED10EF01E00000000000070 +:10179C00010000000902430002010080320904002C +:1017AC0000010202000005240010010424020005BF +:1017BC00240600010524010001070583030800FF2E +:1017CC0009040100020A0000000705810240000024 +:1017DC00070502024000000000C2010000000800E2 +:0C17EC0069000000410000000000000047 +:04000003000005E90B +:00000001FF diff --git a/cores/arduino/USB/CDC.cpp b/cores/arduino/USB/CDC.cpp index 5a111dce9..b9687b902 100644 --- a/cores/arduino/USB/CDC.cpp +++ b/cores/arduino/USB/CDC.cpp @@ -23,6 +23,8 @@ #include #include +uint8_t USB_TXLEDticks = 0, USB_RXLEDticks = 0; + #ifdef CDC_ENABLED #define CDC_SERIAL_BUFFER_SIZE 256 @@ -100,6 +102,12 @@ bool CDC_Setup(USBSetup& setup) uint8_t requestType = setup.bmRequestType; uint8_t r = setup.bRequest; + digitalWrite(PIN_LED_RXL, HIGH); + digitalWrite(PIN_LED_TXL, HIGH); + pinMode(PIN_LED_RXL, OUTPUT); + pinMode(PIN_LED_TXL, OUTPUT); + USB_TXLEDticks = USB_RXLEDticks = 0; + if (requestType == REQUEST_DEVICETOHOST_CLASS_INTERFACE) { if (r == CDC_GET_LINE_CODING) @@ -221,6 +229,9 @@ int Serial_::read(void) { ring_buffer *buffer = &cdc_rx_buffer; + digitalWrite(PIN_LED_RXL, LOW); + USB_RXLEDticks = 10; // how many ms to keep LED on + // if the head isn't ahead of the tail, we don't have any characters if (buffer->head == buffer->tail && !buffer->full) { @@ -255,6 +266,9 @@ size_t Serial_::write(const uint8_t *buffer, size_t size) bytes sent before the user opens the connection or after the connection is closed are lost - just like with a UART. */ + digitalWrite(PIN_LED_TXL, LOW); + USB_TXLEDticks = 10; // how many ms to keep LED on + // TODO - ZE - check behavior on different OSes and test what happens if an // open connection isn't broken cleanly (cable is yanked out, host dies // or locks up, or host virtual serial port hangs) @@ -345,6 +359,6 @@ bool Serial_::rts() { return _usbLineInfo.lineState & 0x2; } -Serial_ SerialUSB(USBDevice); +Serial_ Serial(USBDevice); #endif diff --git a/cores/arduino/USB/USBAPI.h b/cores/arduino/USB/USBAPI.h index 1de826608..a27a115e9 100644 --- a/cores/arduino/USB/USBAPI.h +++ b/cores/arduino/USB/USBAPI.h @@ -170,7 +170,7 @@ class Serial_ : public Stream USBDeviceClass &usb; RingBuffer *_cdc_rx_buffer; }; -extern Serial_ SerialUSB; +extern Serial_ Serial; //================================================================================ //================================================================================ diff --git a/cores/arduino/USB/USBCore.cpp b/cores/arduino/USB/USBCore.cpp index cd356d578..c62cf59a4 100644 --- a/cores/arduino/USB/USBCore.cpp +++ b/cores/arduino/USB/USBCore.cpp @@ -250,7 +250,7 @@ void USBDeviceClass::handleEndpoint(uint8_t ep) // Handle received bytes if (available(CDC_ENDPOINT_OUT)) - SerialUSB.accept(); + Serial.accept(); } if (ep == CDC_ENDPOINT_IN) { diff --git a/cores/arduino/delay.c b/cores/arduino/delay.c index ea000abb0..f73037ea7 100644 --- a/cores/arduino/delay.c +++ b/cores/arduino/delay.c @@ -19,6 +19,9 @@ #include "delay.h" #include "Arduino.h" +extern uint8_t USB_TXLEDticks, USB_RXLEDticks; + + #ifdef __cplusplus extern "C" { #endif @@ -83,6 +86,21 @@ void SysTick_DefaultHandler(void) // Increment tick count each ms _ulTickCount++; tickReset(); + + // turn off CDC LEDs if time + if (USB_RXLEDticks) { + USB_RXLEDticks--; + if (USB_RXLEDticks == 0) { + digitalWrite(PIN_LED_RXL, HIGH); + } + } + + if (USB_TXLEDticks) { + USB_TXLEDticks--; + if (USB_TXLEDticks == 0) { + digitalWrite(PIN_LED_TXL, HIGH); + } + } } #ifdef __cplusplus diff --git a/cores/arduino/wiring_analog.c b/cores/arduino/wiring_analog.c index e148aba4a..a15ccbf8b 100644 --- a/cores/arduino/wiring_analog.c +++ b/cores/arduino/wiring_analog.c @@ -140,10 +140,12 @@ uint32_t analogRead( uint32_t ulPin ) { uint32_t valueRead = 0; - if ( ulPin < A0 ) + if ( ulPin <= 5 ) // turn '0' -> 'A0' { ulPin += A0 ; } + if (ulPin == 6) ulPin = PIN_A6; + if (ulPin == 7) ulPin = PIN_A7; pinPeripheral(ulPin, PIO_ANALOG); diff --git a/libraries/USBHost/examples/KeyboardController/KeyboardController.ino b/libraries/USBHost/examples/KeyboardController/KeyboardController.ino index b869ad803..126bd4754 100644 --- a/libraries/USBHost/examples/KeyboardController/KeyboardController.ino +++ b/libraries/USBHost/examples/KeyboardController/KeyboardController.ino @@ -2,7 +2,7 @@ Keyboard Controller Example Shows the output of a USB Keyboard connected to - the Native USB port on an Arduino Due Board. + the Native USB port on an Arduino Zero created 8 Oct 2012 by Cristian Maglie @@ -15,6 +15,13 @@ // Require keyboard control library #include + +// on a zero with debug port, use debug port +//#define SerialDebug Serial + +// on a feather or non-debug Zero, use Serial1 (since USB is taken!) +#define SerialDebug Serial1 + // Initialize USB Controller USBHost usb; @@ -25,60 +32,62 @@ void printKey(); // This function intercepts key press void keyPressed() { - SERIAL_PORT_MONITOR.print("Pressed: "); + SerialDebug.print("Pressed: "); printKey(); } // This function intercepts key release void keyReleased() { - SERIAL_PORT_MONITOR.print("Released: "); + SerialDebug.print("Released: "); printKey(); } void printKey() { // getOemKey() returns the OEM-code associated with the key - SERIAL_PORT_MONITOR.print(" key:"); - SERIAL_PORT_MONITOR.print(keyboard.getOemKey()); + SerialDebug.print(" key:"); + SerialDebug.print(keyboard.getOemKey()); // getModifiers() returns a bits field with the modifiers-keys int mod = keyboard.getModifiers(); - SERIAL_PORT_MONITOR.print(" mod:"); - SERIAL_PORT_MONITOR.print(mod); + SerialDebug.print(" mod:"); + SerialDebug.print(mod); - SERIAL_PORT_MONITOR.print(" => "); + SerialDebug.print(" => "); if (mod & LeftCtrl) - SERIAL_PORT_MONITOR.print("L-Ctrl "); + SerialDebug.print("L-Ctrl "); if (mod & LeftShift) - SERIAL_PORT_MONITOR.print("L-Shift "); + SerialDebug.print("L-Shift "); if (mod & Alt) - SERIAL_PORT_MONITOR.print("Alt "); + SerialDebug.print("Alt "); if (mod & LeftCmd) - SERIAL_PORT_MONITOR.print("L-Cmd "); + SerialDebug.print("L-Cmd "); if (mod & RightCtrl) - SERIAL_PORT_MONITOR.print("R-Ctrl "); + SerialDebug.print("R-Ctrl "); if (mod & RightShift) - SERIAL_PORT_MONITOR.print("R-Shift "); + SerialDebug.print("R-Shift "); if (mod & AltGr) - SERIAL_PORT_MONITOR.print("AltGr "); + SerialDebug.print("AltGr "); if (mod & RightCmd) - SERIAL_PORT_MONITOR.print("R-Cmd "); + SerialDebug.print("R-Cmd "); // getKey() returns the ASCII translation of OEM key // combined with modifiers. - SERIAL_PORT_MONITOR.write(keyboard.getKey()); - SERIAL_PORT_MONITOR.println(); + SerialDebug.write(keyboard.getKey()); + SerialDebug.println(); } +uint32_t lastUSBstate = 0; + void setup() { - SERIAL_PORT_MONITOR.begin( 115200 ); - while (!SERIAL_PORT_MONITOR); // Wait for serial port to connect - used on Leonardo, Teensy and other boards with built-in USB CDC serial connection - SERIAL_PORT_MONITOR.println("Keyboard Controller Program started"); + SerialDebug.begin( 115200 ); + SerialDebug.println("USB Host Keyboard Controller Program started"); if (usb.Init() == -1) - SERIAL_PORT_MONITOR.println("OSC did not start."); - + SerialDebug.println("USB Host did not start."); + + SerialDebug.println("USB Host started"); delay( 20 ); } @@ -86,4 +95,21 @@ void loop() { // Process USB tasks usb.Task(); + + uint32_t currentUSBstate = usb.getUsbTaskState(); + if (lastUSBstate != currentUSBstate) { + SerialDebug.print("USB state changed: 0x"); + SerialDebug.print(lastUSBstate, HEX); + SerialDebug.print(" -> 0x"); + SerialDebug.println(currentUSBstate, HEX); + switch (currentUSBstate) { + case USB_ATTACHED_SUBSTATE_SETTLE: SerialDebug.println("Device Attached"); break; + case USB_DETACHED_SUBSTATE_WAIT_FOR_DEVICE: SerialDebug.println("Detached, waiting for Device"); break; + case USB_ATTACHED_SUBSTATE_RESET_DEVICE: SerialDebug.println("Resetting Device"); break; + case USB_ATTACHED_SUBSTATE_WAIT_RESET_COMPLETE: SerialDebug.println("Reset complete"); break; + case USB_STATE_CONFIGURING: SerialDebug.println("USB Configuring"); break; + case USB_STATE_RUNNING: SerialDebug.println("USB Running"); break; + } + lastUSBstate = currentUSBstate; + } } diff --git a/libraries/USBHost/examples/MouseController/MouseController.ino b/libraries/USBHost/examples/MouseController/MouseController.ino index 0cdeef677..62604fc7a 100644 --- a/libraries/USBHost/examples/MouseController/MouseController.ino +++ b/libraries/USBHost/examples/MouseController/MouseController.ino @@ -15,6 +15,14 @@ // Require mouse control library #include +// on a zero with debug port, use debug port +//#define SerialDebug Serial + +// on a feather or non-debug Zero, use Serial1 (since USB is taken!) +#define SerialDebug Serial1 + +uint32_t lastUSBstate = 0; + // Initialize USB Controller USBHost usb; @@ -28,65 +36,65 @@ boolean rightButton = false; // This function intercepts mouse movements void mouseMoved() { - SERIAL_PORT_MONITOR.print("Move: "); - SERIAL_PORT_MONITOR.print(mouse.getXChange()); - SERIAL_PORT_MONITOR.print(", "); - SERIAL_PORT_MONITOR.println(mouse.getYChange()); + SerialDebug.print("Move: "); + SerialDebug.print(mouse.getXChange()); + SerialDebug.print(", "); + SerialDebug.println(mouse.getYChange()); } // This function intercepts mouse movements while a button is pressed void mouseDragged() { - SERIAL_PORT_MONITOR.print("DRAG: "); - SERIAL_PORT_MONITOR.print(mouse.getXChange()); - SERIAL_PORT_MONITOR.print(", "); - SERIAL_PORT_MONITOR.println(mouse.getYChange()); + SerialDebug.print("Drag: "); + SerialDebug.print(mouse.getXChange()); + SerialDebug.print(", "); + SerialDebug.println(mouse.getYChange()); } // This function intercepts mouse button press void mousePressed() { - SERIAL_PORT_MONITOR.print("Pressed: "); + SerialDebug.print("Pressed: "); if (mouse.getButton(LEFT_BUTTON)) { - SERIAL_PORT_MONITOR.print("L"); + SerialDebug.print("L"); leftButton = true; } if (mouse.getButton(MIDDLE_BUTTON)) { - SERIAL_PORT_MONITOR.print("M"); + SerialDebug.print("M"); middleButton = true; } if (mouse.getButton(RIGHT_BUTTON)) { - SERIAL_PORT_MONITOR.print("R"); + SerialDebug.print("R"); rightButton = true; } - SERIAL_PORT_MONITOR.println(); + SerialDebug.println(); } // This function intercepts mouse button release void mouseReleased() { - SERIAL_PORT_MONITOR.print("Released: "); + SerialDebug.print("Released: "); if (!mouse.getButton(LEFT_BUTTON) && leftButton == true) { - SERIAL_PORT_MONITOR.print("L"); + SerialDebug.print("L"); leftButton = false; } if (!mouse.getButton(MIDDLE_BUTTON) && middleButton == true) { - SERIAL_PORT_MONITOR.print("M"); + SerialDebug.print("M"); middleButton = false; } if (!mouse.getButton(RIGHT_BUTTON) && rightButton == true) { - SERIAL_PORT_MONITOR.print("R"); + SerialDebug.print("R"); rightButton = false; } - SERIAL_PORT_MONITOR.println(); + SerialDebug.println(); } void setup() { - SERIAL_PORT_MONITOR.begin( 115200 ); - while (!SERIAL_PORT_MONITOR); // Wait for serial port to connect - used on Leonardo, Teensy and other boards with built-in USB CDC serial connection - SERIAL_PORT_MONITOR.println("Mouse Controller Program started"); + SerialDebug.begin( 115200 ); + SerialDebug.println("USB Host Mouse Controller Program started"); if (usb.Init() == -1) - SERIAL_PORT_MONITOR.println("OSC did not start."); + SerialDebug.println("USB Host did not start."); + SerialDebug.println("USB Host started"); delay( 20 ); } @@ -94,4 +102,21 @@ void loop() { // Process USB tasks usb.Task(); + + uint32_t currentUSBstate = usb.getUsbTaskState(); + if (lastUSBstate != currentUSBstate) { + SerialDebug.print("USB state changed: 0x"); + SerialDebug.print(lastUSBstate, HEX); + SerialDebug.print(" -> 0x"); + SerialDebug.println(currentUSBstate, HEX); + switch (currentUSBstate) { + case USB_ATTACHED_SUBSTATE_SETTLE: SerialDebug.println("Device Attached"); break; + case USB_DETACHED_SUBSTATE_WAIT_FOR_DEVICE: SerialDebug.println("Detached, waiting for Device"); break; + case USB_ATTACHED_SUBSTATE_RESET_DEVICE: SerialDebug.println("Resetting Device"); break; + case USB_ATTACHED_SUBSTATE_WAIT_RESET_COMPLETE: SerialDebug.println("Reset complete"); break; + case USB_STATE_CONFIGURING: SerialDebug.println("USB Configuring"); break; + case USB_STATE_RUNNING: SerialDebug.println("USB Running"); break; + } + lastUSBstate = currentUSBstate; + } } diff --git a/libraries/USBHost/examples/USB_desc/USB_desc.ino b/libraries/USBHost/examples/USB_desc/USB_desc.ino index 87b9df6e8..4d61c6ec0 100644 --- a/libraries/USBHost/examples/USB_desc/USB_desc.ino +++ b/libraries/USBHost/examples/USB_desc/USB_desc.ino @@ -1,22 +1,16 @@ - - #include "Arduino.h" #include #include "wiring_constants.h" #include "pgmstrings.h" -// Satisfy IDE, which only needs to see the include statment in the ino. -#ifdef dobogusinclude -#include -#endif + + +// on a zero with debug port, use debug port +//#define SerialDebug Serial + +// on a feather or non-debug Zero, use Serial1 (since USB is taken!) +#define SerialDebug Serial1 USBHost usb; -//USBHub Hub1(&Usb); -//USBHub Hub2(&Usb); -//USBHub Hub3(&Usb); -//USBHub Hub4(&Usb); -//USBHub Hub5(&Usb); -//USBHub Hub6(&Usb); -//USBHub Hub7(&Usb); uint32_t next_time; @@ -33,39 +27,40 @@ void PrintAllAddresses(UsbDeviceDefinition *pdev) { UsbDeviceAddress adr; adr.devAddress = pdev->address.devAddress; - SERIAL_PORT_MONITOR.print("\r\nAddr:"); - SERIAL_PORT_MONITOR.print(adr.devAddress, HEX); - SERIAL_PORT_MONITOR.print("("); - SERIAL_PORT_MONITOR.print(adr.bmHub, HEX); - SERIAL_PORT_MONITOR.print("."); - SERIAL_PORT_MONITOR.print(adr.bmParent, HEX); - SERIAL_PORT_MONITOR.print("."); - SERIAL_PORT_MONITOR.print(adr.bmAddress, HEX); - SERIAL_PORT_MONITOR.println(")"); + SerialDebug.print("\r\nAddr:"); + SerialDebug.print(adr.devAddress, HEX); + SerialDebug.print("("); + SerialDebug.print(adr.bmHub, HEX); + SerialDebug.print("."); + SerialDebug.print(adr.bmParent, HEX); + SerialDebug.print("."); + SerialDebug.print(adr.bmAddress, HEX); + SerialDebug.println(")"); } void PrintAddress(uint8_t addr) { UsbDeviceAddress adr; adr.devAddress = addr; - SERIAL_PORT_MONITOR.print("\r\nADDR:\t"); - SERIAL_PORT_MONITOR.println(adr.devAddress,HEX); - SERIAL_PORT_MONITOR.print("DEV:\t"); - SERIAL_PORT_MONITOR.println(adr.bmAddress,HEX); - SERIAL_PORT_MONITOR.print("PRNT:\t"); - SERIAL_PORT_MONITOR.println(adr.bmParent,HEX); - SERIAL_PORT_MONITOR.print("HUB:\t"); - SERIAL_PORT_MONITOR.println(adr.bmHub,HEX); + SerialDebug.print("\r\nADDR:\t"); + SerialDebug.println(adr.devAddress,HEX); + SerialDebug.print("DEV:\t"); + SerialDebug.println(adr.bmAddress,HEX); + SerialDebug.print("PRNT:\t"); + SerialDebug.println(adr.bmParent,HEX); + SerialDebug.print("HUB:\t"); + SerialDebug.println(adr.bmHub,HEX); } void setup() { - SERIAL_PORT_MONITOR.begin( 115200 ); - while (!Serial); // Wait for serial port to connect - used on Leonardo, Teensy and other boards with built-in USB CDC serial connection - SERIAL_PORT_MONITOR.println("Start USB Desc"); + Serial.begin(115200); + SerialDebug.begin(115200); + SerialDebug.println("Starting USB Descriptor test"); + SerialDebug.println("Initializing USB"); if (usb.Init() == -1) - SERIAL_PORT_MONITOR.println("OSC did not start."); + SerialDebug.println("USBhost did not start."); delay( 20 ); @@ -85,7 +80,7 @@ void PrintDescriptors(uint8_t addr) printProgStr(Gen_Error_str); print_hex( rcode, 8 ); } - SERIAL_PORT_MONITOR.print("\r\n"); + SerialDebug.print("\r\n"); for (int i=0; iaddress.devAddress, 8); - SERIAL_PORT_MONITOR.println("\r\n--"); + SerialDebug.println("\r\n--"); PrintDescriptors( pdev->address.devAddress ); } @@ -171,37 +166,37 @@ void printhubdescr(uint8_t *descrptr, uint8_t addr) printProgStr(PSTR("\r\n\r\nHub Descriptor:\r\n")); printProgStr(PSTR("bDescLength:\t\t")); - SERIAL_PORT_MONITOR.println(pHub->bDescLength, HEX); + SerialDebug.println(pHub->bDescLength, HEX); printProgStr(PSTR("bDescriptorType:\t")); - SERIAL_PORT_MONITOR.println(pHub->bDescriptorType, HEX); + SerialDebug.println(pHub->bDescriptorType, HEX); printProgStr(PSTR("bNbrPorts:\t\t")); - SERIAL_PORT_MONITOR.println(pHub->bNbrPorts, HEX); + SerialDebug.println(pHub->bNbrPorts, HEX); printProgStr(PSTR("LogPwrSwitchMode:\t")); - SERIAL_PORT_MONITOR.println(pHub->LogPwrSwitchMode, BIN); + SerialDebug.println(pHub->LogPwrSwitchMode, BIN); printProgStr(PSTR("CompoundDevice:\t\t")); - SERIAL_PORT_MONITOR.println(pHub->CompoundDevice, BIN); + SerialDebug.println(pHub->CompoundDevice, BIN); printProgStr(PSTR("OverCurrentProtectMode:\t")); - SERIAL_PORT_MONITOR.println(pHub->OverCurrentProtectMode, BIN); + SerialDebug.println(pHub->OverCurrentProtectMode, BIN); printProgStr(PSTR("TTThinkTime:\t\t")); - SERIAL_PORT_MONITOR.println(pHub->TTThinkTime, BIN); + SerialDebug.println(pHub->TTThinkTime, BIN); printProgStr(PSTR("PortIndicatorsSupported:")); - SERIAL_PORT_MONITOR.println(pHub->PortIndicatorsSupported, BIN); + SerialDebug.println(pHub->PortIndicatorsSupported, BIN); printProgStr(PSTR("Reserved:\t\t")); - SERIAL_PORT_MONITOR.println(pHub->Reserved, HEX); + SerialDebug.println(pHub->Reserved, HEX); printProgStr(PSTR("bPwrOn2PwrGood:\t\t")); - SERIAL_PORT_MONITOR.println(pHub->bPwrOn2PwrGood, HEX); + SerialDebug.println(pHub->bPwrOn2PwrGood, HEX); printProgStr(PSTR("bHubContrCurrent:\t")); - SERIAL_PORT_MONITOR.println(pHub->bHubContrCurrent, HEX); + SerialDebug.println(pHub->bHubContrCurrent, HEX); for (uint8_t i=7; i> (num_nibbles-1) * 4)) & 0x0f; - SERIAL_PORT_MONITOR.print(digit, HEX); + SerialDebug.print(digit, HEX); } while(--num_nibbles); } @@ -329,7 +324,7 @@ void printHIDdescr( uint8_t* descr_ptr ) printProgStr(PSTR("\r\nNumb Class Descriptor:\t")); print_hex( ep_ptr->bNumDescriptors, 8 ); printProgStr(PSTR("\r\nDescriptor Type:\t")); - if( ep_ptr->bDescrType == 0x22 ) + if( ep_ptr->bDescrType == 0x22 ) printProgStr(PSTR("REPORT DESCRIPTOR")); else print_hex( ep_ptr->bDescrType, 8 ); @@ -386,5 +381,4 @@ void printProgStr(const prog_char str[]) char c; if(!str) return; while((c = pgm_read_byte(str++))) - SERIAL_PORT_MONITOR.print(c); -} + SerialDebug.print(c); diff --git a/libraries/USBHost/src/Usb.cpp b/libraries/USBHost/src/Usb.cpp index be1d800f6..fca015895 100644 --- a/libraries/USBHost/src/Usb.cpp +++ b/libraries/USBHost/src/Usb.cpp @@ -123,7 +123,7 @@ uint32_t USBHost::SetPipeAddress(uint32_t addr, uint32_t ep, EpInfo **ppep, uint /* 01-0f = non-zero HRSLT */ uint32_t USBHost::ctrlReq(uint32_t addr, uint32_t ep, uint8_t bmReqType, uint8_t bRequest, uint8_t wValLo, uint8_t wValHi, uint16_t wInd, uint16_t total, uint32_t nbytes, uint8_t* dataptr, USBReadParser *p) { - + uint32_t direction = 0; // Request direction, IN or OUT uint32_t rcode; SETUP_PKT setup_pkt; @@ -194,14 +194,14 @@ uint32_t USBHost::ctrlReq(uint32_t addr, uint32_t ep, uint8_t bmReqType, uint8_t ((USBReadParser*)p)->Parse(read, dataptr, total - left); } else // OUT transfer - { + { pep->bmSndToggle = 1; //bmSNDTOG1; rcode = OutTransfer(pep, nak_limit, nbytes, dataptr); } if(rcode) //return error return (rcode); } - + // Status stage UHD_Pipe_CountZero(pep->epAddr); USB->HOST.HostPipe[pep->epAddr].PSTATUSSET.reg = USB_HOST_PSTATUSSET_DTGL; @@ -263,16 +263,17 @@ uint32_t USBHost::InTransfer(EpInfo *pep, uint32_t nak_limit, uint8_t *nbytesptr } if(rcode) { uhd_freeze_pipe(pep->epAddr); + //printf(">>>>>>>> Problem! dispatchPkt %2.2x\r\n", rcode); return(rcode);// break; //should be 0, indicating ACK. Else return error code. } /* check for RCVDAVIRQ and generate error if not present */ /* the only case when absence of RCVDAVIRQ makes sense is when toggle error occurred. Need to add handling for that */ - + pktsize = uhd_byte_count(pep->epAddr); // Number of received bytes - + USB->HOST.HostPipe[pep->epAddr].PSTATUSCLR.reg = USB_HOST_PSTATUSCLR_BK0RDY; - + //printf("Got %i bytes \r\n", pktsize); // This would be OK, but... //assert(pktsize <= nbytes); @@ -297,7 +298,7 @@ uint32_t USBHost::InTransfer(EpInfo *pep, uint32_t nak_limit, uint8_t *nbytesptr /* 1. The device sent a short packet (L.T. maxPacketSize) */ /* 2. 'nbytes' have been transferred. */ if((pktsize < maxpktsize) || (*nbytesptr >= nbytes)) // have we transferred 'nbytes' bytes? - { + { // Save toggle value pep->bmRcvToggle = USB_HOST_DTGL(pep->epAddr); //printf("\r\n"); @@ -505,7 +506,7 @@ void USBHost::Task(void) //USB state machine TRACE_USBHOST(printf(" + USB_DETACHED_SUBSTATE_INITIALIZE\r\n");) // Init USB stack and driver - UHD_Init(); + Init(); // Free all USB resources for (uint32_t i = 0; i < USB_NUMDEVICES; ++i) diff --git a/libraries/USBHost/src/Usb.h b/libraries/USBHost/src/Usb.h index 919b83523..9ac26c7c4 100644 --- a/libraries/USBHost/src/Usb.h +++ b/libraries/USBHost/src/Usb.h @@ -27,7 +27,7 @@ e-mail : support@circuitsathome.com // None of these should ever be included by a driver, or a user's sketch. #include "variant.h" -#define USB_HOST_SERIAL SERIAL_PORT_MONITOR +#define USB_HOST_SERIAL Serial1 #include "Print.h" #include "printhex.h" #include "message.h" diff --git a/platform.txt b/platform.txt index 7d733b19a..76c62d974 100644 --- a/platform.txt +++ b/platform.txt @@ -139,5 +139,4 @@ tools.openocd.erase.pattern= tools.openocd.bootloader.params.verbose=-d2 tools.openocd.bootloader.params.quiet=-d0 -tools.openocd.bootloader.pattern="{path}/{cmd}" {bootloader.verbose} -s "{path}/share/openocd/scripts/" -f "{runtime.platform.path}/variants/{build.variant}/{build.openocdscript}" -c "telnet_port disabled; init; halt; at91samd bootloader 0; program {{{runtime.platform.path}/bootloaders/{bootloader.file}}} verify reset; shutdown" - +tools.openocd.bootloader.pattern="{path}/{cmd}" {bootloader.verbose} -s "{path}/share/openocd/scripts/" -f "{runtime.platform.path}/variants/{build.variant}/{build.openocdscript}" -c "telnet_port disabled; init; halt; at91samd bootloader 0; program {{{runtime.platform.path}/bootloaders/{bootloader.file}}} verify reset; shutdown" \ No newline at end of file diff --git a/variants/arduino_zero/variant.cpp b/variants/arduino_zero/variant.cpp index 8a10fea25..a6cb3056b 100644 --- a/variants/arduino_zero/variant.cpp +++ b/variants/arduino_zero/variant.cpp @@ -127,8 +127,8 @@ const PinDescription g_APinDescription[]= { PORTA, 21, PIO_DIGITAL, (PIN_ATTR_DIGITAL), No_ADC_Channel, NOT_ON_PWM, NOT_ON_TIMER, EXTERNAL_INT_5 }, // Digital High - { PORTA, 6, PIO_TIMER, (PIN_ATTR_DIGITAL|PIN_ATTR_PWM|PIN_ATTR_TIMER), No_ADC_Channel, PWM1_CH0, TCC1_CH0, EXTERNAL_INT_6 }, // TCC1/WO[0] - { PORTA, 7, PIO_TIMER, (PIN_ATTR_DIGITAL|PIN_ATTR_PWM|PIN_ATTR_TIMER), No_ADC_Channel, PWM1_CH1, TCC1_CH1, EXTERNAL_INT_7 }, // TCC1/WO[1] + { PORTA, 6, PIO_TIMER, (PIN_ATTR_DIGITAL|PIN_ATTR_PWM|PIN_ATTR_TIMER|PIN_ATTR_ANALOG), ADC_Channel6, PWM1_CH0, TCC1_CH0, EXTERNAL_INT_6 }, // TCC1/WO[0] + { PORTA, 7, PIO_TIMER, (PIN_ATTR_DIGITAL|PIN_ATTR_PWM|PIN_ATTR_TIMER|PIN_ATTR_ANALOG), ADC_Channel7, PWM1_CH1, TCC1_CH1, EXTERNAL_INT_7 }, // TCC1/WO[1] { PORTA, 18, PIO_TIMER, (PIN_ATTR_DIGITAL|PIN_ATTR_PWM|PIN_ATTR_TIMER), No_ADC_Channel, PWM3_CH0, TC3_CH0, EXTERNAL_INT_2 }, // TC3/WO[0] { PORTA, 16, PIO_TIMER, (PIN_ATTR_DIGITAL|PIN_ATTR_PWM|PIN_ATTR_TIMER), No_ADC_Channel, PWM2_CH0, TCC2_CH0, EXTERNAL_INT_0 }, // TCC2/WO[0] { PORTA, 19, PIO_TIMER_ALT, (PIN_ATTR_DIGITAL|PIN_ATTR_PWM|PIN_ATTR_TIMER_ALT), No_ADC_Channel, PWM0_CH3, TCC0_CH3, EXTERNAL_INT_3 }, // TCC0/WO[3] @@ -208,14 +208,18 @@ SERCOM sercom4( SERCOM4 ) ; SERCOM sercom5( SERCOM5 ) ; Uart Serial1( &sercom0, PIN_SERIAL1_RX, PIN_SERIAL1_TX, PAD_SERIAL1_RX, PAD_SERIAL1_TX ) ; -Uart Serial( &sercom5, PIN_SERIAL_RX, PIN_SERIAL_TX, PAD_SERIAL_RX, PAD_SERIAL_TX ) ; void SERCOM0_Handler() { Serial1.IrqHandler(); } + +// Serial5 not available on Feather so ditch it + +//Uart Serial5( &sercom5, PIN_SERIAL_RX, PIN_SERIAL_TX, PAD_SERIAL_RX, PAD_SERIAL_TX ) ; +/* void SERCOM5_Handler() { - Serial.IrqHandler(); + Serial5.IrqHandler(); } - +*/ diff --git a/variants/arduino_zero/variant.h b/variants/arduino_zero/variant.h index 50ba88772..32e79792b 100644 --- a/variants/arduino_zero/variant.h +++ b/variants/arduino_zero/variant.h @@ -55,7 +55,7 @@ extern "C" // Number of pins defined in PinDescription array #define PINS_COUNT (26u) #define NUM_DIGITAL_PINS (14u) -#define NUM_ANALOG_INPUTS (6u) +#define NUM_ANALOG_INPUTS (8u) #define NUM_ANALOG_OUTPUTS (1u) #define digitalPinToPort(P) ( &(PORT->Group[g_APinDescription[P].ulPort]) ) @@ -96,6 +96,8 @@ extern "C" #define PIN_A3 (17ul) #define PIN_A4 (18ul) #define PIN_A5 (19ul) +#define PIN_A6 (8ul) +#define PIN_A7 (9ul) static const uint8_t A0 = PIN_A0 ; static const uint8_t A1 = PIN_A1 ; @@ -103,6 +105,8 @@ static const uint8_t A2 = PIN_A2 ; static const uint8_t A3 = PIN_A3 ; static const uint8_t A4 = PIN_A4 ; static const uint8_t A5 = PIN_A5 ; +static const uint8_t A6 = PIN_A6 ; +static const uint8_t A7 = PIN_A7 ; #define ADC_RESOLUTION 12 // Other pins @@ -179,7 +183,7 @@ extern SERCOM sercom3; extern SERCOM sercom4; extern SERCOM sercom5; -extern Uart Serial; +extern Uart Serial5; extern Uart Serial1; #endif @@ -199,7 +203,7 @@ extern Uart Serial1; // // SERIAL_PORT_HARDWARE_OPEN Hardware serial ports which are open for use. Their RX & TX // pins are NOT connected to anything by default. -#define SERIAL_PORT_USBVIRTUAL SerialUSB +#define SERIAL_PORT_USBVIRTUAL Serial #define SERIAL_PORT_MONITOR Serial // Serial has no physical pins broken out, so it's not listed as HARDWARE port #define SERIAL_PORT_HARDWARE Serial1