Commit f70bebbc authored by Tomasz Wlostowski's avatar Tomasz Wlostowski

tools: added UART bootloader

parent 4c152dca
#!/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
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
$(SIZE) $(OUTPUT).elf
../genraminit $(OUTPUT).bin 32 0 0 > wrc-bootloader.ram
../genraminit $(OUTPUT).bin 512 88064 22016 >> 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 UART_BAUDRATE 115200
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);
}
#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:
.global _reset_handler
.type _reset_handler, @function
_reset_handler:
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
/* boot.c - a trivial serial port bootloader for LM32.
Public domain.
Awful code below. Be warned. */
#include <stdint.h>
#include "board.h"
#include "uart.h"
#define USER_START 0x0
const char hexchars[] = "0123456789abcdef";
void dump_int(uint32_t v)
{
int i;
for(i=7;i>=0;i--)
{
uart_write_byte(hexchars[(v>>(i*4)) & 0xf]);
}
uart_write_byte('\n');
uart_write_byte('\r');
}
int read_blocking(uint8_t *what)
{
int cnt = 500000;
int b;
while(cnt--)
{
b=uart_read_byte();
if(b >= 0)
break;
}
if(cnt)
{
*what = b;
return 0;
}else
return -1;
}
main()
{
int i;
int len, boot_active = 0;
uint8_t *ptr;
uart_init_hw();
again:
len = 0;
boot_active = 0;
ptr = (uint8_t*)USER_START;
uart_write_byte('B');
uart_write_byte('o');
uart_write_byte('o');
uart_write_byte('t');
uart_write_byte('?');
for(i=0;i<500000;i++)
if(uart_read_byte () == 'Y')
{
boot_active = 1;
break;
}
if(boot_active)
{
uint8_t b;
uart_write_byte('O');
uart_write_byte('K');
if(read_blocking(&b) < 0) goto again;
len = (uint32_t)b;
len <<=8;
if(read_blocking(&b) < 0) goto again;
len |= (uint32_t)b;
len <<=8;
if(read_blocking(&b) < 0) goto again;
len |= (uint32_t)b;
len <<=8;
if(read_blocking(&b) < 0) goto again;
len |= (uint32_t)b;
for(i=0;i<len;i++)
{
if(read_blocking(ptr) < 0)
goto again;
ptr++;
}
uart_write_byte('G');
uart_write_byte('o');
uart_write_byte('!');
asm volatile("wcsr ICC, r0"); // flush the I cache
void (*f)() = USER_START;
f();
} else {
uart_write_byte('T');
uart_write_byte('o');
uart_write_byte('u');
uart_write_byte('t');
void (*f)() = USER_START;
f();
// goto again;
}
}
OUTPUT_FORMAT("elf32-lm32")
ENTRY(_start)
MEMORY
{
preboot :
ORIGIN = 0x00000000,
LENGTH = 0x100
ram :
ORIGIN = 90112 - 2048,
LENGTH = 1536
stack :
ORIGIN = 90112 - 512,
LENGTH = 512
}
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
/*
* 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
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