This commit is contained in:
mpabi 2024-06-01 21:14:04 +00:00
commit ef53cf7ccd
11 changed files with 1087 additions and 0 deletions

134
makefile Normal file
View File

@ -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 ?= riscv32-unknown-elf
RISCV_PATH ?= /home/user/riscv/opt/rv32im/
else
RISCV_NAME ?= riscv32-unknown-elf
ifeq ($(MULDIV),yes)
RISCV_PATH ?= /opt/riscv32im/
else
RISCV_PATH ?= /opt/riscv32i/
endif
endif
MABI=ilp32
MARCH := rv32i_zicsr
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)-g++
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)

98
src/crt.S Normal file
View File

@ -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

15
src/gpio.h Normal file
View File

@ -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_ */

17
src/interrupt.h Normal file
View File

@ -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_ */

110
src/linker.ld Normal file
View File

@ -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 = 128k
}
_stack_size = DEFINED(_stack_size) ? _stack_size : 8192;
_heap_size = DEFINED(_heap_size) ? _heap_size : 8192;
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
}

75
src/main.cpp Normal file
View File

@ -0,0 +1,75 @@
//#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;
}
}
volatile int mati = 0;
// Modern C++ aproach
// ---
class TimeR {
public:
static inline uint32_t readValue() {
return ptr->VALUE;
}
private:
static const Timer_Reg* ptr ;
};
const Timer_Reg* TimeR::ptr = reinterpret_cast<const Timer_Reg*>(0xF0020040);
// ---
int main() {
GPIO_A->OUTPUT_ENABLE = 0x0000000F;
GPIO_A->OUTPUT = 0x00000001;
println("hello world arty a7 v1");
const int nleds = 4;
const int nloops = 10;
interruptCtrl_init(TIMER_INTERRUPT);
prescaler_init(TIMER_PRESCALER);
timer_init(TIMER_A);
TIMER_PRESCALER->LIMIT = 0x10;
TIMER_A->LIMIT = 0x10000-1;
TIMER_A->CLEARS_TICKS = 0x10002;
TIMER_INTERRUPT->PENDINGS = 0xF;
TIMER_INTERRUPT->MASKS = 0x1;
while(1){
++mati;
}
}
extern "C" void irqCallback(){
static volatile int count = 0;
++count;
TIMER_INTERRUPT->PENDINGS = 1;
}

17
src/murax.h Normal file
View File

@ -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__ */

16
src/prescaler.h Normal file
View File

@ -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_ */

543
src/spindal/Murax.scala Normal file
View File

@ -0,0 +1,543 @@
package vexriscv.demo
import spinal.core._
import spinal.lib._
import spinal.lib.bus.amba3.apb._
import spinal.lib.bus.misc.SizeMapping
import spinal.lib.bus.simple.PipelinedMemoryBus
import spinal.lib.com.jtag.Jtag
import spinal.lib.com.spi.ddr.SpiXdrMaster
import spinal.lib.com.uart._
import spinal.lib.io.{InOutWrapper, TriStateArray}
import spinal.lib.misc.{InterruptCtrl, Prescaler, Timer}
import spinal.lib.soc.pinsec.{PinsecTimerCtrl, PinsecTimerCtrlExternal}
import vexriscv.plugin._
import vexriscv.{VexRiscv, VexRiscvConfig, plugin}
import spinal.lib.com.spi.ddr._
import spinal.lib.bus.simple._
import scala.collection.mutable.ArrayBuffer
import scala.collection.Seq
/**
* Created by PIC32F_USER on 28/07/2017.
*
* Murax is a very light SoC which could work without any external component.
* - ICE40-hx8k + icestorm => 53 Mhz, 2142 LC
* - 0.37 DMIPS/Mhz
* - 8 kB of on-chip ram
* - JTAG debugger (eclipse/GDB/openocd ready)
* - Interrupt support
* - APB bus for peripherals
* - 32 GPIO pin
* - one 16 bits prescaler, two 16 bits timers
* - one UART with tx/rx fifo
*/
case class MuraxConfig(coreFrequency : HertzNumber,
onChipRamSize : BigInt,
onChipRamHexFile : String,
pipelineDBus : Boolean,
pipelineMainBus : Boolean,
pipelineApbBridge : Boolean,
gpioWidth : Int,
uartCtrlConfig : UartCtrlMemoryMappedConfig,
xipConfig : SpiXdrMasterCtrl.MemoryMappingParameters,
hardwareBreakpointCount : Int,
cpuPlugins : ArrayBuffer[Plugin[VexRiscv]]){
require(pipelineApbBridge || pipelineMainBus, "At least pipelineMainBus or pipelineApbBridge should be enable to avoid wipe transactions")
val genXip = xipConfig != null
}
object MuraxConfig{
def default : MuraxConfig = default(false, false)
def default(withXip : Boolean = false, bigEndian : Boolean = false) = MuraxConfig(
coreFrequency = 12 MHz,
onChipRamSize = 1024 kB,
onChipRamHexFile = null,
pipelineDBus = true,
pipelineMainBus = false,
pipelineApbBridge = true,
gpioWidth = 32,
xipConfig = ifGen(withXip) (SpiXdrMasterCtrl.MemoryMappingParameters(
SpiXdrMasterCtrl.Parameters(8, 12, SpiXdrParameter(2, 2, 1)).addFullDuplex(0,1,false),
cmdFifoDepth = 32,
rspFifoDepth = 32,
xip = SpiXdrMasterCtrl.XipBusParameters(addressWidth = 24, lengthWidth = 2)
)),
hardwareBreakpointCount = if(withXip) 3 else 0,
cpuPlugins = ArrayBuffer( //DebugPlugin added by the toplevel
new IBusSimplePlugin(
resetVector = if(withXip) 0xF001E000l else 0x80000000l,
cmdForkOnSecondStage = true,
cmdForkPersistence = withXip, //Required by the Xip controller
prediction = NONE,
catchAccessFault = false,
compressedGen = false,
bigEndian = bigEndian
),
new DBusSimplePlugin(
catchAddressMisaligned = false,
catchAccessFault = false,
earlyInjection = false,
bigEndian = bigEndian
),
new CsrPlugin(CsrPluginConfig.smallest(mtvecInit = if(withXip) 0xE0040020l else 0x80000020l)),
new DecoderSimplePlugin(
catchIllegalInstruction = false
),
new RegFilePlugin(
regFileReadyKind = plugin.SYNC,
zeroBoot = false
),
new IntAluPlugin,
new SrcPlugin(
separatedAddSub = false,
executeInsertion = false
),
new LightShifterPlugin,
new HazardSimplePlugin(
bypassExecute = false,
bypassMemory = false,
bypassWriteBack = false,
bypassWriteBackBuffer = false,
pessimisticUseSrc = false,
pessimisticWriteRegFile = false,
pessimisticAddressMatch = false
),
new BranchPlugin(
earlyBranch = false,
catchAddressMisaligned = false
),
new YamlPlugin("cpu0.yaml")
),
uartCtrlConfig = UartCtrlMemoryMappedConfig(
uartCtrlConfig = UartCtrlGenerics(
dataWidthMax = 8,
clockDividerWidth = 20,
preSamplingSize = 1,
samplingSize = 3,
postSamplingSize = 1
),
initConfig = UartCtrlInitConfig(
baudrate = 115200,
dataLength = 7, //7 => 8 bits
parity = UartParityType.NONE,
stop = UartStopType.ONE
),
busCanWriteClockDividerConfig = false,
busCanWriteFrameConfig = false,
txFifoDepth = 16,
rxFifoDepth = 16
)
)
def fast = {
val config = default
//Replace HazardSimplePlugin to get datapath bypass
config.cpuPlugins(config.cpuPlugins.indexWhere(_.isInstanceOf[HazardSimplePlugin])) = new HazardSimplePlugin(
bypassExecute = true,
bypassMemory = true,
bypassWriteBack = true,
bypassWriteBackBuffer = true
)
// config.cpuPlugins(config.cpuPlugins.indexWhere(_.isInstanceOf[LightShifterPlugin])) = new FullBarrelShifterPlugin()
config
}
}
case class Murax(config : MuraxConfig) extends Component{
import config._
val io = new Bundle {
//Clocks / reset
val asyncReset = in Bool()
val mainClk = in Bool()
//Main components IO
val jtag = slave(Jtag())
//Peripherals IO
val gpioA = master(TriStateArray(gpioWidth bits))
val uart = master(Uart())
val xip = ifGen(genXip)(master(SpiXdrMaster(xipConfig.ctrl.spi)))
}
val resetCtrlClockDomain = ClockDomain(
clock = io.mainClk,
config = ClockDomainConfig(
resetKind = BOOT
)
)
val resetCtrl = new ClockingArea(resetCtrlClockDomain) {
val mainClkResetUnbuffered = False
//Implement an counter to keep the reset axiResetOrder high 64 cycles
// Also this counter will automatically do a reset when the system boot.
val systemClkResetCounter = Reg(UInt(6 bits)) init(0)
when(systemClkResetCounter =/= U(systemClkResetCounter.range -> true)){
systemClkResetCounter := systemClkResetCounter + 1
mainClkResetUnbuffered := True
}
when(BufferCC(io.asyncReset)){
systemClkResetCounter := 0
}
//Create all reset used later in the design
val mainClkReset = RegNext(mainClkResetUnbuffered)
val systemReset = RegNext(mainClkResetUnbuffered)
}
val systemClockDomain = ClockDomain(
clock = io.mainClk,
reset = resetCtrl.systemReset,
frequency = FixedFrequency(coreFrequency)
)
val debugClockDomain = ClockDomain(
clock = io.mainClk,
reset = resetCtrl.mainClkReset,
frequency = FixedFrequency(coreFrequency)
)
val system = new ClockingArea(systemClockDomain) {
val pipelinedMemoryBusConfig = PipelinedMemoryBusConfig(
addressWidth = 32,
dataWidth = 32
)
val bigEndianDBus = config.cpuPlugins.exists(_ match{ case plugin : DBusSimplePlugin => plugin.bigEndian case _ => false})
//Arbiter of the cpu dBus/iBus to drive the mainBus
//Priority to dBus, !! cmd transactions can change on the fly !!
val mainBusArbiter = new MuraxMasterArbiter(pipelinedMemoryBusConfig, bigEndianDBus)
//Instanciate the CPU
val cpu = new VexRiscv(
config = VexRiscvConfig(
plugins = cpuPlugins += new DebugPlugin(debugClockDomain, hardwareBreakpointCount)
)
)
//Checkout plugins used to instanciate the CPU to connect them to the SoC
val timerInterrupt = False
val externalInterrupt = False
for(plugin <- cpu.plugins) plugin match{
case plugin : IBusSimplePlugin =>
mainBusArbiter.io.iBus.cmd <> plugin.iBus.cmd
mainBusArbiter.io.iBus.rsp <> plugin.iBus.rsp
case plugin : DBusSimplePlugin => {
if(!pipelineDBus)
mainBusArbiter.io.dBus <> plugin.dBus
else {
mainBusArbiter.io.dBus.cmd << plugin.dBus.cmd.halfPipe()
mainBusArbiter.io.dBus.rsp <> plugin.dBus.rsp
}
}
case plugin : CsrPlugin => {
plugin.externalInterrupt := externalInterrupt
plugin.timerInterrupt := timerInterrupt
}
case plugin : DebugPlugin => plugin.debugClockDomain{
resetCtrl.systemReset setWhen(RegNext(plugin.io.resetOut))
io.jtag <> plugin.io.bus.fromJtag()
}
case _ =>
}
//****** MainBus slaves ********
val mainBusMapping = ArrayBuffer[(PipelinedMemoryBus,SizeMapping)]()
val ram = new MuraxPipelinedMemoryBusRam(
onChipRamSize = onChipRamSize,
onChipRamHexFile = onChipRamHexFile,
pipelinedMemoryBusConfig = pipelinedMemoryBusConfig,
bigEndian = bigEndianDBus
)
mainBusMapping += ram.io.bus -> (0x80000000l, onChipRamSize)
val apbBridge = new PipelinedMemoryBusToApbBridge(
apb3Config = Apb3Config(
addressWidth = 20,
dataWidth = 32
),
pipelineBridge = pipelineApbBridge,
pipelinedMemoryBusConfig = pipelinedMemoryBusConfig
)
mainBusMapping += apbBridge.io.pipelinedMemoryBus -> (0xF0000000l, 1 MB)
//******** APB peripherals *********
val apbMapping = ArrayBuffer[(Apb3, SizeMapping)]()
val gpioACtrl = Apb3Gpio(gpioWidth = gpioWidth, withReadSync = true)
io.gpioA <> gpioACtrl.io.gpio
apbMapping += gpioACtrl.io.apb -> (0x00000, 4 kB)
val uartCtrl = Apb3UartCtrl(uartCtrlConfig)
uartCtrl.io.uart <> io.uart
externalInterrupt setWhen(uartCtrl.io.interrupt)
apbMapping += uartCtrl.io.apb -> (0x10000, 4 kB)
val timer = new MuraxApb3Timer()
timerInterrupt setWhen(timer.io.interrupt)
apbMapping += timer.io.apb -> (0x20000, 4 kB)
val xip = ifGen(genXip)(new Area{
val ctrl = Apb3SpiXdrMasterCtrl(xipConfig)
ctrl.io.spi <> io.xip
externalInterrupt setWhen(ctrl.io.interrupt)
apbMapping += ctrl.io.apb -> (0x1F000, 4 kB)
val accessBus = new PipelinedMemoryBus(PipelinedMemoryBusConfig(24,32))
mainBusMapping += accessBus -> (0xE0000000l, 16 MB)
ctrl.io.xip.fromPipelinedMemoryBus() << accessBus
val bootloader = Apb3Rom("src/main/c/murax/xipBootloader/crt.bin")
apbMapping += bootloader.io.apb -> (0x1E000, 4 kB)
})
//******** Memory mappings *********
val apbDecoder = Apb3Decoder(
master = apbBridge.io.apb,
slaves = apbMapping.toSeq
)
val mainBusDecoder = new Area {
val logic = new MuraxPipelinedMemoryBusDecoder(
master = mainBusArbiter.io.masterBus,
specification = mainBusMapping.toSeq,
pipelineMaster = pipelineMainBus
)
}
}
}
object Murax{
def main(args: Array[String]) {
SpinalVerilog(Murax(MuraxConfig.default))
}
}
object MuraxCfu{
def main(args: Array[String]) {
SpinalVerilog{
val config = MuraxConfig.default
config.cpuPlugins += new CfuPlugin(
stageCount = 1,
allowZeroLatency = true,
encodings = List(
CfuPluginEncoding (
instruction = M"-------------------------0001011",
functionId = List(14 downto 12),
input2Kind = CfuPlugin.Input2Kind.RS
)
),
busParameter = CfuBusParameter(
CFU_VERSION = 0,
CFU_INTERFACE_ID_W = 0,
CFU_FUNCTION_ID_W = 3,
CFU_REORDER_ID_W = 0,
CFU_REQ_RESP_ID_W = 0,
CFU_INPUTS = 2,
CFU_INPUT_DATA_W = 32,
CFU_OUTPUTS = 1,
CFU_OUTPUT_DATA_W = 32,
CFU_FLOW_REQ_READY_ALWAYS = false,
CFU_FLOW_RESP_READY_ALWAYS = false,
CFU_WITH_STATUS = true,
CFU_RAW_INSN_W = 32,
CFU_CFU_ID_W = 4,
CFU_STATE_INDEX_NUM = 5
)
)
val toplevel = Murax(config)
toplevel.rework {
for (plugin <- toplevel.system.cpu.plugins) plugin match {
case plugin: CfuPlugin => plugin.bus.toIo().setName("miaou")
case _ =>
}
}
toplevel
}
}
}
object Murax_iCE40_hx8k_breakout_board_xip{
case class SB_GB() extends BlackBox{
val USER_SIGNAL_TO_GLOBAL_BUFFER = in Bool()
val GLOBAL_BUFFER_OUTPUT = out Bool()
}
case class SB_IO_SCLK() extends BlackBox{
addGeneric("PIN_TYPE", B"010000")
val PACKAGE_PIN = out Bool()
val OUTPUT_CLK = in Bool()
val CLOCK_ENABLE = in Bool()
val D_OUT_0 = in Bool()
val D_OUT_1 = in Bool()
setDefinitionName("SB_IO")
}
case class SB_IO_DATA() extends BlackBox{
addGeneric("PIN_TYPE", B"110000")
val PACKAGE_PIN = inout(Analog(Bool))
val CLOCK_ENABLE = in Bool()
val INPUT_CLK = in Bool()
val OUTPUT_CLK = in Bool()
val OUTPUT_ENABLE = in Bool()
val D_OUT_0 = in Bool()
val D_OUT_1 = in Bool()
val D_IN_0 = out Bool()
val D_IN_1 = out Bool()
setDefinitionName("SB_IO")
}
case class Murax_iCE40_hx8k_breakout_board_xip() extends Component{
val io = new Bundle {
val mainClk = in Bool()
val jtag_tck = in Bool()
val jtag_tdi = in Bool()
val jtag_tdo = out Bool()
val jtag_tms = in Bool()
val uart_txd = out Bool()
val uart_rxd = in Bool()
val mosi = inout(Analog(Bool))
val miso = inout(Analog(Bool))
val sclk = out Bool()
val spis = out Bool()
val led = out Bits(8 bits)
}
val murax = Murax(MuraxConfig.default(withXip = true).copy(onChipRamSize = 8 kB))
murax.io.asyncReset := False
val mainClkBuffer = SB_GB()
mainClkBuffer.USER_SIGNAL_TO_GLOBAL_BUFFER <> io.mainClk
mainClkBuffer.GLOBAL_BUFFER_OUTPUT <> murax.io.mainClk
val jtagClkBuffer = SB_GB()
jtagClkBuffer.USER_SIGNAL_TO_GLOBAL_BUFFER <> io.jtag_tck
jtagClkBuffer.GLOBAL_BUFFER_OUTPUT <> murax.io.jtag.tck
io.led <> murax.io.gpioA.write(7 downto 0)
murax.io.jtag.tdi <> io.jtag_tdi
murax.io.jtag.tdo <> io.jtag_tdo
murax.io.jtag.tms <> io.jtag_tms
murax.io.gpioA.read <> 0
murax.io.uart.txd <> io.uart_txd
murax.io.uart.rxd <> io.uart_rxd
val xip = new ClockingArea(murax.systemClockDomain) {
RegNext(murax.io.xip.ss.asBool) <> io.spis
val sclkIo = SB_IO_SCLK()
sclkIo.PACKAGE_PIN <> io.sclk
sclkIo.CLOCK_ENABLE := True
sclkIo.OUTPUT_CLK := ClockDomain.current.readClockWire
sclkIo.D_OUT_0 <> murax.io.xip.sclk.write(0)
sclkIo.D_OUT_1 <> RegNext(murax.io.xip.sclk.write(1))
val datas = for ((data, pin) <- (murax.io.xip.data, List(io.mosi, io.miso)).zipped) yield new Area {
val dataIo = SB_IO_DATA()
dataIo.PACKAGE_PIN := pin
dataIo.CLOCK_ENABLE := True
dataIo.OUTPUT_CLK := ClockDomain.current.readClockWire
dataIo.OUTPUT_ENABLE <> data.writeEnable
dataIo.D_OUT_0 <> data.write(0)
dataIo.D_OUT_1 <> RegNext(data.write(1))
dataIo.INPUT_CLK := ClockDomain.current.readClockWire
data.read(0) := dataIo.D_IN_0
data.read(1) := RegNext(dataIo.D_IN_1)
}
}
}
def main(args: Array[String]) {
SpinalVerilog(Murax_iCE40_hx8k_breakout_board_xip())
}
}
object MuraxDhrystoneReady{
def main(args: Array[String]) {
SpinalVerilog(Murax(MuraxConfig.fast.copy(onChipRamSize = 256 kB)))
}
}
object MuraxDhrystoneReadyMulDivStatic{
def main(args: Array[String]) {
SpinalVerilog({
val config = MuraxConfig.fast.copy(onChipRamSize = 256 kB)
config.cpuPlugins += new MulPlugin
config.cpuPlugins += new DivPlugin
config.cpuPlugins.remove(config.cpuPlugins.indexWhere(_.isInstanceOf[BranchPlugin]))
config.cpuPlugins +=new BranchPlugin(
earlyBranch = false,
catchAddressMisaligned = false
)
config.cpuPlugins += new IBusSimplePlugin(
resetVector = 0x80000000l,
cmdForkOnSecondStage = true,
cmdForkPersistence = false,
prediction = STATIC,
catchAccessFault = false,
compressedGen = false
)
config.cpuPlugins.remove(config.cpuPlugins.indexWhere(_.isInstanceOf[LightShifterPlugin]))
config.cpuPlugins += new FullBarrelShifterPlugin
Murax(config)
})
}
}
//Will blink led and echo UART RX to UART TX (in the verilator sim, type some text and press enter to send UART frame to the Murax RX pin)
object MuraxWithRamInit{
def main(args: Array[String]) {
SpinalVerilog(Murax(MuraxConfig.default.copy(onChipRamSize = 4 kB, onChipRamHexFile = "src/main/ressource/hex/muraxDemo.hex")))
}
}
object Murax_arty{
def main(args: Array[String]) {
val hex = "src/main/c/murax/hello_world/build/hello_world.hex"
SpinalVerilog(Murax(MuraxConfig.default(false).copy(coreFrequency = 100 MHz,onChipRamSize = 32 kB, onChipRamHexFile = hex)))
}
}
object MuraxAsicBlackBox extends App{
println("Warning this soc do not has any rom to boot on.")
val config = SpinalConfig()
config.addStandardMemBlackboxing(blackboxAll)
config.generateVerilog(Murax(MuraxConfig.default()))
}

20
src/timer.h Normal file
View File

@ -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_ */

42
src/uart.h Normal file
View File

@ -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_ */