From: Joseph Coffland Date: Mon, 23 Jan 2017 00:03:27 +0000 (-0800) Subject: xboot -> boot X-Git-Url: https://git.buildbotics.com/?a=commitdiff_plain;h=c24758dfc58016dd0225a3806a636fda03fa0920;p=bbctrl-firmware xboot -> boot --- diff --git a/avr/Makefile b/avr/Makefile index 89e0930..a332d06 100644 --- a/avr/Makefile +++ b/avr/Makefile @@ -47,8 +47,8 @@ SRC += $(wildcard src/plan/*.c) OBJ = $(patsubst src/%.c,build/%.o,$(SRC)) # Boot SRC -BOOT_SRC = $(wildcard src/xboot/*.S) -BOOT_SRC += $(wildcard src/xboot/*.c) +BOOT_SRC = $(wildcard src/boot/*.S) +BOOT_SRC += $(wildcard src/boot/*.c) BOOT_OBJ = $(patsubst src/%.c,build/%.o,$(BOOT_SRC)) BOOT_OBJ := $(patsubst src/%.S,build/%.o,$(BOOT_OBJ)) @@ -57,7 +57,7 @@ BOOT_LDFLAGS = $(LDFLAGS) -Wl,--section-start=.text=0x030000 # Build all: $(PROJECT).hex build/vars.json boot size -boot: xboot.hex boot-size +boot: boot.hex boot-size build/vars.json: src/vars.def @@ -77,7 +77,7 @@ build/%.o: src/%.S $(TARGET): $(OBJ) $(CC) $(LDFLAGS) $(OBJ) $(LIBS) -o $@ -xboot.elf: $(BOOT_OBJ) +boot.elf: $(BOOT_OBJ) $(CC) $(BOOT_LDFLAGS) $(BOOT_OBJ) -o $@ %.hex: %.elf @@ -95,7 +95,7 @@ _size: avr-size -$$X --mcu=$(MCU) $(SIZE_TARGET) ;\ done -boot-size: xboot.elf +boot-size: boot.elf @$(MAKE) SIZE_TARGET=$< _size size: $(TARGET) @@ -120,8 +120,8 @@ program: $(PROJECT).hex verify: $(PROJECT).hex avrdude $(AVRDUDE_OPTS) -U flash:v:$(PROJECT).hex:i -program-boot: xboot.hex - avrdude $(AVRDUDE_OPTS) -U flash:w:xboot.hex:i +program-boot: boot.hex + avrdude $(AVRDUDE_OPTS) -U flash:w:boot.hex:i fuses: avrdude $(AVRDUDE_OPTS) -U fuse0:w:$(FUSE0):m -U fuse1:w:$(FUSE1):m \ @@ -146,7 +146,7 @@ tidy: clean: tidy rm -rf $(PROJECT).elf $(PROJECT).hex $(PROJECT).eep $(PROJECT).lss \ - $(PROJECT).map build xboot.hex xboot.elf + $(PROJECT).map build boot.hex boot.elf .PHONY: tidy clean size all reset erase program fuses read_fuses prodsig .PHONY: signature usersig diff --git a/avr/src/boot/boot.c b/avr/src/boot/boot.c new file mode 100644 index 0000000..ff66553 --- /dev/null +++ b/avr/src/boot/boot.c @@ -0,0 +1,408 @@ +/******************************************************************************\ + + This file is part of the Buildbotics firmware. + + Copyright (c) 2015 - 2017 Buildbotics LLC + Copyright (c) 2010 Alex Forencich + All rights reserved. + + This file ("the software") is free software: you can redistribute it + and/or modify it under the terms of the GNU General Public License, + version 2 as published by the Free Software Foundation. You should + have received a copy of the GNU General Public License, version 2 + along with the software. If not, see . + + The software 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 the software. If not, see + . + + For information regarding this software email: + "Joseph Coffland" + +\******************************************************************************/ + +#include "boot.h" +#include "sp_driver.h" + +#include +#include + +#include +#include + +#include + + +uint8_t buffer[SPM_PAGESIZE]; +uint16_t block_crc = 0; + + +void clock_init() { + // External 16Mhz Xtal w/ 2x PLL = 32 Mhz + // 12-16 MHz crystal; 0.4-16 MHz XTAL w/ 16K CLK startup + OSC.XOSCCTRL = OSC_FRQRANGE_12TO16_gc | OSC_XOSCSEL_XTAL_16KCLK_gc; + OSC.CTRL = OSC_XOSCEN_bm; // enable external crystal oscillator + while (!(OSC.STATUS & OSC_XOSCRDY_bm)); // wait for oscillator ready + + OSC.PLLCTRL = OSC_PLLSRC_XOSC_gc | 2; // PLL source, 2x (32 MHz sys clock) + OSC.CTRL = OSC_PLLEN_bm | OSC_XOSCEN_bm; // Enable PLL & External Oscillator + while (!(OSC.STATUS & OSC_PLLRDY_bm)); // wait for PLL ready + + CCP = CCP_IOREG_gc; + CLK.CTRL = CLK_SCLKSEL_PLL_gc; // switch to PLL clock + OSC.CTRL &= ~OSC_RC2MEN_bm; // disable internal 2 MHz clock +} + + +bool uart_has_char() {return UART_DEVICE.STATUS & USART_RXCIF_bm;} +uint8_t uart_recv_char() {return UART_DEVICE.DATA;} + + +void uart_send_char_blocking(uint8_t c) { + UART_DEVICE.DATA = c; + while (!(UART_DEVICE.STATUS & USART_TXCIF_bm)) continue; + UART_DEVICE.STATUS |= USART_TXCIF_bm; +} + + +void uart_init() { + UART_PORT.DIRSET = 1 << UART_TX_PIN; + UART_DEVICE.BAUDCTRLA = UART_BSEL_VALUE & USART_BSEL_gm; + UART_DEVICE.BAUDCTRLB = + ((UART_BSCALE_VALUE << USART_BSCALE_gp) & USART_BSCALE_gm) | + ((UART_BSEL_VALUE >> 8) & ~USART_BSCALE_gm); + UART_DEVICE.CTRLB = USART_RXEN_bm | USART_TXEN_bm; + + PORTC.OUTCLR = 1 << 4; // CTS Lo (enable) + PORTC.DIRSET = 1 << 4; // CTS Output +} + + +void uart_deinit() { + UART_DEVICE.CTRLB = 0; + UART_DEVICE.BAUDCTRLA = 0; + UART_DEVICE.BAUDCTRLB = 0; + UART_PORT.DIRCLR = 1 << UART_TX_PIN; +} + + +void watchdog_init() { + uint8_t temp = WDT_ENABLE_bm | WDT_CEN_bm | WDT_PER_1KCLK_gc; + CCP = CCP_IOREG_gc; + WDT.CTRL = temp; + while (WDT.STATUS & WDT_SYNCBUSY_bm) continue; +} + + +void watchdog_reset() {asm("wdr");} + + +void watchdog_disable() { + uint8_t temp = (WDT.CTRL & ~WDT_ENABLE_bm) | WDT_CEN_bm; + CCP = CCP_IOREG_gc; + WDT.CTRL = temp; +} + + +void nvm_wait() {while (NVM_STATUS & NVM_NVMBUSY_bp) watchdog_reset();} + + +void nvm_exec() { + void *z = (void *)&NVM_CTRLA; + + __asm__ volatile + ("out %[ccp], %[ioreg]\n" + "st z, %[cmdex]" :: + [ccp] "I" (_SFR_IO_ADDR(CCP)), + [ioreg] "d" (CCP_IOREG_gc), + [cmdex] "r" (NVM_CMDEX_bm), + [z] "z" (z)); +} + + +uint8_t get_char() { + while (!uart_has_char()) continue; + return uart_recv_char(); +} + + +void send_char(uint8_t c) {uart_send_char_blocking(c);} + + +uint16_t get_word() { + uint8_t hi = get_char(); + uint8_t lo = get_char(); + return ((uint16_t)hi << 8) | lo; +} + + +uint8_t BlockLoad(unsigned size, uint8_t mem, uint32_t *address) { + watchdog_reset(); + + // fill up buffer + block_crc = 0xffff; + for (int i = 0; i < SPM_PAGESIZE; i++) + if (i < size) { + buffer[i] = get_char(); + block_crc = _crc16_update(block_crc, buffer[i]); + + } else buffer[i] = 0xff; + + switch (mem) { + case MEM_EEPROM: + eeprom_write_block(buffer, (uint8_t *)(uint16_t)*address, size); + *address += size; + break; + + case MEM_FLASH: + // NOTE: Flash programming, address is given in words. + SP_LoadFlashPage(buffer); + SP_EraseWriteApplicationPage(*address << 1); + *address += size >> 1; + nvm_wait(); + break; + + case MEM_USERSIG: + SP_LoadFlashPage(buffer); + SP_EraseUserSignatureRow(); + nvm_wait(); + SP_WriteUserSignatureRow(); + nvm_wait(); + break; + + default: return REPLY_ERROR; + } + + return REPLY_ACK; +} + + + +void BlockRead(unsigned size, uint8_t mem, uint32_t *address) { + switch (mem) { + case MEM_EEPROM: + eeprom_read_block(buffer, (uint8_t *)(uint16_t)*address, size); + *address += size; + + // send bytes + for (int i = 0; i < size; i++) + send_char(buffer[i]); + break; + + case MEM_FLASH: case MEM_USERSIG: case MEM_PRODSIG: { + *address <<= 1; // Convert address to bytes temporarily + + do { + switch (mem) { + case MEM_FLASH: send_char(SP_ReadByte(*address)); break; + case MEM_USERSIG: send_char(SP_ReadUserSignatureByte(*address)); break; + case MEM_PRODSIG: send_char(SP_ReadCalibrationByte(*address)); break; + } + + nvm_wait(); + + (*address)++; // Select next word in memory. + size--; // Subtract two bytes from number of bytes to read + } while (size); // Repeat until all block has been read + + *address >>= 1; // Convert address back to Flash words again. + break; + } + + default: break; + } +} + + +int main() { + // Init + clock_init(); + uart_init(); + watchdog_init(); + + // Check for trigger + bool in_bootloader = false; + uint16_t j = INITIAL_WAIT; + while (!in_bootloader && 0 < j--) { + if (uart_has_char()) in_bootloader = uart_recv_char() == CMD_SYNC; + watchdog_reset(); + _delay_ms(1); + } + + // Main bootloader + uint32_t address = 0; + uint16_t i = 0; + + while (in_bootloader) { + uint8_t val = get_char(); + watchdog_reset(); + + // Main bootloader parser + switch (val) { + case CMD_CHECK_AUTOINCREMENT: send_char(REPLY_YES); break; + + case CMD_SET_ADDRESS: + address = get_word(); + send_char(REPLY_ACK); + break; + + case CMD_SET_EXT_ADDRESS: { + uint8_t hi = get_char(); + address = ((uint32_t)hi << 16) | get_word(); + send_char(REPLY_ACK); + break; + } + + case CMD_CHIP_ERASE: + // Erase the application section + SP_EraseApplicationSection(); + + // Wait for completion + nvm_wait(); + + // Erase EEPROM + NVM.CMD = NVM_CMD_ERASE_EEPROM_gc; + nvm_exec(); + + send_char(REPLY_ACK); + break; + + case CMD_CHECK_BLOCK_SUPPORT: + send_char(REPLY_YES); + // Send block size (page size) + send_char(SPM_PAGESIZE >> 8); + send_char((uint8_t)SPM_PAGESIZE); + break; + + case CMD_BLOCK_LOAD: + i = get_word(); // Block size + val = get_char(); // Memory type + send_char(BlockLoad(i, val, &address)); // Load it + break; + + case CMD_BLOCK_READ: + i = get_word(); // Block size + val = get_char(); // Memory type + BlockRead(i, val, &address); // Read it + break; + + case CMD_READ_BYTE: { + unsigned w = SP_ReadWord(address << 1); + + send_char(w >> 8); + send_char(w); + + address++; + break; + } + + case CMD_WRITE_LOW_BYTE: + i = get_char(); // get low byte + send_char(REPLY_ACK); + break; + + case CMD_WRITE_HIGH_BYTE: + i |= (get_char() << 8); // get high byte; combine + SP_LoadFlashWord(address << 1, i); + address++; + send_char(REPLY_ACK); + break; + + case CMD_WRITE_PAGE: + if (address >= (APP_SECTION_SIZE >> 1)) + send_char(REPLY_ERROR); // don't allow bootloader overwrite + + else { + SP_WriteApplicationPage(address << 1); + send_char(REPLY_ACK); + } + break; + + case CMD_WRITE_EEPROM_BYTE: + eeprom_write_byte((uint8_t *)(uint16_t)address, get_char()); + address++; + send_char(REPLY_ACK); + break; + + case CMD_READ_EEPROM_BYTE: + send_char(eeprom_read_byte((uint8_t *)(uint16_t)address)); + address++; + break; + + case CMD_READ_LOW_FUSE_BITS: send_char(SP_ReadFuseByte(0)); break; + case CMD_READ_HIGH_FUSE_BITS: send_char(SP_ReadFuseByte(1)); break; + case CMD_READ_EXT_FUSE_BITS: send_char(SP_ReadFuseByte(2)); break; + + case CMD_ENTER_PROG_MODE: case CMD_LEAVE_PROG_MODE: + send_char(REPLY_ACK); + break; + + case CMD_EXIT_BOOTLOADER: + in_bootloader = false; + send_char(REPLY_ACK); + break; + + case CMD_PROGRAMMER_TYPE: send_char('S'); break; // serial + + case CMD_DEVICE_CODE: + send_char(123); // send only this device + send_char(0); // terminator + break; + + case CMD_SET_LED: case CMD_CLEAR_LED: case CMD_SET_TYPE: + get_char(); // discard parameter + send_char(REPLY_ACK); + break; + + case CMD_PROGRAM_ID: + send_char('b'); + send_char('b'); + send_char('c'); + send_char('t'); + send_char('r'); + send_char('l'); + send_char(' '); + break; + + case CMD_VERSION: + send_char('0'); + send_char('1'); + break; + + case CMD_READ_SIGNATURE: + send_char(SIGNATURE_2); + send_char(SIGNATURE_1); + send_char(SIGNATURE_0); + break; + + case CMD_BLOCK_CRC: + send_char(block_crc >> 8); + send_char((uint8_t)block_crc); + break; + + case CMD_SYNC: break; // ESC (0x1b) to sync + + default: // otherwise, error + send_char(REPLY_ERROR); + break; + } + + // Wait for any lingering SPM instructions to finish + nvm_wait(); + } + + // Deinit + uart_deinit(); + watchdog_disable(); + + // Disable further self programming until next reset + SP_LockSPM(); + + // Jump to application code + asm("jmp 0"); +} diff --git a/avr/src/boot/boot.h b/avr/src/boot/boot.h new file mode 100644 index 0000000..e4705b7 --- /dev/null +++ b/avr/src/boot/boot.h @@ -0,0 +1,108 @@ +/******************************************************************************\ + + This file is part of the Buildbotics firmware. + + Copyright (c) 2015 - 2017 Buildbotics LLC + Copyright (c) 2010 Alex Forencich + All rights reserved. + + This file ("the software") is free software: you can redistribute it + and/or modify it under the terms of the GNU General Public License, + version 2 as published by the Free Software Foundation. You should + have received a copy of the GNU General Public License, version 2 + along with the software. If not, see . + + The software 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 the software. If not, see + . + + For information regarding this software email: + "Joseph Coffland" + +\******************************************************************************/ + +#pragma once + +#define INITIAL_WAIT 1000 // In ms + +#define UART_RX_PIN 2 +#define UART_TX_PIN 3 +#define UART_PORT PORTC +#define UART_DEVICE USARTC0 + +// Baud rate 115200 @ 32Mhz +#define UART_BSEL_VALUE 150 +#define UART_BSCALE_VALUE -7 + + +// Protocol +enum { + CMD_SYNC = '\x1b', + + // Informational + CMD_CHECK_AUTOINCREMENT = 'a', + CMD_CHECK_BLOCK_SUPPORT = 'b', + CMD_PROGRAMMER_TYPE = 'p', + CMD_DEVICE_CODE = 't', + CMD_PROGRAM_ID = 'S', + CMD_VERSION = 'V', + CMD_HW_VERSION = 'v', // Unsupported extension + CMD_READ_SIGNATURE = 's', + + // Addressing + CMD_SET_ADDRESS = 'A', + CMD_SET_EXT_ADDRESS = 'H', + + // Erase + CMD_CHIP_ERASE = 'e', + + // Block Access + CMD_BLOCK_LOAD = 'B', + CMD_BLOCK_READ = 'g', + CMD_BLOCK_CRC = 'i', + + // Byte Access + CMD_READ_BYTE = 'R', + CMD_WRITE_LOW_BYTE = 'c', + CMD_WRITE_HIGH_BYTE = 'C', + CMD_WRITE_PAGE = 'm', + CMD_WRITE_EEPROM_BYTE = 'D', + CMD_READ_EEPROM_BYTE = 'd', + + // Lock and Fuse Bits + CMD_WRITE_LOCK_BITS = 'l', + CMD_READ_LOCK_BITS = 'r', + CMD_READ_LOW_FUSE_BITS = 'F', + CMD_READ_HIGH_FUSE_BITS = 'N', + CMD_READ_EXT_FUSE_BITS = 'Q', + + // Control + CMD_ENTER_PROG_MODE = 'P', + CMD_LEAVE_PROG_MODE = 'L', + CMD_EXIT_BOOTLOADER = 'E', + CMD_SET_LED = 'x', + CMD_CLEAR_LED = 'y', + CMD_SET_TYPE = 'T', +}; + + +// Memory types for block access +enum { + MEM_EEPROM = 'E', + MEM_FLASH = 'F', + MEM_USERSIG = 'U', + MEM_PRODSIG = 'P', +}; + + +// Command Responses +enum { + REPLY_ACK = '\r', + REPLY_YES = 'Y', + REPLY_ERROR = '?', +}; diff --git a/avr/src/boot/sp_driver.S b/avr/src/boot/sp_driver.S new file mode 100644 index 0000000..bbb1ee7 --- /dev/null +++ b/avr/src/boot/sp_driver.S @@ -0,0 +1,403 @@ +;****************************************************************************** +;* $Revision: 1153 $ +;* $Date: 2007-12-18 09:48:23 +0100 (ti, 18 des 2007) $ +;* +;* Copyright (c) 2007, Atmel Corporation 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. The name of ATMEL may not be used to endorse or promote products derived +;* from this software without specific prior written permission. +;* +;* THIS SOFTWARE IS PROVIDED BY ATMEL "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 EXPRESSLY AND +;* SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR ANY DIRECT, +;* INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +;* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +;* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +;* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +;* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +;* THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +;****************************************************************************** +;* +;* XMEGA Self-programming driver assembly source file. +;* +;* This file contains the low-level implementations for the +;* XMEGA Self-programming driver. It is written for the GCC Assembler. +;* +;* If any SPM instructions are used, the linker file must define a segment +;* named bootloader which must be located in the device Boot section. +;* This can be done by passing "-Wl,--section-start=.BOOT=0x020000" to the +;* linker with the correct address for the boot section. +;* +;* None of these routines clean up the NVM Command Register after use. It +;* is therefore important to write NVM_CMD_NO_OPERATION_gc (0x00) to this +;* register when finished using any of the functions in this driver. +;* +;* For all routines, it is important that any interrupt handlers do not +;* perform NVM operations. The user must implement a scheme for mutually +;* exclusive access to NVM. However, the 4-cycle timeout will work fine, +;* since writing to the Configuration Change Protection register (CCP) +;* automatically disables interrupts for 4 instruction cycles. +;* +;* Note on IAR calling convention: +;* Scratch registers: R18-R27, R30-R31 +;* Preserved registers: R2-R17, R28-R29 +;* Parameter registers: R8-R25 (2-,4-, or 8- byte alignment) +;* Return registers: R18-R25 (up to 64-bit) +;* +;* Application note: +;* AVR1316: XMEGA Self-programming +;* +;* Documentation +;* For comprehensive code documentation, supported compilers, compiler +;* settings and supported devices see readme.html +;* +;* Atmel Corporation: http:;www.atmel.com \n +;* Support email: avr@atmel.com + +#include + +; Defines not yet included in header file. +#define NVM_CMD_NO_OPERATION_gc 0x00 +#define NVM_CMD_READ_USER_SIG_ROW_gc 0x01 +#define NVM_CMD_READ_CALIB_ROW_gc 0x02 +#define NVM_CMD_READ_EEPROM_gc 0x06 +#define NVM_CMD_READ_FUSES_gc 0x07 +#define NVM_CMD_WRITE_LOCK_BITS_gc 0x08 +#define NVM_CMD_ERASE_USER_SIG_ROW_gc 0x18 +#define NVM_CMD_WRITE_USER_SIG_ROW_gc 0x1a +#define NVM_CMD_ERASE_APP_gc 0x20 +#define NVM_CMD_ERASE_APP_PAGE_gc 0x22 +#define NVM_CMD_LOAD_FLASH_BUFFER_gc 0x23 +#define NVM_CMD_WRITE_APP_PAGE_gc 0x24 +#define NVM_CMD_ERASE_WRITE_APP_PAGE_gc 0x25 +#define NVM_CMD_ERASE_FLASH_BUFFER_gc 0x26 +#define NVM_CMD_ERASE_BOOT_PAGE_gc 0x2a +#define NVM_CMD_WRITE_BOOT_PAGE_gc 0x2c +#define NVM_CMD_ERASE_WRITE_BOOT_PAGE_gc 0x2d +#define NVM_CMD_ERASE_EEPROM_gc 0x30 +#define NVM_CMD_ERASE_EEPROM_PAGE_gc 0x32 +#define NVM_CMD_LOAD_EEPROM_BUFFER_gc 0x33 +#define NVM_CMD_WRITE_EEPROM_PAGE_gc 0x34 +#define NVM_CMD_ERASE_WRITE_EEPROM_PAGE_gc 0x35 +#define NVM_CMD_ERASE_EEPROM_BUFFER_gc 0x36 +#define NVM_CMD_APP_CRC_gc 0x38 +#define NVM_CMD_BOOT_CRC_gc 0x39 +#define NVM_CMD_FLASH_RANGE_CRC_gc 0x3a +#define CCP_SPM_gc 0x9d +#define CCP_IOREG_gc 0xd8 + + +; Reads a byte from flash given by the address in R25:R24:R23:R22. +; +; Input: R25:R24:R23:R22. +; Returns: R24 - Read byte. +.section .text +.global SP_ReadByte + +SP_ReadByte: + in r19, RAMPZ ; Save RAMPZ. + out RAMPZ, r24 ; Load RAMPZ with the MSB of the address. + movw ZL, r22 ; Move the low bytes to the Z pointer + elpm r24, Z ; Extended load byte from address pointed to by Z. + out RAMPZ, r19 ; Restore RAMPZ register. + ret + + +; Reads a word from flash given by the address in R25:R24:R23:R22. +; +; Input: R25:R24:R23:R22. +; Returns: R25:R24 - Read word. +.section .text +.global SP_ReadWord + +SP_ReadWord: + in r19, RAMPZ ; Save RAMPZ. + out RAMPZ, r24 ; Load RAMPZ with the MSB of the address. + movw ZL, r22 ; Move the low bytes to the Z pointer + elpm r24, Z+ ; Extended load byte from address pointed to by Z. + elpm r25, Z ; Extended load byte from address pointed to by Z. + out RAMPZ, r19 ; Restore RAMPZ register. + ret + + +; Reads the calibration byte given by the index in R24. +; +; Input: R24 - Byte index. +; Returns: R24 - Calibration byte. +.section .text +.global SP_ReadCalibrationByte + +SP_ReadCalibrationByte: + ldi r20, NVM_CMD_READ_CALIB_ROW_gc ; Prepare NVM command in R20. + rjmp SP_CommonLPM ; Jump to common LPM code. + + +; Reads the user signature byte given by the index in R25:R24. +; +; Input: R25:R24 - Byte index. +; Returns: R24 - Signature byte. +.section .text +.global SP_ReadUserSignatureByte + +SP_ReadUserSignatureByte: + ldi r20, NVM_CMD_READ_USER_SIG_ROW_gc ; Prepare NVM command in R20. + rjmp SP_CommonLPM ; Jump to common LPM code. + + +; Reads the fuse byte given by the index in R24. +; +; Input: R24 - Byte index. +; Returns: R24 - Fuse byte. +.section .text +.global SP_ReadFuseByte + +SP_ReadFuseByte: + sts NVM_ADDR0, r24 ; Load fuse index into NVM Address Reg 0. + clr r24 ; Prepare a zero. + sts NVM_ADDR1, r24 ; Load zero into NVM Address Register 1. + sts NVM_ADDR2, r24 ; Load zero into NVM Address Register 2. + ldi r20, NVM_CMD_READ_FUSES_gc ; Prepare NVM command in R20. + rcall SP_CommonCMD ; Jump to common NVM Action code. + movw r24, r22 ; Move low byte to 1 byte return address. + ret + + +; Erases the user signature row. +.section .text +.global SP_EraseUserSignatureRow + +SP_EraseUserSignatureRow: + in r19, RAMPZ ; Save RAMPZ, restored in SP_CommonSPM. + ldi r20, NVM_CMD_ERASE_USER_SIG_ROW_gc ; Prepare NVM command in R20. + jmp SP_CommonSPM ; Jump to common SPM code. + + +; Writes the flash buffer to the user signature row. +.section .text +.global SP_WriteUserSignatureRow + +SP_WriteUserSignatureRow: + in r19, RAMPZ ; Save RAMPZ, restored in SP_CommonSPM. + ldi r20, NVM_CMD_WRITE_USER_SIG_ROW_gc ; Prepare NVM command in R20. + jmp SP_CommonSPM ; Jump to common SPM code. + + +; Erases the entire application section. +.section .text +.global SP_EraseApplicationSection + +SP_EraseApplicationSection: + in r19, RAMPZ ; Save RAMPZ, restored in SP_CommonSPM. + clr r24 ; Prepare a zero. + clr r25 + out RAMPZ, r24 ; Point into Application area. + ldi r20, NVM_CMD_ERASE_APP_gc ; Prepare NVM command in R20. + jmp SP_CommonSPM ; Jump to common SPM code. + + +; Writes the word from R23:R22 into the Flash page buffer at address R25:R24. +; +; Input: +; R25:R24 - Byte address into Flash page. +; R23:R22 - Word to write. +.section .text +.global SP_LoadFlashWord + +SP_LoadFlashWord: + in r19, RAMPZ ; Save RAMPZ, restored in SP_CommonSPM. + movw r0, r22 ; Prepare flash word in R1:R0. + ldi r20, NVM_CMD_LOAD_FLASH_BUFFER_gc ; Prepare NVM command in R20. + jmp SP_CommonSPM ; Jump to common SPM code. + + +; Writes an entire page from the SRAM buffer at +; address R25:R24 into the Flash page buffer. +; +; Note that you must define "-Wl,--section-start=.BOOT=0x020000" for the +; linker to place this function in the boot section with the correct address. +; +; Input: R25:R24 - 16-bit pointer to SRAM buffer. +.section .text +.global SP_LoadFlashPage + +SP_LoadFlashPage: + clr ZL ; Clear low byte of Z, to indicate start of page. + clr ZH ; Clear high byte of Z, to indicate start of page. + + out RAMPX, r1 ; Clear RAMPX pointer. + movw XL, r24 ; Load X with data buffer address. + + ldi r20, NVM_CMD_LOAD_FLASH_BUFFER_gc ; Prepare NVM command code in R20. + sts NVM_CMD, r20 ; Load it into NVM command register. + +#if APP_SECTION_PAGE_SIZE > 512 + ldi r22, ((APP_SECTION_PAGE_SIZE / 2) >> 8) +#endif + ldi r21, ((APP_SECTION_PAGE_SIZE / 2) & 0xff) ; Load R21 page word count. + ldi r18, CCP_SPM_gc ; Prepare Protect SPM signature in R16. + +SP_LoadFlashPage_1: + ld r0, X+ ; Load low byte from buffer into R0. + ld r1, X+ ; Load high byte from buffer into R1. + sts CCP, r18 ; Enable SPM operation (disables interrupts for 4 cycles). + spm ; Self-program. + adiw ZL, 2 ; Move Z to next Flash word. + +#if APP_SECTION_PAGE_SIZE > 512 + subi r21, 1 ; Decrement word count. + sbci r22, 0 +#else + dec r21 ; Decrement word count. +#endif + + brne SP_LoadFlashPage_1 ; Repeat until word cont is zero. + clr r1 ; Clear R1 for GCC _zero_reg_ to function properly. + ret + + +; Writes the page buffer to Flash at address R25:R24:R23:R22 +; in the application section. The address can point anywhere inside the page. +; +; Input: R25:R24:R23:R22 - Byte address into Flash page. +.section .text +.global SP_WriteApplicationPage + +SP_WriteApplicationPage: + in r19, RAMPZ ; Save RAMPZ, restored in SP_CommonSPM. + out RAMPZ, r24 ; Load RAMPZ with the MSB of the address. + movw r24, r22 ; Move low bytes of address to ZH:ZL from R23:R22 + ldi r20, NVM_CMD_WRITE_APP_PAGE_gc ; Prepare NVM command in R20. + jmp SP_CommonSPM ; Jump to common SPM code. + + +; Erases first and then writes the page buffer to the +; Flash page at address R25:R24:R23:R22 in the application section. The address +; can point anywhere inside the page. +; +; Input: R25:R24:R23:R22 - Byte address into Flash page. +.section .text +.global SP_EraseWriteApplicationPage + +SP_EraseWriteApplicationPage: + in r19, RAMPZ ; Save RAMPZ, restored in SP_CommonSPM. + out RAMPZ, r24 ; Load RAMPZ with the MSB of the address. + movw r24, r22 ; Move low bytes of address to ZH:ZL from R23:R22 + ldi r20, NVM_CMD_ERASE_WRITE_APP_PAGE_gc ; Prepare NVM command in R20. + jmp SP_CommonSPM ; Jump to common SPM code. + + + +; Locks all further access to SPM operations until next reset. +.section .text +.global SP_LockSPM + +SP_LockSPM: + ldi r18, CCP_IOREG_gc ; Prepare Protect IO-register signature in R18. + sts CCP, r18 ; Enable IO-register operation + ; (disables interrupts for 4 cycles). + ldi r18, NVM_SPMLOCK_bm ; Prepare bitmask for locking SPM into R18. + sts NVM_CTRLB, r18 ; Load bitmask into NVM Control Register B, + ; which locks SPM. + ret + + +; Wait for the SPM to finish and clears the command register. +; +; Note that this routine is blocking, and will halt any execution until the SPM +; is finished. +.section .text +.global SP_WaitForSPM + +SP_WaitForSPM: + lds r18, NVM_STATUS ; Load the NVM Status register. + sbrc r18, NVM_NVMBUSY_bp ; Check if bit is cleared. + rjmp SP_WaitForSPM ; Repeat check if bit is not cleared. + clr r18 + sts NVM_CMD, r18 ; Clear up command register to NO_OPERATION. + ret + + +; Called by several other routines, and contains common code +; for executing an NVM command, including the return statement itself. +; +; If the operation (NVM command) requires the NVM Address registers to be +; prepared, this must be done before jumping to this routine. +; +; Note that R25:R24:R23:R22 is used for returning results, even if the +; C-domain calling function only expects a single byte or even void. +; +; Input: R20 - NVM Command code. +; Returns: R25:R24:R23:R22 - 32-bit result from NVM operation. +.section .text + +SP_CommonCMD: + sts NVM_CMD, r20 ; Load command into NVM Command register. + ldi r18, CCP_IOREG_gc ; Prepare Protect IO-register signature in R18. + ldi r19, NVM_CMDEX_bm ; Prepare bitmask for setting NVM Command Execute + ; bit into R19. + sts CCP, r18 ; Enable IO-register operation + ; (disables interrupts for 4 cycles). + sts NVM_CTRLA, r19 ; Load bitmask into NVM Control Register A, + ; which executes the command. + lds r22, NVM_DATA0 ; Load NVM Data Register 0 into R22. + lds r23, NVM_DATA1 ; Load NVM Data Register 1 into R23. + lds r24, NVM_DATA2 ; Load NVM Data Register 2 into R24. + clr r25 ; Clear R25 in order to return a clean 32-bit value. + ret + + +; Called by several other routines, and contains common code +; for executing an LPM command, including the return statement itself. +; +; Note that R24 is used for returning results, even if the +; C-domain calling function expects a void. +; +; Input: +; R25:R24 - Low bytes of Z pointer. +; R20 - NVM Command code. +; +; Returns: R24 - Result from LPM operation. +.section .text + +SP_CommonLPM: + movw ZL, r24 ; Load index into Z. + sts NVM_CMD, r20 ; Load prepared command into NVM Command register. + lpm r24,Z + ret + + +; Called by several other routines, and contains common code +; for executing an SPM command, including the return statement itself. +; +; If the operation (SPM command) requires the R1:R0 registers to be +; prepared, this must be done before jumping to this routine. +; +; Note that you must define "-Wl,--section-start=.BOOT=0x020000" for the +; linker to place this function in the boot section with the correct address. +; +; Input: +; R1:R0 - Optional input to SPM command. +; R25:R24 - Low bytes of Z pointer. +; R20 - NVM Command code. +.section .text + +SP_CommonSPM: + movw ZL, r24 ; Load R25:R24 into Z. + sts NVM_CMD, r20 ; Load prepared command into NVM Command register. + ldi r18, CCP_SPM_gc ; Prepare Protect SPM signature in R18 + sts CCP, r18 ; Enable SPM operation (disables interrupts for 4 cycles). + spm ; Self-program. + clr r1 ; Clear R1 for GCC _zero_reg_ to function properly. + out RAMPZ, r19 ; Restore RAMPZ register. + ret diff --git a/avr/src/boot/sp_driver.h b/avr/src/boot/sp_driver.h new file mode 100644 index 0000000..01aeaee --- /dev/null +++ b/avr/src/boot/sp_driver.h @@ -0,0 +1,173 @@ +/******************************************************************************* + * $Revision: 1691 $ + * $Date: 2008-07-29 13:25:40 +0200 (ti, 29 jul 2008) $ \n + * + * Copyright (c) 2008, Atmel Corporation 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. The name of ATMEL may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "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 EXPRESSLY AND + * SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR ANY DIRECT, + * INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND + * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF + * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + ******************************************************************************/ + +/*! \file ********************************************************************** + * \brief XMEGA Self-programming driver header file. + * + * This file contains the function prototypes for the + * XMEGA Self-programming driver. + * If any SPM instructions are used, the linker file must define + * a segment named BOOT which must be located in the device boot section. + * + * + * None of these functions clean up the NVM Command Register after use. + * It is therefore important to write NVMCMD_NO_OPERATION (0x00) to this + * register when you are finished using any of the functions in this + * driver. + * + * For all functions, it is important that no interrupt handlers perform + * any NVM operations. The user must implement a scheme for mutually + * exclusive access to the NVM. However, the 4-cycle timeout will work + * fine, since writing to the Configuration Change Protection register + * (CCP) automatically disables interrupts for 4 instruction cycles. + * + * \par Application note: AVR1316: XMEGA Self-programming + * + * \par Documentation + * For comprehensive code documentation, supported compilers, compiler + * settings and supported devices see readme.html + * + * \author + * Atmel Corporation: http://www.atmel.com + * Support email: avr@atmel.com + ******************************************************************************/ + +#pragma once + +#include + +#include + +#ifndef APP_SECTION_PAGE_SIZE +#error APP_SECTION_PAGE_SIZE must be defined if not defined in header files. +#endif + +#ifndef APPTABLE_SECTION_START +#error APPTABLE_SECTION_START must be defined if not defined in header files. +#endif + + +/*! \brief Read a byte from flash. + * + * \param address Address to the location of the byte to read. + * \retval Byte read from flash. + */ +uint8_t SP_ReadByte(uint32_t address); + +/*! \brief Read a word from flash. + * + * This function reads one word from the flash. + * + * \param address Address to the location of the word to read. + * + * \retval word read from flash. + */ +uint16_t SP_ReadWord(uint32_t address); + +/*! \brief Read calibration byte at given index. + * + * This function reads one calibration byte from the Calibration signature row. + * + * \param index Index of the byte in the calibration signature row. + * + * \retval Calibration byte + */ +uint8_t SP_ReadCalibrationByte(uint8_t index); + +/*! \brief Read fuse byte from given index. + * + * This function reads the fuse byte at the given index. + * + * \param index Index of the fuse byte. + * \retval Fuse byte + */ +uint8_t SP_ReadFuseByte(uint8_t index); + +/*! \brief Read user signature at given index. + * + * \param index Index of the byte in the user signature row. + * \retval User signature byte + */ +uint8_t SP_ReadUserSignatureByte(uint16_t index); + +/// Erase user signature row. +void SP_EraseUserSignatureRow(); + +/// Write user signature row. +void SP_WriteUserSignatureRow(); + +/*! \brief Erase entire application section. + * + * \note If the lock bits is set to not allow SPM in the application or + * application table section the erase is not done. + */ +void SP_EraseApplicationSection(); + +/*! \brief Erase and write page buffer to application or application table + * section at byte address. + * + * \param address Byte address for flash page. + */ +void SP_EraseWriteApplicationPage(uint32_t address); + +/*! \brief Write page buffer to application or application table section at + * byte address. + * + * \note The page that is written to must be erased before it is written to. + * + * \param address Byte address for flash page. + */ +void SP_WriteApplicationPage(uint32_t address); + +/*! \brief Load one word into Flash page buffer. + * + * \param address Position in inside the flash page buffer. + * \param data Value to be put into the buffer. + */ +void SP_LoadFlashWord(uint16_t address, uint16_t data); + +/*! \brief Load entire page from SRAM buffer into Flash page buffer. + * + * \param data Pointer to the data to put in buffer. + * + * \note The __near keyword limits the pointer to two bytes which means that + * only data up to 64K (internal SRAM) can be used. + */ +void SP_LoadFlashPage(const uint8_t *data); + +/// Flush Flash page buffer. +void SP_EraseFlashBuffer(); + +/// Disables the use of SPM until the next reset. +void SP_LockSPM(); + +/// Waits for the SPM to finish and clears the command register. +void SP_WaitForSPM(); diff --git a/avr/src/drv8711.c b/avr/src/drv8711.c index 7788334..71b840a 100644 --- a/avr/src/drv8711.c +++ b/avr/src/drv8711.c @@ -233,7 +233,7 @@ static void _init_spi_commands() { // Set DECAY commands[spi.ncmds++] = - DRV8711_WRITE(DRV8711_DECAY_REG, DRV8711_DECAY_DECMOD_OPT | 6); + DRV8711_WRITE(DRV8711_DECAY_REG, DRV8711_DECAY_DECMOD_AUTO_OPT | 6); // Set STALL commands[spi.ncmds++] = diff --git a/avr/src/xboot/sp_driver.S b/avr/src/xboot/sp_driver.S deleted file mode 100644 index bbb1ee7..0000000 --- a/avr/src/xboot/sp_driver.S +++ /dev/null @@ -1,403 +0,0 @@ -;****************************************************************************** -;* $Revision: 1153 $ -;* $Date: 2007-12-18 09:48:23 +0100 (ti, 18 des 2007) $ -;* -;* Copyright (c) 2007, Atmel Corporation 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. The name of ATMEL may not be used to endorse or promote products derived -;* from this software without specific prior written permission. -;* -;* THIS SOFTWARE IS PROVIDED BY ATMEL "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 EXPRESSLY AND -;* SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR ANY DIRECT, -;* INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES -;* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; -;* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND -;* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT -;* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF -;* THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. -;****************************************************************************** -;* -;* XMEGA Self-programming driver assembly source file. -;* -;* This file contains the low-level implementations for the -;* XMEGA Self-programming driver. It is written for the GCC Assembler. -;* -;* If any SPM instructions are used, the linker file must define a segment -;* named bootloader which must be located in the device Boot section. -;* This can be done by passing "-Wl,--section-start=.BOOT=0x020000" to the -;* linker with the correct address for the boot section. -;* -;* None of these routines clean up the NVM Command Register after use. It -;* is therefore important to write NVM_CMD_NO_OPERATION_gc (0x00) to this -;* register when finished using any of the functions in this driver. -;* -;* For all routines, it is important that any interrupt handlers do not -;* perform NVM operations. The user must implement a scheme for mutually -;* exclusive access to NVM. However, the 4-cycle timeout will work fine, -;* since writing to the Configuration Change Protection register (CCP) -;* automatically disables interrupts for 4 instruction cycles. -;* -;* Note on IAR calling convention: -;* Scratch registers: R18-R27, R30-R31 -;* Preserved registers: R2-R17, R28-R29 -;* Parameter registers: R8-R25 (2-,4-, or 8- byte alignment) -;* Return registers: R18-R25 (up to 64-bit) -;* -;* Application note: -;* AVR1316: XMEGA Self-programming -;* -;* Documentation -;* For comprehensive code documentation, supported compilers, compiler -;* settings and supported devices see readme.html -;* -;* Atmel Corporation: http:;www.atmel.com \n -;* Support email: avr@atmel.com - -#include - -; Defines not yet included in header file. -#define NVM_CMD_NO_OPERATION_gc 0x00 -#define NVM_CMD_READ_USER_SIG_ROW_gc 0x01 -#define NVM_CMD_READ_CALIB_ROW_gc 0x02 -#define NVM_CMD_READ_EEPROM_gc 0x06 -#define NVM_CMD_READ_FUSES_gc 0x07 -#define NVM_CMD_WRITE_LOCK_BITS_gc 0x08 -#define NVM_CMD_ERASE_USER_SIG_ROW_gc 0x18 -#define NVM_CMD_WRITE_USER_SIG_ROW_gc 0x1a -#define NVM_CMD_ERASE_APP_gc 0x20 -#define NVM_CMD_ERASE_APP_PAGE_gc 0x22 -#define NVM_CMD_LOAD_FLASH_BUFFER_gc 0x23 -#define NVM_CMD_WRITE_APP_PAGE_gc 0x24 -#define NVM_CMD_ERASE_WRITE_APP_PAGE_gc 0x25 -#define NVM_CMD_ERASE_FLASH_BUFFER_gc 0x26 -#define NVM_CMD_ERASE_BOOT_PAGE_gc 0x2a -#define NVM_CMD_WRITE_BOOT_PAGE_gc 0x2c -#define NVM_CMD_ERASE_WRITE_BOOT_PAGE_gc 0x2d -#define NVM_CMD_ERASE_EEPROM_gc 0x30 -#define NVM_CMD_ERASE_EEPROM_PAGE_gc 0x32 -#define NVM_CMD_LOAD_EEPROM_BUFFER_gc 0x33 -#define NVM_CMD_WRITE_EEPROM_PAGE_gc 0x34 -#define NVM_CMD_ERASE_WRITE_EEPROM_PAGE_gc 0x35 -#define NVM_CMD_ERASE_EEPROM_BUFFER_gc 0x36 -#define NVM_CMD_APP_CRC_gc 0x38 -#define NVM_CMD_BOOT_CRC_gc 0x39 -#define NVM_CMD_FLASH_RANGE_CRC_gc 0x3a -#define CCP_SPM_gc 0x9d -#define CCP_IOREG_gc 0xd8 - - -; Reads a byte from flash given by the address in R25:R24:R23:R22. -; -; Input: R25:R24:R23:R22. -; Returns: R24 - Read byte. -.section .text -.global SP_ReadByte - -SP_ReadByte: - in r19, RAMPZ ; Save RAMPZ. - out RAMPZ, r24 ; Load RAMPZ with the MSB of the address. - movw ZL, r22 ; Move the low bytes to the Z pointer - elpm r24, Z ; Extended load byte from address pointed to by Z. - out RAMPZ, r19 ; Restore RAMPZ register. - ret - - -; Reads a word from flash given by the address in R25:R24:R23:R22. -; -; Input: R25:R24:R23:R22. -; Returns: R25:R24 - Read word. -.section .text -.global SP_ReadWord - -SP_ReadWord: - in r19, RAMPZ ; Save RAMPZ. - out RAMPZ, r24 ; Load RAMPZ with the MSB of the address. - movw ZL, r22 ; Move the low bytes to the Z pointer - elpm r24, Z+ ; Extended load byte from address pointed to by Z. - elpm r25, Z ; Extended load byte from address pointed to by Z. - out RAMPZ, r19 ; Restore RAMPZ register. - ret - - -; Reads the calibration byte given by the index in R24. -; -; Input: R24 - Byte index. -; Returns: R24 - Calibration byte. -.section .text -.global SP_ReadCalibrationByte - -SP_ReadCalibrationByte: - ldi r20, NVM_CMD_READ_CALIB_ROW_gc ; Prepare NVM command in R20. - rjmp SP_CommonLPM ; Jump to common LPM code. - - -; Reads the user signature byte given by the index in R25:R24. -; -; Input: R25:R24 - Byte index. -; Returns: R24 - Signature byte. -.section .text -.global SP_ReadUserSignatureByte - -SP_ReadUserSignatureByte: - ldi r20, NVM_CMD_READ_USER_SIG_ROW_gc ; Prepare NVM command in R20. - rjmp SP_CommonLPM ; Jump to common LPM code. - - -; Reads the fuse byte given by the index in R24. -; -; Input: R24 - Byte index. -; Returns: R24 - Fuse byte. -.section .text -.global SP_ReadFuseByte - -SP_ReadFuseByte: - sts NVM_ADDR0, r24 ; Load fuse index into NVM Address Reg 0. - clr r24 ; Prepare a zero. - sts NVM_ADDR1, r24 ; Load zero into NVM Address Register 1. - sts NVM_ADDR2, r24 ; Load zero into NVM Address Register 2. - ldi r20, NVM_CMD_READ_FUSES_gc ; Prepare NVM command in R20. - rcall SP_CommonCMD ; Jump to common NVM Action code. - movw r24, r22 ; Move low byte to 1 byte return address. - ret - - -; Erases the user signature row. -.section .text -.global SP_EraseUserSignatureRow - -SP_EraseUserSignatureRow: - in r19, RAMPZ ; Save RAMPZ, restored in SP_CommonSPM. - ldi r20, NVM_CMD_ERASE_USER_SIG_ROW_gc ; Prepare NVM command in R20. - jmp SP_CommonSPM ; Jump to common SPM code. - - -; Writes the flash buffer to the user signature row. -.section .text -.global SP_WriteUserSignatureRow - -SP_WriteUserSignatureRow: - in r19, RAMPZ ; Save RAMPZ, restored in SP_CommonSPM. - ldi r20, NVM_CMD_WRITE_USER_SIG_ROW_gc ; Prepare NVM command in R20. - jmp SP_CommonSPM ; Jump to common SPM code. - - -; Erases the entire application section. -.section .text -.global SP_EraseApplicationSection - -SP_EraseApplicationSection: - in r19, RAMPZ ; Save RAMPZ, restored in SP_CommonSPM. - clr r24 ; Prepare a zero. - clr r25 - out RAMPZ, r24 ; Point into Application area. - ldi r20, NVM_CMD_ERASE_APP_gc ; Prepare NVM command in R20. - jmp SP_CommonSPM ; Jump to common SPM code. - - -; Writes the word from R23:R22 into the Flash page buffer at address R25:R24. -; -; Input: -; R25:R24 - Byte address into Flash page. -; R23:R22 - Word to write. -.section .text -.global SP_LoadFlashWord - -SP_LoadFlashWord: - in r19, RAMPZ ; Save RAMPZ, restored in SP_CommonSPM. - movw r0, r22 ; Prepare flash word in R1:R0. - ldi r20, NVM_CMD_LOAD_FLASH_BUFFER_gc ; Prepare NVM command in R20. - jmp SP_CommonSPM ; Jump to common SPM code. - - -; Writes an entire page from the SRAM buffer at -; address R25:R24 into the Flash page buffer. -; -; Note that you must define "-Wl,--section-start=.BOOT=0x020000" for the -; linker to place this function in the boot section with the correct address. -; -; Input: R25:R24 - 16-bit pointer to SRAM buffer. -.section .text -.global SP_LoadFlashPage - -SP_LoadFlashPage: - clr ZL ; Clear low byte of Z, to indicate start of page. - clr ZH ; Clear high byte of Z, to indicate start of page. - - out RAMPX, r1 ; Clear RAMPX pointer. - movw XL, r24 ; Load X with data buffer address. - - ldi r20, NVM_CMD_LOAD_FLASH_BUFFER_gc ; Prepare NVM command code in R20. - sts NVM_CMD, r20 ; Load it into NVM command register. - -#if APP_SECTION_PAGE_SIZE > 512 - ldi r22, ((APP_SECTION_PAGE_SIZE / 2) >> 8) -#endif - ldi r21, ((APP_SECTION_PAGE_SIZE / 2) & 0xff) ; Load R21 page word count. - ldi r18, CCP_SPM_gc ; Prepare Protect SPM signature in R16. - -SP_LoadFlashPage_1: - ld r0, X+ ; Load low byte from buffer into R0. - ld r1, X+ ; Load high byte from buffer into R1. - sts CCP, r18 ; Enable SPM operation (disables interrupts for 4 cycles). - spm ; Self-program. - adiw ZL, 2 ; Move Z to next Flash word. - -#if APP_SECTION_PAGE_SIZE > 512 - subi r21, 1 ; Decrement word count. - sbci r22, 0 -#else - dec r21 ; Decrement word count. -#endif - - brne SP_LoadFlashPage_1 ; Repeat until word cont is zero. - clr r1 ; Clear R1 for GCC _zero_reg_ to function properly. - ret - - -; Writes the page buffer to Flash at address R25:R24:R23:R22 -; in the application section. The address can point anywhere inside the page. -; -; Input: R25:R24:R23:R22 - Byte address into Flash page. -.section .text -.global SP_WriteApplicationPage - -SP_WriteApplicationPage: - in r19, RAMPZ ; Save RAMPZ, restored in SP_CommonSPM. - out RAMPZ, r24 ; Load RAMPZ with the MSB of the address. - movw r24, r22 ; Move low bytes of address to ZH:ZL from R23:R22 - ldi r20, NVM_CMD_WRITE_APP_PAGE_gc ; Prepare NVM command in R20. - jmp SP_CommonSPM ; Jump to common SPM code. - - -; Erases first and then writes the page buffer to the -; Flash page at address R25:R24:R23:R22 in the application section. The address -; can point anywhere inside the page. -; -; Input: R25:R24:R23:R22 - Byte address into Flash page. -.section .text -.global SP_EraseWriteApplicationPage - -SP_EraseWriteApplicationPage: - in r19, RAMPZ ; Save RAMPZ, restored in SP_CommonSPM. - out RAMPZ, r24 ; Load RAMPZ with the MSB of the address. - movw r24, r22 ; Move low bytes of address to ZH:ZL from R23:R22 - ldi r20, NVM_CMD_ERASE_WRITE_APP_PAGE_gc ; Prepare NVM command in R20. - jmp SP_CommonSPM ; Jump to common SPM code. - - - -; Locks all further access to SPM operations until next reset. -.section .text -.global SP_LockSPM - -SP_LockSPM: - ldi r18, CCP_IOREG_gc ; Prepare Protect IO-register signature in R18. - sts CCP, r18 ; Enable IO-register operation - ; (disables interrupts for 4 cycles). - ldi r18, NVM_SPMLOCK_bm ; Prepare bitmask for locking SPM into R18. - sts NVM_CTRLB, r18 ; Load bitmask into NVM Control Register B, - ; which locks SPM. - ret - - -; Wait for the SPM to finish and clears the command register. -; -; Note that this routine is blocking, and will halt any execution until the SPM -; is finished. -.section .text -.global SP_WaitForSPM - -SP_WaitForSPM: - lds r18, NVM_STATUS ; Load the NVM Status register. - sbrc r18, NVM_NVMBUSY_bp ; Check if bit is cleared. - rjmp SP_WaitForSPM ; Repeat check if bit is not cleared. - clr r18 - sts NVM_CMD, r18 ; Clear up command register to NO_OPERATION. - ret - - -; Called by several other routines, and contains common code -; for executing an NVM command, including the return statement itself. -; -; If the operation (NVM command) requires the NVM Address registers to be -; prepared, this must be done before jumping to this routine. -; -; Note that R25:R24:R23:R22 is used for returning results, even if the -; C-domain calling function only expects a single byte or even void. -; -; Input: R20 - NVM Command code. -; Returns: R25:R24:R23:R22 - 32-bit result from NVM operation. -.section .text - -SP_CommonCMD: - sts NVM_CMD, r20 ; Load command into NVM Command register. - ldi r18, CCP_IOREG_gc ; Prepare Protect IO-register signature in R18. - ldi r19, NVM_CMDEX_bm ; Prepare bitmask for setting NVM Command Execute - ; bit into R19. - sts CCP, r18 ; Enable IO-register operation - ; (disables interrupts for 4 cycles). - sts NVM_CTRLA, r19 ; Load bitmask into NVM Control Register A, - ; which executes the command. - lds r22, NVM_DATA0 ; Load NVM Data Register 0 into R22. - lds r23, NVM_DATA1 ; Load NVM Data Register 1 into R23. - lds r24, NVM_DATA2 ; Load NVM Data Register 2 into R24. - clr r25 ; Clear R25 in order to return a clean 32-bit value. - ret - - -; Called by several other routines, and contains common code -; for executing an LPM command, including the return statement itself. -; -; Note that R24 is used for returning results, even if the -; C-domain calling function expects a void. -; -; Input: -; R25:R24 - Low bytes of Z pointer. -; R20 - NVM Command code. -; -; Returns: R24 - Result from LPM operation. -.section .text - -SP_CommonLPM: - movw ZL, r24 ; Load index into Z. - sts NVM_CMD, r20 ; Load prepared command into NVM Command register. - lpm r24,Z - ret - - -; Called by several other routines, and contains common code -; for executing an SPM command, including the return statement itself. -; -; If the operation (SPM command) requires the R1:R0 registers to be -; prepared, this must be done before jumping to this routine. -; -; Note that you must define "-Wl,--section-start=.BOOT=0x020000" for the -; linker to place this function in the boot section with the correct address. -; -; Input: -; R1:R0 - Optional input to SPM command. -; R25:R24 - Low bytes of Z pointer. -; R20 - NVM Command code. -.section .text - -SP_CommonSPM: - movw ZL, r24 ; Load R25:R24 into Z. - sts NVM_CMD, r20 ; Load prepared command into NVM Command register. - ldi r18, CCP_SPM_gc ; Prepare Protect SPM signature in R18 - sts CCP, r18 ; Enable SPM operation (disables interrupts for 4 cycles). - spm ; Self-program. - clr r1 ; Clear R1 for GCC _zero_reg_ to function properly. - out RAMPZ, r19 ; Restore RAMPZ register. - ret diff --git a/avr/src/xboot/sp_driver.h b/avr/src/xboot/sp_driver.h deleted file mode 100644 index 01aeaee..0000000 --- a/avr/src/xboot/sp_driver.h +++ /dev/null @@ -1,173 +0,0 @@ -/******************************************************************************* - * $Revision: 1691 $ - * $Date: 2008-07-29 13:25:40 +0200 (ti, 29 jul 2008) $ \n - * - * Copyright (c) 2008, Atmel Corporation 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. The name of ATMEL may not be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY ATMEL "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 EXPRESSLY AND - * SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR ANY DIRECT, - * INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES - * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND - * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT - * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF - * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - ******************************************************************************/ - -/*! \file ********************************************************************** - * \brief XMEGA Self-programming driver header file. - * - * This file contains the function prototypes for the - * XMEGA Self-programming driver. - * If any SPM instructions are used, the linker file must define - * a segment named BOOT which must be located in the device boot section. - * - * - * None of these functions clean up the NVM Command Register after use. - * It is therefore important to write NVMCMD_NO_OPERATION (0x00) to this - * register when you are finished using any of the functions in this - * driver. - * - * For all functions, it is important that no interrupt handlers perform - * any NVM operations. The user must implement a scheme for mutually - * exclusive access to the NVM. However, the 4-cycle timeout will work - * fine, since writing to the Configuration Change Protection register - * (CCP) automatically disables interrupts for 4 instruction cycles. - * - * \par Application note: AVR1316: XMEGA Self-programming - * - * \par Documentation - * For comprehensive code documentation, supported compilers, compiler - * settings and supported devices see readme.html - * - * \author - * Atmel Corporation: http://www.atmel.com - * Support email: avr@atmel.com - ******************************************************************************/ - -#pragma once - -#include - -#include - -#ifndef APP_SECTION_PAGE_SIZE -#error APP_SECTION_PAGE_SIZE must be defined if not defined in header files. -#endif - -#ifndef APPTABLE_SECTION_START -#error APPTABLE_SECTION_START must be defined if not defined in header files. -#endif - - -/*! \brief Read a byte from flash. - * - * \param address Address to the location of the byte to read. - * \retval Byte read from flash. - */ -uint8_t SP_ReadByte(uint32_t address); - -/*! \brief Read a word from flash. - * - * This function reads one word from the flash. - * - * \param address Address to the location of the word to read. - * - * \retval word read from flash. - */ -uint16_t SP_ReadWord(uint32_t address); - -/*! \brief Read calibration byte at given index. - * - * This function reads one calibration byte from the Calibration signature row. - * - * \param index Index of the byte in the calibration signature row. - * - * \retval Calibration byte - */ -uint8_t SP_ReadCalibrationByte(uint8_t index); - -/*! \brief Read fuse byte from given index. - * - * This function reads the fuse byte at the given index. - * - * \param index Index of the fuse byte. - * \retval Fuse byte - */ -uint8_t SP_ReadFuseByte(uint8_t index); - -/*! \brief Read user signature at given index. - * - * \param index Index of the byte in the user signature row. - * \retval User signature byte - */ -uint8_t SP_ReadUserSignatureByte(uint16_t index); - -/// Erase user signature row. -void SP_EraseUserSignatureRow(); - -/// Write user signature row. -void SP_WriteUserSignatureRow(); - -/*! \brief Erase entire application section. - * - * \note If the lock bits is set to not allow SPM in the application or - * application table section the erase is not done. - */ -void SP_EraseApplicationSection(); - -/*! \brief Erase and write page buffer to application or application table - * section at byte address. - * - * \param address Byte address for flash page. - */ -void SP_EraseWriteApplicationPage(uint32_t address); - -/*! \brief Write page buffer to application or application table section at - * byte address. - * - * \note The page that is written to must be erased before it is written to. - * - * \param address Byte address for flash page. - */ -void SP_WriteApplicationPage(uint32_t address); - -/*! \brief Load one word into Flash page buffer. - * - * \param address Position in inside the flash page buffer. - * \param data Value to be put into the buffer. - */ -void SP_LoadFlashWord(uint16_t address, uint16_t data); - -/*! \brief Load entire page from SRAM buffer into Flash page buffer. - * - * \param data Pointer to the data to put in buffer. - * - * \note The __near keyword limits the pointer to two bytes which means that - * only data up to 64K (internal SRAM) can be used. - */ -void SP_LoadFlashPage(const uint8_t *data); - -/// Flush Flash page buffer. -void SP_EraseFlashBuffer(); - -/// Disables the use of SPM until the next reset. -void SP_LockSPM(); - -/// Waits for the SPM to finish and clears the command register. -void SP_WaitForSPM(); diff --git a/avr/src/xboot/xboot.c b/avr/src/xboot/xboot.c deleted file mode 100644 index e2d700f..0000000 --- a/avr/src/xboot/xboot.c +++ /dev/null @@ -1,408 +0,0 @@ -/******************************************************************************\ - - This file is part of the Buildbotics firmware. - - Copyright (c) 2015 - 2017 Buildbotics LLC - Copyright (c) 2010 Alex Forencich - All rights reserved. - - This file ("the software") is free software: you can redistribute it - and/or modify it under the terms of the GNU General Public License, - version 2 as published by the Free Software Foundation. You should - have received a copy of the GNU General Public License, version 2 - along with the software. If not, see . - - The software 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 the software. If not, see - . - - For information regarding this software email: - "Joseph Coffland" - -\******************************************************************************/ - -#include "xboot.h" -#include "sp_driver.h" - -#include -#include - -#include -#include - -#include - - -uint8_t buffer[SPM_PAGESIZE]; -uint16_t block_crc = 0; - - -void clock_init() { - // External 16Mhz Xtal w/ 2x PLL = 32 Mhz - // 12-16 MHz crystal; 0.4-16 MHz XTAL w/ 16K CLK startup - OSC.XOSCCTRL = OSC_FRQRANGE_12TO16_gc | OSC_XOSCSEL_XTAL_16KCLK_gc; - OSC.CTRL = OSC_XOSCEN_bm; // enable external crystal oscillator - while (!(OSC.STATUS & OSC_XOSCRDY_bm)); // wait for oscillator ready - - OSC.PLLCTRL = OSC_PLLSRC_XOSC_gc | 2; // PLL source, 2x (32 MHz sys clock) - OSC.CTRL = OSC_PLLEN_bm | OSC_XOSCEN_bm; // Enable PLL & External Oscillator - while (!(OSC.STATUS & OSC_PLLRDY_bm)); // wait for PLL ready - - CCP = CCP_IOREG_gc; - CLK.CTRL = CLK_SCLKSEL_PLL_gc; // switch to PLL clock - OSC.CTRL &= ~OSC_RC2MEN_bm; // disable internal 2 MHz clock -} - - -bool uart_has_char() {return UART_DEVICE.STATUS & USART_RXCIF_bm;} -uint8_t uart_recv_char() {return UART_DEVICE.DATA;} - - -void uart_send_char_blocking(uint8_t c) { - UART_DEVICE.DATA = c; - while (!(UART_DEVICE.STATUS & USART_TXCIF_bm)) continue; - UART_DEVICE.STATUS |= USART_TXCIF_bm; -} - - -void uart_init() { - UART_PORT.DIRSET = 1 << UART_TX_PIN; - UART_DEVICE.BAUDCTRLA = UART_BSEL_VALUE & USART_BSEL_gm; - UART_DEVICE.BAUDCTRLB = - ((UART_BSCALE_VALUE << USART_BSCALE_gp) & USART_BSCALE_gm) | - ((UART_BSEL_VALUE >> 8) & ~USART_BSCALE_gm); - UART_DEVICE.CTRLB = USART_RXEN_bm | USART_TXEN_bm; - - PORTC.OUTCLR = 1 << 4; // CTS Lo (enable) - PORTC.DIRSET = 1 << 4; // CTS Output -} - - -void uart_deinit() { - UART_DEVICE.CTRLB = 0; - UART_DEVICE.BAUDCTRLA = 0; - UART_DEVICE.BAUDCTRLB = 0; - UART_PORT.DIRCLR = 1 << UART_TX_PIN; -} - - -void watchdog_init() { - uint8_t temp = WDT_ENABLE_bm | WDT_CEN_bm | WDT_PER_1KCLK_gc; - CCP = CCP_IOREG_gc; - WDT.CTRL = temp; - while (WDT.STATUS & WDT_SYNCBUSY_bm) continue; -} - - -void watchdog_reset() {asm("wdr");} - - -void watchdog_disable() { - uint8_t temp = (WDT.CTRL & ~WDT_ENABLE_bm) | WDT_CEN_bm; - CCP = CCP_IOREG_gc; - WDT.CTRL = temp; -} - - -void nvm_wait() {while (NVM_STATUS & NVM_NVMBUSY_bp) watchdog_reset();} - - -void nvm_exec() { - void *z = (void *)&NVM_CTRLA; - - __asm__ volatile - ("out %[ccp], %[ioreg]\n" - "st z, %[cmdex]" :: - [ccp] "I" (_SFR_IO_ADDR(CCP)), - [ioreg] "d" (CCP_IOREG_gc), - [cmdex] "r" (NVM_CMDEX_bm), - [z] "z" (z)); -} - - -uint8_t get_char() { - while (!uart_has_char()) continue; - return uart_recv_char(); -} - - -void send_char(uint8_t c) {uart_send_char_blocking(c);} - - -uint16_t get_word() { - uint8_t hi = get_char(); - uint8_t lo = get_char(); - return ((uint16_t)hi << 8) | lo; -} - - -uint8_t BlockLoad(unsigned size, uint8_t mem, uint32_t *address) { - watchdog_reset(); - - // fill up buffer - block_crc = 0xffff; - for (int i = 0; i < SPM_PAGESIZE; i++) - if (i < size) { - buffer[i] = get_char(); - block_crc = _crc16_update(block_crc, buffer[i]); - - } else buffer[i] = 0xff; - - switch (mem) { - case MEM_EEPROM: - eeprom_write_block(buffer, (uint8_t *)(uint16_t)*address, size); - *address += size; - break; - - case MEM_FLASH: - // NOTE: Flash programming, address is given in words. - SP_LoadFlashPage(buffer); - SP_EraseWriteApplicationPage(*address << 1); - *address += size >> 1; - nvm_wait(); - break; - - case MEM_USERSIG: - SP_LoadFlashPage(buffer); - SP_EraseUserSignatureRow(); - nvm_wait(); - SP_WriteUserSignatureRow(); - nvm_wait(); - break; - - default: return REPLY_ERROR; - } - - return REPLY_ACK; -} - - - -void BlockRead(unsigned size, uint8_t mem, uint32_t *address) { - switch (mem) { - case MEM_EEPROM: - eeprom_read_block(buffer, (uint8_t *)(uint16_t)*address, size); - *address += size; - - // send bytes - for (int i = 0; i < size; i++) - send_char(buffer[i]); - break; - - case MEM_FLASH: case MEM_USERSIG: case MEM_PRODSIG: { - *address <<= 1; // Convert address to bytes temporarily - - do { - switch (mem) { - case MEM_FLASH: send_char(SP_ReadByte(*address)); break; - case MEM_USERSIG: send_char(SP_ReadUserSignatureByte(*address)); break; - case MEM_PRODSIG: send_char(SP_ReadCalibrationByte(*address)); break; - } - - nvm_wait(); - - (*address)++; // Select next word in memory. - size--; // Subtract two bytes from number of bytes to read - } while (size); // Repeat until all block has been read - - *address >>= 1; // Convert address back to Flash words again. - break; - } - - default: break; - } -} - - -int main() { - // Init - clock_init(); - uart_init(); - watchdog_init(); - - // Check for trigger - bool in_bootloader = false; - uint16_t j = INITIAL_WAIT; - while (!in_bootloader && 0 < j--) { - if (uart_has_char()) in_bootloader = uart_recv_char() == CMD_SYNC; - watchdog_reset(); - _delay_ms(1); - } - - // Main bootloader - uint32_t address = 0; - uint16_t i = 0; - - while (in_bootloader) { - uint8_t val = get_char(); - watchdog_reset(); - - // Main bootloader parser - switch (val) { - case CMD_CHECK_AUTOINCREMENT: send_char(REPLY_YES); break; - - case CMD_SET_ADDRESS: - address = get_word(); - send_char(REPLY_ACK); - break; - - case CMD_SET_EXT_ADDRESS: { - uint8_t hi = get_char(); - address = ((uint32_t)hi << 16) | get_word(); - send_char(REPLY_ACK); - break; - } - - case CMD_CHIP_ERASE: - // Erase the application section - SP_EraseApplicationSection(); - - // Wait for completion - nvm_wait(); - - // Erase EEPROM - NVM.CMD = NVM_CMD_ERASE_EEPROM_gc; - nvm_exec(); - - send_char(REPLY_ACK); - break; - - case CMD_CHECK_BLOCK_SUPPORT: - send_char(REPLY_YES); - // Send block size (page size) - send_char(SPM_PAGESIZE >> 8); - send_char((uint8_t)SPM_PAGESIZE); - break; - - case CMD_BLOCK_LOAD: - i = get_word(); // Block size - val = get_char(); // Memory type - send_char(BlockLoad(i, val, &address)); // Load it - break; - - case CMD_BLOCK_READ: - i = get_word(); // Block size - val = get_char(); // Memory type - BlockRead(i, val, &address); // Read it - break; - - case CMD_READ_BYTE: { - unsigned w = SP_ReadWord(address << 1); - - send_char(w >> 8); - send_char(w); - - address++; - break; - } - - case CMD_WRITE_LOW_BYTE: - i = get_char(); // get low byte - send_char(REPLY_ACK); - break; - - case CMD_WRITE_HIGH_BYTE: - i |= (get_char() << 8); // get high byte; combine - SP_LoadFlashWord(address << 1, i); - address++; - send_char(REPLY_ACK); - break; - - case CMD_WRITE_PAGE: - if (address >= (APP_SECTION_SIZE >> 1)) - send_char(REPLY_ERROR); // don't allow bootloader overwrite - - else { - SP_WriteApplicationPage(address << 1); - send_char(REPLY_ACK); - } - break; - - case CMD_WRITE_EEPROM_BYTE: - eeprom_write_byte((uint8_t *)(uint16_t)address, get_char()); - address++; - send_char(REPLY_ACK); - break; - - case CMD_READ_EEPROM_BYTE: - send_char(eeprom_read_byte((uint8_t *)(uint16_t)address)); - address++; - break; - - case CMD_READ_LOW_FUSE_BITS: send_char(SP_ReadFuseByte(0)); break; - case CMD_READ_HIGH_FUSE_BITS: send_char(SP_ReadFuseByte(1)); break; - case CMD_READ_EXT_FUSE_BITS: send_char(SP_ReadFuseByte(2)); break; - - case CMD_ENTER_PROG_MODE: case CMD_LEAVE_PROG_MODE: - send_char(REPLY_ACK); - break; - - case CMD_EXIT_BOOTLOADER: - in_bootloader = false; - send_char(REPLY_ACK); - break; - - case CMD_PROGRAMMER_TYPE: send_char('S'); break; // serial - - case CMD_DEVICE_CODE: - send_char(123); // send only this device - send_char(0); // terminator - break; - - case CMD_SET_LED: case CMD_CLEAR_LED: case CMD_SET_TYPE: - get_char(); // discard parameter - send_char(REPLY_ACK); - break; - - case CMD_PROGRAM_ID: - send_char('b'); - send_char('b'); - send_char('c'); - send_char('t'); - send_char('r'); - send_char('l'); - send_char(' '); - break; - - case CMD_VERSION: - send_char('0'); - send_char('1'); - break; - - case CMD_READ_SIGNATURE: - send_char(SIGNATURE_2); - send_char(SIGNATURE_1); - send_char(SIGNATURE_0); - break; - - case CMD_BLOCK_CRC: - send_char(block_crc >> 8); - send_char((uint8_t)block_crc); - break; - - case CMD_SYNC: break; // ESC (0x1b) to sync - - default: // otherwise, error - send_char(REPLY_ERROR); - break; - } - - // Wait for any lingering SPM instructions to finish - nvm_wait(); - } - - // Deinit - uart_deinit(); - watchdog_disable(); - - // Disable further self programming until next reset - SP_LockSPM(); - - // Jump to application code - asm("jmp 0"); -} diff --git a/avr/src/xboot/xboot.h b/avr/src/xboot/xboot.h deleted file mode 100644 index e4705b7..0000000 --- a/avr/src/xboot/xboot.h +++ /dev/null @@ -1,108 +0,0 @@ -/******************************************************************************\ - - This file is part of the Buildbotics firmware. - - Copyright (c) 2015 - 2017 Buildbotics LLC - Copyright (c) 2010 Alex Forencich - All rights reserved. - - This file ("the software") is free software: you can redistribute it - and/or modify it under the terms of the GNU General Public License, - version 2 as published by the Free Software Foundation. You should - have received a copy of the GNU General Public License, version 2 - along with the software. If not, see . - - The software 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 the software. If not, see - . - - For information regarding this software email: - "Joseph Coffland" - -\******************************************************************************/ - -#pragma once - -#define INITIAL_WAIT 1000 // In ms - -#define UART_RX_PIN 2 -#define UART_TX_PIN 3 -#define UART_PORT PORTC -#define UART_DEVICE USARTC0 - -// Baud rate 115200 @ 32Mhz -#define UART_BSEL_VALUE 150 -#define UART_BSCALE_VALUE -7 - - -// Protocol -enum { - CMD_SYNC = '\x1b', - - // Informational - CMD_CHECK_AUTOINCREMENT = 'a', - CMD_CHECK_BLOCK_SUPPORT = 'b', - CMD_PROGRAMMER_TYPE = 'p', - CMD_DEVICE_CODE = 't', - CMD_PROGRAM_ID = 'S', - CMD_VERSION = 'V', - CMD_HW_VERSION = 'v', // Unsupported extension - CMD_READ_SIGNATURE = 's', - - // Addressing - CMD_SET_ADDRESS = 'A', - CMD_SET_EXT_ADDRESS = 'H', - - // Erase - CMD_CHIP_ERASE = 'e', - - // Block Access - CMD_BLOCK_LOAD = 'B', - CMD_BLOCK_READ = 'g', - CMD_BLOCK_CRC = 'i', - - // Byte Access - CMD_READ_BYTE = 'R', - CMD_WRITE_LOW_BYTE = 'c', - CMD_WRITE_HIGH_BYTE = 'C', - CMD_WRITE_PAGE = 'm', - CMD_WRITE_EEPROM_BYTE = 'D', - CMD_READ_EEPROM_BYTE = 'd', - - // Lock and Fuse Bits - CMD_WRITE_LOCK_BITS = 'l', - CMD_READ_LOCK_BITS = 'r', - CMD_READ_LOW_FUSE_BITS = 'F', - CMD_READ_HIGH_FUSE_BITS = 'N', - CMD_READ_EXT_FUSE_BITS = 'Q', - - // Control - CMD_ENTER_PROG_MODE = 'P', - CMD_LEAVE_PROG_MODE = 'L', - CMD_EXIT_BOOTLOADER = 'E', - CMD_SET_LED = 'x', - CMD_CLEAR_LED = 'y', - CMD_SET_TYPE = 'T', -}; - - -// Memory types for block access -enum { - MEM_EEPROM = 'E', - MEM_FLASH = 'F', - MEM_USERSIG = 'U', - MEM_PRODSIG = 'P', -}; - - -// Command Responses -enum { - REPLY_ACK = '\r', - REPLY_YES = 'Y', - REPLY_ERROR = '?', -};