diff options
Diffstat (limited to 'VexRiscv/src/main/c/murax')
17 files changed, 942 insertions, 0 deletions
diff --git a/VexRiscv/src/main/c/murax/hello_world/makefile b/VexRiscv/src/main/c/murax/hello_world/makefile new file mode 100644 index 0000000..dc560c0 --- /dev/null +++ b/VexRiscv/src/main/c/murax/hello_world/makefile @@ -0,0 +1,134 @@ +PROJ_NAME=hello_world +DEBUG=no +BENCH=no +MULDIV=no + +SRCS = $(wildcard src/*.c) \ + $(wildcard src/*.cpp) \ + $(wildcard src/*.S) + +OBJDIR = build + +INC = +LIBS = +LIBSINC = -L$(OBJDIR) +LDSCRIPT = ./src/linker.ld + +#include ../../../resources/gcc.mk +# Set it to yes if you are using the sifive precompiled GCC pack +SIFIVE_GCC_PACK ?= yes + +ifeq ($(SIFIVE_GCC_PACK),yes) + RISCV_NAME ?= riscv64-unknown-elf + RISCV_PATH ?= /opt/riscv/ +else + RISCV_NAME ?= riscv32-unknown-elf + ifeq ($(MULDIV),yes) + RISCV_PATH ?= /opt/riscv32im/ + else + RISCV_PATH ?= /opt/riscv32i/ + endif +endif + +MABI=ilp32 +MARCH := rv32i +ifeq ($(MULDIV),yes) + MARCH := $(MARCH)m +endif +ifeq ($(COMPRESSED),yes) + MARCH := $(MARCH)ac +endif + +CFLAGS += -march=$(MARCH) -mabi=$(MABI) -DNDEBUG +LDFLAGS += -march=$(MARCH) -mabi=$(MABI) + + + +#include ../../../resources/subproject.mk + + +ifeq ($(DEBUG),yes) + CFLAGS += -g3 -O0 +endif + +ifeq ($(DEBUG),no) + CFLAGS += -g -Os +endif + +ifeq ($(BENCH),yes) + CFLAGS += -fno-inline +endif + +ifeq ($(SIFIVE_GCC_PACK),yes) + RISCV_CLIB=$(RISCV_PATH)/$(RISCV_NAME)/lib/$(MARCH)/$(MABI)/ +else + RISCV_CLIB=$(RISCV_PATH)/$(RISCV_NAME)/lib/ +endif + + + + + +RISCV_OBJCOPY = $(RISCV_PATH)/bin/$(RISCV_NAME)-objcopy +RISCV_OBJDUMP = $(RISCV_PATH)/bin/$(RISCV_NAME)-objdump +RISCV_CC=$(RISCV_PATH)/bin/$(RISCV_NAME)-gcc + +CFLAGS += -MD -fstrict-volatile-bitfields -fno-strict-aliasing +LDFLAGS += -nostdlib -lgcc -mcmodel=medany -nostartfiles -ffreestanding -Wl,-Bstatic,-T,$(LDSCRIPT),-Map,$(OBJDIR)/$(PROJ_NAME).map,--print-memory-usage +#LDFLAGS += -lgcc -lc -lg -nostdlib -lgcc -msave-restore --strip-debug, + +OBJS := $(SRCS) +OBJS := $(OBJS:.c=.o) +OBJS := $(OBJS:.cpp=.o) +OBJS := $(OBJS:.S=.o) +OBJS := $(OBJS:..=miaou) +OBJS := $(addprefix $(OBJDIR)/,$(OBJS)) + + +all: $(OBJDIR)/$(PROJ_NAME).elf $(OBJDIR)/$(PROJ_NAME).hex $(OBJDIR)/$(PROJ_NAME).asm $(OBJDIR)/$(PROJ_NAME).v + +$(OBJDIR)/%.elf: $(OBJS) | $(OBJDIR) + $(RISCV_CC) $(CFLAGS) -o $@ $^ $(LDFLAGS) $(LIBSINC) $(LIBS) + +%.hex: %.elf + $(RISCV_OBJCOPY) -O ihex $^ $@ + +%.bin: %.elf + $(RISCV_OBJCOPY) -O binary $^ $@ + +%.v: %.elf + $(RISCV_OBJCOPY) -O verilog $^ $@ + +%.asm: %.elf + $(RISCV_OBJDUMP) -S -d $^ > $@ + +$(OBJDIR)/%.o: %.c + mkdir -p $(dir $@) + $(RISCV_CC) -c $(CFLAGS) $(INC) -o $@ $^ + $(RISCV_CC) -S $(CFLAGS) $(INC) -o $@.disasm $^ + +$(OBJDIR)/%.o: %.cpp + mkdir -p $(dir $@) + $(RISCV_CC) -c $(CFLAGS) $(INC) -o $@ $^ + +$(OBJDIR)/%.o: %.S + mkdir -p $(dir $@) + $(RISCV_CC) -c $(CFLAGS) -o $@ $^ -D__ASSEMBLY__=1 + +$(OBJDIR): + mkdir -p $@ + +.PHONY: clean +clean: + rm -rf $(OBJDIR)/src + rm -f $(OBJDIR)/$(PROJ_NAME).elf + rm -f $(OBJDIR)/$(PROJ_NAME).hex + rm -f $(OBJDIR)/$(PROJ_NAME).map + rm -f $(OBJDIR)/$(PROJ_NAME).v + rm -f $(OBJDIR)/$(PROJ_NAME).asm + find $(OBJDIR) -type f -name '*.o' -print0 | xargs -0 -r rm + find $(OBJDIR) -type f -name '*.d' -print0 | xargs -0 -r rm + +clean-all : clean + +.SECONDARY: $(OBJS) diff --git a/VexRiscv/src/main/c/murax/hello_world/src/crt.S b/VexRiscv/src/main/c/murax/hello_world/src/crt.S new file mode 100644 index 0000000..62d67b9 --- /dev/null +++ b/VexRiscv/src/main/c/murax/hello_world/src/crt.S @@ -0,0 +1,98 @@ +.global crtStart +.global main +.global irqCallback + + .section .start_jump,"ax",@progbits +crtStart: + //long jump to allow crtInit to be anywhere + //do it always in 12 bytes + lui x2, %hi(crtInit) + addi x2, x2, %lo(crtInit) + jalr x1,x2 + nop + +.section .text + +.global trap_entry +.align 5 +trap_entry: + sw x1, - 1*4(sp) + sw x5, - 2*4(sp) + sw x6, - 3*4(sp) + sw x7, - 4*4(sp) + sw x10, - 5*4(sp) + sw x11, - 6*4(sp) + sw x12, - 7*4(sp) + sw x13, - 8*4(sp) + sw x14, - 9*4(sp) + sw x15, -10*4(sp) + sw x16, -11*4(sp) + sw x17, -12*4(sp) + sw x28, -13*4(sp) + sw x29, -14*4(sp) + sw x30, -15*4(sp) + sw x31, -16*4(sp) + addi sp,sp,-16*4 + call irqCallback + lw x1 , 15*4(sp) + lw x5, 14*4(sp) + lw x6, 13*4(sp) + lw x7, 12*4(sp) + lw x10, 11*4(sp) + lw x11, 10*4(sp) + lw x12, 9*4(sp) + lw x13, 8*4(sp) + lw x14, 7*4(sp) + lw x15, 6*4(sp) + lw x16, 5*4(sp) + lw x17, 4*4(sp) + lw x28, 3*4(sp) + lw x29, 2*4(sp) + lw x30, 1*4(sp) + lw x31, 0*4(sp) + addi sp,sp,16*4 + mret + .text + + +crtInit: + .option push + .option norelax + la gp, __global_pointer$ + .option pop + la sp, _stack_start + +bss_init: + la a0, _bss_start + la a1, _bss_end +bss_loop: + beq a0,a1,bss_done + sw zero,0(a0) + add a0,a0,4 + j bss_loop +bss_done: + +ctors_init: + la a0, _ctors_start + addi sp,sp,-4 +ctors_loop: + la a1, _ctors_end + beq a0,a1,ctors_done + lw a3,0(a0) + add a0,a0,4 + sw a0,0(sp) + jalr a3 + lw a0,0(sp) + j ctors_loop +ctors_done: + addi sp,sp,4 + + + li a0, 0x880 //880 enable timer + external interrupts + csrw mie,a0 + li a0, 0x1808 //1808 enable interrupts + csrw mstatus,a0 + + call main +infinitLoop: + j infinitLoop diff --git a/VexRiscv/src/main/c/murax/hello_world/src/gpio.h b/VexRiscv/src/main/c/murax/hello_world/src/gpio.h new file mode 100644 index 0000000..34348fe --- /dev/null +++ b/VexRiscv/src/main/c/murax/hello_world/src/gpio.h @@ -0,0 +1,15 @@ +#ifndef GPIO_H_ +#define GPIO_H_ + + +typedef struct +{ + volatile uint32_t INPUT; + volatile uint32_t OUTPUT; + volatile uint32_t OUTPUT_ENABLE; +} Gpio_Reg; + + +#endif /* GPIO_H_ */ + + diff --git a/VexRiscv/src/main/c/murax/hello_world/src/interrupt.h b/VexRiscv/src/main/c/murax/hello_world/src/interrupt.h new file mode 100644 index 0000000..23b7d27 --- /dev/null +++ b/VexRiscv/src/main/c/murax/hello_world/src/interrupt.h @@ -0,0 +1,17 @@ +#ifndef INTERRUPTCTRL_H_ +#define INTERRUPTCTRL_H_ + +#include <stdint.h> + +typedef struct +{ + volatile uint32_t PENDINGS; + volatile uint32_t MASKS; +} InterruptCtrl_Reg; + +static void interruptCtrl_init(InterruptCtrl_Reg* reg){ + reg->MASKS = 0; + reg->PENDINGS = 0xFFFFFFFF; +} + +#endif /* INTERRUPTCTRL_H_ */ diff --git a/VexRiscv/src/main/c/murax/hello_world/src/linker.ld b/VexRiscv/src/main/c/murax/hello_world/src/linker.ld new file mode 100644 index 0000000..57bc2f7 --- /dev/null +++ b/VexRiscv/src/main/c/murax/hello_world/src/linker.ld @@ -0,0 +1,110 @@ +/* +This is free and unencumbered software released into the public domain. + +Anyone is free to copy, modify, publish, use, compile, sell, or +distribute this software, either in source code form or as a compiled +binary, for any purpose, commercial or non-commercial, and by any +means. +*/ +OUTPUT_FORMAT("elf32-littleriscv", "elf32-littleriscv", "elf32-littleriscv") +OUTPUT_ARCH(riscv) +ENTRY(crtStart) + +MEMORY { + RAM (rwx): ORIGIN = 0x80000000, LENGTH = 2k +} + +_stack_size = DEFINED(_stack_size) ? _stack_size : 256; +_heap_size = DEFINED(_heap_size) ? _heap_size : 0; + +SECTIONS { + + ._vector ORIGIN(RAM): { + *crt.o(.start_jump); + *crt.o(.text); + } > RAM + + ._user_heap (NOLOAD): + { + . = ALIGN(8); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + PROVIDE ( _heap_start = .); + . = . + _heap_size; + . = ALIGN(8); + PROVIDE ( _heap_end = .); + } > RAM + +._stack (NOLOAD): + { + . = ALIGN(16); + PROVIDE (_stack_end = .); + . = . + _stack_size; + . = ALIGN(16); + PROVIDE (_stack_start = .); + } > RAM + + .data : + { + *(.rdata) + *(.rodata .rodata.*) + *(.gnu.linkonce.r.*) + *(.data .data.*) + *(.gnu.linkonce.d.*) + . = ALIGN(8); + PROVIDE( __global_pointer$ = . + 0x800 ); + *(.sdata .sdata.*) + *(.gnu.linkonce.s.*) + . = ALIGN(8); + *(.srodata.cst16) + *(.srodata.cst8) + *(.srodata.cst4) + *(.srodata.cst2) + *(.srodata .srodata.*) + } > RAM + + .bss (NOLOAD) : { + . = ALIGN(4); + /* This is used by the startup in order to initialize the .bss secion */ + _bss_start = .; + *(.sbss*) + *(.gnu.linkonce.sb.*) + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _bss_end = .; + } > RAM + + + .rodata : + { + *(.rdata) + *(.rodata .rodata.*) + *(.gnu.linkonce.r.*) + } > RAM + + .noinit (NOLOAD) : { + . = ALIGN(4); + *(.noinit .noinit.*) + . = ALIGN(4); + } > RAM + + .memory : { + *(.text); + end = .; + } > RAM + + .ctors : + { + . = ALIGN(4); + _ctors_start = .; + KEEP(*(.init_array*)) + KEEP (*(SORT(.ctors.*))) + KEEP (*(.ctors)) + . = ALIGN(4); + _ctors_end = .; + PROVIDE ( END_OF_SW_IMAGE = . ); + } > RAM + +} diff --git a/VexRiscv/src/main/c/murax/hello_world/src/main.c b/VexRiscv/src/main/c/murax/hello_world/src/main.c new file mode 100644 index 0000000..05f3227 --- /dev/null +++ b/VexRiscv/src/main/c/murax/hello_world/src/main.c @@ -0,0 +1,42 @@ +//#include "stddefs.h" +#include <stdint.h> + +#include "murax.h" + +void print(const char*str){ + while(*str){ + uart_write(UART,*str); + str++; + } +} +void println(const char*str){ + print(str); + uart_write(UART,'\n'); +} + +void delay(uint32_t loops){ + for(int i=0;i<loops;i++){ + int tmp = GPIO_A->OUTPUT; + } +} + +void main() { + GPIO_A->OUTPUT_ENABLE = 0x0000000F; + GPIO_A->OUTPUT = 0x00000001; + println("hello world arty a7 v1"); + const int nleds = 4; + const int nloops = 2000000; + while(1){ + for(unsigned int i=0;i<nleds-1;i++){ + GPIO_A->OUTPUT = 1<<i; + delay(nloops); + } + for(unsigned int i=0;i<nleds-1;i++){ + GPIO_A->OUTPUT = (1<<(nleds-1))>>i; + delay(nloops); + } + } +} + +void irqCallback(){ +} diff --git a/VexRiscv/src/main/c/murax/hello_world/src/murax.h b/VexRiscv/src/main/c/murax/hello_world/src/murax.h new file mode 100644 index 0000000..fbfdf3e --- /dev/null +++ b/VexRiscv/src/main/c/murax/hello_world/src/murax.h @@ -0,0 +1,17 @@ +#ifndef __MURAX_H__ +#define __MURAX_H__ + +#include "timer.h" +#include "prescaler.h" +#include "interrupt.h" +#include "gpio.h" +#include "uart.h" + +#define GPIO_A ((Gpio_Reg*)(0xF0000000)) +#define TIMER_PRESCALER ((Prescaler_Reg*)0xF0020000) +#define TIMER_INTERRUPT ((InterruptCtrl_Reg*)0xF0020010) +#define TIMER_A ((Timer_Reg*)0xF0020040) +#define TIMER_B ((Timer_Reg*)0xF0020050) +#define UART ((Uart_Reg*)(0xF0010000)) + +#endif /* __MURAX_H__ */ diff --git a/VexRiscv/src/main/c/murax/hello_world/src/prescaler.h b/VexRiscv/src/main/c/murax/hello_world/src/prescaler.h new file mode 100644 index 0000000..6bd9694 --- /dev/null +++ b/VexRiscv/src/main/c/murax/hello_world/src/prescaler.h @@ -0,0 +1,16 @@ +#ifndef PRESCALERCTRL_H_ +#define PRESCALERCTRL_H_ + +#include <stdint.h> + + +typedef struct +{ + volatile uint32_t LIMIT; +} Prescaler_Reg; + +static void prescaler_init(Prescaler_Reg* reg){ + +} + +#endif /* PRESCALERCTRL_H_ */ diff --git a/VexRiscv/src/main/c/murax/hello_world/src/timer.h b/VexRiscv/src/main/c/murax/hello_world/src/timer.h new file mode 100644 index 0000000..1577535 --- /dev/null +++ b/VexRiscv/src/main/c/murax/hello_world/src/timer.h @@ -0,0 +1,20 @@ +#ifndef TIMERCTRL_H_ +#define TIMERCTRL_H_ + +#include <stdint.h> + + +typedef struct +{ + volatile uint32_t CLEARS_TICKS; + volatile uint32_t LIMIT; + volatile uint32_t VALUE; +} Timer_Reg; + +static void timer_init(Timer_Reg *reg){ + reg->CLEARS_TICKS = 0; + reg->VALUE = 0; +} + + +#endif /* TIMERCTRL_H_ */ diff --git a/VexRiscv/src/main/c/murax/hello_world/src/uart.h b/VexRiscv/src/main/c/murax/hello_world/src/uart.h new file mode 100644 index 0000000..c3a30a5 --- /dev/null +++ b/VexRiscv/src/main/c/murax/hello_world/src/uart.h @@ -0,0 +1,42 @@ +#ifndef UART_H_ +#define UART_H_ + + +typedef struct +{ + volatile uint32_t DATA; + volatile uint32_t STATUS; + volatile uint32_t CLOCK_DIVIDER; + volatile uint32_t FRAME_CONFIG; +} Uart_Reg; + +enum UartParity {NONE = 0,EVEN = 1,ODD = 2}; +enum UartStop {ONE = 0,TWO = 1}; + +typedef struct { + uint32_t dataLength; + enum UartParity parity; + enum UartStop stop; + uint32_t clockDivider; +} Uart_Config; + +static uint32_t uart_writeAvailability(Uart_Reg *reg){ + return (reg->STATUS >> 16) & 0xFF; +} +static uint32_t uart_readOccupancy(Uart_Reg *reg){ + return reg->STATUS >> 24; +} + +static void uart_write(Uart_Reg *reg, uint32_t data){ + while(uart_writeAvailability(reg) == 0); + reg->DATA = data; +} + +static void uart_applyConfig(Uart_Reg *reg, Uart_Config *config){ + reg->CLOCK_DIVIDER = config->clockDivider; + reg->FRAME_CONFIG = ((config->dataLength-1) << 0) | (config->parity << 8) | (config->stop << 16); +} + +#endif /* UART_H_ */ + + diff --git a/VexRiscv/src/main/c/murax/xipBootloader/.gitignore b/VexRiscv/src/main/c/murax/xipBootloader/.gitignore new file mode 100644 index 0000000..2b33f1e --- /dev/null +++ b/VexRiscv/src/main/c/murax/xipBootloader/.gitignore @@ -0,0 +1,5 @@ +*.elf +*.map +*.d +*.asm +*.o
\ No newline at end of file diff --git a/VexRiscv/src/main/c/murax/xipBootloader/crt.S b/VexRiscv/src/main/c/murax/xipBootloader/crt.S new file mode 100644 index 0000000..5268767 --- /dev/null +++ b/VexRiscv/src/main/c/murax/xipBootloader/crt.S @@ -0,0 +1,74 @@ +#define CTRL_BASE 0xF001F000 +#define XIP_BASE 0xE0040000 +#define CTRL_DATA 0x00 +#define CTRL_STATUS 0x04 +#define CTRL_MODE 0x08 +#define CTRL_RATE 0x20 +#define CTRL_SS_SETUP 0x24 +#define CTRL_SS_HOLD 0x28 +#define CTRL_SS_DISABLE 0x2C + +#define CTRL_XIP_CONFIG 0x40 +#define CTRL_XIP_MODE 0x44 + +.global crtStart +.global main + +#define CTRL x31 + +crtStart: + li x31, CTRL_BASE + sw x0, CTRL_MODE(CTRL) + li t0, 2 + sw t0, CTRL_RATE(CTRL) + li t0, 4 + sw t0, CTRL_SS_SETUP(CTRL) + sw t0, CTRL_SS_HOLD(CTRL) + sw t0, CTRL_SS_DISABLE(CTRL) + + + li a0, 0x880 + call spiWrite + li a0, 0x181 + call spiWrite + li a0, 0x183 + call spiWrite + li a0, 0x800 + call spiWrite + + + li t0, 0x00FF010B + sw t0, CTRL_XIP_MODE(CTRL) + li t0, 0x1 + sw t0, CTRL_XIP_CONFIG(CTRL) + li t0, XIP_BASE + lw t1, (t0) + li t2, 0xFFFFFFFF + xor t3,t1,t2 + beqz t3,retry + //if we are here we have read a value from flash which is not all ones + lw t2, (t0) + xor t3,t1,t2 + bnez t3,retry + lw t2, (t0) + xor t3,t1,t2 + bnez t3,retry + //if we are here we have read the same value 3 times, so flash seems good, lets's jump + jr t0 + +retry: + li a0, 0x800 + call spiWrite + li t1,100000 +loop: + addi t1,t1,-1 + bnez t1, loop + j crtStart + +spiWrite: + sw a0,CTRL_DATA(CTRL) +spiWrite_wait: + lw t0,CTRL_STATUS(CTRL) + slli t0,t0,0x10 + beqz t0,spiWrite_wait + ret diff --git a/VexRiscv/src/main/c/murax/xipBootloader/demo.S b/VexRiscv/src/main/c/murax/xipBootloader/demo.S new file mode 100644 index 0000000..064db6f --- /dev/null +++ b/VexRiscv/src/main/c/murax/xipBootloader/demo.S @@ -0,0 +1,27 @@ +#define GPIO_BASE 0xF0000000 +#define GPIO_OUTPUT 4 +#define GPIO_OUTPUT_ENABLE 8 + + +.global crtStart + +crtStart: + + li x31, 0x12340000 // magic word expected by bootloader + + li x31, GPIO_BASE + li t0, 0x000000FF + sw t0, GPIO_OUTPUT_ENABLE(x31) + + li t0,1 +redo: + sw t0, GPIO_OUTPUT(x31) + li t1,10000 + slli t0,t0,1 + andi t0,t0,0xFF + bnez t0, loop + li t0,1 +loop: + addi t1,t1,-1 + bnez t1, loop + j redo diff --git a/VexRiscv/src/main/c/murax/xipBootloader/makefile b/VexRiscv/src/main/c/murax/xipBootloader/makefile new file mode 100644 index 0000000..e08c17b --- /dev/null +++ b/VexRiscv/src/main/c/murax/xipBootloader/makefile @@ -0,0 +1,37 @@ +CFLAGS= -march=rv32i -mabi=ilp32 -g -O3 -MD +LFLAGS= -nostdlib -mcmodel=medany -nostartfiles -ffreestanding -fPIC -fPIE + + +all: crt.S demo.S + riscv64-unknown-elf-gcc -c $(CFLAGS) -o crt.o crt.S + riscv64-unknown-elf-gcc $(CFLAGS) -o crt.elf crt.o $(LFLAGS) -Wl,-Bstatic,-T,mapping_rom.ld,-Map,crt.map,--print-memory-usage + riscv64-unknown-elf-objdump -S -d crt.elf > crt.asm + riscv64-unknown-elf-objcopy -O binary crt.elf crt.bin + + riscv64-unknown-elf-gcc $(CFLAGS) -o crt_ram.elf crt.o $(LFLAGS) -Wl,-Bstatic,-T,mapping.ld,-Map,crt_ram.map,--print-memory-usage + riscv64-unknown-elf-objdump -S -d crt_ram.elf > crt_ram.asm + riscv64-unknown-elf-objcopy -O binary crt_ram.elf crt_ram.bin + + riscv64-unknown-elf-gcc -c $(CFLAGS) -o demo.o demo.S + riscv64-unknown-elf-gcc $(CFLAGS) -o demo.elf demo.o $(LFLAGS) -Wl,-Bstatic,-T,mapping.ld,-Map,demo.map,--print-memory-usage + riscv64-unknown-elf-objdump -S -d demo.elf > demo.asm + riscv64-unknown-elf-objcopy -O binary demo.elf demo.bin + + riscv64-unknown-elf-gcc $(CFLAGS) -o demo_rom.elf demo.o $(LFLAGS) -Wl,-Bstatic,-T,mapping_rom.ld,-Map,demo_rom.map,--print-memory-usage + riscv64-unknown-elf-objdump -S -d demo_rom.elf > demo_rom.asm + riscv64-unknown-elf-objcopy -O binary demo_rom.elf demo_rom.bin + + riscv64-unknown-elf-gcc $(CFLAGS) -o demo_xip.elf demo.o $(LFLAGS) -Wl,-Bstatic,-T,mapping_xip.ld,-Map,demo_xip.map,--print-memory-usage + riscv64-unknown-elf-objdump -S -d demo_xip.elf > demo_xip.asm + riscv64-unknown-elf-objcopy -O binary demo_xip.elf demo_xip.bin + +clean-for-commit: + rm -f *.o + rm -f *.elf + rm -f *.asm + rm -f *.map + rm -f *.d + rm demo_rom.bin demo.bin crt_ram.bin + +clean: clean-for-commit + rm -f *.bin diff --git a/VexRiscv/src/main/c/murax/xipBootloader/mapping.ld b/VexRiscv/src/main/c/murax/xipBootloader/mapping.ld new file mode 100644 index 0000000..cc1b070 --- /dev/null +++ b/VexRiscv/src/main/c/murax/xipBootloader/mapping.ld @@ -0,0 +1,96 @@ +/* +This is free and unencumbered software released into the public domain. + +Anyone is free to copy, modify, publish, use, compile, sell, or +distribute this software, either in source code form or as a compiled +binary, for any purpose, commercial or non-commercial, and by any +means. +*/ +OUTPUT_FORMAT("elf32-littleriscv", "elf32-littleriscv", "elf32-littleriscv") +OUTPUT_ARCH(riscv) +ENTRY(crtStart) + +MEMORY { + mem : ORIGIN = 0x80000000, LENGTH = 0x00000400 +} + +_stack_size = DEFINED(_stack_size) ? _stack_size : 0; + +SECTIONS { + + .vector : { + *crt.o(.text); + } > mem + + .memory : { + *(.text); + end = .; + } > mem + + .rodata : + { + *(.rdata) + *(.rodata .rodata.*) + *(.gnu.linkonce.r.*) + } > mem + + .ctors : + { + . = ALIGN(4); + _ctors_start = .; + KEEP(*(.init_array*)) + KEEP (*(SORT(.ctors.*))) + KEEP (*(.ctors)) + . = ALIGN(4); + _ctors_end = .; + } > mem + + .data : + { + *(.rdata) + *(.rodata .rodata.*) + *(.gnu.linkonce.r.*) + *(.data .data.*) + *(.gnu.linkonce.d.*) + . = ALIGN(8); + PROVIDE( __global_pointer$ = . + 0x800 ); + *(.sdata .sdata.*) + *(.gnu.linkonce.s.*) + . = ALIGN(8); + *(.srodata.cst16) + *(.srodata.cst8) + *(.srodata.cst4) + *(.srodata.cst2) + *(.srodata .srodata.*) + } > mem + + .bss (NOLOAD) : { + . = ALIGN(4); + /* This is used by the startup in order to initialize the .bss secion */ + _bss_start = .; + *(.sbss*) + *(.gnu.linkonce.sb.*) + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _bss_end = .; + } > mem + + .noinit (NOLOAD) : { + . = ALIGN(4); + *(.noinit .noinit.*) + . = ALIGN(4); + } > mem + + ._stack (NOLOAD): + { + . = ALIGN(16); + PROVIDE (_stack_end = .); + . = . + _stack_size; + . = ALIGN(16); + PROVIDE (_stack_start = .); + } > mem + +} + diff --git a/VexRiscv/src/main/c/murax/xipBootloader/mapping_rom.ld b/VexRiscv/src/main/c/murax/xipBootloader/mapping_rom.ld new file mode 100644 index 0000000..aaa0c3c --- /dev/null +++ b/VexRiscv/src/main/c/murax/xipBootloader/mapping_rom.ld @@ -0,0 +1,96 @@ +/* +This is free and unencumbered software released into the public domain. + +Anyone is free to copy, modify, publish, use, compile, sell, or +distribute this software, either in source code form or as a compiled +binary, for any purpose, commercial or non-commercial, and by any +means. +*/ +OUTPUT_FORMAT("elf32-littleriscv", "elf32-littleriscv", "elf32-littleriscv") +OUTPUT_ARCH(riscv) +ENTRY(crtStart) + +MEMORY { + mem : ORIGIN = 0x80000000, LENGTH = 0x00000400 + rom : ORIGIN = 0xF001E000, LENGTH = 0x00000400 +} + +_stack_size = DEFINED(_stack_size) ? _stack_size : 0; + +SECTIONS { + + .vector : { + *crt.o(.text); + } > rom + + .memory : { + *(.text); + end = .; + } > rom + + .rodata : + { + *(.rdata) + *(.rodata .rodata.*) + *(.gnu.linkonce.r.*) + } > rom + + .ctors : + { + . = ALIGN(4); + _ctors_start = .; + KEEP(*(.init_array*)) + KEEP (*(SORT(.ctors.*))) + KEEP (*(.ctors)) + . = ALIGN(4); + _ctors_end = .; + } > rom + + .data : + { + *(.rdata) + *(.rodata .rodata.*) + *(.gnu.linkonce.r.*) + *(.data .data.*) + *(.gnu.linkonce.d.*) + . = ALIGN(8); + PROVIDE( __global_pointer$ = . + 0x800 ); + *(.sdata .sdata.*) + *(.gnu.linkonce.s.*) + . = ALIGN(8); + *(.srodata.cst16) + *(.srodata.cst8) + *(.srodata.cst4) + *(.srodata.cst2) + *(.srodata .srodata.*) + } > rom + + .bss (NOLOAD) : { + . = ALIGN(4); + /* This is used by the startup in order to initialize the .bss secion */ + _bss_start = .; + *(.sbss*) + *(.gnu.linkonce.sb.*) + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _bss_end = .; + } > mem + + .noinit (NOLOAD) : { + . = ALIGN(4); + *(.noinit .noinit.*) + . = ALIGN(4); + } > mem + + ._stack (NOLOAD): + { + . = ALIGN(16); + PROVIDE (_stack_end = .); + . = . + _stack_size; + . = ALIGN(16); + PROVIDE (_stack_start = .); + } > mem + +} diff --git a/VexRiscv/src/main/c/murax/xipBootloader/mapping_xip.ld b/VexRiscv/src/main/c/murax/xipBootloader/mapping_xip.ld new file mode 100644 index 0000000..ed56400 --- /dev/null +++ b/VexRiscv/src/main/c/murax/xipBootloader/mapping_xip.ld @@ -0,0 +1,96 @@ +/* +This is free and unencumbered software released into the public domain. + +Anyone is free to copy, modify, publish, use, compile, sell, or +distribute this software, either in source code form or as a compiled +binary, for any purpose, commercial or non-commercial, and by any +means. +*/ +OUTPUT_FORMAT("elf32-littleriscv", "elf32-littleriscv", "elf32-littleriscv") +OUTPUT_ARCH(riscv) +ENTRY(crtStart) + +MEMORY { + mem : ORIGIN = 0x80000000, LENGTH = 0x00000400 + xip : ORIGIN = 0xE0040000, LENGTH = 0x00000400 +} + +_stack_size = DEFINED(_stack_size) ? _stack_size : 0; + +SECTIONS { + + .vector : { + *crt.o(.text); + } > xip + + .memory : { + *(.text); + end = .; + } > xip + + .rodata : + { + *(.rdata) + *(.rodata .rodata.*) + *(.gnu.linkonce.r.*) + } > xip + + .ctors : + { + . = ALIGN(4); + _ctors_start = .; + KEEP(*(.init_array*)) + KEEP (*(SORT(.ctors.*))) + KEEP (*(.ctors)) + . = ALIGN(4); + _ctors_end = .; + } > xip + + .data : + { + *(.rdata) + *(.rodata .rodata.*) + *(.gnu.linkonce.r.*) + *(.data .data.*) + *(.gnu.linkonce.d.*) + . = ALIGN(8); + PROVIDE( __global_pointer$ = . + 0x800 ); + *(.sdata .sdata.*) + *(.gnu.linkonce.s.*) + . = ALIGN(8); + *(.srodata.cst16) + *(.srodata.cst8) + *(.srodata.cst4) + *(.srodata.cst2) + *(.srodata .srodata.*) + } > xip + + .bss (NOLOAD) : { + . = ALIGN(4); + /* This is used by the startup in order to initialize the .bss secion */ + _bss_start = .; + *(.sbss*) + *(.gnu.linkonce.sb.*) + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _bss_end = .; + } > mem + + .noinit (NOLOAD) : { + . = ALIGN(4); + *(.noinit .noinit.*) + . = ALIGN(4); + } > mem + + ._stack (NOLOAD): + { + . = ALIGN(16); + PROVIDE (_stack_end = .); + . = . + _stack_size; + . = ALIGN(16); + PROVIDE (_stack_start = .); + } > mem + +} |