hwstub rk27xx port

Change-Id: I85ac57117911544b65ccd56eb16303e30be67cab
This commit is contained in:
Marcin Bukat 2013-07-18 23:55:35 +02:00
parent 1ed57aaa50
commit 8e63338591
15 changed files with 1932 additions and 24 deletions

View file

@ -101,6 +101,7 @@ struct usb_resp_info_features_t
#define HWSTUB_TARGET_UNK ('U' | 'N' << 8 | 'K' << 16 | ' ' << 24)
#define HWSTUB_TARGET_STMP ('S' | 'T' << 8 | 'M' << 16 | 'P' << 24)
#define HWSTUB_TARGET_RK27 ('R' | 'K' << 8 | '2' << 16 | '7' << 24)
struct usb_resp_info_target_t
{

View file

@ -1,5 +1,4 @@
main.c
crt0.S
logf.c
memcpy.S
memmove.S
@ -7,6 +6,11 @@ memset.S
string.c
format.c
#ifdef CONFIG_STMP
usb_drv_arc.c
stmp/crt0.S
stmp/target.c
usb_drv_arc.c
#elif defined(CONFIG_RK27XX)
rk27xx/crt0.S
rk27xx/usb_drv_rk27xx.c
rk27xx/target.c
#endif

View file

@ -1,5 +1,5 @@
INCLUDES+=-I$(ROOT_DIR)
LINKER_FILE=$(ROOT_DIR)/hwstub.lds
LINKER_FILE=hwstub.lds
TMP_LDS=$(BUILD_DIR)/link.lds
TMP_MAP=$(BUILD_DIR)/hwstub.map
CFLAGS=$(GCCOPTS) $(DEFINES) -W -Wall -Wundef -O -nostdlib -ffreestanding -Wstrict-prototypes -pipe -std=gnu99 -fomit-frame-pointer -Wno-pointer-sign -Wno-override-init $(INCLUDES)
@ -12,7 +12,7 @@ SRC:=$(shell cat $(ROOT_DIR)/SOURCES | $(CC) $(INCLUDES) \
SRC:=$(foreach src,$(SRC),$(BUILD_DIR)/$(src))
OBJ=$(SRC:.c=.o)
OBJ:=$(OBJ:.S=.o)
OBJ_EXCEPT_CRT0=$(filter-out $(BUILD_DIR)/crt0.o,$(OBJ))
OBJ_EXCEPT_CRT0=$(filter-out $(BUILD_DIR)/%/crt0.o,$(OBJ))
EXEC_ELF=$(BUILD_DIR)/hwstub.elf
EXEC_BIN=$(BUILD_DIR)/hwstub.bin
DEPS=$(foreach obj,$(OBJ),$(obj).d)

View file

@ -0,0 +1,14 @@
#
# common
#
CC=arm-elf-eabi-gcc
LD=arm-elf-eabi-gcc
AS=arm-elf-eabi-gcc
OC=arm-elf-eabi-objcopy
DEFINES=
INCLUDES=-I$(CURDIR)
GCCOPTS=-march=armv5te
BUILD_DIR=$(CURDIR)/build/
ROOT_DIR=$(CURDIR)/..
include ../hwstub.make

View file

@ -0,0 +1,2 @@
/home/wodz/rockbox-dev/bin/arm-elf-eabi-objcopy -O binary hwstub.elf hwstub.bin
/home/wodz/rockbox/tools/scramble -rkw -modelnum=73 hwstub.bin hwstub.rkw

View file

@ -0,0 +1,164 @@
/***************************************************************************
* __________ __ ___.
* Open \______ \ ____ ____ | | _\_ |__ _______ ___
* Source | _// _ \_/ ___\| |/ /| __ \ / _ \ \/ /
* Jukebox | | ( <_> ) \___| < | \_\ ( <_> > < <
* Firmware |____|_ /\____/ \___ >__|_ \|___ /\____/__/\_ \
* \/ \/ \/ \/ \/
*
* Copyright (C) 2008 by Marcoen Hirschberg
* Copyright (C) 2008 by Denes Balatoni
* Copyright (C) 2010 by Marcin Bukat
*
* 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 2
* of the License, or (at your option) any later version.
*
* This software is distributed on an "AS IS" basis, WITHOUT WARRANTY OF ANY
* KIND, either express or implied.
*
****************************************************************************/
.extern INT_UDC
.global start
.global entry_point
/* Exception vectors */
.section .intvect,"ax",%progbits
ldr pc, =start
ldr pc, =start
ldr pc, =start
ldr pc, =start
ldr pc, =start
ldr pc, =start
ldr pc, =irq_handler
ldr pc, =start
.ltorg
.section .text,"ax",%progbits
start:
msr cpsr_c, #0xd3 /* enter supervisor mode, disable IRQ/FIQ */
sub r4, pc, #12 /* copy running address, accomodate
* for prefetch (-8) and msr instr (-4)
*/
ldr r0, =0xefff0000 /* cache controler base address */
ldrh r1, [r0]
strh r1, [r0] /* global cache disable */
ldr r2, =_relocstart
ldr r3, =_relocend
cmp r2, r4
beq entry_point /* skip copying if we are in place already */
1:
cmp r3, r2
ldrhi r1, [r4], #4
strhi r1, [r2], #4
bhi 1b
entry_point_jmp:
ldr pc, =entry_point
entry_point:
mov r0, #0x18000000
add r0, r0, #0x1c000
/* setup ARM core freq = 200MHz
* AHB bus freq (HCLK) = 100MHz
* APB bus freq (PCLK) = 50MHz
* Note: it seems there is no way to run AHB bus at ARM freq
* bit2 in DIVCON1 must have different meaning to what datasheet
* states. It influences SDRAM read speed but does not change
* APB freq
*/
ldr r1, [r0,#0x14] /* SCU_DIVCON1 */
bic r1, r1, #0x1f
orr r1, r1, #9 /* ((1<<3)|(1<<0)) ARM slow mode, HCLK:PCLK = 2:1 */
str r1, [r0,#0x14]
ldr r1,=0x1850310 /* ((1<<24)|(1<<23)|(5<<16)|(49<<4)) */
str r1, [r0,#0x08]
ldr r2,=0x40000
1:
ldr r1, [r0,#0x2c] /* SCU_STATUS */
tst r1, #1 /* ARM pll lock */
bne 1f
subs r2, r2, #1
bne 1b
1:
ldr r1, [r0,#0x14] /* SCU_DIVCON1 */
bic r1, #1 /* leave ARM slow mode */
str r1, [r0,#0x14]
/* remap iram to 0x00000000 */
ldr r1,=0xdeadbeef
str r1, [r0, #4]
/* Copy interrupt vectors to iram */
ldr r2, =_intvectstart
ldr r3, =_intvectend
ldr r4, =_intvectcopy
1:
cmp r3, r2
ldrhi r1, [r4], #4
strhi r1, [r2], #4
bhi 1b
/* Initialise bss section to zero */
ldr r2, =_edata
ldr r3, =_end
mov r4, #0
1:
cmp r3, r2
strhi r4, [r2], #4
bhi 1b
/* Set up stack for IRQ mode */
msr cpsr_c, #0xd2
ldr sp, =_irqstackend
/* Set up stack for FIQ mode */
msr cpsr_c, #0xd1
ldr sp, =_fiqstackend
/* Let svc, abort and undefined modes use irq stack */
msr cpsr_c, #0xd3
ldr sp, =_irqstackend
msr cpsr_c, #0xd7
ldr sp, =_irqstackend
msr cpsr_c, #0xdb
ldr sp, =_irqstackend
/* Switch to sys mode */
msr cpsr_c, #0xdf
/* Set up some stack and munge it with 0xdeadbeef */
ldr sp, =stackend
ldr r2, =stackbegin
ldr r3, =0xdeadbeef
1:
cmp sp, r2
strhi r3, [r2], #4
bhi 1b
/* Jump to C code */
b main
/* copy from rockbox code - context save may be excessive but who cares */
irq_handler:
stmfd sp!, {r0-r5, ip, lr} /* store context */
ldr r4, =0x18080000 /* INTC base */
ldr r5, [r4, #0x104] /* INTC_ISR */
and r5, r5, #0x1f /* irq_no = INTC_ISR & 0x1f */
cmp r5, #0x10 /* UDC irq */
bleq INT_UDC /* handle it */
mov r3, #1
lsl r5, r3, r5 /* clear interrupt */
str r5, [r4, #0x118] /* INTC_ICCR = (1<<irq_no) */
ldmfd sp!, {r0-r5, ip, lr} /* restore context */
subs pc, lr, #4

View file

@ -0,0 +1,88 @@
ENTRY(start)
OUTPUT_FORMAT(elf32-littlearm)
OUTPUT_ARCH(arm)
STARTUP(rk27xx/crt0.o)
#define DRAMORIG 0x60000000
#define DRAMSIZE (16 * 0x100000)
#define DRAM_END_ADDRESS (DRAMORIG + DRAMSIZE)
#define IRAMORIG 0x00000000
#define IRAMSIZE 4K
MEMORY
{
DRAM : ORIGIN = DRAMORIG, LENGTH = DRAMSIZE
IRAM : ORIGIN = IRAMORIG, LENGTH = IRAMSIZE
}
SECTIONS
{
.relocstart (NOLOAD) : {
_relocstart = .;
} > DRAM
.text : {
oc_codestart = .;
*(.init.text)
*(.text*)
*(.icode*)
*(.glue_7*)
} > DRAM
.intvect : {
_intvectstart = . ;
KEEP(*(.intvect))
_intvectend = . ;
} > IRAM AT > DRAM
_intvectcopy = LOADADDR(.intvect) ;
.rodata : {
*(.rodata*)
*(.irodata*)
. = ALIGN(0x4);
} > DRAM
.data : {
*(.data*)
*(.idata*)
. = ALIGN(0x4);
} > DRAM
.relocend (NOLOAD) : {
_relocend = .;
} > DRAM
.stack (NOLOAD) :
{
*(.stack)
oc_stackstart = .;
_stackbegin = .;
stackbegin = .;
. += 0x2000;
_stackend = .;
stackend = .;
_irqstackbegin = .;
. += 0x400;
_irqstackend = .;
_fiqstackbegin = .;
. += 0x400;
_fiqstackend = .;
oc_stackend = .;
} > DRAM
.bss (NOLOAD) : {
_edata = .;
*(.bss*);
*(.ibss);
*(COMMON);
. = ALIGN(0x4);
_end = .;
oc_codeend = .;
oc_bufferstart = .;
} > DRAM
.dramend DRAM_END_ADDRESS (NOLOAD) : {
oc_bufferend = .;
} > DRAM
}

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,9 @@
#define CONFIG_RK27XX
#define IRAM_ORIG 0x60000000
#define IRAM_SIZE 0x8000
#define DRAM_ORIG 0x60000000
#define DRAM_SIZE (MEMORYSIZE * 0x100000)
#define CPU_ARM
#define ARM_ARCH 5
#define USB_BASE 0x180A000
#define USB_NUM_ENDPOINTS 2

View file

@ -0,0 +1,172 @@
/***************************************************************************
* __________ __ ___.
* Open \______ \ ____ ____ | | _\_ |__ _______ ___
* Source | _// _ \_/ ___\| |/ /| __ \ / _ \ \/ /
* Jukebox | | ( <_> ) \___| < | \_\ ( <_> > < <
* Firmware |____|_ /\____/ \___ >__|_ \|___ /\____/__/\_ \
* \/ \/ \/ \/ \/
*
* Copyright (C) 2013 by Marcin Bukat
*
* 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 2
* of the License, or (at your option) any later version.
*
* This software is distributed on an "AS IS" basis, WITHOUT WARRANTY OF ANY
* KIND, either express or implied.
*
****************************************************************************/
#include "stddef.h"
#include "target.h"
#include "system.h"
#include "logf.h"
#include "rk27xx.h"
#define HZ 1000000
enum rk27xx_family_t
{
UNKNOWN,
REV_A,
REV_B,
};
static enum rk27xx_family_t g_rk27xx_family = UNKNOWN;
static int g_atexit = HWSTUB_ATEXIT_OFF;
static void _enable_irq(void)
{
asm volatile ("mrs r0, cpsr\n"
"bic r0, r0, #0x80\n"
"msr cpsr_c, r0\n"
);
}
static void power_off(void)
{
GPIO_PCCON &= ~(1<<0);
while(1);
}
static void rk27xx_reset(void)
{
/* use Watchdog to reset */
SCU_CLKCFG &= ~CLKCFG_WDT;
WDTLR = 1;
WDTCON = (1<<4) | (1<<3);
/* Wait for reboot to kick in */
while(1);
}
/* us may be at most 2^31/200 (~10 seconds) for 200MHz max cpu freq */
void target_udelay(int us)
{
unsigned cycles_per_us;
unsigned delay;
cycles_per_us = (200000000 + 999999) / 1000000;
delay = (us * cycles_per_us) / 5;
asm volatile(
"1: subs %0, %0, #1 \n" /* 1 cycle */
" nop \n" /* 1 cycle */
" bne 1b \n" /* 3 cycles */
: : "r"(delay)
);
}
void target_mdelay(int ms)
{
return target_udelay(ms * 1000);
}
void target_init(void)
{
/* ungate all clocks */
SCU_CLKCFG = 0;
/* keep act line */
GPIO_PCDR |= (1<<0);
GPIO_PCCON |= (1<<0);
/* disable watchdog */
WDTCON &= ~(1<<3);
/* enable UDC interrupt */
INTC_IMR = (1<<16);
INTC_IECR = (1<<16);
EN_INT = EN_SUSP_INTR | /* Enable Suspend Interrupt */
EN_RESUME_INTR | /* Enable Resume Interrupt */
EN_USBRST_INTR | /* Enable USB Reset Interrupt */
EN_OUT0_INTR | /* Enable OUT Token receive Interrupt EP0 */
EN_IN0_INTR | /* Enable IN Token transmits Interrupt EP0 */
EN_SETUP_INTR; /* Enable SETUP Packet Receive Interrupt */
/* 6. configure INTCON */
INTCON = UDC_INTHIGH_ACT | /* interrupt high active */
UDC_INTEN; /* enable EP0 interrupts */
/* enable irq */
_enable_irq();
/* detect revision */
uint32_t rk27xx_id = SCU_ID;
if(rk27xx_id == 0xa1000604)
{
logf("identified rk27xx REV_A \n");
g_rk27xx_family = REV_A;
}
else if(rk27xx_id == 0xa100027b)
{
logf("identified rk27xx REV_B \n");
g_rk27xx_family = REV_B;
}
else
{
logf("unknown rk27xx revision \n");
}
}
static struct usb_resp_info_target_t g_target =
{
.id = HWSTUB_TARGET_RK27,
.name = "Rockchip RK27XX"
};
int target_get_info(int info, void **buffer)
{
if(info == HWSTUB_INFO_TARGET)
{
*buffer = &g_target;
return sizeof(g_target);
}
else
return -1;
}
int target_atexit(int method)
{
g_atexit = method;
return 0;
}
void target_exit(void)
{
switch(g_atexit)
{
case HWSTUB_ATEXIT_OFF:
power_off();
// fallthrough in case of return
case HWSTUB_ATEXIT_REBOOT:
rk27xx_reset();
// fallthrough in case of return
case HWSTUB_ATEXIT_NOP:
default:
return;
}
}

View file

@ -0,0 +1,313 @@
/***************************************************************************
* __________ __ ___.
* Open \______ \ ____ ____ | | _\_ |__ _______ ___
* Source | _// _ \_/ ___\| |/ /| __ \ / _ \ \/ /
* Jukebox | | ( <_> ) \___| < | \_\ ( <_> > < <
* Firmware |____|_ /\____/ \___ >__|_ \|___ /\____/__/\_ \
* \/ \/ \/ \/ \/
*
* Copyright (C) 2011 by Marcin Bukat
* Copyright (C) 2012 by Amaury Pouly
*
* 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 2
* of the License, or (at your option) any later version.
*
* This software is distributed on an "AS IS" basis, WITHOUT WARRANTY OF ANY
* KIND, either express or implied.
*
****************************************************************************/
#include "usb_drv.h"
#include "config.h"
#include "memory.h"
#include "target.h"
#include "rk27xx.h"
typedef volatile uint32_t reg32;
#define USB_FULL_SPEED 0
#define USB_HIGH_SPEED 1
/* max allowed packet size definitions */
#define CTL_MAX_SIZE 64
struct endpoint_t {
const int type; /* EP type */
const int dir; /* DIR_IN/DIR_OUT */
const unsigned int intr_mask;
bool allocated; /* flag to mark EPs taken */
volatile void *buf; /* tx/rx buffer address */
volatile int len; /* size of the transfer (bytes) */
volatile int cnt; /* number of bytes transfered/received */
};
static struct endpoint_t ctrlep[2] = {
{USB_ENDPOINT_XFER_CONTROL, DIR_OUT, 0, true, NULL, 0, 0},
{USB_ENDPOINT_XFER_CONTROL, DIR_IN, 0, true, NULL, 0, 0}
};
volatile bool setup_data_valid = false;
static volatile uint32_t setup_data[2];
static volatile bool usb_drv_send_done = false;
void usb_drv_configure_endpoint(int ep_num, int type)
{
/* not needed as we use EP0 only */
(void)ep_num;
(void)type;
}
int usb_drv_recv_setup(struct usb_ctrlrequest *req)
{
while (!setup_data_valid)
;
memcpy(req, (void *)setup_data, sizeof(struct usb_ctrlrequest));
setup_data_valid = false;
return 0;
}
static void setup_irq_handler(void)
{
/* copy setup data from packet */
setup_data[0] = SETUP1;
setup_data[1] = SETUP2;
/* ack upper layer we have setup data */
setup_data_valid = true;
}
/* service ep0 IN transaction */
static void ctr_write(void)
{
int xfer_size = MIN(ctrlep[DIR_IN].cnt, CTL_MAX_SIZE);
while (TX0BUF & TXFULL) /* TX0FULL flag */
;
TX0STAT = xfer_size; /* size of the transfer */
TX0DMALM_IADDR = (uint32_t)ctrlep[DIR_IN].buf; /* local buffer address */
TX0DMAINCTL = DMA_START; /* start DMA */
TX0CON &= ~TXNAK; /* clear NAK */
/* Decrement by max packet size is intentional.
* This way if we have final packet short one we will get negative len
* after transfer, which in turn indicates we *don't* need to send
* zero length packet. If the final packet is max sized packet we will
* get zero len after transfer which indicates we need to send
* zero length packet to signal host end of the transfer.
*/
ctrlep[DIR_IN].cnt -= CTL_MAX_SIZE;
ctrlep[DIR_IN].buf += xfer_size;
}
static void ctr_read(void)
{
int xfer_size = RX0STAT & 0xffff;
/* clear NAK bit */
RX0CON &= ~RXNAK;
ctrlep[DIR_OUT].cnt -= xfer_size;
ctrlep[DIR_OUT].buf += xfer_size;
RX0DMAOUTLMADDR = (uint32_t)ctrlep[DIR_OUT].buf; /* buffer address */
RX0DMACTLO = DMA_START; /* start DMA */
}
static void udc_phy_reset(void)
{
DEV_CTL |= SOFT_POR;
target_mdelay(10); /* min 10ms */
DEV_CTL &= ~SOFT_POR;
}
static void udc_soft_connect(void)
{
DEV_CTL |= CSR_DONE |
DEV_SOFT_CN |
DEV_SELF_PWR;
}
/* return port speed */
int usb_drv_port_speed(void)
{
return ((DEV_INFO & DEV_SPEED) ? USB_FULL_SPEED : USB_HIGH_SPEED);
}
/* Set the address (usually it's in a register).
* There is a problem here: some controller want the address to be set between
* control out and ack and some want to wait for the end of the transaction.
* In the first case, you need to write some code special code when getting
* setup packets and ignore this function (have a look at other drives)
*/
void usb_drv_set_address(int address)
{
(void)address;
/* UDC sets this automaticaly */
}
int usb_drv_send(int endpoint, void *ptr, int length)
{
(void)endpoint;
struct endpoint_t *ep = &ctrlep[DIR_IN];
ep->buf = ptr;
ep->len = ep->cnt = length;
ctr_write();
/* wait for transfer to end */
while(!usb_drv_send_done)
;
usb_drv_send_done = false;
return 0;
}
/* Setup a receive transfer. (non blocking) */
int usb_drv_recv(int endpoint, void* ptr, int length)
{
(void)endpoint;
struct endpoint_t *ep = &ctrlep[DIR_OUT];
ep->buf = ptr;
ep->len = ep->cnt = length;
/* clear NAK bit */
RX0CON &= ~RXNAK;
RX0DMAOUTLMADDR = (uint32_t)ptr; /* buffer address */
RX0DMACTLO = DMA_START; /* start DMA */
return 0;
}
/* Stall the endpoint. Usually set a flag in the controller */
void usb_drv_stall(int endpoint, bool stall, bool in)
{
/* ctrl only anyway */
(void)endpoint;
if(in)
{
if(stall)
TX0CON |= TXSTALL;
else
TX0CON &= ~TXSTALL;
}
else
{
if (stall)
RX0CON |= RXSTALL;
else
RX0CON &= ~RXSTALL; /* doc says Auto clear by UDC 2.0 */
}
}
/* one time init (once per connection) - basicaly enable usb core */
void usb_drv_init(void)
{
udc_phy_reset();
target_mdelay(10); /* wait at least 10ms */
udc_soft_connect();
EN_INT = EN_SUSP_INTR | /* Enable Suspend Irq */
EN_RESUME_INTR | /* Enable Resume Irq */
EN_USBRST_INTR | /* Enable USB Reset Irq */
EN_OUT0_INTR | /* Enable OUT Token receive Irq EP0 */
EN_IN0_INTR | /* Enable IN Token transmit Irq EP0 */
EN_SETUP_INTR; /* Enable SETUP Packet Receive Irq */
INTCON = UDC_INTHIGH_ACT | /* interrupt high active */
UDC_INTEN; /* enable EP0 irqs */
}
/* turn off usb core */
void usb_drv_exit(void)
{
/* udc module reset */
SCU_RSTCFG |= (1<<1);
target_udelay(10);
SCU_RSTCFG &= ~(1<<1);
}
/* UDC ISR function */
void INT_UDC(void)
{
uint32_t txstat, rxstat;
/* read what caused UDC irq */
uint32_t intsrc = INT2FLAG & 0x7fffff;
if (intsrc & USBRST_INTR) /* usb reset */
{
EN_INT = EN_SUSP_INTR | /* Enable Suspend Irq */
EN_RESUME_INTR | /* Enable Resume Irq */
EN_USBRST_INTR | /* Enable USB Reset Irq */
EN_OUT0_INTR | /* Enable OUT Token receive Irq EP0 */
EN_IN0_INTR | /* Enable IN Token transmit Irq EP0 */
EN_SETUP_INTR; /* Enable SETUP Packet Receive Irq */
TX0CON = TXACKINTEN | /* Set as one to enable the EP0 tx irq */
TXNAK; /* Set as one to response NAK handshake */
RX0CON = RXACKINTEN |
RXEPEN | /* Endpoint 0 Enable. When cleared the
* endpoint does not respond to an SETUP
* or OUT token */
RXNAK; /* Set as one to response NAK handshake */
}
if (intsrc & SETUP_INTR) /* setup interrupt */
{
setup_irq_handler();
}
if (intsrc & IN0_INTR) /* ep0 in interrupt */
{
txstat = TX0STAT; /* read clears flags */
/* TODO handle errors */
if (txstat & TXACK) /* check TxACK flag */
{
if (ctrlep[DIR_IN].cnt > 0)
{
/* we still have data to send */
ctr_write();
}
else
{
if (ctrlep[DIR_IN].cnt == 0)
ctr_write();
/* final ack received */
usb_drv_send_done = true;
}
}
}
if (intsrc & OUT0_INTR) /* ep0 out interrupt */
{
rxstat = RX0STAT;
/* TODO handle errors */
if (rxstat & RXACK) /* RxACK */
{
if (ctrlep[DIR_OUT].cnt > 0)
ctr_read();
}
}
if (intsrc & RESUME_INTR) /* usb resume */
{
TX0CON |= TXCLR; /* TxClr */
TX0CON &= ~TXCLR;
RX0CON |= RXCLR; /* RxClr */
RX0CON &= ~RXCLR;
}
}

View file

@ -23,7 +23,7 @@
ENTRY(start)
OUTPUT_FORMAT(elf32-littlearm)
OUTPUT_ARCH(arm)
STARTUP(crt0.o)
STARTUP(stmp/crt0.o)
#define IRAM_END_ADDR (IRAM_ORIG + IRAM_SIZE)

View file

@ -826,24 +826,6 @@ int main(int argc, char **argv)
goto Lerr;
}
}
// dump ROM
if(!g_quiet)
{
void *rom = malloc(64 * 1024);
ret = hwstub_rw_mem(&g_hwdev, 1, 0xc0000000, rom, 64 * 1024);
if(ret != 64 * 1024)
{
printf("Cannot read ROM: %d\n", ret);
goto Lerr;
}
printf("ROM successfully read!\n");
FILE *f = fopen("rom.bin", "wb");
fwrite(rom, 64 * 1024, 1, f);
fclose(f);
}
/** Init lua */
// create lua state

View file

@ -3,4 +3,5 @@ package.path = string.sub(string.gsub(debug.getinfo(1).source, "load.lua", "?.lu
if hwstub.dev.target.id == hwstub.dev.target.STMP then
require "stmp"
end
require "dumper"
require "dumper"