diff --git a/bootloaders/artemis/!artemis_svl/Makefile b/bootloaders/artemis/!artemis_svl/Makefile deleted file mode 100644 index 76eef78e..00000000 --- a/bootloaders/artemis/!artemis_svl/Makefile +++ /dev/null @@ -1,45 +0,0 @@ -#****************************************************************************** -# -# Makefile - Rules for compiling -# -# Copyright (c) 2019, Ambiq Micro -# All rights reserved. -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# 1. Redistributions of source code must retain the above copyright notice, -# this list of conditions and the following disclaimer. -# -# 2. Redistributions in binary form must reproduce the above copyright -# notice, this list of conditions and the following disclaimer in the -# documentation and/or other materials provided with the distribution. -# -# 3. Neither the name of the copyright holder nor the names of its -# contributors may be used to endorse or promote products derived from this -# software without specific prior written permission. -# -# Third party software included in this distribution is subject to the -# additional license terms as defined in the /docs/licenses directory. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE. -# -# This is part of revision 2.1.0 of the AmbiqSuite Development Package. -# -#****************************************************************************** - -# All makefiles use this to find the top level directory. -SWROOT?=../../../.. - -# Include rules for building generic examples. -include $(SWROOT)/makedefs/example.mk diff --git a/bootloaders/artemis/!artemis_svl/README.txt b/bootloaders/artemis/!artemis_svl/README.txt deleted file mode 100644 index a92195b2..00000000 --- a/bootloaders/artemis/!artemis_svl/README.txt +++ /dev/null @@ -1,20 +0,0 @@ -Name: -===== - artemis_svl - - -Description: -============ - Variable baud rate bootloader for Apollo3/Artemis - - - Usage: - ===== - This source code is provided mostly for reference. The easiest way to upload the SVL is by using the Arduino "burn bootloader" tool and selecting "Ambiq Secure Bootloader" as the "Programmer" option. - - If you want to make changes you can compile and upload the artemis_svl using the AmbiqSuite SDK. - - -****************************************************************************** - - diff --git a/bootloaders/artemis/!artemis_svl/gcc/.gitignore b/bootloaders/artemis/!artemis_svl/gcc/.gitignore deleted file mode 100644 index 158efab2..00000000 --- a/bootloaders/artemis/!artemis_svl/gcc/.gitignore +++ /dev/null @@ -1 +0,0 @@ -*bin* \ No newline at end of file diff --git a/bootloaders/artemis/!artemis_svl/gcc/Makefile b/bootloaders/artemis/!artemis_svl/gcc/Makefile deleted file mode 100644 index 5ee7e580..00000000 --- a/bootloaders/artemis/!artemis_svl/gcc/Makefile +++ /dev/null @@ -1,244 +0,0 @@ -#****************************************************************************** -# -# Makefile - Rules for building the libraries, examples and docs. -# -# Copyright (c) 2019, Ambiq Micro -# All rights reserved. -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# 1. Redistributions of source code must retain the above copyright notice, -# this list of conditions and the following disclaimer. -# -# 2. Redistributions in binary form must reproduce the above copyright -# notice, this list of conditions and the following disclaimer in the -# documentation and/or other materials provided with the distribution. -# -# 3. Neither the name of the copyright holder nor the names of its -# contributors may be used to endorse or promote products derived from this -# software without specific prior written permission. -# -# Third party software included in this distribution is subject to the -# additional license terms as defined in the /docs/licenses directory. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE. -# -# This is part of revision 2.1.0 of the AmbiqSuite Development Package. -# -#****************************************************************************** - -# ARTEMIS_BIN2BOARD is the command to run the combined Ambiq tools (bin to ota blob, -# ota blob to wired blob, wired update). You'll need to determine how to engage it -# for your own system. (You might use pyinstaller to create a binary executable, or) -# call it via python3 -# Examples: -# (via python) ARTEMIS_BIN2BOARD=python "path_to_tool/ambiq_bin2board.py" -# (via executable [windows]) ARTEMIS_BIN2BOARD="path_to_tool/ambiq_bin2board_installed.exe" -# (via executable [*nix]) ARTEMIS_BIN2BOARD=./path_to_tool/ambiq_bin2board_installed -# (via executable on in the default search path) ARTEMIS_BIN2BOARD=ambiq_bin2board_installed -ARTEMIS_SVL= -# COM_PORT is the serial port to use for uploading. For example COM#### on Windows or /dev/cu.usbserial-#### on *nix -COM_PORT= -ifeq ($(ARTEMIS_SVL),) - $(warning warning: you have not defined ARTEMIS_SVL so bootloading will not work) -endif -ifeq ($(COM_PORT),) - $(warning warning: you have not defined COM_PORT so bootloading will not work) -endif - -# SDKPATH =C:/Users/owen.lyke/AppData/Roaming/AmbiqSDK/AmbiqSuite-Rel2.1.0# Note that if you copy/paste a windows file path here you need to change backslashes to forward slashes -SDKPATH = -ifeq ($(SDKPATH),) - SDKPATH =../../../../.. - $(warning warning: you have not defined SDK_PATH so will continue assuming that the SDK root is at $(SDKPATH)) - -endif - -BOARDPATH =${SDKPATH}/boards/artemis# Set this as the path to the Artemis BSP (Board Support Package) directory. Initially assumes that you put the BSP under the 'boards' directory in the SDK - - -USER_INCLUDE_DIRS = -I../src/svl_ringbuf -USER_INCLUDE_DIRS += -I../src/svl_packet -USER_INCLUDE_DIRS += -I../src/svl_uart -USER_INCLUDE_DIRS += -I../src/svl_utils - -USER_SOURCEDIRS = ../src -USER_SOURCEDIRS += ../src/svl_ringbuf -USER_SOURCEDIRS += ../src/svl_packet -USER_SOURCEDIRS += ../src/svl_uart -USER_SOURCEDIRS += ../src/svl_utils - -USER_MAIN_SRC = main.c -USER_SOURCE_FILES = svl_ringbuf.c -USER_SOURCE_FILES += svl_packet.c -USER_SOURCE_FILES += svl_uart.c -USER_SOURCE_FILES += svl_utils.c - - -#### Names #### -TARGET := artemis_svl -COMPILERNAME := gcc -PROJECT := artemis_svl_gcc -CONFIG := bin - -SHELL:=/bin/bash -#### Setup #### - -TOOLCHAIN ?= arm-none-eabi -PART = apollo3 -CPU = cortex-m4 -FPU = fpv4-sp-d16 -# Default to FPU hardware calling convention. However, some customers and/or -# applications may need the software calling convention. -#FABI = softfp -FABI = hard - -LINKER_FILE := ./artemis_svl_gcc.ld -STARTUP_FILE := ./startup_$(COMPILERNAME).c - -#### Required Executables #### -CC = $(TOOLCHAIN)-gcc -GCC = $(TOOLCHAIN)-gcc -CPP = $(TOOLCHAIN)-cpp -LD = $(TOOLCHAIN)-ld -CP = $(TOOLCHAIN)-objcopy -OD = $(TOOLCHAIN)-objdump -RD = $(TOOLCHAIN)-readelf -AR = $(TOOLCHAIN)-ar -SIZE = $(TOOLCHAIN)-size -RM = $(shell which rm 2>/dev/null) - -EXECUTABLES = CC LD CP OD AR RD SIZE GCC -K := $(foreach exec,$(EXECUTABLES),\ - $(if $(shell which $($(exec)) 2>/dev/null),,\ - $(info $(exec) not found on PATH ($($(exec))).)$(exec))) -$(if $(strip $(value K)),$(info Required Program(s) $(strip $(value K)) not found)) - -ifneq ($(strip $(value K)),) -all clean: - $(info Tools $(TOOLCHAIN)-$(COMPILERNAME) not installed.) - $(RM) -rf bin -else - -DEFINES = -DPART_$(PART) -DEFINES+= -DAM_PART_APOLLO3 -DEFINES+= -DAM_PACKAGE_BGA - -# Includes from the SDK -# INCLUDES+= -I../../../../.. # This one doesn't make much sense to me -INCLUDES = -I${SDKPATH}/CMSIS/AmbiqMicro/Include -INCLUDES+= -I${SDKPATH}/mcu/apollo3 -INCLUDES+= -I${SDKPATH}/CMSIS/ARM/Include -INCLUDES+= -I${SDKPATH}/utils -INCLUDES+= -I${SDKPATH}/devices - -# Includes for the board you've chosen -INCLUDES+= -I../src # This is where the source for the particular project is -INCLUDES+= -I${BOARDPATH}/bsp - -INCLUDES+= ${USER_INCLUDE_DIRS} - -VPATH = ${SDKPATH}/devices -VPATH+= ${SDKPATH}/utils -VPATH+= ${USER_SOURCEDIRS} - -SRC = ${USER_MAIN_SRC} -SRC += am_devices_led.c -SRC += am_util_delay.c -SRC += am_util_faultisr.c -SRC += am_util_stdio.c -SRC += am_util_id.c -SRC += startup_gcc.c -SRC += ${USER_SOURCE_FILES} - -CSRC = $(filter %.c,$(SRC)) -ASRC = $(filter %.s,$(SRC)) - -OBJS = $(CSRC:%.c=$(CONFIG)/%.o) -OBJS+= $(ASRC:%.s=$(CONFIG)/%.o) - -DEPS = $(CSRC:%.c=$(CONFIG)/%.d) -DEPS+= $(ASRC:%.s=$(CONFIG)/%.d) - -LIBS = ../../../../../mcu/apollo3/hal/gcc/bin/libam_hal.a -LIBS += ../../../bsp/gcc/bin/libam_bsp.a - -CFLAGS = -mthumb -mcpu=$(CPU) -mfpu=$(FPU) -mfloat-abi=$(FABI) -CFLAGS+= -ffunction-sections -fdata-sections -CFLAGS+= -MMD -MP -std=c99 -Wall -g -CFLAGS+= -O1 -# CFLAGS+= -O0 -CFLAGS+= $(DEFINES) -CFLAGS+= $(INCLUDES) -CFLAGS+= - -LFLAGS = -mthumb -mcpu=$(CPU) -mfpu=$(FPU) -mfloat-abi=$(FABI) -LFLAGS+= -nostartfiles -static -LFLAGS+= -Wl,--gc-sections,--entry,Reset_Handler,-Map,$(CONFIG)/$(TARGET).map -LFLAGS+= -Wl,--start-group -lm -lc -lgcc $(LIBS) -Wl,--end-group -LFLAGS+= -specs=nano.specs -specs=nosys.specs - -# Additional user specified CFLAGS -CFLAGS+=$(EXTRA_CFLAGS) - -CPFLAGS = -Obinary - -ODFLAGS = -S - -#### Rules #### -all: directories $(CONFIG)/$(TARGET).bin - -directories: $(CONFIG) - -$(CONFIG): - @mkdir -p $@ - -$(CONFIG)/%.o: %.c $(CONFIG)/%.d - @echo " Compiling $(COMPILERNAME) $<" ;\ - $(CC) -c $(CFLAGS) $< -o $@ - -$(CONFIG)/%.o: %.s $(CONFIG)/%.d - @echo " Assembling $(COMPILERNAME) $<" ;\ - $(CC) -c $(CFLAGS) $< -o $@ - -$(CONFIG)/$(TARGET).axf: $(OBJS) $(LIBS) - @echo " Linking $(COMPILERNAME) $@" ;\ - $(CC) -Wl,-T,$(LINKER_FILE) -o $@ $(OBJS) $(LFLAGS) - -$(CONFIG)/$(TARGET).bin: $(CONFIG)/$(TARGET).axf - @echo " Copying $(COMPILERNAME) $@..." ;\ - $(CP) $(CPFLAGS) $< $@ ;\ - $(OD) $(ODFLAGS) $< > $(CONFIG)/$(TARGET).lst - -clean: - @echo "Cleaning..." ;\ - $(RM) -f $(OBJS) $(DEPS) \ - $(CONFIG)/$(TARGET).bin $(CONFIG)/$(TARGET).axf \ - $(CONFIG)/$(TARGET).lst $(CONFIG)/$(TARGET).map - -bootload: all - C:\Users\owen.lyke\AppData\Local\Arduino15\packages\SparkFun\hardware\apollo3\1.0.2/tools/ambiq/windows/ambiq_bin2board.exe --bin C:\Users\owen.lyke\AppData\Roaming\AmbiqSDK\AmbiqSuite-Rel2.2.0\boards\artemis\examples\!artemis_svl\gcc\bin\artemis_svl.bin --load-address-blob 0x20000 --magic-num 0xCB -o C:\Users\owen.lyke\AppData\Roaming\AmbiqSDK\AmbiqSuite-Rel2.2.0\boards\artemis\examples\!artemis_svl\gcc\bin\artemis_svl --version 0x0 --load-address-wired 0xC000 -i 6 --options 0x1 -b 115200 -port COM4 -r 2 -v - -$(CONFIG)/%.d: ; - -../../../../../mcu/apollo3/hal/gcc/bin/libam_hal.a: - $(MAKE) -C ../../../../../mcu/apollo3/hal - -../../../bsp/gcc/bin/libam_bsp.a: - $(MAKE) -C ../../../bsp - -# Automatically include any generated dependencies --include $(DEPS) -endif -.PHONY: all clean directories diff --git a/bootloaders/artemis/!artemis_svl/gcc/artemis_svl_gcc.ld b/bootloaders/artemis/!artemis_svl/gcc/artemis_svl_gcc.ld deleted file mode 100644 index 2d820694..00000000 --- a/bootloaders/artemis/!artemis_svl/gcc/artemis_svl_gcc.ld +++ /dev/null @@ -1,79 +0,0 @@ -/****************************************************************************** - * - * artemis_svl_gcc.ld - Linker script for the artemis svl (provides _sbrk for vsnprintf) - * - *****************************************************************************/ -ENTRY(Reset_Handler) - -MEMORY -{ - FLASH (rx) : ORIGIN = 0x0000C000, LENGTH = 960K - SRAM (rwx) : ORIGIN = 0x10000000, LENGTH = 384K -} - -SECTIONS -{ - .text : - { - . = ALIGN(4); - KEEP(*(.isr_vector)) - KEEP(*(.patch)) - *(.text) - *(.text*) - *(.rodata) - *(.rodata*) - -/* - . = ALIGN(4); - __init_array_start = .; - KEEP(*(.init_array)) C++ constructors - KEEP(*(.ctors)) and vtable init - __init_array_end = .; -*/ - - _etext = .; - } > FLASH - - /* User stack section initialized by startup code. */ - .stack (NOLOAD): - { - . = ALIGN(8); - *(.stack) - *(.stack*) - . = ALIGN(8); - } > SRAM - - .data : - { - . = ALIGN(4); - _sdata = .; - *(.data) - *(.data*) - . = ALIGN(4); - _edata = .; - } > SRAM AT>FLASH - - /* used by startup to initialize data */ - _init_data = LOADADDR(.data); - - .bss : - { - . = ALIGN(4); - _sbss = .; - *(.bss) - *(.bss*) - *(COMMON) - . = ALIGN(4); - _ebss = .; - } > SRAM - - .heap (COPY): - { - __end__ = .; - PROVIDE(end = .); - *(.heap*) - __HeapLimit = .; - } > SRAM - - .ARM.attributes 0 : { *(.ARM.attributes) } -} \ No newline at end of file diff --git a/bootloaders/artemis/!artemis_svl/gcc/startup_gcc.c b/bootloaders/artemis/!artemis_svl/gcc/startup_gcc.c deleted file mode 100644 index f67a8de9..00000000 --- a/bootloaders/artemis/!artemis_svl/gcc/startup_gcc.c +++ /dev/null @@ -1,350 +0,0 @@ -//***************************************************************************** -// -//! @file startup_gcc.c -//! -//! @brief Definitions for interrupt handlers, the vector table, and the stack. -// -//***************************************************************************** - -//***************************************************************************** -// -// Copyright (c) 2019, Ambiq Micro -// All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are met: -// -// 1. Redistributions of source code must retain the above copyright notice, -// this list of conditions and the following disclaimer. -// -// 2. Redistributions in binary form must reproduce the above copyright -// notice, this list of conditions and the following disclaimer in the -// documentation and/or other materials provided with the distribution. -// -// 3. Neither the name of the copyright holder nor the names of its -// contributors may be used to endorse or promote products derived from this -// software without specific prior written permission. -// -// Third party software included in this distribution is subject to the -// additional license terms as defined in the /docs/licenses directory. -// -// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -// POSSIBILITY OF SUCH DAMAGE. -// -// This is part of revision 2.1.0 of the AmbiqSuite Development Package. -// -//***************************************************************************** - -#include - -//***************************************************************************** -// -// Forward declaration of interrupt handlers. -// -//***************************************************************************** -extern void Reset_Handler(void) __attribute ((naked)); -extern void NMI_Handler(void) __attribute ((weak)); -extern void HardFault_Handler(void) __attribute ((weak)); -extern void MemManage_Handler(void) __attribute ((weak, alias ("HardFault_Handler"))); -extern void BusFault_Handler(void) __attribute ((weak, alias ("HardFault_Handler"))); -extern void UsageFault_Handler(void) __attribute ((weak, alias ("HardFault_Handler"))); -extern void SecureFault_Handler(void) __attribute ((weak)); -extern void SVC_Handler(void) __attribute ((weak, alias ("am_default_isr"))); -extern void DebugMon_Handler(void) __attribute ((weak, alias ("am_default_isr"))); -extern void PendSV_Handler(void) __attribute ((weak, alias ("am_default_isr"))); -extern void SysTick_Handler(void) __attribute ((weak, alias ("am_default_isr"))); - -extern void am_brownout_isr(void) __attribute ((weak, alias ("am_default_isr"))); -extern void am_watchdog_isr(void) __attribute ((weak, alias ("am_default_isr"))); -extern void am_rtc_isr(void) __attribute ((weak, alias ("am_default_isr"))); -extern void am_vcomp_isr(void) __attribute ((weak, alias ("am_default_isr"))); -extern void am_ioslave_ios_isr(void) __attribute ((weak, alias ("am_default_isr"))); -extern void am_ioslave_acc_isr(void) __attribute ((weak, alias ("am_default_isr"))); -extern void am_iomaster0_isr(void) __attribute ((weak, alias ("am_default_isr"))); -extern void am_iomaster1_isr(void) __attribute ((weak, alias ("am_default_isr"))); -extern void am_iomaster2_isr(void) __attribute ((weak, alias ("am_default_isr"))); -extern void am_iomaster3_isr(void) __attribute ((weak, alias ("am_default_isr"))); -extern void am_iomaster4_isr(void) __attribute ((weak, alias ("am_default_isr"))); -extern void am_iomaster5_isr(void) __attribute ((weak, alias ("am_default_isr"))); -extern void am_ble_isr(void) __attribute ((weak, alias ("am_default_isr"))); -extern void am_gpio_isr(void) __attribute ((weak, alias ("am_default_isr"))); -extern void am_ctimer_isr(void) __attribute ((weak, alias ("am_default_isr"))); -extern void am_uart_isr(void) __attribute ((weak, alias ("am_default_isr"))); -extern void am_uart1_isr(void) __attribute ((weak, alias ("am_default_isr"))); -extern void am_scard_isr(void) __attribute ((weak, alias ("am_default_isr"))); -extern void am_adc_isr(void) __attribute ((weak, alias ("am_default_isr"))); -extern void am_pdm0_isr(void) __attribute ((weak, alias ("am_default_isr"))); -extern void am_mspi0_isr(void) __attribute ((weak, alias ("am_default_isr"))); -extern void am_software0_isr(void) __attribute ((weak, alias ("am_default_isr"))); -extern void am_stimer_isr(void) __attribute ((weak, alias ("am_default_isr"))); -extern void am_stimer_cmpr0_isr(void) __attribute ((weak, alias ("am_default_isr"))); -extern void am_stimer_cmpr1_isr(void) __attribute ((weak, alias ("am_default_isr"))); -extern void am_stimer_cmpr2_isr(void) __attribute ((weak, alias ("am_default_isr"))); -extern void am_stimer_cmpr3_isr(void) __attribute ((weak, alias ("am_default_isr"))); -extern void am_stimer_cmpr4_isr(void) __attribute ((weak, alias ("am_default_isr"))); -extern void am_stimer_cmpr5_isr(void) __attribute ((weak, alias ("am_default_isr"))); -extern void am_stimer_cmpr6_isr(void) __attribute ((weak, alias ("am_default_isr"))); -extern void am_stimer_cmpr7_isr(void) __attribute ((weak, alias ("am_default_isr"))); -extern void am_clkgen_isr(void) __attribute ((weak, alias ("am_default_isr"))); - -extern void am_default_isr(void) __attribute ((weak)); - -//***************************************************************************** -// -// The entry point for the application. -// -//***************************************************************************** -extern int main(void); - -//***************************************************************************** -// -// Reserve space for the system stack. -// -//***************************************************************************** -__attribute__ ((section(".stack"))) -static uint32_t g_pui32Stack[1024]; - -//***************************************************************************** -// -// The vector table. Note that the proper constructs must be placed on this to -// ensure that it ends up at physical address 0x0000.0000. -// -// Note: Aliasing and weakly exporting am_mpufault_isr, am_busfault_isr, and -// am_usagefault_isr does not work if am_fault_isr is defined externally. -// Therefore, we'll explicitly use am_fault_isr in the table for those vectors. -// -//***************************************************************************** -__attribute__ ((section(".isr_vector"))) -void (* const g_am_pfnVectors[])(void) = -{ - (void (*)(void))((uint32_t)g_pui32Stack + sizeof(g_pui32Stack)), - // The initial stack pointer - Reset_Handler, // The reset handler - NMI_Handler, // The NMI handler - HardFault_Handler, // The hard fault handler - HardFault_Handler, // The MemManage_Handler - HardFault_Handler, // The BusFault_Handler - HardFault_Handler, // The UsageFault_Handler - SecureFault_Handler, // The SecureFault_Handler - 0, // Reserved - 0, // Reserved - 0, // Reserved - SVC_Handler, // SVCall handler - DebugMon_Handler, // Debug monitor handler - 0, // Reserved - PendSV_Handler, // The PendSV handler - SysTick_Handler, // The SysTick handler - - // - // Peripheral Interrupts - // - am_brownout_isr, // 0: Brownout (rstgen) - am_watchdog_isr, // 1: Watchdog - am_rtc_isr, // 2: RTC - am_vcomp_isr, // 3: Voltage Comparator - am_ioslave_ios_isr, // 4: I/O Slave general - am_ioslave_acc_isr, // 5: I/O Slave access - am_iomaster0_isr, // 6: I/O Master 0 - am_iomaster1_isr, // 7: I/O Master 1 - am_iomaster2_isr, // 8: I/O Master 2 - am_iomaster3_isr, // 9: I/O Master 3 - am_iomaster4_isr, // 10: I/O Master 4 - am_iomaster5_isr, // 11: I/O Master 5 - am_ble_isr, // 12: BLEIF - am_gpio_isr, // 13: GPIO - am_ctimer_isr, // 14: CTIMER - am_uart_isr, // 15: UART0 - am_uart1_isr, // 16: UART1 - am_scard_isr, // 17: SCARD - am_adc_isr, // 18: ADC - am_pdm0_isr, // 19: PDM - am_mspi0_isr, // 20: MSPI - am_software0_isr, // 21: SOFTWARE0 - am_stimer_isr, // 22: SYSTEM TIMER - am_stimer_cmpr0_isr, // 23: SYSTEM TIMER COMPARE0 - am_stimer_cmpr1_isr, // 24: SYSTEM TIMER COMPARE1 - am_stimer_cmpr2_isr, // 25: SYSTEM TIMER COMPARE2 - am_stimer_cmpr3_isr, // 26: SYSTEM TIMER COMPARE3 - am_stimer_cmpr4_isr, // 27: SYSTEM TIMER COMPARE4 - am_stimer_cmpr5_isr, // 28: SYSTEM TIMER COMPARE5 - am_stimer_cmpr6_isr, // 29: SYSTEM TIMER COMPARE6 - am_stimer_cmpr7_isr, // 30: SYSTEM TIMER COMPARE7 - am_clkgen_isr, // 31: CLKGEN -}; - -//****************************************************************************** -// -// Place code immediately following vector table. -// -//****************************************************************************** -//****************************************************************************** -// -// The Patch table. -// -//****************************************************************************** -__attribute__ ((section(".patch"))) -uint32_t const __Patchable[] = -{ - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, - 0, -}; - -//***************************************************************************** -// -// The following are constructs created by the linker, indicating where the -// the "data" and "bss" segments reside in memory. The initializers for the -// "data" segment resides immediately following the "text" segment. -// -//***************************************************************************** -extern uint32_t _etext; -extern uint32_t _sdata; -extern uint32_t _edata; -extern uint32_t _sbss; -extern uint32_t _ebss; - -//***************************************************************************** -// -// This is the code that gets called when the processor first starts execution -// following a reset event. Only the absolutely necessary set is performed, -// after which the application supplied entry() routine is called. -// -//***************************************************************************** -#if defined(__GNUC_STDC_INLINE__) -void -Reset_Handler(void) -{ - // - // Set the vector table pointer. - // - __asm(" ldr r0, =0xE000ED08\n" - " ldr r1, =g_am_pfnVectors\n" - " str r1, [r0]"); - - // - // Set the stack pointer. - // - __asm(" ldr sp, [r1]"); -#ifndef NOFPU - // - // Enable the FPU. - // - __asm("ldr r0, =0xE000ED88\n" - "ldr r1,[r0]\n" - "orr r1,#(0xF << 20)\n" - "str r1,[r0]\n" - "dsb\n" - "isb\n"); -#endif - // - // Copy the data segment initializers from flash to SRAM. - // - __asm(" ldr r0, =_init_data\n" - " ldr r1, =_sdata\n" - " ldr r2, =_edata\n" - "copy_loop:\n" - " ldr r3, [r0], #4\n" - " str r3, [r1], #4\n" - " cmp r1, r2\n" - " blt copy_loop\n"); - // - // Zero fill the bss segment. - // - __asm(" ldr r0, =_sbss\n" - " ldr r1, =_ebss\n" - " mov r2, #0\n" - "zero_loop:\n" - " cmp r0, r1\n" - " it lt\n" - " strlt r2, [r0], #4\n" - " blt zero_loop"); - - // - // Call the application's entry point. - // - main(); - - // - // If main returns then execute a break point instruction - // - __asm(" bkpt "); -} -#else -#error GNU STDC inline not supported. -#endif - -//***************************************************************************** -// -// This is the code that gets called when the processor receives a NMI. This -// simply enters an infinite loop, preserving the system state for examination -// by a debugger. -// -//***************************************************************************** -void -NMI_Handler(void) -{ - // - // Go into an infinite loop. - // - while(1) - { - } -} - -//***************************************************************************** -// -// This is the code that gets called when the processor receives a fault -// interrupt. This simply enters an infinite loop, preserving the system state -// for examination by a debugger. -// -//***************************************************************************** -void -HardFault_Handler(void) -{ - // - // Go into an infinite loop. - // - while(1) - { - } -} - -//***************************************************************************** -// -// This is the code that gets called when the processor receives an unexpected -// interrupt. This simply enters an infinite loop, preserving the system state -// for examination by a debugger. -// -//***************************************************************************** -void -am_default_isr(void) -{ - // - // Go into an infinite loop. - // - while(1) - { - } -} diff --git a/bootloaders/artemis/!artemis_svl/src/main.c b/bootloaders/artemis/!artemis_svl/src/main.c deleted file mode 100644 index df05687c..00000000 --- a/bootloaders/artemis/!artemis_svl/src/main.c +++ /dev/null @@ -1,735 +0,0 @@ -//***************************************************************************** -// -//! @file main.c -//! -//! @brief A variable-baud rate bootloader for Apollo3 / Artemis module -//! -//! Purpose: -// -//***************************************************************************** - -/* -Copyright (c) 2019 SparkFun Electronics - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -*/ - -/* - -Authors: -Owen Lyke, Nathan Seidle - -Modified: Juy 22 2019 - -*/ - -//***************************************************************************** -// -// Includes -// -//***************************************************************************** -#include "am_mcu_apollo.h" -#include "am_bsp.h" -#include "am_util.h" - -#include "stdint.h" - -#include "svl_ringbuf.h" -#include "svl_packet.h" -#include "svl_uart.h" -#include "svl_utils.h" - - -//***************************************************************************** -// -// Defines -// -//***************************************************************************** -#define SVL_VERSION_NUMBER 0x03 - - -// **************************************** -// -// Bootloader Options -// -// **************************************** -#define BL_UART_BUF_LEN (2048 + 512) // must be larger than maximum frame transmission length for guaranteed performance -#define BL_UART_INST 0 // which UART peripheral to use for BL data -#define BL_RX_PAD 49 // RX pad for BL_UART_INST -#define BL_TX_PAD 48 // TX pad for BL_UART_INST -#define USERCODE_OFFSET (0xC000 + 0x4000) // location in flash to begin storing user's code (Linker script needs to be adjusted to offset user's flash to this address) -#define FRAME_BUFFER_SIZE 512 // maximum number of 4-byte words that can be transmitted in a single frame packet - -// **************************************** -// -// Debug Options -// -// **************************************** - -// #define DEBUG 1 // uncomment to enable debug output - -#ifdef DEBUG -#define DEBUG_BAUD_RATE 921600 // debug output baud rate -#define DEBUG_UART_INST 1 // debug UART peripheral instance (should not be the same as BL_UART_INST) -#define DEBUG_RX_PAD 25 // RX pad for -#define DEBUG_TX_PAD 24 -#define DEBUG_UART_BUF_LEN 256 -#define DEBUG_PRINT_APP 1 // undefine to not print app pages -#define APP_PRINT_NUM_PAGE 1 -#undef APP_PRINT_PRETTY // define APP_PRINT_PRETTY for the alternate app data print format -uint8_t debug_buffer[DEBUG_UART_BUF_LEN] = {0}; -#endif // DEBUG - - - -// **************************************** -// -// Bootloader Commands -// -// **************************************** -#define CMD_VERSION (0x01) -#define CMD_BLMODE (0x02) -#define CMD_NEXT (0x03) -#define CMD_FRAME (0x04) -#define CMD_RETRY (0x05) -#define CMD_DONE (0x06) - - - - -//***************************************************************************** -// -// Macros -// -//***************************************************************************** -#define UART_GPIO_PINCONFIG_INNER( INST, TXRX, PAD ) { .uFuncSel = AM_HAL_PIN_ ## PAD ## _UART ## INST ## TXRX, .eDriveStrength = AM_HAL_GPIO_PIN_DRIVESTRENGTH_2MA } -#define UART_GPIO_PINCONFIG( INST, TXRX, PAD ) UART_GPIO_PINCONFIG_INNER( INST, TXRX, PAD ) - - - -//***************************************************************************** -// -// Forward Declarations -// -//***************************************************************************** -void setup ( void ); -bool detect_baud_rate ( uint32_t* baud ); -void start_uart_bl ( uint32_t baud ); -void enter_bootload ( void ); -uint8_t handle_frame_packet ( svl_packet_t* packet, uint32_t* p_frame_address, uint16_t* p_last_page_erased ); -void app_start ( void ); -void debug_printf ( char* fmt, ... ); - - - - -//***************************************************************************** -// -// Globals -// -//***************************************************************************** -art_svl_ringbuf_t bl_rx_ringbuf = { - .buf = NULL, - .len = 0, - .r_offset = 0, - .w_offset = 0, -}; -void* hUART_bl = NULL; // pointer to handle for bootloader UART -void* hUART_debug = NULL; // pointer to handle for debug UART - -#define BL_BAUD_SAMPLES (5) -volatile uint8_t bl_baud_ticks_index = 0x00; -volatile uint32_t bl_baud_ticks[BL_BAUD_SAMPLES] = {0}; - - - - - -//***************************************************************************** -// -// Main -// -//***************************************************************************** -int main(void){ - - bool baud_valid = false; - uint32_t bl_baud = 0x00; - uint8_t bl_buffer[BL_UART_BUF_LEN] = {0}; - - #define PLLEN_VER 1 - uint8_t packet_ver_buf[PLLEN_VER] = {SVL_VERSION_NUMBER}; - svl_packet_t svl_packet_version = { CMD_VERSION, packet_ver_buf, PLLEN_VER, PLLEN_VER }; - svl_packet_t svl_packet_blmode = { CMD_BLMODE, NULL, 0, 0 }; - - art_svl_ringbuf_init( &bl_rx_ringbuf, bl_buffer, BL_UART_BUF_LEN ); - setup(); - - debug_printf("\n\nArtemis SVL Bootloader - DEBUG\n\n"); - - baud_valid = detect_baud_rate( &bl_baud ); // Detects the baud rate. Returns true if a valid baud rate was found - if( baud_valid == false ){ - app_start(); // w/o valid baud rate jump t the app - } - - start_uart_bl( bl_baud ); // This will create a 23 us wide low 'blip' on the TX line (until possibly fixed) - am_util_delay_us(200); // At the minimum baud rate of 115200 one byte (10 bits with start/stop) takes 10/115200 or 87 us. 87+23 = 100, double to be safe - - debug_printf("phase:\tconfirm bootloading entry\n"); - debug_printf("\tsending Artemis SVL version packet\n"); - svl_packet_send( &svl_packet_version ); // when baud rate is determined send the version packet - - debug_printf("\twaiting for bootloader confirmation\n"); - if(svl_packet_wait( &svl_packet_blmode ) != 0){ // wait for the bootloader to confirm bootloader mode entry - debug_printf("\tno confirmation received\n"); - app_start(); // break to app - } - debug_printf("\tentering bootloader\n\n"); - - enter_bootload(); // Now we are locked in - am_util_delay_ms(10); - - am_hal_reset_control(AM_HAL_RESET_CONTROL_SWPOI, 0); //Cause a system Power On Init to release as much of the stack as possible - - debug_printf("ERROR - runoff"); - while (1){ // Loop forever while sleeping. - am_hal_sysctrl_sleep(AM_HAL_SYSCTRL_SLEEP_DEEP); // Go to Deep Sleep. - } -} - - - - - -//***************************************************************************** -// -// Function definitions below -// -//***************************************************************************** - - - - - -#ifdef DEBUG -void start_uart_debug( void ){ - const am_hal_gpio_pincfg_t debug_uart_tx_pinconfig = UART_GPIO_PINCONFIG( DEBUG_UART_INST, TX, DEBUG_TX_PAD ); - const am_hal_gpio_pincfg_t debug_uart_rx_pinconfig = UART_GPIO_PINCONFIG( DEBUG_UART_INST, RX, DEBUG_RX_PAD ); - const am_hal_uart_config_t debug_uart_config = { - // Standard UART settings: 115200-8-N-1 - .ui32BaudRate = DEBUG_BAUD_RATE, - .ui32DataBits = AM_HAL_UART_DATA_BITS_8, - .ui32Parity = AM_HAL_UART_PARITY_NONE, - .ui32StopBits = AM_HAL_UART_ONE_STOP_BIT, - .ui32FlowControl = AM_HAL_UART_FLOW_CTRL_NONE, - - // Set TX and RX FIFOs to interrupt at half-full. - .ui32FifoLevels = (AM_HAL_UART_TX_FIFO_1_2 | - AM_HAL_UART_RX_FIFO_1_2), - - // Buffers - .pui8TxBuffer = NULL, - .ui32TxBufferSize = 0, - .pui8RxBuffer = NULL, - .ui32RxBufferSize = 0, - }; - - // Initialize the printf interface for UART output. - am_hal_uart_initialize(DEBUG_UART_INST, &hUART_debug); - am_hal_uart_power_control(hUART_debug, AM_HAL_SYSCTRL_WAKE, false); - am_hal_uart_configure(hUART_debug, &debug_uart_config); - - // Disable that pesky FIFO - UARTn(DEBUG_UART_INST)->LCRH_b.FEN = 0; - - // Enable the UART pins. - am_hal_gpio_pinconfig(DEBUG_TX_PAD, debug_uart_tx_pinconfig); - am_hal_gpio_pinconfig(DEBUG_RX_PAD, debug_uart_rx_pinconfig); - - // Enable interrupts. - NVIC_EnableIRQ((IRQn_Type)(UART0_IRQn + DEBUG_UART_INST)); - am_hal_uart_interrupt_enable(hUART_debug, (AM_HAL_UART_INT_RX)); -} -#endif // DEBUG - - -//***************************************************************************** -// -// Setup -// -//***************************************************************************** -void setup( void ){ - // Set the clock frequency. - am_hal_clkgen_control(AM_HAL_CLKGEN_CONTROL_SYSCLK_MAX, 0); - - // Set the default cache configuration - am_hal_cachectrl_config(&am_hal_cachectrl_defaults); - am_hal_cachectrl_enable(); - - // Configure the stimer - am_hal_stimer_int_enable(AM_HAL_STIMER_INT_OVERFLOW); - NVIC_EnableIRQ(STIMER_IRQn); - am_hal_stimer_config(AM_HAL_STIMER_CFG_CLEAR | AM_HAL_STIMER_CFG_FREEZE); - am_hal_stimer_config(AM_HAL_STIMER_HFRC_3MHZ); - -#ifdef DEBUG - start_uart_debug(); -#endif - - // Enable interrupts. - am_hal_interrupt_master_enable(); -} - - -// //***************************************************************************** -// // -// // Un-set-up -// // -// //***************************************************************************** -// void unsetup( void ){ -// // Set the clock frequency. -// am_hal_clkgen_control(AM_HAL_CLKGEN_CONTROL_SYSCLK_MAX, 0); - -// // Set the default cache configuration -// am_hal_cachectrl_config(&am_hal_cachectrl_defaults); -// am_hal_cachectrl_enable(); - -// // Configure the stimer -// am_hal_stimer_int_enable(AM_HAL_STIMER_INT_OVERFLOW); -// NVIC_EnableIRQ(STIMER_IRQn); -// am_hal_stimer_config(AM_HAL_STIMER_CFG_CLEAR | AM_HAL_STIMER_CFG_FREEZE); -// am_hal_stimer_config(AM_HAL_STIMER_HFRC_3MHZ); - -// #ifdef DEBUG -// start_uart_debug(); -// #endif - -// // Enable interrupts. -// am_hal_interrupt_master_enable(); -// } - - -// **************************************** -// -// Baud Rate Detect Phase -// -// **************************************** -bool detect_baud_rate( uint32_t* baud ){ - uint32_t bl_entry_timeout_ms = 200; - uint32_t bl_entry_timeout_start = millis(); - bool baud_is_valid = false; - bool timed_out = true; - - debug_printf("phase:\tdetect baud rate\n"); - - enable_burst_mode(); - - am_hal_gpio_pinconfig(BL_RX_PAD, g_AM_HAL_GPIO_INPUT_PULLUP); - - ap3_gpio_enable_interrupts(BL_RX_PAD, AM_HAL_GPIO_PIN_INTDIR_LO2HI); - am_hal_gpio_interrupt_clear(AM_HAL_GPIO_BIT(BL_RX_PAD)); - am_hal_gpio_interrupt_enable(AM_HAL_GPIO_BIT(BL_RX_PAD)); - NVIC_EnableIRQ(GPIO_IRQn); - - while( (millis() - bl_entry_timeout_start) < bl_entry_timeout_ms ){ - // try to detect baud rate - - // debug_printf("\ttime (ms):\t%d\n", millis()); - - if( bl_baud_ticks_index == BL_BAUD_SAMPLES ){ - - // compute differences between samples - for(uint8_t indi = 0; indi < (BL_BAUD_SAMPLES-1); indi++){ - bl_baud_ticks[indi] = bl_baud_ticks[indi+1]-bl_baud_ticks[indi]; - } - - float mean = 0.0; - for(uint8_t indi = 0; indi < (BL_BAUD_SAMPLES-1); indi++){ - mean += bl_baud_ticks[indi]; - } - mean /= (BL_BAUD_SAMPLES-1); - - - if( mean < 3 ){ - // invalid - }else if( ( mean >= 4) && ( mean <= 8) ){ - *baud = 921600; - baud_is_valid = true; - }else if( ( mean >= 10) && ( mean <= 14) ){ - *baud = 460800; - baud_is_valid = true; - }else if( ( mean >= 25) && ( mean <= 30) ){ - *baud = 230400; - baud_is_valid = true; - }else if( ( mean >= 45) && ( mean <= 55) ){ - *baud = 115200; - baud_is_valid = true; - }else if( ( mean >= 91) && ( mean <= 111) ){ - *baud = 57600; - baud_is_valid = true; - }else{ - // invalid - } - - if(baud_is_valid){ - timed_out = false; - } - - break; // exit the timeout loop - } - } - - am_hal_gpio_interrupt_disable(AM_HAL_GPIO_BIT(BL_RX_PAD)); - am_hal_gpio_interrupt_clear(AM_HAL_GPIO_BIT(BL_RX_PAD)); - NVIC_DisableIRQ(GPIO_IRQn); - - disable_burst_mode(); - - -#ifdef DEBUG - // show differences for debugging purposes - debug_printf("\ttiming differences: { "); - for(uint8_t indi = 0; indi < (BL_BAUD_SAMPLES-1); indi++){ - debug_printf("%d", bl_baud_ticks[indi] ); - if( indi < (BL_BAUD_SAMPLES - 2) ){ - debug_printf(", "); - } - } - debug_printf("}\n"); -#endif // DEBUG - - if(!baud_is_valid){ - debug_printf("\tbaud rate not detected.\n\t\trising edges:\t%d\n\t\ttimed out:\t%d\n\n", bl_baud_ticks_index, timed_out); - }else{ - debug_printf("\tdetected valid baud rate:\t%d\n\n", *baud); - } - - return baud_is_valid; -} - - - -//***************************************************************************** -// -// Start BL UART at desired baud -// -//***************************************************************************** -void start_uart_bl( uint32_t baud ){ - const am_hal_gpio_pincfg_t bl_uart_tx_pinconfig = UART_GPIO_PINCONFIG( BL_UART_INST, TX, BL_TX_PAD ); - const am_hal_gpio_pincfg_t bl_uart_rx_pinconfig = UART_GPIO_PINCONFIG( BL_UART_INST, RX, BL_RX_PAD ); - am_hal_uart_config_t bl_uart_config = - { - // Standard UART settings: 115200-8-N-1 - .ui32BaudRate = baud, - .ui32DataBits = AM_HAL_UART_DATA_BITS_8, - .ui32Parity = AM_HAL_UART_PARITY_NONE, - .ui32StopBits = AM_HAL_UART_ONE_STOP_BIT, - .ui32FlowControl = AM_HAL_UART_FLOW_CTRL_NONE, - - // Set TX and RX FIFOs to interrupt at half-full. - .ui32FifoLevels = (AM_HAL_UART_TX_FIFO_1_2 | - AM_HAL_UART_RX_FIFO_1_2), - - // Buffers - .pui8TxBuffer = NULL, - .ui32TxBufferSize = 0, - .pui8RxBuffer = NULL, - .ui32RxBufferSize = 0, - }; - - // Initialize the printf interface for UART output. - am_hal_uart_initialize(BL_UART_INST, &hUART_bl); - am_hal_uart_power_control(hUART_bl, AM_HAL_SYSCTRL_WAKE, false); - am_hal_uart_configure(hUART_bl, &bl_uart_config); - - // Disable that pesky FIFO - UARTn(BL_UART_INST)->LCRH_b.FEN = 0; - - // Enable the UART pins. - am_hal_gpio_pinconfig(BL_TX_PAD, bl_uart_tx_pinconfig); - am_hal_gpio_pinconfig(BL_RX_PAD, bl_uart_rx_pinconfig); - - // Enable interrupts. - NVIC_EnableIRQ((IRQn_Type)(UART0_IRQn + BL_UART_INST)); - am_hal_uart_interrupt_enable(hUART_bl, (AM_HAL_UART_INT_RX)); - - // Provide SVL Packet interfaces - svl_packet_link_read_fn ( art_svl_ringbuf_read, &bl_rx_ringbuf ); - svl_packet_link_avail_fn ( art_svl_ringbuf_available, &bl_rx_ringbuf ); - svl_packet_link_millis_fn ( millis ); - svl_packet_link_write_fn ( svl_uart_write_byte, hUART_bl ); -} - - - -// **************************************** -// -// Bootload phase -// -// **************************************** -void enter_bootload( void ){ - - bool done = false; - uint32_t frame_address = 0; - uint16_t last_page_erased = 0; - uint8_t retransmit = 0; - static uint32_t frame_buffer[FRAME_BUFFER_SIZE]; - - svl_packet_t svl_packet_incoming_frame = { CMD_FRAME, (uint8_t*)frame_buffer, sizeof(frame_buffer)/sizeof(uint8_t), sizeof(frame_buffer)/sizeof(uint8_t) }; - svl_packet_t svl_packet_retry = { CMD_RETRY, NULL, 0, 0 }; - svl_packet_t svl_packet_next = { CMD_NEXT, NULL, 0, 0 }; - - debug_printf("phase:\tbootload\n"); - - while(!done){ - - if(retransmit != 0){ - debug_printf("\trequesting retransmission\n"); - svl_packet_send( (svl_packet_t*)&svl_packet_retry ); // Ask to retransmit - }else{ - debug_printf("\trequesting next app frame\n"); - svl_packet_send( (svl_packet_t*)&svl_packet_next ); // Ask for the next frame packet - } - retransmit = 0; - - uint8_t stat = svl_packet_wait( &svl_packet_incoming_frame ); - if( stat != 0 ){ // wait for either a frame or the done command - debug_printf("\t\terror receiving packet (%d)\n", stat); - retransmit = 1; - continue; - } - - // debug_printf("Successfully received incoming frame packet (todo: add extra details in debug)\n", stat); - - if( svl_packet_incoming_frame.cmd == CMD_FRAME ){ - debug_printf("\t\treceived an app frame\n"); - if( handle_frame_packet( &svl_packet_incoming_frame, &frame_address, &last_page_erased ) != 0 ){ - // debug_printf("\t\t\tbootload error - packet could not be handled\n"); - retransmit = 1; - continue; - } - }else if( svl_packet_incoming_frame.cmd == CMD_DONE ){ - debug_printf("\t\treceived done signal!\n\n"); - done = true; - }else{ - debug_printf("bootload error - unknown command\n"); - retransmit = 1; - continue; - } - } - - // finish bootloading -} - - - -// **************************************** -// -// Handle a frame packet -// -// **************************************** -uint8_t handle_frame_packet(svl_packet_t* packet, uint32_t* p_frame_address, uint16_t* p_last_page_erased ){ - - // debug_printf("\t\thandling frame\n"); - - uint32_t num_words = (packet->pl_len / 4); - int32_t i32ReturnCode = 0; - - debug_printf("\t\tframe_address = 0x%08X, num_words = %d\n", *(p_frame_address), num_words); - - // Check payload length is multiple of words - if( (packet->pl_len % 4) ){ - debug_printf("Error: frame packet not integer multiple of words (4 bytes per word)\n"); - return 1; - } - - uint32_t offset_address = (*(p_frame_address) + USERCODE_OFFSET); - if ( (*p_last_page_erased) < AM_HAL_FLASH_ADDR2PAGE( offset_address ) ) { // Prevent erasing partially-filled pages - // debug_printf("Erasing instance %d, page %d\n\r", AM_HAL_FLASH_ADDR2INST( offset_address ), AM_HAL_FLASH_ADDR2PAGE(offset_address) ); - - //Erase the 8k page for this address - i32ReturnCode = am_hal_flash_page_erase(AM_HAL_FLASH_PROGRAM_KEY, AM_HAL_FLASH_ADDR2INST( offset_address ), AM_HAL_FLASH_ADDR2PAGE( offset_address ) ); - *(p_last_page_erased) = AM_HAL_FLASH_ADDR2PAGE( offset_address ); - - if (i32ReturnCode) - { - debug_printf("FLASH_MASS_ERASE i32ReturnCode = 0x%x.\n\r", i32ReturnCode); - } - } - - // //Record the array - // debug_printf("Recording %d words (%d bytes) to memory\n", num_words, 4*num_words); - i32ReturnCode = am_hal_flash_program_main(AM_HAL_FLASH_PROGRAM_KEY, (uint32_t*)packet->pl, (uint32_t*)(*(p_frame_address) + USERCODE_OFFSET), num_words); - if (i32ReturnCode){ - debug_printf("FLASH_WRITE error = 0x%x.\n\r", i32ReturnCode); - return 1; - } - - // debug_printf("Array recorded to flash\n"); - *(p_frame_address) += num_words*4; - return 0; -} - - - -// **************************************** -// -// Jump to the application -// -// **************************************** -void app_start( void ){ -// debug_printf("\n\t-- app start --\n"); -// #ifdef DEBUG -// #ifdef DEBUG_PRINT_APP -// uint32_t start_address = USERCODE_OFFSET; // Print a section of flash -// debug_printf("Printing page starting at offset 0x%04X\n", start_address); -// #ifdef APP_PRINT_PRETTY -// for (uint16_t x = 0; x < 512*APP_PRINT_NUM_PAGE; x++){ -// if (x % 8 == 0){ -// debug_printf("\nAdr: 0x%04X", start_address + (x * 4)); -// } -// debug_printf(" 0x%08X", *(uint32_t *)(start_address + (x * 4))); -// } -// debug_printf("\n"); -// #else -// for (uint16_t x = 0; x < 512*APP_PRINT_NUM_PAGE; x++){ -// if (x % 4 == 0){ -// debug_printf("\n"); -// } -// uint32_t wor = *(uint32_t *)(start_address + (x * 4)); -// debug_printf("%02x%02x %02x%02x", (wor & 0x000000FF), (wor & 0x0000FF00) >> 8, (wor & 0x00FF0000) >> 16, (wor & 0xFF000000) >> 24 ); -// if( (x%4) != 3 ){ -// debug_printf(" "); -// } -// } -// debug_printf("\n"); -// #endif // APP_PRINT_PRETTY -// #endif // DEBUG_PRINT_APP -// #endif // DEBUG - - // unsetup(); // todo: - - void* entryPoint = (void *)(*((uint32_t*)(USERCODE_OFFSET + 4))); - debug_printf("\nJump to App at 0x%08X\n\n", (uint32_t)entryPoint); - am_util_delay_ms(10); // Wait for prints to complete - goto *entryPoint; // Jump to start of user code -} - - - - - - -// **************************************** -// -// Debug printf function -// -// **************************************** -void debug_printf(char* fmt, ...){ -#ifdef DEBUG - char debug_buffer [DEBUG_UART_BUF_LEN]; - va_list args; - va_start (args, fmt); - vsnprintf(debug_buffer, DEBUG_UART_BUF_LEN, (const char*)fmt, args); - va_end (args); - - svl_uart_print(hUART_debug, debug_buffer); -#endif //DEBUG -} - - - -//***************************************************************************** -// -// UART interrupt handlers -// -//***************************************************************************** -void am_uart_isr(void){ - // Service the FIFOs as necessary, and clear the interrupts. -#if BL_UART_INST == 0 - uint32_t ui32Status, ui32Idle; - am_hal_uart_interrupt_status_get(hUART_bl, &ui32Status, true); - am_hal_uart_interrupt_clear(hUART_bl, ui32Status); - am_hal_uart_interrupt_service(hUART_bl, ui32Status, &ui32Idle); - if (ui32Status & AM_HAL_UART_INT_RX) - { - uint8_t c = 0x00; - if ( svl_uart_read( hUART_bl, (char*)&c, 1) != 0 ){ - art_svl_ringbuf_write( &bl_rx_ringbuf, c ); - } - } -#else -#ifdef DEBUG - am_hal_uart_interrupt_status_get(hUART_debug, &ui32Status, true); - am_hal_uart_interrupt_clear(hUART_debug, ui32Status); - am_hal_uart_interrupt_service(hUART_debug, ui32Status, &ui32Idle); -#endif // DEBUG -#endif // BL_UART_INST == 0 -} - -void am_uart1_isr(void){ - // Service the FIFOs as necessary, and clear the interrupts. -#if BL_UART_INST == 1 - uint32_t ui32Status, ui32Idle; - am_hal_uart_interrupt_status_get(hUART_bl, &ui32Status, true); - am_hal_uart_interrupt_clear(hUART_bl, ui32Status); - am_hal_uart_interrupt_service(hUART_bl, ui32Status, &ui32Idle); - if (ui32Status & AM_HAL_UART_INT_RX) - { - uint8_t c = 0x00; - if ( read( hUART_bl, &c, 1) != 0 ){ - art_svl_ringbuf_write( &bl_rx_ringbuf, c ); - } - } -#else -#ifdef DEBUG - uint32_t ui32Status, ui32Idle; - am_hal_uart_interrupt_status_get(hUART_debug, &ui32Status, true); - am_hal_uart_interrupt_clear(hUART_debug, ui32Status); - am_hal_uart_interrupt_service(hUART_debug, ui32Status, &ui32Idle); -#endif // DEBUG -#endif // BL_UART_INST == 0 -} - - - -//***************************************************************************** -// -// GPIO interrupt handler -// -//***************************************************************************** -void am_gpio_isr( void ){ - am_hal_gpio_interrupt_clear(AM_HAL_GPIO_BIT(BL_RX_PAD)); - if( bl_baud_ticks_index < BL_BAUD_SAMPLES ){ - bl_baud_ticks[bl_baud_ticks_index++] = CTIMER->STTMR; - } -} - -//***************************************************************************** -// -// STimer interrupt handler -// -//***************************************************************************** -void am_stimer_isr(void) -{ - am_hal_stimer_int_clear(AM_HAL_STIMER_INT_OVERFLOW); - ap3_stimer_overflows += 1; - // At the fastest rate (3MHz) the 64 bits of the stimer - // along with this overflow counter can keep track of - // the time for ~ 195,000 years without wrapping to 0 -} \ No newline at end of file diff --git a/bootloaders/artemis/!artemis_svl/src/svl_packet/svl_packet.c b/bootloaders/artemis/!artemis_svl/src/svl_packet/svl_packet.c deleted file mode 100644 index 7256d2ed..00000000 --- a/bootloaders/artemis/!artemis_svl/src/svl_packet/svl_packet.c +++ /dev/null @@ -1,183 +0,0 @@ -#include "svl_packet.h" - -void* read_param = NULL; -void* write_param = NULL; -void* avail_param = NULL; - -svl_packet_read_byte_fn_t read_fn = NULL; -svl_packet_write_byte_fn_t write_fn = NULL; -svl_packet_avail_bytes_fn_t avail_fn = NULL; -svl_packet_millis_fn_t millis_fn = NULL; - -inline __attribute__((always_inline)) size_t svl_packet_read_byte( uint8_t* c ){ - size_t retval = 0x00; - if(read_fn != NULL){ retval = read_fn( read_param, c ); } - return retval; -} - -inline __attribute__((always_inline)) size_t svl_packet_write_byte( uint8_t c ){ - size_t retval = 0x00; - if(write_fn != NULL){ retval = write_fn( write_param, c ); } - return retval; -} - -inline __attribute__((always_inline)) size_t svl_packet_avail_bytes( void ){ - size_t retval = 0x00; - if(avail_fn != NULL){ retval = avail_fn( avail_param ); } - return retval; -} - -inline __attribute__((always_inline)) size_t svl_packet_millis( void ){ - size_t retval = 0x00; - if(millis_fn != NULL){ retval = millis_fn(); } - return retval; -} - -void svl_packet_link_read_fn (svl_packet_read_byte_fn_t fn, void* param){ - read_param = param; - read_fn = fn; -} - -void svl_packet_link_write_fn (svl_packet_write_byte_fn_t fn, void* param){ - write_param = param; - write_fn = fn; -} - -void svl_packet_link_avail_fn (svl_packet_avail_bytes_fn_t fn, void* param){ - avail_param = param; - avail_fn = fn; -} - -void svl_packet_link_millis_fn ( svl_packet_millis_fn_t fn ){ - millis_fn = fn; -} - - - - -void svl_packet_send(svl_packet_t* packet ){ - uint16_t crc = svl_packet_get_crc16(packet); - - svl_packet_write_byte( ((packet->pl_len + 3) >> 8) ); // len high byte (including command and CRC bytes) - svl_packet_write_byte( ((packet->pl_len + 3) & 0xFF) ); // len low byte (including command and CRC bytes) - - svl_packet_write_byte( (packet->cmd) ); // command byte - - if((packet->pl != NULL) && (packet->pl_len != 0)){ - for(uint16_t indi = 0; indi < packet->pl_len; indi++){ // payload - svl_packet_write_byte( *(packet->pl + indi) ); - } - } - - svl_packet_write_byte( (uint8_t)(crc >> 8) ); // CRC H - svl_packet_write_byte( (uint8_t)(crc & 0xFF) ); // CRC L -} - - - -uint8_t svl_packet_wait(svl_packet_t* packet ){ - - // wait for 2 bytes (the length bytes) - // wait for length bytes to come in - // make sure that 'length' bytes are enough to satisfy the desired payload length - - if(packet == NULL) { return (SVL_PACKET_ERR); } - - const uint8_t num_bytes_length = 2; - if(svl_packet_wait_bytes(num_bytes_length)) { return (SVL_PACKET_ERR_TIMEOUT | SVL_PACKET_LEN); } - uint16_t len = svl_packet_get_uint16_t(); - - if( len == 0 ) { return ( SVL_PACKET_ERR_ZLP ); } - if( (len-3) > packet->max_pl_len ) { return ( SVL_PACKET_ERR_MEM | SVL_PACKET_PL ); } - if(svl_packet_wait_bytes(len)) { return ( SVL_PACKET_ERR_TIMEOUT | SVL_PACKET_PL ); } - - svl_packet_read_byte( &packet->cmd ); - packet->pl_len = (len-3); - if((packet->pl != NULL) && (packet->max_pl_len != 0)){ - uint32_t indi = 0x00; - for( indi = 0; indi < packet->pl_len; indi++ ){ // Fill payload with data - svl_packet_read_byte( (packet->pl + indi) ); - } - for( ; indi < packet->max_pl_len; indi++ ){ // Zero out remaining bytes - *(packet->pl + indi) = 0x00; - } - } - - uint16_t crc = svl_packet_get_uint16_t(); - uint16_t check = svl_packet_get_crc16( packet ); - - if( crc != check ){ return (SVL_PACKET_ERR_CRC); } - - return (SVL_PACKET_OK); -} - - - -uint16_t svl_packet_get_uint16_t( void ){ - uint8_t h = 0x00; - uint8_t l = 0x00; - svl_packet_read_byte( &h ); - svl_packet_read_byte( &l ); - return (((uint16_t)h << 8) | (l & 0xFF)); -} - - - -uint8_t svl_packet_wait_bytes(uint32_t num){ - uint32_t timeout_ms = 500; - - uint32_t start = svl_packet_millis(); - uint32_t avail = 0; - while((svl_packet_millis() - start) < timeout_ms){ - avail = svl_packet_avail_bytes(); - if(avail >= num){ - return 0; - } - } - - // debug_printf("only got %d bytes...\n",avail); - return 1; -} - - - -uint16_t svl_packet_get_crc16(svl_packet_t* packet){ -// # Load the register with zero bits. -// # Augment the message by appending W zero bits to the end of it. -// # While (more message bits) -// # Begin -// # Shift the register left by one bit, reading the next bit of the -// # augmented message into register bit position 0. -// # If (a 1 bit popped out of the register during step 3) -// # Register = Register XOR Poly. -// # End -// # The register now contains the remainder. - uint16_t reg = 0x0000; - bool c = false; - uint16_t poly = 0x8005; - for( uint16_t indi = 0; indi < packet->pl_len + 2 + 1; indi++ ){ // addtl 2 bytes for padding, 1 byte to process cmd - for( uint8_t b = 0; b < 8; b++ ){ - c = false; - if(reg & 0x8000){ - c = true; - } - reg <<= 1; - reg &= 0xFFFF; - if(indi < (packet->pl_len + 1)){ - if(indi == 0){ - if( packet->cmd & (0x80 >> b)){ - reg |= 0x0001; - } - }else{ - if((*(packet->pl + indi - 1)) & (0x80 >> b)){ - reg |= 0x0001; - } - } - } - if(c){ - reg = (reg ^ poly); - } - } - } - return reg; -} \ No newline at end of file diff --git a/bootloaders/artemis/!artemis_svl/src/svl_packet/svl_packet.h b/bootloaders/artemis/!artemis_svl/src/svl_packet/svl_packet.h deleted file mode 100644 index 56bb1c68..00000000 --- a/bootloaders/artemis/!artemis_svl/src/svl_packet/svl_packet.h +++ /dev/null @@ -1,46 +0,0 @@ -#ifndef _SVL_PACKET_H_ -#define _SVL_PACKET_H_ - -#include "stdint.h" -#include "stdlib.h" -#include "stdbool.h" - -typedef struct _svl_packet_t{ // An SVL3 packet consists of 5+N bytes. N is the length of the data payload, and there are 5 bytes that are always transmitted - // len // 2 - length of the remainder of the packet (pllen + 3) (note, this is automatically calculated) - uint8_t cmd; // 1 - The command - uint8_t* pl; // N - The payload (pointer) - uint16_t pl_len; // - Length of the payload in bytes (note, this is not transmitted across the line, just used internally) - // crc // 2 - CRC16 on the command and the payload. poly = 0x8005, nothing extra or fancy. Byte order MSB first, bit order MSB first - uint16_t max_pl_len; // - This is the number of bytes pointed to by 'pl' -}svl_packet_t; - -enum{ - SVL_PACKET_OK = 0x00, - SVL_PACKET_ERR = 0x01, // general error - SVL_PACKET_ERR_TIMEOUT = 0x02, // timeout - SVL_PACKET_ERR_ZLP = 0x04, // zero length packet - SVL_PACKET_ERR_MEM = 0x08, // not enough space to receive packet - SVL_PACKET_ERR_CRC = 0x10, // crc mismatch - - SVL_PACKET_LEN = 0x80, // flag indicating 'len' header - SVL_PACKET_PL = 0x40, // flag indicating payload -}; - -typedef size_t (*svl_packet_read_byte_fn_t) ( void*, uint8_t* ); -typedef size_t (*svl_packet_write_byte_fn_t) ( void*, uint8_t ); -typedef size_t (*svl_packet_avail_bytes_fn_t) ( void* ); -typedef size_t (*svl_packet_millis_fn_t) ( void ); - -void svl_packet_link_read_fn ( svl_packet_read_byte_fn_t fn, void* param ); -void svl_packet_link_write_fn ( svl_packet_write_byte_fn_t fn, void* param ); -void svl_packet_link_avail_fn ( svl_packet_avail_bytes_fn_t fn, void* param ); -void svl_packet_link_millis_fn ( svl_packet_millis_fn_t fn ); - -void svl_packet_send (svl_packet_t* packet ); -uint8_t svl_packet_wait (svl_packet_t* packet ); - -uint16_t svl_packet_get_uint16_t ( void ); -uint8_t svl_packet_wait_bytes ( uint32_t num ); -uint16_t svl_packet_get_crc16 (svl_packet_t* packet); - -#endif // _SVL_PACKET_H_ \ No newline at end of file diff --git a/bootloaders/artemis/!artemis_svl/src/svl_ringbuf/svl_ringbuf.c b/bootloaders/artemis/!artemis_svl/src/svl_ringbuf/svl_ringbuf.c deleted file mode 100644 index c8c5cd20..00000000 --- a/bootloaders/artemis/!artemis_svl/src/svl_ringbuf/svl_ringbuf.c +++ /dev/null @@ -1,69 +0,0 @@ -#include "svl_ringbuf.h" - -size_t art_svl_ringbuf_init( void* vrb, uint8_t* buf, size_t len ){ - if( vrb == NULL ){ return 0; } - art_svl_ringbuf_t* rb = (art_svl_ringbuf_t*)vrb; - - rb->buf = buf; - rb->len = len; - rb->r_offset = 0; - rb->w_offset = 0; - - return rb->len; -} - -size_t art_svl_ringbuf_available( void* vrb ){ - if( vrb == NULL ){ return 0; } - art_svl_ringbuf_t* rb = (art_svl_ringbuf_t*)vrb; - - size_t avail = 0x00; - if((rb->w_offset) >= (rb->r_offset)){ - avail = rb->w_offset - rb->r_offset; - }else{ - avail = rb->len - (rb->r_offset - rb->w_offset); - } - return avail; -} - -size_t art_svl_ringbuf_bytes_free( void* vrb ){ - if( vrb == NULL ){ return 0; } - art_svl_ringbuf_t* rb = (art_svl_ringbuf_t*)vrb; - - size_t friegh = 0x00; - if((rb->w_offset) >= (rb->r_offset)){ - friegh = rb->len - rb->w_offset + rb->r_offset -1; - }else{ - friegh = rb->r_offset - rb->w_offset - 1; - } - return friegh; -} - -size_t art_svl_ringbuf_write( void* vrb, uint8_t c ){ - if( vrb == NULL ){ return 0; } - art_svl_ringbuf_t* rb = (art_svl_ringbuf_t*)vrb; - - if(art_svl_ringbuf_bytes_free(rb) > 0){ - *(rb->buf + rb->w_offset) = c; - rb->w_offset++; - if(rb->w_offset >= rb->len){ - rb->w_offset = 0; - } - return 1; - } - return 0; -} - -size_t art_svl_ringbuf_read( void* vrb, uint8_t* c ){ - if( vrb == NULL ){ return 0; } - art_svl_ringbuf_t* rb = (art_svl_ringbuf_t*)vrb; - - if(art_svl_ringbuf_available(rb) > 0){ - *c = *(rb->buf + rb->r_offset); - rb->r_offset++; - if(rb->r_offset >= rb->len){ - rb->r_offset = 0; - } - return 1; - } - return 0; -} \ No newline at end of file diff --git a/bootloaders/artemis/!artemis_svl/src/svl_ringbuf/svl_ringbuf.h b/bootloaders/artemis/!artemis_svl/src/svl_ringbuf/svl_ringbuf.h deleted file mode 100644 index f1391cce..00000000 --- a/bootloaders/artemis/!artemis_svl/src/svl_ringbuf/svl_ringbuf.h +++ /dev/null @@ -1,20 +0,0 @@ -#ifndef _SVL_RINGBUF_H_ -#define _SVL_RINGBUF_H_ - -#include "stdio.h" - -typedef struct _art_svl_ringbuf_t { - uint8_t* buf; - size_t len; - volatile size_t r_offset; - volatile size_t w_offset; -}art_svl_ringbuf_t; - -size_t art_svl_ringbuf_init ( void* rb, uint8_t* buf, size_t len ); -size_t art_svl_ringbuf_available ( void* rb ); -size_t art_svl_ringbuf_bytes_free ( void* rb ); -size_t art_svl_ringbuf_write ( void* rb, uint8_t c ); -size_t art_svl_ringbuf_read ( void* rb, uint8_t* c ); - - -#endif // _SVL_RINGBUF_H_ \ No newline at end of file diff --git a/bootloaders/artemis/!artemis_svl/src/svl_uart/svl_uart.c b/bootloaders/artemis/!artemis_svl/src/svl_uart/svl_uart.c deleted file mode 100644 index 76c08908..00000000 --- a/bootloaders/artemis/!artemis_svl/src/svl_uart/svl_uart.c +++ /dev/null @@ -1,70 +0,0 @@ -#include "svl_uart.h" - - - - - -//***************************************************************************** -// -// UART read buffer -// -//***************************************************************************** -size_t svl_uart_read(void *pHandle, char* buf, size_t len){ - uint32_t ui32BytesRead = 0x00; - am_hal_uart_transfer_t sRead = { - .ui32Direction = AM_HAL_UART_READ, - .pui8Data = (uint8_t*)buf, - .ui32NumBytes = len, - .ui32TimeoutMs = 0, - .pui32BytesTransferred = &ui32BytesRead, - }; - am_hal_uart_transfer(pHandle, &sRead); - return ui32BytesRead; -} - -//***************************************************************************** -// -// UART write buffer -// -//***************************************************************************** -size_t svl_uart_write(void *pHandle, char* buf, size_t len){ - uint32_t ui32BytesWritten = 0; - const am_hal_uart_transfer_t sUartWrite = - { - .ui32Direction = AM_HAL_UART_WRITE, - .pui8Data = (uint8_t*) buf, - .ui32NumBytes = len, - .ui32TimeoutMs = AM_HAL_UART_WAIT_FOREVER, - .pui32BytesTransferred = &ui32BytesWritten, - }; - - am_hal_uart_transfer(pHandle, &sUartWrite); - - return ui32BytesWritten; -} - -//***************************************************************************** -// -// UART write byte -// -//***************************************************************************** -size_t svl_uart_write_byte(void *pHandle, uint8_t c){ - return svl_uart_write(pHandle, (char*)&c, 1); -} - -//***************************************************************************** -// -// UART send string -// -//***************************************************************************** -size_t svl_uart_print(void *pHandle, char* str){ - uint32_t ui32StrLen = 0; - while (str[ui32StrLen] != 0){ ui32StrLen++; } // Measure the length of the string. - return svl_uart_write( pHandle, str, ui32StrLen); - - // uint16_t indi = 0; - // while((*(debug_buffer+indi)!='\0') && (indi < DEBUG_UART_BUF_LEN)){ - // svl_uart_write(hUART_debug, debug_buffer+indi, 1); - // indi++; - // } -} \ No newline at end of file diff --git a/bootloaders/artemis/!artemis_svl/src/svl_uart/svl_uart.h b/bootloaders/artemis/!artemis_svl/src/svl_uart/svl_uart.h deleted file mode 100644 index e1667301..00000000 --- a/bootloaders/artemis/!artemis_svl/src/svl_uart/svl_uart.h +++ /dev/null @@ -1,15 +0,0 @@ -#ifndef _SVL_UART_H_ -#define _SVL_UART_H_ - -#include "am_mcu_apollo.h" -#include "am_bsp.h" -#include "am_util.h" - - -size_t svl_uart_read (void *pHandle, char* buf, size_t len); -size_t svl_uart_write (void *pHandle, char* buf, size_t len); -size_t svl_uart_write_byte (void *pHandle, uint8_t c); -size_t svl_uart_print (void *pHandle, char* str); - - -#endif // _SVL_UART_H_ \ No newline at end of file diff --git a/bootloaders/artemis/!artemis_svl/src/svl_utils/svl_utils.c b/bootloaders/artemis/!artemis_svl/src/svl_utils/svl_utils.c deleted file mode 100644 index 4cbd1cd8..00000000 --- a/bootloaders/artemis/!artemis_svl/src/svl_utils/svl_utils.c +++ /dev/null @@ -1,119 +0,0 @@ -#include "svl_utils.h" - -#define AP3_STIMER_FREQ_HZ (3000000) -#define AP3_STIMER_FREQ_KHZ (AP3_STIMER_FREQ_HZ / 1000) -#define AP3_STIMER_FREQ_MHZ (AP3_STIMER_FREQ_HZ / 1000000) - -volatile uint32_t ap3_stimer_overflows = 0x00; -uint64_t ticks = 0; - -void _fill_ticks(void) -{ - ticks = ap3_stimer_overflows; - ticks <<= 32; - ticks |= (am_hal_stimer_counter_get() & 0xFFFFFFFF); -} - -size_t millis(void){ - _fill_ticks(); - return (uint32_t)(ticks / AP3_STIMER_FREQ_KHZ); -} - - -//***************************************************************************** -// -// Burst mode -// -//***************************************************************************** -bool enable_burst_mode(void) -{ - // Check that the Burst Feature is available. - am_hal_burst_avail_e eBurstModeAvailable; - if (AM_HAL_STATUS_SUCCESS != am_hal_burst_mode_initialize(&eBurstModeAvailable)) - { - return (false); - } - - // Put the MCU into "Burst" mode. - am_hal_burst_mode_e eBurstMode; - if (AM_HAL_STATUS_SUCCESS != am_hal_burst_mode_enable(&eBurstMode)) - { - return (false); - } - return (true); -} - -//Turns main processor from 96MHz to 48MHz -//Returns false if disable fails -bool disable_burst_mode(void) -{ - am_hal_burst_mode_e eBurstMode; - if (AM_HAL_STATUS_SUCCESS == am_hal_burst_mode_disable(&eBurstMode)) - { - if (AM_HAL_NORMAL_MODE != eBurstMode) - { - return (false); - } - } - else - { - return (false); - } - return (true); -} - - - -//***************************************************************************** -// Local defines. Copied from am_hal_gpio.c -//***************************************************************************** -// -// Generally define GPIO PADREG and GPIOCFG bitfields -// -#define PADREG_FLD_76_S 6 -#define PADREG_FLD_FNSEL_S 3 -#define PADREG_FLD_DRVSTR_S 2 -#define PADREG_FLD_INPEN_S 1 -#define PADREG_FLD_PULLUP_S 0 - -#define GPIOCFG_FLD_INTD_S 3 -#define GPIOCFG_FLD_OUTCFG_S 1 -#define GPIOCFG_FLD_INCFG_S 0 - -uint32_t ap3_gpio_enable_interrupts(uint32_t ui32Pin, uint32_t eIntDir){ - uint32_t ui32Padreg, ui32AltPadCfg, ui32GPCfg; - bool bClearEnable = false; - - - ui32GPCfg = ui32Padreg = ui32AltPadCfg = 0; - ui32GPCfg |= (((eIntDir >> 0) & 0x1) << GPIOCFG_FLD_INTD_S) | (((eIntDir >> 1) & 0x1) << GPIOCFG_FLD_INCFG_S); - - uint32_t ui32GPCfgAddr; - uint32_t ui32GPCfgClearMask; - uint32_t ui32GPCfgShft; - - ui32GPCfgShft = ((ui32Pin & 0x7) << 2); - - ui32GPCfgAddr = AM_REGADDR(GPIO, CFGA) + ((ui32Pin >> 1) & ~0x3); - ui32GPCfgClearMask = ~((uint32_t)0xF << ui32GPCfgShft); - - ui32GPCfg <<= ui32GPCfgShft; - - AM_CRITICAL_BEGIN - - if (bClearEnable) - { - am_hal_gpio_output_tristate_disable(ui32Pin); - } - - GPIO->PADKEY = GPIO_PADKEY_PADKEY_Key; - - // Here's where the magic happens - AM_REGVAL(ui32GPCfgAddr) = (AM_REGVAL(ui32GPCfgAddr) & ui32GPCfgClearMask) | ui32GPCfg; - - GPIO->PADKEY = 0; - - AM_CRITICAL_END - - return AM_HAL_STATUS_SUCCESS; -} diff --git a/bootloaders/artemis/!artemis_svl/src/svl_utils/svl_utils.h b/bootloaders/artemis/!artemis_svl/src/svl_utils/svl_utils.h deleted file mode 100644 index c870e47a..00000000 --- a/bootloaders/artemis/!artemis_svl/src/svl_utils/svl_utils.h +++ /dev/null @@ -1,18 +0,0 @@ -#ifndef _SVL_UTILS_H_ -#define _SVL_UTILS_H_ - -#include "am_mcu_apollo.h" -#include "am_bsp.h" -#include "am_util.h" - -#include "stdint.h" - -void _fill_ticks(void); -size_t millis(void); -bool enable_burst_mode(void); -bool disable_burst_mode(void); -uint32_t ap3_gpio_enable_interrupts(uint32_t ui32Pin, uint32_t eIntDir); - -extern volatile uint32_t ap3_stimer_overflows; - -#endif // _SVL_UTILS_H_ \ No newline at end of file diff --git a/bootloaders/artemis/README.txt b/bootloaders/artemis/README.txt new file mode 100644 index 00000000..8e671b0b --- /dev/null +++ b/bootloaders/artemis/README.txt @@ -0,0 +1,6 @@ +The artemis_svl bootloader is the default bootloader on Artemis module--based boards. A copy of the executable is located here to enable Arduino to re-flash it when needed. To view the source code visit the [SparkFun AmbiqSuite BSPs Repo](https://github.com/sparkfun/SparkFun_Apollo3_AmbiqSuite_BSPs)/common/examples/[artemis_svl](https://github.com/sparkfun/SparkFun_Apollo3_AmbiqSuite_BSPs/tree/master/common/examples/artemis_svl) +The easiest way to upload the SVL is by using the Arduino "burn bootloader" tool and selecting "Ambiq Secure Bootloader" as the "Programmer" option. + +Artemis SVL Versions: +v4 - Added peripheral deinitialization to deliver the Apollo3 closer to the initial reset state. +v3 - Initial version \ No newline at end of file diff --git a/bootloaders/artemis/artemis_svl.bin b/bootloaders/artemis/artemis_svl.bin index 5d0d3e56..b407e0c9 100644 Binary files a/bootloaders/artemis/artemis_svl.bin and b/bootloaders/artemis/artemis_svl.bin differ