Commit 6e897670 authored by Tomasz Wlostowski's avatar Tomasz Wlostowski Committed by Grzegorz Daniluk

uart-bootloader: temporary commit for eRTM14, to be cleaned up

parent c1fa3d6a
......@@ -7,14 +7,14 @@ 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
CFLAGS = -Os -I../common -I. -mmultiply-enabled -mbarrel-shift-enabled -ffunction-sections -fdata-sections -I../../include -DCONFIG_ERTM14 -I../../pp_printf -DCONFIG_PRINT_BUFSIZE=128
OBJS = boot-crt0.o boot.o timer.o ../../dev/bb_spi.o ../../dev/gpio.o ../../dev/spi_flash.o ../../dev/simple_uart.o ../../pp_printf/printf.o ../../pp_printf/vsprintf-mini.o ../../pp_printf/div64.o
LDS = boot.ld
LDFLAGS = -mmultiply-enabled -mbarrel-shift-enabled -Wl,--gc-sections
LDFLAGS = -Os -mmultiply-enabled -mbarrel-shift-enabled -Wl,--gc-sections
OUTPUT=boot
$(OUTPUT): $(LDS) $(OBJS)
${CC} -o $(OUTPUT).elf -nostartfiles $(OBJS) -T $(LDS) -lgcc -lc
${CC} -o $(OUTPUT).elf -nostartfiles $(LDFLAGS) $(OBJS) -T $(LDS) -lgcc -lc
${OBJCOPY} -O binary $(OUTPUT).elf $(OUTPUT).bin
${OBJDUMP} -D $(OUTPUT).elf > disasm.S
$(SIZE) $(OUTPUT).elf
......
......@@ -123,7 +123,7 @@ _crt0:
mvi r1, 0
mvi r2, 0
mvi r3, 0
calli main
calli boot_main
loopf:
bi loopf
......
......@@ -22,23 +22,31 @@
#include <stdint.h>
#include <stdio.h>
#define CONFIG_ERTM14_FLASH
#include "board.h"
#ifdef CONFIG_FLASH
#include "flash.h"
#ifdef CONFIG_ERTM14_FLASH
#include "dev/bb_spi.h"
#include "dev/gpio.h"
#include "dev/spi_flash.h"
#endif
#ifndef CONFIG_USER_START
#define CONFIG_USER_START 0x0
#endif
#include "uart.h"
#include "dev/simple_uart.h"
#include "hw/wrc_syscon_regs.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 CMD_GET_FLASH_ID 6
#define CMD_EXIT 7
#define RSP_OK 1
#define RSP_HELLO 5
......@@ -50,7 +58,7 @@
#define RX_BUF_SIZE (256 + 16)
#define BOOT_TIMEOUT 500
#define BOOT_TIMEOUT 2000
#define UART_TIMEOUT 2000
......@@ -60,6 +68,62 @@ static uint32_t orig_reset_vector = 0x4;
typedef void (*voidfunc_t)();
struct simple_uart_device dev_uart;
#ifdef CONFIG_ERTM14_FLASH
#define BASE_AUXWB 0x48000
struct gpio_device gpio_aux;
struct spi_bus spi_flash;
struct spi_flash_device dev_flash;
static void boot_sysc_gpio_set_dir(const struct gpio_pin *pin, int dir)
{
}
static void boot_sysc_gpio_set_out(const struct gpio_pin *pin, int value)
{
if(value)
writel( ( 1<< pin->pin), (void*) ( BASE_SYSCON + SYSC_REG_GPSR) );
else
writel( ( 1<< pin->pin), (void *) ( BASE_SYSCON + SYSC_REG_GPCR) );
}
static int boot_sysc_gpio_read_pin(const struct gpio_pin *pin)
{
return readl(BASE_SYSCON + SYSC_REG_GPSR) & (1<<pin->pin) ? 1 : 0;
}
static const struct gpio_device boot_syscon_gpio = {
NULL,
boot_sysc_gpio_set_dir,
boot_sysc_gpio_set_out,
boot_sysc_gpio_read_pin
};
static const struct gpio_pin boot_pin_sysc_spi_sclk = { &boot_syscon_gpio, 10 };
static const struct gpio_pin boot_pin_sysc_spi_ncs = { &boot_syscon_gpio, 11 };
static const struct gpio_pin boot_pin_sysc_spi_mosi = { &boot_syscon_gpio, 12 };
static const struct gpio_pin boot_pin_sysc_spi_miso = { &boot_syscon_gpio, 13 };
void boot_flash_init()
{
wb_gpio_create( &gpio_aux, BASE_AUXWB );
bb_spi_create( &spi_flash,
&boot_pin_sysc_spi_ncs,
&boot_pin_sysc_spi_mosi,
&boot_pin_sysc_spi_miso,
&boot_pin_sysc_spi_sclk, 10 );
spi_flash_create( &dev_flash, &spi_flash );
}
#endif
uint16_t crc_xmodem_update(uint16_t crc, uint8_t data)
{
int i;
......@@ -95,13 +159,13 @@ crc16(unsigned char *buf, int len)
int timeout_hit = 0;
uint8_t uart_read_blocking()
uint8_t suart_read_blocking()
{
uint32_t t_end = get_ms_ticks() + UART_TIMEOUT;
uint32_t t_end = timer_get_tics() + UART_TIMEOUT;
while (get_ms_ticks() < t_end)
if (uart_poll())
return uart_read_byte();
while (timer_get_tics() < t_end)
if (suart_poll(&dev_uart))
return suart_read_byte(&dev_uart);
timeout_hit = 1;
......@@ -114,37 +178,40 @@ void uart_readm_blocking(uint8_t *buf, int count)
for (i = 0; i < count; i++)
{
buf[i] = uart_read_blocking();
buf[i] = suart_read_blocking();
if (timeout_hit)
return;
}
}
void send_reply(uint8_t code)
void send_reply(uint8_t code, int length, uint8_t *data)
{
uint8_t buf[16];
uint8_t buf[32];
uint16_t crc, i;
buf[0] = 0x55;
buf[1] = 0xaa;
buf[2] = code;
buf[3] = 0;
buf[4] = 0;
buf[3] = (length >> 8) & 0xff;
buf[4] = (length & 0xff);
if(length > 0)
memcpy(buf+5, data, length);
crc = crc16(buf, 5);
crc = crc16(buf, length+5);
buf[5] = (crc >> 8);
buf[6] = (crc & 0xff);
buf[length+5] = (crc >> 8);
buf[length+6] = (crc & 0xff);
for (i = 0; i < 7; i++)
uart_write_byte(buf[i]);
for (i = 0; i < length+7; i++)
suart_write_byte(&dev_uart, buf[i]);
}
void on_cmd_init()
{
boot_wait = 0;
send_reply(RSP_OK);
send_reply(RSP_OK, 0, NULL);
}
uint32_t unpack_be32(uint8_t *p)
......@@ -158,26 +225,32 @@ uint32_t unpack_be32(uint8_t *p)
return rv;
}
#ifdef CONFIG_FLASH
#ifdef CONFIG_ERTM14_FLASH
void on_cmd_erase_sector(uint8_t *payload, int len)
{
uint32_t base = unpack_be32(payload);
flash_write_enable();
flash_erase_sector(base);
spi_flash_erase_sector(&dev_flash, base);
send_reply(RSP_OK);
send_reply(RSP_OK, 0, NULL);
}
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);
spi_flash_write(&dev_flash, base, payload + 4, len - 4);
send_reply(RSP_OK, 0, NULL);
}
void on_cmd_get_flash_id(uint8_t *payload, int len)
{
uint32_t id = spi_flash_read_id(&dev_flash);
send_reply(RSP_OK);
send_reply(RSP_OK, 4, &id);
}
#endif
void on_cmd_write_ram(uint8_t *payload, int len)
......@@ -204,7 +277,7 @@ void on_cmd_write_ram(uint8_t *payload, int len)
}
}
send_reply(RSP_OK);
send_reply(RSP_OK, 0, NULL);
}
void on_cmd_go(uint8_t *payload, int len)
......@@ -213,49 +286,52 @@ void on_cmd_go(uint8_t *payload, int len)
voidfunc_t f = (voidfunc_t)base;
send_reply(RSP_OK);
send_reply(RSP_OK, 0, NULL);
f();
}
void boot_fsm()
{
uint32_t t_exit = get_ms_ticks() + BOOT_TIMEOUT;
uint32_t t_exit = timer_get_tics() + BOOT_TIMEOUT;
boot_wait = 1;
send_reply(RSP_HELLO);
send_reply(RSP_HELLO, 0, NULL);
for (;;)
{
int pos = 0, i;
uint16_t crc;
if (boot_wait && (get_ms_ticks() > t_exit))
if (boot_wait && (timer_get_tics() > t_exit))
return;
timeout_hit = 0;
int c = uart_read_blocking();
int c = suart_read_blocking();
if ((c != 0x55) || timeout_hit)
if(timeout_hit && boot_wait)
break;
if (c != 0x55)
{
continue;
}
rxbuf[pos++] = c;
c = uart_read_blocking();
c = suart_read_blocking();
if ((c != 0xaa) || timeout_hit)
continue;
rxbuf[pos++] = c;
uint8_t command = uart_read_blocking();
uint8_t command = suart_read_blocking();
rxbuf[pos++] = command;
rxbuf[pos++] = uart_read_blocking();
rxbuf[pos++] = uart_read_blocking();
rxbuf[pos++] = suart_read_blocking();
rxbuf[pos++] = suart_read_blocking();
uint16_t len = (uint16_t)rxbuf[3] << 8 | rxbuf[4];
......@@ -263,17 +339,17 @@ void boot_fsm()
continue;
for (i = 0; i < len; i++)
rxbuf[pos++] = uart_read_blocking();
rxbuf[pos++] = suart_read_blocking();
crc = (uint16_t)uart_read_blocking() << 8;
crc |= (uint16_t)uart_read_blocking();
crc = (uint16_t)suart_read_blocking() << 8;
crc |= (uint16_t)suart_read_blocking();
if (timeout_hit)
continue;
if (crc != crc16(rxbuf, len + 5))
{
send_reply(RSP_BAD_CRC);
send_reply(RSP_BAD_CRC, 0, NULL);
}
......@@ -284,13 +360,13 @@ void boot_fsm()
break;
case CMD_ERASE_SECTOR:
#ifdef CONFIG_FLASH
#ifdef CONFIG_ERTM14_FLASH
on_cmd_erase_sector(rxbuf + 5, len);
#endif
break;
case CMD_WRITE_PAGE:
#ifdef CONFIG_FLASH
#ifdef CONFIG_ERTM14_FLASH
on_cmd_write_page(rxbuf + 5, len);
#endif
break;
......@@ -302,6 +378,15 @@ void boot_fsm()
case CMD_GO:
on_cmd_go(rxbuf + 5, len);
break;
case CMD_EXIT:
return;
#ifdef CONFIG_ERTM14_FLASH
case CMD_GET_FLASH_ID:
on_cmd_get_flash_id(rxbuf + 5, len);
break;
#endif
default:
break;
......@@ -309,6 +394,32 @@ void boot_fsm()
}
}
#define ERTM14_FLASH_PAGE_SIZE 65536
#define ERTM14_FLASH_SIZE 16777216
#define ERTM14_FIRMWARE_MAGIC 0xf1dee41a
void try_flash_boot()
{
uint8_t buf[512];
uint32_t offset;
for(offset = 0; offset < ERTM14_FLASH_SIZE; offset += ERTM14_FLASH_PAGE_SIZE)
{
uint32_t magic, size;
spi_flash_read(&dev_flash, offset, buf, 8 );
magic = unpack_be32( buf );
size = unpack_be32( buf + 4 );
if ( magic == ERTM14_FIRMWARE_MAGIC )
{
spi_flash_read(&dev_flash, offset + 8, (void*)0, size);
start_user();
}
}
}
void start_user()
{
voidfunc_t f = (voidfunc_t)orig_reset_vector;
......@@ -316,13 +427,21 @@ void start_user()
f();
}
int main()
int boot_main()
{
uart_init_hw();
#ifdef CONFIG_FLASH
flash_init();
suart_init_default_baudrate( &dev_uart, BASE_UART );
timer_init(1);
#ifdef CONFIG_ERTM14_FLASH
boot_flash_init();
#endif
boot_fsm();
#ifdef CONFIG_ERTM14_FLASH
try_flash_boot();
#endif
start_user();
return 0;
......
......@@ -7,10 +7,10 @@ MEMORY
LENGTH = 0x100
ram :
ORIGIN = 131072 - 4096,
LENGTH = 2048
ORIGIN = 131072 + 65536 - 8192
LENGTH = 6800
stack :
ORIGIN = 131072 - 2048,
ORIGIN = 131072 + 65536 - 2048,
LENGTH = 2038
}
......
#include "board.h"
#include "hw/wrc_syscon_regs.h"
void timer_init()
void timer_init(int enable)
{
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
}
......@@ -23,21 +23,28 @@ import time
import serial
import struct
import getopt
import signal
import sys
kill_usb = False
def signal_handler(sig, frame):
global kill_usb
print('You pressed Ctrl+C!')
kill_usb = True
sys.exit(0)
class SerialIF:
def __init__(self, device="/dev/ttyUSB0"):
self.ser = serial.Serial(
port=device, baudrate=115200, timeout=0, rtscts=False)
port=device, baudrate=921600, 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)
print ("Resetting...\n")
for k in range(0,12):
self.ser.setDTR(True)
self.ser.setDTR(False)
def send(self, x):
if isinstance(x, int):
self.ser.write(struct.pack("B", x))
......@@ -45,18 +52,20 @@ class SerialIF:
self.ser.write(x)
def recv(self):
global kill_usb
while True:
if kill_usb:
return None
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)
time.sleep(1)
pass
def recv_nonblock(self):
......@@ -165,6 +174,12 @@ class DSIBootloader:
def cmd_boot_enter(self):
return self.command(self.CMD_BOOT_INIT, [])
def cmd_read_flash_id(self):
data = [(addr >> 24) & 0xff, (addr >> 16) & 0xff, (addr >> 8) & 0xff,
addr & 0xff]
return self.command(self.CMD_FLASH_ERASE_SECTOR, data)
def cmd_erase_sector(self, addr):
data = [(addr >> 24) & 0xff, (addr >> 16) & 0xff, (addr >> 8) & 0xff,
addr & 0xff]
......@@ -198,11 +213,33 @@ class DSIBootloader:
SECTOR_SIZE = 0x10000
PAGE_SIZE = 0x100
def program_flash(self, fw, target):
#print("PGM", target)
if target.lower() == "fpga":
offset = 0
image = fw
elif target.lower() == "wrc":
offset = 0x300000
image = struct.pack(">LLL", 0xf1dee41a, len(fw), 0xe000b800) + fw[4:]
#print(type(fw), len(fw), len(image))
elif target.lower() == "autoexec":
offset = 0x610000
image = struct.pack(">H", len(fw)) + fw
elif target.lower() == "sdbfs":
offset = 0x600000
image = fw
else:
print("Unknown flash target: %s" % target)
return
def program_flash(self, fw):
return self.do_program_flash(image, offset)
def do_program_flash(self, fw, offset = 0):
remaining = len(fw)
for i in range(0,
(remaining + self.SECTOR_SIZE - 1) / self.SECTOR_SIZE):
for i in range(offset / self.SECTOR_SIZE,
(offset + (remaining + self.SECTOR_SIZE - 1)) / self.SECTOR_SIZE):
sys.stdout.write("\rErasing sector 0x%x " %
(i * self.SECTOR_SIZE))
sys.stdout.flush()
......@@ -215,7 +252,9 @@ class DSIBootloader:
for b in fw[p:p + n]:
data.append(ord(b))
self.cmd_program_page(p, data)
#print("b0 %x" % data[0])
self.cmd_program_page(p + offset, data)
p += n
remaining -= n
......@@ -301,10 +340,12 @@ def run_terminal(ser):
def main(argv):
signal.signal(signal.SIGINT, signal_handler)
our_port = "/dev/ttyUSB0"
do_flash = False
try:
opts, args = getopt.getopt(argv[1:], "hfp:", ["uart"])
opts, args = getopt.getopt(argv[1:], "hf:p:", ["uart"])
except getopt.GetoptError:
print('Usage: %s [-f] [-p serial_port_device] file.bin' % argv[0])
sys.exit(2)
......@@ -313,13 +354,14 @@ def main(argv):
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!)'
'-f / --flash [fpga|autoexec|wrc|sdbfs] - flashes the FPGA bitstream/autoexec file/WRC image 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"):
flash_target = arg
do_flash = True
elif opt in ("-p", "--port"):
our_port = arg
......@@ -335,7 +377,7 @@ def main(argv):
boot.boot_enter()
if do_flash:
boot.program_flash(fw)
boot.program_flash(fw, flash_target)
else:
boot.load_ram(fw, 0x0)
run_terminal(boot.sock)
......
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