Commit 0491bb50 authored by Tomasz Wlostowski's avatar Tomasz Wlostowski Committed by Grzegorz Daniluk

tools: added simple UART bootloader

parent 1533d7f7
This diff is collapsed.
#!/usr/bin/python
our_port="/dev/ttyUSB0"
import sys
import time
import serial
ser = serial.Serial(port=our_port,baudrate=115200,timeout=1,rtscts=False)
fw = open(sys.argv[1], "rb").read()
while(ser.read(1) != 'B'):
pass
while(ser.read(1) != 'o'):
pass
while(ser.read(1) != 'o'):
pass
while(ser.read(1) != 't'):
pass
while(ser.read(1) != '?'):
pass
time.sleep(0.01)
ser.write('Y')
while(ser.read(1) != 'O'):
pass
while(ser.read(1) != 'K'):
pass
time.sleep(10e-6);
l = len(fw)
print("Bootloader OK, writing %d bytes." % l)
ser.write(chr((l >> 24) & 0xff));
time.sleep(100e-6);
ser.write(chr((l >> 16) & 0xff));
time.sleep(100e-6);
ser.write(chr((l >> 8) & 0xff));
time.sleep(100e-6);
ser.write(chr((l >> 0) & 0xff));
n=0
for b in fw:
n+=1
ser.write(b)
time.sleep(100e-6)
if n % 10000 == 0:
print("%d/%d bytes programmed." % (n,len(fw)))
while(ser.read(1) != 'G'):
time.sleep(100e-6)
print("Programming done!")
# and don't touch the rest unless you know what you're doing.
CROSS_COMPILE ?= lm32-elf-
CC = $(CROSS_COMPILE)gcc
LD = $(CROSS_COMPILE)ld
OBJDUMP = $(CROSS_COMPILE)objdump
OBJCOPY = $(CROSS_COMPILE)objcopy
SIZE = $(CROSS_COMPILE)size
CFLAGS = -Os -I../common -I. -mmultiply-enabled -mbarrel-shift-enabled -ffunction-sections -fdata-sections
OBJS = boot-crt0.o uart.o boot.o timer.o
LDS = boot.ld
LDFLAGS = -mmultiply-enabled -mbarrel-shift-enabled -Wl,--gc-sections
OUTPUT=boot
$(OUTPUT): $(LDS) $(OBJS)
${CC} -o $(OUTPUT).elf -nostartfiles $(OBJS) -T $(LDS) -lgcc -lc
${OBJCOPY} -O binary $(OUTPUT).elf $(OUTPUT).bin
${OBJDUMP} -D $(OUTPUT).elf > disasm.S
$(SIZE) $(OUTPUT).elf
../genraminit $(OUTPUT).bin 32768 > wrc-bootloader.ram
clean:
rm -f $(OBJS) $(OUTPUT).bin
\ No newline at end of file
/*
* DSI Shield
*
* Copyright (C) 2013-2014 twl
*
* This program is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or (at your
* option) any later version.
*
* This program 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
* General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/* board.h - system/hardware definitions */
#ifndef __BOARD_H
#define __BOARD_H
#include <stdint.h>
#define BASE_CLOCK 62500000 // Xtal frequency
#define BASE_UART 0x20500
#define BASE_SYSCON 0x20400
#define UART_BAUDRATE 115200
void timer_init();
uint32_t timer_get_tics();
static inline void writel ( uint32_t reg, uint32_t val)
{
*(volatile uint32_t *)(reg) = val;
}
static inline uint32_t readl ( uint32_t reg )
{
return *(volatile uint32_t *)(reg);
}
static inline uint32_t get_ms_ticks()
{
return timer_get_tics();
}
#endif
/****************************************************************************
**
** Name: crt0ram.S
**
** Description:
** Implements boot-code that calls LatticeDDInit (that calls main())
** Implements exception handlers (actually, redirectors)
**
** $Revision: $
**
** Disclaimer:
**
** This source code is intended as a design reference which
** illustrates how these types of functions can be implemented. It
** is the user's responsibility to verify their design for
** consistency and functionality through the use of formal
** verification methods. Lattice Semiconductor provides no warranty
** regarding the use or functionality of this code.
**
** --------------------------------------------------------------------
**
** Lattice Semiconductor Corporation
** 5555 NE Moore Court
** Hillsboro, OR 97214
** U.S.A
**
** TEL: 1-800-Lattice (USA and Canada)
** (503)268-8001 (other locations)
**
** web: http://www.latticesemi.com
** email: techsupport@latticesemi.com
**
** --------------------------------------------------------------------------
**
** Change History (Latest changes on top)
**
** Ver Date Description
** --------------------------------------------------------------------------
** 3.8 Apr-15-2011 Added __MICO_USER_<handler>_HANDLER__ preprocessor to
** allow customers to implement their own handlers for:
** DATA_ABORT, INST_ABORT
**
** 3.1 Jun-18-2008 Added __MICO_NO_INTERRUPTS__ preprocessor
** option to exclude invoking MicoISRHandler
** to reduce code-size in apps that don't use
** interrupts
**
** 3.0 Mar-25-2008 Added Header
**
**---------------------------------------------------------------------------
*****************************************************************************/
/*
* LatticeMico32 C startup code.
*
* 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.
*
* THIS SOFTWARE IS PROVIDED BY THE AUTHOR 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 AUTHOR 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.
*/
/* From include/sys/signal.h */
#define SIGINT 2 /* interrupt */
#define SIGTRAP 5 /* trace trap */
#define SIGFPE 8 /* arithmetic exception */
#define SIGSEGV 11 /* segmentation violation */
//#define MICO32_FULL_CONTEXT_SAVE_RESTORE
/* Exception handlers - Must be 32 bytes long. */
.section .boot, "ax", @progbits
.global _start
_start:
_reset_handler:
bi _reset_handler_bootldr
.section .text
.global _reset_handler_bootldr
.type _reset_handler_bootldr, @function
_reset_handler_bootldr:
xor r0, r0, r0
wcsr IE, r0
wcsr IM, r0
wcsr ICC, r0
mvhi r1, hi(_reset_handler)
ori r1, r1, lo(_reset_handler)
wcsr EBA, r1
calli _crt0
nop
/* .size _reset_handler, .-_reset_handler */
.global _crt0
.type _crt0, @function
_crt0:
/* Clear r0 */
xor r0, r0, r0
/* Setup stack and global pointer */
mvhi sp, hi(_fstack)
ori sp, sp, lo(_fstack)
mvhi gp, hi(_gp)
ori gp, gp, lo(_gp)
mvi r1, 0
mvi r2, 0
mvi r3, 0
calli main
loopf:
bi loopf
/*
* DSI Shield
*
* Copyright (C) 2013-2015 twl
*
* This program is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or (at your
* option) any later version.
*
* This program 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
* General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/* main.c - main bootloader application */
#include <stdint.h>
#include <stdio.h>
#include "board.h"
#ifdef CONFIG_FLASH
#include "flash.h"
#endif
#ifndef CONFIG_USER_START
#define CONFIG_USER_START 0x0
#endif
#include "uart.h"
#define CMD_INIT 1
#define CMD_ERASE_SECTOR 2
#define CMD_WRITE_PAGE 3
#define CMD_WRITE_RAM 4
#define CMD_GO 5
#define RSP_OK 1
#define RSP_HELLO 5
#define RSP_CRC_ERROR 2
#define RSP_VERIFY_ERROR 3
#define RSP_BAD_CRC 4
#define POLY 0x8408
#define RX_BUF_SIZE (256 + 16)
#define BOOT_TIMEOUT 500
#define UART_TIMEOUT 2000
uint8_t rxbuf[RX_BUF_SIZE];
int boot_wait;
static uint32_t orig_reset_vector = 0x4;
typedef void (*voidfunc_t)();
uint16_t crc_xmodem_update(uint16_t crc, uint8_t data)
{
int i;
crc = crc ^ (((uint16_t)data) << 8);
for (i = 0; i < 8; i++)
{
if (crc & 0x8000)
{
crc = (crc << 1) ^ 0x1021;
} else {
crc <<= 1;
}
}
return crc;
}
uint16_t
crc16(unsigned char *buf, int len)
{
int i;
uint16_t cksum;
cksum = 0;
for (i = 0; i < len; i++) {
cksum = crc_xmodem_update(cksum, buf[i]);
}
return cksum;
}
int timeout_hit = 0;
uint8_t uart_read_blocking()
{
uint32_t t_end = get_ms_ticks() + UART_TIMEOUT;
while (get_ms_ticks() < t_end)
if (uart_poll())
return uart_read_byte();
timeout_hit = 1;
return 0;
}
void uart_readm_blocking(uint8_t *buf, int count)
{
int i;
for (i = 0; i < count; i++)
{
buf[i] = uart_read_blocking();
if (timeout_hit)
return;
}
}
void send_reply(uint8_t code)
{
uint8_t buf[16];
uint16_t crc, i;
buf[0] = 0x55;
buf[1] = 0xaa;
buf[2] = code;
buf[3] = 0;
buf[4] = 0;
crc = crc16(buf, 5);
buf[5] = (crc >> 8);
buf[6] = (crc & 0xff);
for (i = 0; i < 7; i++)
uart_write_byte(buf[i]);
}
void on_cmd_init()
{
boot_wait = 0;
send_reply(RSP_OK);
}
uint32_t unpack_be32(uint8_t *p)
{
uint32_t rv = 0;
rv |= p[3];
rv |= ((uint32_t)p[2]) << 8;
rv |= ((uint32_t)p[1]) << 16;
rv |= ((uint32_t)p[0]) << 24;
return rv;
}
#ifdef CONFIG_FLASH
void on_cmd_erase_sector(uint8_t *payload, int len)
{
uint32_t base = unpack_be32(payload);
flash_write_enable();
flash_erase_sector(base);
send_reply(RSP_OK);
}
void on_cmd_write_page(uint8_t *payload, int len)
{
uint32_t base = unpack_be32(payload);
flash_write_enable();
flash_program_page(base, payload + 4, len - 4);
send_reply(RSP_OK);
}
#endif
void on_cmd_write_ram(uint8_t *payload, int len)
{
int i;
uint32_t base = unpack_be32(payload);
for (i = 0; i < len - 4; i++)
{
if (base + i < 4)
{ // special case for the entry vector address
switch(base + i)
{
case 1: orig_reset_vector = ((uint32_t)payload[i+4]) << 18; break;
case 2: orig_reset_vector |= ((uint32_t)payload[i+4]) << 10; break;
case 3: orig_reset_vector |= ((uint32_t)payload[i+4]) << 2; break;
default:
break;
}
}
else
{
*(uint8_t *)(base + i) = payload[i + 4];
}
}
send_reply(RSP_OK);
}
void on_cmd_go(uint8_t *payload, int len)
{
uint32_t base = unpack_be32(payload);
voidfunc_t f = (voidfunc_t)base;
send_reply(RSP_OK);
f();
}
void boot_fsm()
{
uint32_t t_exit = get_ms_ticks() + BOOT_TIMEOUT;
boot_wait = 1;
send_reply(RSP_HELLO);
for (;;)
{
int pos = 0, i;
uint16_t crc;
if (boot_wait && (get_ms_ticks() > t_exit))
return;
timeout_hit = 0;
int c = uart_read_blocking();
if ((c != 0x55) || timeout_hit)
{
continue;
}
rxbuf[pos++] = c;
c = uart_read_blocking();
if ((c != 0xaa) || timeout_hit)
continue;
rxbuf[pos++] = c;
uint8_t command = uart_read_blocking();
rxbuf[pos++] = command;
rxbuf[pos++] = uart_read_blocking();
rxbuf[pos++] = uart_read_blocking();
uint16_t len = (uint16_t)rxbuf[3] << 8 | rxbuf[4];
if (timeout_hit)
continue;
for (i = 0; i < len; i++)
rxbuf[pos++] = uart_read_blocking();
crc = (uint16_t)uart_read_blocking() << 8;
crc |= (uint16_t)uart_read_blocking();
if (timeout_hit)
continue;
if (crc != crc16(rxbuf, len + 5))
{
send_reply(RSP_BAD_CRC);
}
switch (command)
{
case CMD_INIT:
on_cmd_init(rxbuf + 5, len);
break;
case CMD_ERASE_SECTOR:
#ifdef CONFIG_FLASH
on_cmd_erase_sector(rxbuf + 5, len);
#endif
break;
case CMD_WRITE_PAGE:
#ifdef CONFIG_FLASH
on_cmd_write_page(rxbuf + 5, len);
#endif
break;
case CMD_WRITE_RAM:
on_cmd_write_ram(rxbuf + 5, len);
break;
case CMD_GO:
on_cmd_go(rxbuf + 5, len);
break;
default:
break;
}
}
}
void start_user()
{
voidfunc_t f = (voidfunc_t)orig_reset_vector;
f();
}
int main()
{
uart_init_hw();
#ifdef CONFIG_FLASH
flash_init();
#endif
boot_fsm();
start_user();
return 0;
}
OUTPUT_FORMAT("elf32-lm32")
ENTRY(_start)
MEMORY
{
preboot :
ORIGIN = 0x00000000,
LENGTH = 0x100
ram :
ORIGIN = 131072 - 4096,
LENGTH = 2048
stack :
ORIGIN = 131072 - 2048,
LENGTH = 2038
}
SECTIONS
{
.boot : { *(.boot) } > preboot
.text : { *(.text .text.*) } > ram =0
.rodata : { *(.rodata .rodata.*) } > ram
.data : {
*(.data .data.*)
_gp = ALIGN(16) + 0x7ff0;
} > ram
.bss : {
_fbss = .;
*(.bss .bss.*)
*(COMMON)
_ebss = .;
} > ram
PROVIDE(_endram = ORIGIN(stack));
PROVIDE(_fstack = ORIGIN(stack) + LENGTH(stack) - 4);
}
PROVIDE(mprintf = pp_printf);
/*
Register definitions for slave core: Simple Wishbone UART
* File : ../../../../software/include/hw/wb_uart.h
* Author : auto-generated by wbgen2 from uart.wb
* Created : Mon Feb 21 22:25:02 2011
* Standard : ANSI C
THIS FILE WAS GENERATED BY wbgen2 FROM SOURCE FILE uart.wb
DO NOT HAND-EDIT UNLESS IT'S ABSOLUTELY NECESSARY!
*/
#ifndef __WBGEN2_REGDEFS_UART_WB
#define __WBGEN2_REGDEFS_UART_WB
#include <inttypes.h>
#if defined( __GNUC__)
#define PACKED __attribute__ ((packed))
#else
#error "Unsupported compiler?"
#endif
#ifndef __WBGEN2_MACROS_DEFINED__
#define __WBGEN2_MACROS_DEFINED__
#define WBGEN2_GEN_MASK(offset, size) (((1<<(size))-1) << (offset))
#define WBGEN2_GEN_WRITE(value, offset, size) (((value) & ((1<<(size))-1)) << (offset))
#define WBGEN2_GEN_READ(reg, offset, size) (((reg) >> (offset)) & ((1<<(size))-1))
#define WBGEN2_SIGN_EXTEND(value, bits) (((value) & (1<<bits) ? ~((1<<(bits))-1): 0 ) | (value))
#endif
/* definitions for register: Status Register */
/* definitions for field: TX busy in reg: Status Register */
#define UART_SR_TX_BUSY WBGEN2_GEN_MASK(0, 1)
/* definitions for field: RX ready in reg: Status Register */
#define UART_SR_RX_RDY WBGEN2_GEN_MASK(1, 1)
/* definitions for register: Baudrate control register */
/* definitions for register: Transmit data regsiter */
/* definitions for field: Transmit data in reg: Transmit data regsiter */
#define UART_TDR_TX_DATA_MASK WBGEN2_GEN_MASK(0, 8)
#define UART_TDR_TX_DATA_SHIFT 0
#define UART_TDR_TX_DATA_W(value) WBGEN2_GEN_WRITE(value, 0, 8)
#define UART_TDR_TX_DATA_R(reg) WBGEN2_GEN_READ(reg, 0, 8)
/* definitions for register: Receive data regsiter */
/* definitions for field: Received data in reg: Receive data regsiter */
#define UART_RDR_RX_DATA_MASK WBGEN2_GEN_MASK(0, 8)
#define UART_RDR_RX_DATA_SHIFT 0
#define UART_RDR_RX_DATA_W(value) WBGEN2_GEN_WRITE(value, 0, 8)
#define UART_RDR_RX_DATA_R(reg) WBGEN2_GEN_READ(reg, 0, 8)
/* [0x0]: REG Status Register */
#define UART_REG_SR 0x00000000
/* [0x4]: REG Baudrate control register */
#define UART_REG_BCR 0x00000004
/* [0x8]: REG Transmit data regsiter */
#define UART_REG_TDR 0x00000008
/* [0xc]: REG Receive data regsiter */
#define UART_REG_RDR 0x0000000c
PACKED struct UART_WB {
/* [0x0]: REG Status Register */
uint32_t SR;
/* [0x4]: REG Baudrate control register */
uint32_t BCR;
/* [0x8]: REG Transmit data regsiter */
uint32_t TDR;
/* [0xc]: REG Receive data regsiter */
uint32_t RDR;
};
#endif
/*
Register definitions for slave core: WR Core System Controller
* File : wrc_syscon_regs.h
* Author : auto-generated by wbgen2 from wrc_syscon_wb.wb
* Created : Fri Feb 17 10:20:14 2012
* Standard : ANSI C
THIS FILE WAS GENERATED BY wbgen2 FROM SOURCE FILE wrc_syscon_wb.wb
DO NOT HAND-EDIT UNLESS IT'S ABSOLUTELY NECESSARY!
*/
#ifndef __WBGEN2_REGDEFS_WRC_SYSCON_WB_WB
#define __WBGEN2_REGDEFS_WRC_SYSCON_WB_WB
#include <inttypes.h>
#if defined( __GNUC__)
#define PACKED __attribute__ ((packed))
#else
#error "Unsupported compiler?"
#endif
#ifndef __WBGEN2_MACROS_DEFINED__
#define __WBGEN2_MACROS_DEFINED__
#define WBGEN2_GEN_MASK(offset, size) (((1<<(size))-1) << (offset))
#define WBGEN2_GEN_WRITE(value, offset, size) (((value) & ((1<<(size))-1)) << (offset))
#define WBGEN2_GEN_READ(reg, offset, size) (((reg) >> (offset)) & ((1<<(size))-1))
#define WBGEN2_SIGN_EXTEND(value, bits) (((value) & (1<<bits) ? ~((1<<(bits))-1): 0 ) | (value))
#endif
/* definitions for register: Syscon reset register */
/* definitions for field: Reset trigger in reg: Syscon reset register */
#define SYSC_RSTR_TRIG_MASK WBGEN2_GEN_MASK(0, 28)
#define SYSC_RSTR_TRIG_SHIFT 0
#define SYSC_RSTR_TRIG_W(value) WBGEN2_GEN_WRITE(value, 0, 28)
#define SYSC_RSTR_TRIG_R(reg) WBGEN2_GEN_READ(reg, 0, 28)
/* definitions for field: Reset line state value in reg: Syscon reset register */
#define SYSC_RSTR_RST WBGEN2_GEN_MASK(28, 1)
/* definitions for register: GPIO Set/Readback Register */
/* definitions for field: Status LED in reg: GPIO Set/Readback Register */
#define SYSC_GPSR_LED_STAT WBGEN2_GEN_MASK(0, 1)
/* definitions for field: Link LED in reg: GPIO Set/Readback Register */
#define SYSC_GPSR_LED_LINK WBGEN2_GEN_MASK(1, 1)
/* definitions for field: FMC I2C bitbanged SCL in reg: GPIO Set/Readback Register */
#define SYSC_GPSR_FMC_SCL WBGEN2_GEN_MASK(2, 1)
/* definitions for field: FMC I2C bitbanged SDA in reg: GPIO Set/Readback Register */
#define SYSC_GPSR_FMC_SDA WBGEN2_GEN_MASK(3, 1)
/* definitions for field: Network AP reset in reg: GPIO Set/Readback Register */
#define SYSC_GPSR_NET_RST WBGEN2_GEN_MASK(4, 1)
/* definitions for field: SPEC Pushbutton 1 state in reg: GPIO Set/Readback Register */
#define SYSC_GPSR_BTN1 WBGEN2_GEN_MASK(5, 1)
/* definitions for field: SPEC Pushbutton 2 state in reg: GPIO Set/Readback Register */
#define SYSC_GPSR_BTN2 WBGEN2_GEN_MASK(6, 1)
/* definitions for field: SFP detect (MOD_DEF0 signal) in reg: GPIO Set/Readback Register */
#define SYSC_GPSR_SFP_DET WBGEN2_GEN_MASK(7, 1)
/* definitions for field: SFP I2C bitbanged SCL in reg: GPIO Set/Readback Register */
#define SYSC_GPSR_SFP_SCL WBGEN2_GEN_MASK(8, 1)
/* definitions for field: SFP I2C bitbanged SDA in reg: GPIO Set/Readback Register */
#define SYSC_GPSR_SFP_SDA WBGEN2_GEN_MASK(9, 1)
/* definitions for register: GPIO Clear Register */
/* definitions for field: Status LED in reg: GPIO Clear Register */
#define SYSC_GPCR_LED_STAT WBGEN2_GEN_MASK(0, 1)
/* definitions for field: Link LED in reg: GPIO Clear Register */
#define SYSC_GPCR_LED_LINK WBGEN2_GEN_MASK(1, 1)
/* definitions for field: FMC I2C bitbanged SCL in reg: GPIO Clear Register */
#define SYSC_GPCR_FMC_SCL WBGEN2_GEN_MASK(2, 1)
/* definitions for field: FMC I2C bitbanged SDA in reg: GPIO Clear Register */
#define SYSC_GPCR_FMC_SDA WBGEN2_GEN_MASK(3, 1)
/* definitions for field: SFP I2C bitbanged SCL in reg: GPIO Clear Register */
#define SYSC_GPCR_SFP_SCL WBGEN2_GEN_MASK(8, 1)
/* definitions for field: FMC I2C bitbanged SDA in reg: GPIO Clear Register */
#define SYSC_GPCR_SFP_SDA WBGEN2_GEN_MASK(9, 1)
/* definitions for register: Hardware Feature Register */
/* definitions for field: Memory size in reg: Hardware Feature Register */
#define SYSC_HWFR_MEMSIZE_MASK WBGEN2_GEN_MASK(0, 4)
#define SYSC_HWFR_MEMSIZE_SHIFT 0
#define SYSC_HWFR_MEMSIZE_W(value) WBGEN2_GEN_WRITE(value, 0, 4)
#define SYSC_HWFR_MEMSIZE_R(reg) WBGEN2_GEN_READ(reg, 0, 4)
/* definitions for register: Timer Control Register */
/* definitions for field: Timer Divider in reg: Timer Control Register */
#define SYSC_TCR_TDIV_MASK WBGEN2_GEN_MASK(0, 12)
#define SYSC_TCR_TDIV_SHIFT 0
#define SYSC_TCR_TDIV_W(value) WBGEN2_GEN_WRITE(value, 0, 12)
#define SYSC_TCR_TDIV_R(reg) WBGEN2_GEN_READ(reg, 0, 12)
/* definitions for field: Timer Enable in reg: Timer Control Register */
#define SYSC_TCR_ENABLE WBGEN2_GEN_MASK(31, 1)
/* definitions for register: Timer Counter Value Register */
/* [0x0]: REG Syscon reset register */
#define SYSC_REG_RSTR 0x00000000
/* [0x4]: REG GPIO Set/Readback Register */
#define SYSC_REG_GPSR 0x00000004
/* [0x8]: REG GPIO Clear Register */
#define SYSC_REG_GPCR 0x00000008
/* [0xc]: REG Hardware Feature Register */
#define SYSC_REG_HWFR 0x0000000c
/* [0x10]: REG Timer Control Register */
#define SYSC_REG_TCR 0x00000010
/* [0x14]: REG Timer Counter Value Register */
#define SYSC_REG_TVR 0x00000014
#endif
#include "board.h"
#include "hw/wrc_syscon_regs.h"
void timer_init()
{
writel( SYSC_TCR_ENABLE, BASE_SYSCON + SYSC_REG_TCR );
}
uint32_t timer_get_tics()
{
pp_printf("getTics: 0x%x\n", BASE_SYSCON + SYSC_REG_TVR, readl( BASE_SYSCON + SYSC_REG_TVR ));
return readl( BASE_SYSCON + SYSC_REG_TVR );
}
\ No newline at end of file
/*
* DSI Shield
*
* Copyright (C) 2013-2014 twl
*
* This program is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or (at your
* option) any later version.
*
* This program 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
* General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/* uart.c - simple UART driver */
#include <stdint.h>
#include "uart.h"
#include "board.h"
#include <hw/wb_uart.h>
#define CALC_BAUD(baudrate) \
( ((( (unsigned int)baudrate << 12)) + \
(BASE_CLOCK >> 8)) / (BASE_CLOCK >> 7) )
volatile struct UART_WB *uart;
void uart_init_hw()
{
uart = (volatile struct UART_WB *)BASE_UART;
#ifndef SIMULATION
uart->BCR = CALC_BAUD(UART_BAUDRATE);
#else
uart->BCR = CALC_BAUD((CPU_CLOCK/10));
#endif
}
void uart_write_byte(int b)
{
if (b == '\n')
uart_write_byte('\r');
while (uart->SR & UART_SR_TX_BUSY)
;
uart->TDR = b;
}
int uart_poll()
{
return uart->SR & UART_SR_RX_RDY;
}
int uart_read_byte()
{
if (!uart_poll())
return -1;
return uart->RDR & 0xff;
}
int puts(const char *s)
{
char c;
while(c=*s++)
uart_write_byte(c);
}
/*
* DSI Shield
*
* Copyright (C) 2013-2014 twl
*
* This program is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or (at your
* option) any later version.
*
* This program 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
* General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef __UART_H
#define __UART_H
void uart_init_sw(void);
void uart_init_hw(void);
void uart_write_byte(int b);
int uart_write_string(const char *s);
int puts(const char *s);
int uart_read_byte(void);
/* uart-sw is used by ppsi (but may be wrapped to normal uart) */
int uart_sw_write_string(const char *s);
#endif
#!/usr/bin/python
#
# DSI Shield
#
# Copyright (C) 2013-2015 twl <twlostow@printf.cc>
#
# This program is free software: you can redistribute it and/or modify it
# under the terms of the GNU General Public License as published by the
# Free Software Foundation, either version 3 of the License, or (at your
# option) any later version.
#
# This program 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
# General Public License for more details.
#
# You should have received a copy of the GNU General Public License along
# with this program. If not, see <http://www.gnu.org/licenses/>.
import sys
import time
import serial
import struct
import getopt
class SerialIF:
def __init__(self, device="/dev/ttyUSB0"):
self.ser = serial.Serial(
port=device, baudrate=115200, timeout=0, rtscts=False)
def reset_board(self):
self.ser.setRTS(True)
time.sleep(0.01)
self.ser.setRTS(False)
time.sleep(0.01)
self.ser.setRTS(True)
time.sleep(0.01)
def send(self, x):
if isinstance(x, int):
self.ser.write(struct.pack("B", x))
else:
self.ser.write(x)
def recv(self):
while True:
try:
#print("State")
state = self.ser.read(1)
#print("2", state)
if state == None or len(state) == 0:
continue
#print ("************************ ST", state)
return state
except:
#print("Sleep")
time.sleep(0.01)
pass
def recv_nonblock(self):
try:
state = self.ser.read(1)
return state
except:
return None
def crc_xmodem_update(self, crc, data):
crc = crc ^ (data << 8)
for i in range(0, 8):
if ((crc & 0x8000) != 0):
crc = (crc << 1) ^ 0x1021
crc &= 0xffff
else:
crc = crc << 1
crc &= 0xffff
return crc
def crc_xmodem(self, data):
crc = 0
for c in data:
crc = self.crc_xmodem_update(crc, c)
return crc
def rx_frame(self):
frame = []
while True:
b = ord(self.recv())
if (b != 0x55):
# sys.stderr.write("%c" % b)
continue
b = ord(self.recv())
if (b != 0xaa):
# sys.stderr.write("%c" % b)
continue
break
frame = [0x55, 0xaa]
rsp = ord(self.recv())
l = ord(self.recv())
l <<= 8
l |= ord(self.recv())
for i in range(0, l):
frame.append(ord(self.recv()))
crc = ord(self.recv())
crc <<= 8
crc |= ord(self.recv())
return rsp
def tx_frame(self, command, data):
frame = []
frame.append(0x55)
frame.append(0xaa)
frame.append(command)
frame.append((len(data) >> 8) & 0xff)
frame.append(len(data) & 0xff)
for b in data:
frame.append(b)
crc = self.crc_xmodem(frame)
frame.append((crc >> 8) & 0xff)
frame.append((crc & 0xff))
for b in frame:
self.send(b)
class DSIBootloader:
def __init__(self, device="/dev/ttyUSB0"):
self.sock = SerialIF(device)
CMD_WRITE_RAM = 4
CMD_FLASH_ERASE_SECTOR = 2
CMD_FLASH_PROGRAM_PAGE = 3
CMD_GO = 5
CMD_BOOT_INIT = 1
RSP_OK = 1
RSP_CRC_ERROR = 2
RSP_VERIFY_ERROR = 3
RSP_BAD_CRC = 4
RSP_HELLO = 5
def command(self, cmd, data):
while True:
self.sock.tx_frame(cmd, data)
status = self.sock.rx_frame()
if (status != self.RSP_CRC_ERROR):
break
time.sleep(0.1)
return status
def cmd_boot_enter(self):
return self.command(self.CMD_BOOT_INIT, [])
def cmd_erase_sector(self, addr):
data = [(addr >> 24) & 0xff, (addr >> 16) & 0xff, (addr >> 8) & 0xff,
addr & 0xff]
return self.command(self.CMD_FLASH_ERASE_SECTOR, data)
def cmd_program_page(self, addr, data):
buf = [(addr >> 24) & 0xff, (addr >> 16) & 0xff, (addr >> 8) & 0xff,
addr & 0xff]
for b in data:
buf.append(b)
return self.command(self.CMD_FLASH_PROGRAM_PAGE, buf)
def cmd_write_ram(self, addr, data):
buf = [(addr >> 24) & 0xff, (addr >> 16) & 0xff, (addr >> 8) & 0xff,
addr & 0xff]
for b in data:
buf.append(b)
# print(len(buf))
return self.command(self.CMD_WRITE_RAM, buf)
def cmd_jump(self, addr):
buf = [(addr >> 24) & 0xff, (addr >> 16) & 0xff, (addr >> 8) & 0xff,
addr & 0xff]
return self.command(self.CMD_GO, buf)
def boot_enter(self):
self.sock.reset_board()
while (self.sock.rx_frame() != self.RSP_HELLO):
pass
self.cmd_boot_enter()
SECTOR_SIZE = 0x10000
PAGE_SIZE = 0x100
def program_flash(self, fw):
remaining = len(fw)
for i in range(0,
(remaining + self.SECTOR_SIZE - 1) / self.SECTOR_SIZE):
sys.stdout.write("\rErasing sector 0x%x " %
(i * self.SECTOR_SIZE))
sys.stdout.flush()
self.cmd_erase_sector(i * self.SECTOR_SIZE)
p = 0
while (remaining > 0):
n = 256 if remaining > 256 else remaining
data = []
for b in fw[p:p + n]:
data.append(ord(b))
self.cmd_program_page(p, data)
p += n
remaining -= n
sys.stdout.write("\rProgramming: %.0f%% " %
(float(p) / len(fw) * 100.0))
sys.stdout.flush()
print(
"\nFlashing complete. Please power-off and power-on again your board."
)
def load_ram(self, image, addr):
remaining = len(image)
p = 0
while (remaining > 0):
n = 256 if remaining > 256 else remaining
data = []
for b in image[p:p + n]:
data.append(ord(b))
# print("addr %x l %d" %( p+addr, len(data)))
self.cmd_write_ram(addr + p, data)
p += n
remaining -= n
sys.stdout.write("\rLoading: %.0f%% " %
(float(p) / len(image) * 100.0))
sys.stdout.flush()
self.cmd_jump(addr + 0x4)
print("\nBoot done..")
def run_terminal(ser):
'''
Opens an interactive terminal session (similar to PuTTY/minicom) bound
to the VUART
'''
import os, termios, sys
def restore_terminal_state():
import termios
if old_settings:
termios.tcsetattr(sys.stdin, termios.TCSADRAIN, old_settings)
fd = sys.stdin.fileno()
old_settings = termios.tcgetattr(fd)
new = termios.tcgetattr(fd)
# iflag
new[0] = termios.IGNPAR
# oflag
new[1] = 0
# cflag
new[2] = termios.B9600 | termios.CS8 | termios.CLOCAL | termios.CREAD
new[3] = 0
new[6][termios.VMIN] = 0 # cc
new[6][termios.VTIME] = 0 # cc
termios.tcsetattr(fd, termios.TCSANOW, new)
print('[Press Ctrl-A to terminate session.]')
import atexit
atexit.register(restore_terminal_state)
while True:
a = ser.recv_nonblock()
if (a != None and len(a) > 0):
sys.stderr.write("%c" % a)
a = os.read(sys.stdin.fileno(), 1)
if a != None and len(a) > 0:
if (ord(a) == 1):
return
else:
ser.send(ord(a))
def main(argv):
our_port = "/dev/ttyUSB0"
do_flash = False
try:
opts, args = getopt.getopt(argv[1:], "hfp:", ["uart"])
except getopt.GetoptError:
print('Usage: %s [-f] [-p serial_port_device] file.bin' % argv[0])
sys.exit(2)
for opt, arg in opts:
if opt == '-h':
print('Usage: %s [-f] [-p serial_port_device] file.bin' % argv[0])
print('Options:')
print(
'-f / --flash - flashes the FPGA bitstream instead of loading the CPU image (can brick your board!)'
)
print(
'-p / --port: - specifies the serial port device (default: %s)'
% our_port)
sys.exit()
elif opt in ("-f", "--flash"):
do_flash = True
elif opt in ("-p", "--port"):
our_port = arg
else:
print("Unrecognized option '%s'" % opt)
if len(args) == 0:
print("No filename specified.")
sys.exit(2)
boot = DSIBootloader(our_port)
fw = open(args[0], "rb").read()
boot.boot_enter()
if do_flash:
boot.program_flash(fw)
else:
boot.load_ram(fw, 0x0)
run_terminal(boot.sock)
if __name__ == "__main__":
main(sys.argv)
This diff is collapsed.
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment