diff options
Diffstat (limited to 'controller')
-rw-r--r-- | controller/fw/Makefile | 108 | ||||
m--------- | controller/fw/cmsis | 0 | ||||
m--------- | controller/fw/libsodium | 0 | ||||
-rw-r--r-- | controller/fw/main.c | 76 | ||||
-rw-r--r-- | controller/fw/mspdebug_wrapper.c | 207 | ||||
-rw-r--r-- | controller/fw/mspdebug_wrapper.h | 6 | ||||
-rw-r--r-- | controller/fw/spi_flash.c | 189 | ||||
-rw-r--r-- | controller/fw/spi_flash.h | 31 | ||||
-rw-r--r-- | controller/fw/sr_global.h | 8 | ||||
m--------- | controller/fw/tinyaes | 0 |
10 files changed, 62 insertions, 563 deletions
diff --git a/controller/fw/Makefile b/controller/fw/Makefile index 52951b1..9895c87 100644 --- a/controller/fw/Makefile +++ b/controller/fw/Makefile @@ -1,13 +1,23 @@ -SOURCES := main.c mspdebug_wrapper.c spi_flash.c -SOURCES += mspdebug/drivers/jtaglib.c +OPENCM3_DIR ?= libopencm3 +CMSIS_DIR ?= cmsis +MSPDEBUG_DIR ?= mspdebug +LIBSODIUM_DIR ?= libsodium +TINYAES_DIR ?= tinyaes +MUSL_DIR ?= musl + +C_SOURCES := src/main.c src/mspdebug_wrapper.c src/spi_flash.c +C_SOURCES += $(MSPDEBUG_DIR)/drivers/jtaglib.c +C_SOURCES += $(CMSIS_DIR)/CMSIS/DSP/Source/TransformFunctions/arm_rfft_f32.c +C_SOURCES += $(CMSIS_DIR)/CMSIS/DSP/Source/TransformFunctions/arm_bitreversal.c +C_SOURCES += $(CMSIS_DIR)/CMSIS/DSP/Source/TransformFunctions/arm_cfft_radix4_f32.c + +CXX_SOURCES += src/ldpc_wrapper.cpp BUILDDIR ?= build BINARY := safetyreset LDSCRIPT := stm32f407.ld -LIBNAME := opencm3_stm32f4 - -OPENCM3_DIR ?= libopencm3 +OPENCM3_LIB := opencm3_stm32f4 PREFIX ?= arm-none-eabi- @@ -21,73 +31,79 @@ OBJCOPY := $(PREFIX)objcopy OBJDUMP := $(PREFIX)objdump GDB := $(PREFIX)gdb +OPENCM3_DIR := $(abspath $(OPENCM3_DIR)) +CMSIS_DIR := $(abspath $(CMSIS_DIR)) +MSPDEBUG_DIR := $(abspath $(MSPDEBUG_DIR)) +LIBSODIUM_DIR := $(abspath $(LIBSODIUM_DIR)) +TINYAES_DIR := $(abspath $(TINYAES_DIR)) +MUSL_DIR := $(abspath $(MUSL_DIR)) CFLAGS += -I$(OPENCM3_DIR)/include -Imspdebug/util -Imspdebug/drivers +CFLAGS += -I$(CMSIS_DIR)/CMSIS/DSP/Include -I$(CMSIS_DIR)/CMSIS/Core/Include CFLAGS += -Os -std=gnu11 -g -DSTM32F4 # Note: libopencm3 requires some standard libc definitions from stdint.h and stdbool.h, so we don't pass -nostdinc here. CFLAGS += -nostdlib -ffreestanding -CFLAGS += -mthumb -mcpu=cortex-m4 -mfloat-abi=hard -mfpu=fpv4-sp-d16 -g -CFLAGS += -Wextra -Wshadow -Wimplicit-function-declaration -Wundef -CFLAGS += -Wredundant-decls -Wmissing-prototypes -Wstrict-prototypes +CFLAGS += -mthumb -mcpu=cortex-m4 -mfloat-abi=hard -mfpu=fpv4-sp-d16 CFLAGS += -fno-common -ffunction-sections -fdata-sections +INT_CFLAGS += -Wextra -Wshadow -Wimplicit-function-declaration -Wundef +INT_CFLAGS += -Wredundant-decls -Wmissing-prototypes -Wstrict-prototypes + +CXXFLAGS += -Os -g +CXXFLAGS += -nostdlib -ffreestanding +CXXFLAGS += -mthumb -mcpu=cortex-m4 -mfloat-abi=hard -mfpu=fpv4-sp-d16 +CXXFLAGS += -fno-common -ffunction-sections -fdata-sections +CXXFLAGS += -Wextra -Wshadow -Wundef -Wredundant-decls +CXXFLAGS += -I. + LDFLAGS += --static -nostartfiles LDFLAGS += -T$(LDSCRIPT) LDFLAGS += -mthumb -mcpu=cortex-m4 -mfloat-abi=hard -mfpu=fpv4-sp-d16 -g LDFLAGS += -Wl,--cre #LDFLAGS += -Wl,--gc-sections LDFLAGS += -Wl,--start-group -lc -lgcc -lnosys -Wl,--end-group -LDFLAGS += -L$(OPENCM3_DIR)/lib -LDFLAGS += -l$(LIBNAME) $(shell $(CC) -print-libgcc-file-name) +LDFLAGS += -L$(OPENCM3_DIR)/lib -l$(OPENCM3_LIB) $(shell $(CC) -print-libgcc-file-name) -all: elf +all: $(BUILDDIR)/$(BINARY).elf -elf: $(BUILDDIR)/$(BINARY).elf -bin: $(BUILDDIR)/$(BINARY).bin -hex: $(BUILDDIR)/$(BINARY).hex -srec: $(BUILDDIR)/$(BINARY).srec -list: $(BUILDDIR)/$(BINARY).list +OBJS := $(addprefix $(BUILDDIR)/,$(C_SOURCES:.c=.o) $(CXX_SOURCES:.cpp=.o)) -images: $(BUILDDIR)/$(BINARY).images -$(OPENCM3_DIR)/lib/lib$(LIBNAME).a: - echo "Warning, $@ not found, attempting to rebuild in $(OPENCM3_DIR)" - $(MAKE) -C $(OPENCM3_DIR) +$(BUILDDIR)/%.elf: $(OBJS) $(LDSCRIPT) $(OPENCM3_DIR)/lib/lib$(OPENCM3_LIB).a $(BUILDDIR)/libsodium/src/libsodium/.libs/libsodium.a $(BUILDDIR)/tinyaes/aes.o $(BUILDDIR)/musl/lib/libc.a + $(LD) $(OBJS) $(LDFLAGS) -o $@ -Wl,-Map=$(BUILDDIR)/src/$*.map $(BUILDDIR)/libsodium/src/libsodium/.libs/libsodium.a $(BUILDDIR)/tinyaes/aes.o -OBJS := $(addprefix $(BUILDDIR)/,$(SOURCES:%.c=%.o)) +$(BUILDDIR)/src/%.o: src/%.c + mkdir -p $(@D) + $(CC) $(CFLAGS) $(INT_CFLAGS) -o $@ -c $< -# Define a helper macro for debugging make errors online -# you can type "make print-OPENCM3_DIR" and it will show you -# how that ended up being resolved by all of the included -# makefiles. -print-%: - @echo $*=$($*) +$(BUILDDIR)/src/%.o: src/%.cpp + mkdir -p $(@D) + $(CXX) $(CXXFLAGS) -o $@ -c $< -$(BUILDDIR)/%.images: $(BUILDDIR)/%.bin $(BUILDDIR)/%.hex $(BUILDDIR)/%.srec $(BUILDDIR)/%.list $(BUILDDIR)/%.map - -$(BUILDDIR)/%.bin: $(BUILDDIR)/%.elf - $(OBJCOPY) -Obinary $< $@ - -$(BUILDDIR)/%.hex: $(BUILDDIR)/%.elf - $(OBJCOPY) -Oihex $< $@ - -$(BUILDDIR)/%.srec: $(BUILDDIR)/%.elf - $(OBJCOPY) -Osrec $< $@ +$(BUILDDIR)/%.o: %.c + mkdir -p $(@D) + $(CC) $(CFLAGS) $(EXT_CFLAGS) -o $@ -c $< -$(BUILDDIR)/%.list: $(BUILDDIR)/%.elf - $(OBJDUMP) -S $< > $@ +$(OPENCM3_DIR)/lib/lib$(OPENCM3_LIB).a: + $(MAKE) -C $(OPENCM3_DIR) -j $(shell nproc) -$(BUILDDIR)/%.elf: $(OBJS) $(LDSCRIPT) $(OPENCM3_DIR)/lib/lib$(LIBNAME).a - $(LD) $(OBJS) $(LDFLAGS) -o $@ -Wl,-Map=$*.map +$(BUILDDIR)/libsodium/src/libsodium/.libs/libsodium.a: + mkdir -p build/libsodium + cd build/libsodium && CFLAGS="$(CFLAGS) -DDEV_MODE=1" $(LIBSODIUM_DIR)/configure --host=arm-none-eabi && $(MAKE) -j $(shell nproc) -$(BUILDDIR)/%.o: %.c - mkdir -p $(dir $@) - $(CC) $(CFLAGS) -o $@ -c $< +$(BUILDDIR)/tinyaes/aes.o: + mkdir -p $(@D) + make -C $(@D) -f $(TINYAES_DIR)/Makefile VPATH=$(TINYAES_DIR) CFLAGS="$(CFLAGS) -c" CC=$(CC) LD=$(LD) AR=$(AR) aes.o clean: - -rm -r $(BUILDDIR) + -rm -r $(BUILDDIR)/src + -rm $(BUILDDIR)/$(BINARY).elf + +mrproper: clean + -rm -r build + -$(MAKE) -C $(OPENCM3_DIR) clean -.PHONY: images clean elf bin hex srec list +.PHONY: clean mrproper -include $(OBJS:.o=.d) diff --git a/controller/fw/cmsis b/controller/fw/cmsis new file mode 160000 +Subproject 02c242de0606a46de29c8deb30954bcf2e9389c diff --git a/controller/fw/libsodium b/controller/fw/libsodium new file mode 160000 +Subproject afae623190f025e7cf2fb0222bfe796b69a3694 diff --git a/controller/fw/main.c b/controller/fw/main.c deleted file mode 100644 index 3131df1..0000000 --- a/controller/fw/main.c +++ /dev/null @@ -1,76 +0,0 @@ - -#include <stdbool.h> - -#include <libopencm3/stm32/rcc.h> -#include <libopencm3/stm32/spi.h> -#include <libopencm3/stm32/gpio.h> - -#include "spi_flash.h" - -static struct spi_flash_if spif; - -static void clock_setup(void) -{ - rcc_clock_setup_pll(&rcc_hse_8mhz_3v3[RCC_CLOCK_3V3_168MHZ]); - rcc_periph_clock_enable(RCC_GPIOA); - rcc_periph_clock_enable(RCC_GPIOB); - rcc_periph_clock_enable(RCC_SPI1); -} - -static void led_setup(void) -{ - gpio_mode_setup(GPIOA, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, GPIO6 | GPIO7); -} - -static void spi_flash_if_set_cs(bool val) { - if (val) - gpio_set(GPIOB, GPIO0); - else - gpio_clear(GPIOB, GPIO0); -} - -static void spi_flash_setup(void) -{ - gpio_mode_setup(GPIOB, GPIO_MODE_AF, GPIO_PUPD_NONE, GPIO3 | GPIO4 | GPIO5); /* SPI flash SCK/MISO/MOSI */ - gpio_mode_setup(GPIOB, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, GPIO0); /* SPI flash CS */ - gpio_set_output_options(GPIOB, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, GPIO0 | GPIO3 | GPIO4 | GPIO5); - gpio_set_af(GPIOB, 5, GPIO3 | GPIO4 | GPIO5); - - spif_init(&spif, 256, SPI1, &spi_flash_if_set_cs); -} - -/* -void spi_flash_test(void) { - spif_clear_mem(&spif); - - uint32_t buf[1024]; - for (size_t addr=0; addr<0x10000; addr += sizeof(buf)) { - for (size_t i=0; i<sizeof(buf); i+= sizeof(buf[0])) - buf[i/sizeof(buf[0])] = addr + i; - - spif_write(&spif, addr, sizeof(buf), (char *)buf); - } - - for (size_t i=0; i<sizeof(buf)/sizeof(buf[0]); i++) - buf[i] = 0; - spif_read(&spif, 0x1030, sizeof(buf), (char *)buf); - asm volatile ("bkpt"); -} -*/ - -int main(void) -{ - clock_setup(); - led_setup(); - spi_flash_setup(); - - gpio_set(GPIOA, GPIO6); - - while (1) { - gpio_toggle(GPIOA, GPIO6 | GPIO7); - for (int i = 0; i < 6000000; i++) - __asm__("nop"); - } - - return 0; -} diff --git a/controller/fw/mspdebug_wrapper.c b/controller/fw/mspdebug_wrapper.c deleted file mode 100644 index 68d3b1d..0000000 --- a/controller/fw/mspdebug_wrapper.c +++ /dev/null @@ -1,207 +0,0 @@ - -#include <unistd.h> -#include <errno.h> - -#include <libopencm3/stm32/gpio.h> - -#include "output.h" -#include "jtaglib.h" - -#include "sr_global.h" -#include "mspdebug_wrapper.h" - -#define BLOCK_SIZE 512 /* bytes */ - - -static struct jtdev sr_jtdev; - - -int flash_and_reset(size_t img_start, size_t img_len, ssize_t (*read_block)(int addr, size_t len, uint8_t *out)) -{ - union { - uint8_t bytes[BLOCK_SIZE]; - uint16_t words[BLOCK_SIZE/2]; - } block; - - /* Initialize JTAG connection */ - unsigned int jtag_id = jtag_init(&sr_jtdev); - - if (sr_jtdev.failed) - return -EPIPE; - - if (jtag_id != 0x89 && jtag_id != 0x91) - return -EINVAL; - - /* Clear flash */ - jtag_erase_flash(&sr_jtdev, JTAG_ERASE_MAIN, 0); - if (sr_jtdev.failed) - return -EPIPE; - - /* Write flash */ - for (size_t p = img_start; p < img_start + img_len; p += BLOCK_SIZE) { - ssize_t nin = read_block(p, BLOCK_SIZE, block.bytes); - - if (nin < 0) - return nin; - - if (nin & 1) { /* pad unaligned */ - block.bytes[nin] = 0; - nin ++; - } - - /* Convert to little-endian */ - for (ssize_t i=0; i<nin/2; i++) - block.words[i] = htole(block.words[i]); - - jtag_write_flash(&sr_jtdev, p, nin/2, block.words); - if (sr_jtdev.failed) - return -EPIPE; - } - - /* Verify flash */ - /* FIXME - word = jtag_read_mem(NULL, 16, addr+index ); - */ - - /* Execute power on reset */ - jtag_execute_puc(&sr_jtdev); - if (sr_jtdev.failed) - return -EPIPE; - - return 0; -} - -/* mspdebug HAL shim */ - -int printc_err(const char *fmt, ...) { - UNUSED(fmt); - /* ignore */ -} - - -static void sr_jtdev_power_on(struct jtdev *p) { - /* ignore */ -} - -static void sr_jtdev_connect(struct jtdev *p) { - /* ignore */ -} - -enum sr_gpio_types { - SR_GPIO_TCK, - SR_GPIO_TMS, - SR_GPIO_TDI, - SR_GPIO_RST, - SR_GPIO_TST, - SR_GPIO_TDO, - SR_NUM_GPIOS -}; - -struct { - uint32_t port; - uint16_t num; -} gpios[SR_NUM_GPIOS] = { - [SR_GPIO_TCK] = {GPIOD, 8}, - [SR_GPIO_TMS] = {GPIOD, 9}, - [SR_GPIO_TDI] = {GPIOD, 10}, - [SR_GPIO_RST] = {GPIOD, 11}, - [SR_GPIO_TST] = {GPIOD, 12}, - [SR_GPIO_TDO] = {GPIOD, 13}, -}; - -static void sr_gpio_write(int num, int out) { - if (out) - gpio_set(gpios[num].port, gpios[num].num); - else - gpio_clear(gpios[num].port, gpios[num].num); -} - -static void sr_jtdev_tck(struct jtdev *p, int out) { - UNUSED(p); - sr_gpio_write(SR_GPIO_TCK, out); -} - -static void sr_jtdev_tms(struct jtdev *p, int out) { - UNUSED(p); - sr_gpio_write(SR_GPIO_TMS, out); -} - -static void sr_jtdev_tdi(struct jtdev *p, int out) { - UNUSED(p); - sr_gpio_write(SR_GPIO_TDI, out); -} - -static void sr_jtdev_rst(struct jtdev *p, int out) { - UNUSED(p); - sr_gpio_write(SR_GPIO_RST, out); -} - -static void sr_jtdev_tst(struct jtdev *p, int out) { - UNUSED(p); - sr_gpio_write(SR_GPIO_TST, out); -} - -static int sr_jtdev_tdo_get(struct jtdev *p) { - return gpio_get(gpios[SR_GPIO_TST].port, gpios[SR_GPIO_TST].num); -} - -static void sr_jtdev_tclk(struct jtdev *p, int out) { - UNUSED(p); - sr_gpio_write(SR_GPIO_TST, out); -} - -static int sr_jtdev_tclk_get(struct jtdev *p) { - return gpio_get(gpios[SR_GPIO_TDI].port, gpios[SR_GPIO_TDI].num); -} - -static void sr_jtdev_tclk_strobe(struct jtdev *p, unsigned int count) { - while (count--) { - gpio_set(gpios[SR_GPIO_TDI].port, gpios[SR_GPIO_TDI].num); - gpio_clear(gpios[SR_GPIO_TDI].port, gpios[SR_GPIO_TDI].num); - } -} - -static void sr_jtdev_led_green(struct jtdev *p, int out) { - UNUSED(p); - UNUSED(out); - /* ignore */ -} - -static void sr_jtdev_led_red(struct jtdev *p, int out) { - UNUSED(p); - UNUSED(out); - /* ignore */ -} - - -static struct jtdev_func sr_jtdev_vtable = { - .jtdev_open = NULL, - .jtdev_close = NULL, - - .jtdev_power_off = NULL, - .jtdev_release = NULL, - - .jtdev_power_on = sr_jtdev_power_on, - .jtdev_connect = sr_jtdev_connect, - - .jtdev_tck = sr_jtdev_tck, - .jtdev_tms = sr_jtdev_tms, - .jtdev_tdi = sr_jtdev_tdi, - .jtdev_rst = sr_jtdev_rst, - .jtdev_tst = sr_jtdev_tst, - .jtdev_tdo_get = sr_jtdev_tdo_get, - - .jtdev_tclk = sr_jtdev_tclk, - .jtdev_tclk_get = sr_jtdev_tclk_get, - .jtdev_tclk_strobe = sr_jtdev_tclk_strobe, - - .jtdev_led_green = sr_jtdev_led_green, - .jtdev_led_red = sr_jtdev_led_red, - -}; - -static struct jtdev sr_jtdev = { - 0, - .f = &sr_jtdev_vtable -}; - diff --git a/controller/fw/mspdebug_wrapper.h b/controller/fw/mspdebug_wrapper.h deleted file mode 100644 index 245d9fb..0000000 --- a/controller/fw/mspdebug_wrapper.h +++ /dev/null @@ -1,6 +0,0 @@ -#ifndef __MSPDEBUG_WRAPPER_H__ -#define __MSPDEBUG_WRAPPER_H__ - -int flash_and_reset(size_t img_start, size_t img_len, ssize_t (*read_block)(int addr, size_t len, uint8_t *out)); - -#endif /* __MSPDEBUG_WRAPPER_H__ */ diff --git a/controller/fw/spi_flash.c b/controller/fw/spi_flash.c deleted file mode 100644 index 98c773f..0000000 --- a/controller/fw/spi_flash.c +++ /dev/null @@ -1,189 +0,0 @@ -/* Library for SPI flash 25* devices. - * Copyright (c) 2014 Multi-Tech Systems - * Copyright (c) 2020 Jan Goette <ma@jaseg.de> - * - * 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. - */ - -#include "spi_flash.h" -#include <libopencm3/stm32/spi.h> - -enum { - WRITE_ENABLE = 0x06, - WRITE_DISABLE = 0x04, - READ_IDENTIFICATION = 0x9F, - READ_STATUS = 0x05, - WRITE_STATUS = 0x01, - READ_DATA = 0x03, - READ_DATA_FAST = 0x0B, - PAGE_PROGRAM = 0x02, - SECTOR_ERASE = 0xD8, - BULK_ERASE = 0xC7, - DEEP_POWER_DOWN = 0xB9, - DEEP_POWER_DOWN_RELEASE = 0xAB, -}; - -enum { - STATUS_SRWD = 0x80, // 0b 1000 0000 - STATUS_BP2 = 0x10, // 0b 0001 0000 - STATUS_BP1 = 0x08, // 0b 0000 1000 - STATUS_BP0 = 0x04, // 0b 0000 0100 - STATUS_WEL = 0x02, // 0b 0000 0010 - STATUS_WIP = 0x01, // 0b 0000 0001 -}; - - -static void spif_write_page(struct spi_flash_if *spif, size_t addr, size_t len, const char* data); -static uint8_t spif_read_status(struct spi_flash_if *spif); -static void spif_enable_write(struct spi_flash_if *spif); -static void spif_wait_for_write(struct spi_flash_if *spif); - -#define low_byte(x) (x&0xff) -#define mid_byte(x) ((x>>8)&0xff) -#define high_byte(x) ((x>>16)&0xff) - - -void spif_init(struct spi_flash_if *spif, size_t page_size, uint32_t spi_base, void (*cs)(bool val)) { - - spif->spi_base = spi_base; - spif->page_size = page_size; - spif->cs = cs; - spif->cs(1); - - spi_reset(spif->spi_base); - spi_init_master(spif->spi_base, - SPI_CR1_BAUDRATE_FPCLK_DIV_2, - SPI_CR1_CPOL_CLK_TO_1_WHEN_IDLE, - SPI_CR1_CPHA_CLK_TRANSITION_2, - SPI_CR1_DFF_8BIT, - SPI_CR1_MSBFIRST); - - spi_enable_software_slave_management(spif->spi_base); - spi_set_nss_high(spif->spi_base); - - spi_enable(spif->spi_base); - - spif->cs(0); - spi_send(spif->spi_base, READ_IDENTIFICATION); - spif->id.mfg_id = spi_xfer(spif->spi_base, 0); - spif->id.type = spi_xfer(spif->spi_base, 0); - spif->id.size = 1<<spi_xfer(spif->spi_base, 0); - spif->cs(1); -} - -void spif_read(struct spi_flash_if *spif, size_t addr, size_t len, char* data) { - spif_enable_write(spif); - - spif->cs(0); - spi_xfer(spif->spi_base, READ_DATA); - spi_xfer(spif->spi_base, high_byte(addr)); - spi_xfer(spif->spi_base, mid_byte(addr)); - spi_xfer(spif->spi_base, low_byte(addr)); - - for (size_t i = 0; i < len; i++) - data[i] = spi_xfer(spif->spi_base, 0); - - spif->cs(1); -} - -void spif_write(struct spi_flash_if *spif, size_t addr, size_t len, const char* data) { - size_t written = 0, write_size = 0; - - while (written < len) { - write_size = spif->page_size - ((addr + written) % spif->page_size); - if (written + write_size > len) - write_size = len - written; - - spif_write_page(spif, addr + written, write_size, data + written); - written += write_size; - } -} - -static uint8_t spif_read_status(struct spi_flash_if *spif) { - spif->cs(0); - spi_xfer(spif->spi_base, READ_STATUS); - uint8_t status = spi_xfer(spif->spi_base, 0); - spif->cs(1); - - return status; -} - -void spif_clear_sector(struct spi_flash_if *spif, size_t addr) { - spif_enable_write(spif); - - spif->cs(0); - spi_xfer(spif->spi_base, SECTOR_ERASE); - spi_xfer(spif->spi_base, high_byte(addr)); - spi_xfer(spif->spi_base, mid_byte(addr)); - spi_xfer(spif->spi_base, low_byte(addr)); - spif->cs(1); - - spif_wait_for_write(spif); -} - -void spif_clear_mem(struct spi_flash_if *spif) { - spif_enable_write(spif); - - spif->cs(0); - spi_xfer(spif->spi_base, BULK_ERASE); - spif->cs(1); - - spif_wait_for_write(spif); -} - -static void spif_write_page(struct spi_flash_if *spif, size_t addr, size_t len, const char* data) { - spif_enable_write(spif); - - spif->cs(0); - spi_xfer(spif->spi_base, PAGE_PROGRAM); - spi_xfer(spif->spi_base, high_byte(addr)); - spi_xfer(spif->spi_base, mid_byte(addr)); - spi_xfer(spif->spi_base, low_byte(addr)); - - for (size_t i = 0; i < len; i++) { - spi_xfer(spif->spi_base, data[i]); - } - - spif->cs(1); - spif_wait_for_write(spif); -} - -static void spif_enable_write(struct spi_flash_if *spif) { - spif->cs(0); - spi_xfer(spif->spi_base, WRITE_ENABLE); - spif->cs(1); -} - -static void spif_wait_for_write(struct spi_flash_if *spif) { - while (spif_read_status(spif) & STATUS_WIP) - for (int i = 0; i < 800; i++) - ; -} - -void spif_deep_power_down(struct spi_flash_if *spif) { - spif->cs(0); - spi_xfer(spif->spi_base, DEEP_POWER_DOWN); - spif->cs(1); -} - -void spif_wakeup(struct spi_flash_if *spif) { - spif->cs(0); - spi_xfer(spif->spi_base, DEEP_POWER_DOWN_RELEASE); - spif->cs(1); -} diff --git a/controller/fw/spi_flash.h b/controller/fw/spi_flash.h deleted file mode 100644 index e647c6a..0000000 --- a/controller/fw/spi_flash.h +++ /dev/null @@ -1,31 +0,0 @@ -#ifndef __SPI_FLASH_H__ -#define __SPI_FLASH_H__ - -#include <stdbool.h> -#include <unistd.h> - -struct spi_mem_id { - size_t size; - uint8_t mfg_id; - uint8_t type; -}; - -struct spi_flash_if { - struct spi_mem_id id; - uint32_t spi_base; - size_t page_size; - void (*cs)(bool val); -}; - -void spif_init(struct spi_flash_if *spif, size_t page_size, uint32_t spi_base, void (*cs)(bool val)); - -void spif_write(struct spi_flash_if *spif, size_t addr, size_t len, const char* data); -void spif_read(struct spi_flash_if *spif, size_t addr, size_t len, char* data); - -void spif_clear_mem(struct spi_flash_if *spif); -void spif_clear_sector(struct spi_flash_if *spif, size_t addr); - -void spif_deep_power_down(struct spi_flash_if *spif); -void spif_wakeup(struct spi_flash_if *spif); - -#endif /* __SPI_FLASH_H__ */ diff --git a/controller/fw/sr_global.h b/controller/fw/sr_global.h deleted file mode 100644 index 8aa219d..0000000 --- a/controller/fw/sr_global.h +++ /dev/null @@ -1,8 +0,0 @@ -#ifndef __SR_GLOBAL_H__ -#define __SR_GLOBAL_H__ - -#define UNUSED(x) ((void) x) - -static inline uint16_t htole(uint16_t val) { return val; } - -#endif /* __SR_GLOBAL_H__ */ diff --git a/controller/fw/tinyaes b/controller/fw/tinyaes new file mode 160000 +Subproject 3fe133ffa32606b0d0d81e0ba1d8bacb392eb7e |