From cb32156c558add3086f8cda3e1c22bbd8045e7b7 Mon Sep 17 00:00:00 2001
From: Tomasz Wlostowski <tomasz.wlostowski@cern.ch>
Date: Tue, 1 Nov 2011 19:28:22 +0100
Subject: [PATCH] added testbench for LM32 sample system

---
 .../lm32_testsys/{manifest.py => Manifest.py} |   2 +-
 .../lm32_testsys/lm32_test_system.vhd         |   4 +-
 testbench/wishbone/lm32_testsys/run.do        |   2 +-
 testbench/wishbone/lm32_testsys/sw/Makefile   |  40 +++
 testbench/wishbone/lm32_testsys/sw/board.h    |  11 +
 .../wishbone/lm32_testsys/sw/genraminit.c     |  25 ++
 testbench/wishbone/lm32_testsys/sw/gpio.h     |  41 +++
 testbench/wishbone/lm32_testsys/sw/inttypes.h |  14 +
 testbench/wishbone/lm32_testsys/sw/main.c     |  31 +++
 .../lm32_testsys/sw/target/lm32/crt0.S        | 259 ++++++++++++++++++
 .../lm32_testsys/sw/target/lm32/irq.c         |  39 +++
 .../lm32_testsys/sw/target/lm32/ram.ld        | 149 ++++++++++
 testbench/wishbone/lm32_testsys/sw/uart.c     |  36 +++
 testbench/wishbone/lm32_testsys/sw/uart.h     |   9 +
 testbench/wishbone/lm32_testsys/sw/wb_uart.h  | 103 +++++++
 testbench/wishbone/lm32_testsys/sw/wb_vuart.h |  67 +++++
 testbench/wishbone/lm32_testsys/wave.do       |  59 ++--
 17 files changed, 844 insertions(+), 47 deletions(-)
 rename testbench/wishbone/lm32_testsys/{manifest.py => Manifest.py} (83%)
 create mode 100644 testbench/wishbone/lm32_testsys/sw/Makefile
 create mode 100644 testbench/wishbone/lm32_testsys/sw/board.h
 create mode 100644 testbench/wishbone/lm32_testsys/sw/genraminit.c
 create mode 100644 testbench/wishbone/lm32_testsys/sw/gpio.h
 create mode 100644 testbench/wishbone/lm32_testsys/sw/inttypes.h
 create mode 100644 testbench/wishbone/lm32_testsys/sw/main.c
 create mode 100755 testbench/wishbone/lm32_testsys/sw/target/lm32/crt0.S
 create mode 100644 testbench/wishbone/lm32_testsys/sw/target/lm32/irq.c
 create mode 100644 testbench/wishbone/lm32_testsys/sw/target/lm32/ram.ld
 create mode 100644 testbench/wishbone/lm32_testsys/sw/uart.c
 create mode 100644 testbench/wishbone/lm32_testsys/sw/uart.h
 create mode 100644 testbench/wishbone/lm32_testsys/sw/wb_uart.h
 create mode 100644 testbench/wishbone/lm32_testsys/sw/wb_vuart.h

diff --git a/testbench/wishbone/lm32_testsys/manifest.py b/testbench/wishbone/lm32_testsys/Manifest.py
similarity index 83%
rename from testbench/wishbone/lm32_testsys/manifest.py
rename to testbench/wishbone/lm32_testsys/Manifest.py
index ace1434f..dc4b4ba4 100644
--- a/testbench/wishbone/lm32_testsys/manifest.py
+++ b/testbench/wishbone/lm32_testsys/Manifest.py
@@ -1,5 +1,5 @@
 action = "simulation"
-target = "simulation"
+target = "xilinx"
 
 modules = {"local" : [ "../../.." ]	};
 files = ["main.sv", "lm32_test_system.vhd"]		
diff --git a/testbench/wishbone/lm32_testsys/lm32_test_system.vhd b/testbench/wishbone/lm32_testsys/lm32_test_system.vhd
index 4a3a05b1..e62f916c 100644
--- a/testbench/wishbone/lm32_testsys/lm32_test_system.vhd
+++ b/testbench/wishbone/lm32_testsys/lm32_test_system.vhd
@@ -50,7 +50,7 @@ begin  -- rtl
 
   U_CPU : xwb_lm32
     generic map (
-      g_profile => "medium")
+      g_profile => "minimal")
     port map (
       clk_sys_i => clk_sys_i,
       rst_n_i   => rst_n_i,
@@ -64,7 +64,7 @@ begin  -- rtl
     generic map (
       g_num_masters => c_cnx_slave_ports,
       g_num_slaves  => c_cnx_master_ports,
-      g_registered  => false)
+      g_registered  => true)
     port map (
       clk_sys_i     => clk_sys_i,
       rst_n_i       => rst_n_i,
diff --git a/testbench/wishbone/lm32_testsys/run.do b/testbench/wishbone/lm32_testsys/run.do
index d29641e2..e6f84ca3 100644
--- a/testbench/wishbone/lm32_testsys/run.do
+++ b/testbench/wishbone/lm32_testsys/run.do
@@ -1,6 +1,6 @@
 make
 
-vsim -L XilinxCoreLib -L secureip work.main -voptargs="+acc"
+vsim -L XilinxCoreLib -L secureip -L unisim work.main -voptargs="+acc"
 radix -hexadecimal
 do wave.do
 set StdArithNoWarnings 1
diff --git a/testbench/wishbone/lm32_testsys/sw/Makefile b/testbench/wishbone/lm32_testsys/sw/Makefile
new file mode 100644
index 00000000..432d3906
--- /dev/null
+++ b/testbench/wishbone/lm32_testsys/sw/Makefile
@@ -0,0 +1,40 @@
+PLATFORM = lm32
+
+OBJS_WRC = main.o uart.o target/lm32/crt0.o
+
+CROSS_COMPILE ?= /opt/gcc-lm32/bin/lm32-elf-
+CFLAGS_PLATFORM  = -mmultiply-enabled -mbarrel-shift-enabled  -I.
+LDFLAGS_PLATFORM = -mmultiply-enabled -mbarrel-shift-enabled   -nostdlib -T target/lm32/ram.ld 
+
+CC=$(CROSS_COMPILE)gcc
+OBJCOPY=$(CROSS_COMPILE)objcopy
+OBJDUMP=$(CROSS_COMPILE)objdump
+CFLAGS= $(CFLAGS_PLATFORM) -ffunction-sections -fdata-sections -Os -Iinclude $(PTPD_CFLAGS) -Iptp-noposix/PTPWRd 
+LDFLAGS= $(LDFLAGS_PLATFORM) -ffunction-sections -fdata-sections -Os -Iinclude 
+SIZE = $(CROSS_COMPILE)size
+OBJS=$(OBJS_PLATFORM) $(OBJS_WRC) $(OBJS_PTPD) $(OBJS_PTPD_FREE) 
+OUTPUT=main
+
+all: 		$(OBJS)
+				$(SIZE) -t $(OBJS)
+				${CC} -o $(OUTPUT).elf $(OBJS) $(LDFLAGS) 
+				${OBJCOPY} -O binary $(OUTPUT).elf $(OUTPUT).bin
+				${OBJDUMP} -d $(OUTPUT).elf > $(OUTPUT)_disasm.S
+				./genraminit $(OUTPUT).bin 0 > $(OUTPUT).ram
+
+clean:	
+	rm -f $(OBJS) $(OUTPUT).elf $(OUTPUT).bin $(OUTPUT).ram
+
+%.o:		%.c
+				${CC} $(CFLAGS) $(PTPD_CFLAGS) $(INCLUDE_DIR) $(LIB_DIR) -c $^ -o $@
+
+load:	all
+		./tools/lm32-loader $(OUTPUT).bin
+
+tools:
+			make -C tools
+		
+fpga:
+		- killall -9 vuart_console
+		../loadfile ../spec_top.bin
+		./tools/zpu-loader $(OUTPUT).bin
diff --git a/testbench/wishbone/lm32_testsys/sw/board.h b/testbench/wishbone/lm32_testsys/sw/board.h
new file mode 100644
index 00000000..6207dc7f
--- /dev/null
+++ b/testbench/wishbone/lm32_testsys/sw/board.h
@@ -0,0 +1,11 @@
+#ifndef __BOARD_H
+#define __BOARD_H
+
+#define BASE_GPIO 	0x20000000
+
+static inline int delay(int x)
+{
+  while(x--) asm volatile("nop");
+}
+  
+#endif
diff --git a/testbench/wishbone/lm32_testsys/sw/genraminit.c b/testbench/wishbone/lm32_testsys/sw/genraminit.c
new file mode 100644
index 00000000..9e278177
--- /dev/null
+++ b/testbench/wishbone/lm32_testsys/sw/genraminit.c
@@ -0,0 +1,25 @@
+#include <stdio.h>
+#include <stdlib.h>
+
+main(int argc, char *argv[])
+{
+	if(argc < 3) return -1;
+	FILE *f = fopen(argv[1],"rb");
+	if(!f) return -1;
+	unsigned char x[4];
+	int i=0;
+	int n = atoi(argv[2]);
+	
+	while(!feof(f))
+	{
+		fread(x,1,4,f);
+		printf("write %x %02X%02X%02X%02X\n", i++, x[0],x[1],x[2],x[3]);
+	}
+	
+	for(;i<n;)
+	{
+		printf("write %x %02X%02X%02X%02X\n", i++, 0,0,0,0);	
+	}
+	fclose(f);
+	return 0;
+}
\ No newline at end of file
diff --git a/testbench/wishbone/lm32_testsys/sw/gpio.h b/testbench/wishbone/lm32_testsys/sw/gpio.h
new file mode 100644
index 00000000..b5614411
--- /dev/null
+++ b/testbench/wishbone/lm32_testsys/sw/gpio.h
@@ -0,0 +1,41 @@
+#ifndef __GPIO_H
+#define __GPIO_H
+
+#include "inttypes.h"
+
+#include "board.h"
+
+struct GPIO_WB
+{
+  uint32_t CODR;  /*Clear output register*/
+  uint32_t SODR;  /*Set output register*/
+  uint32_t DDR;   /*Data direction register (1 means out)*/
+  uint32_t PSR;   /*Pin state register*/
+};
+
+static volatile struct GPIO_WB *__gpio = (volatile struct GPIO_WB *) BASE_GPIO;
+
+static inline void gpio_out(int pin, int val)
+{
+  if(val)
+    __gpio->SODR = (1<<pin);
+  else
+    __gpio->CODR = (1<<pin);
+}
+
+static inline void gpio_dir(int pin, int val)
+{
+  if(val)
+    __gpio->DDR |= (1<<pin);
+  else
+    __gpio->DDR &= ~(1<<pin);
+}
+
+static inline int gpio_in(int pin)
+{
+  return __gpio->PSR & (1<<pin) ? 1: 0;
+}
+
+        
+#endif
+        
diff --git a/testbench/wishbone/lm32_testsys/sw/inttypes.h b/testbench/wishbone/lm32_testsys/sw/inttypes.h
new file mode 100644
index 00000000..2e0fedcf
--- /dev/null
+++ b/testbench/wishbone/lm32_testsys/sw/inttypes.h
@@ -0,0 +1,14 @@
+#ifndef __WRAPPED_INTTYPES_H
+#define __WRAPPED_INTTYPES_H
+
+typedef unsigned char uint8_t;
+typedef unsigned short uint16_t;
+typedef unsigned int uint32_t;
+typedef signed long long uint64_t;
+
+typedef signed char int8_t;
+typedef signed short int16_t;
+typedef signed int int32_t;
+typedef signed long long int64_t;
+
+#endif
diff --git a/testbench/wishbone/lm32_testsys/sw/main.c b/testbench/wishbone/lm32_testsys/sw/main.c
new file mode 100644
index 00000000..a3b3b96c
--- /dev/null
+++ b/testbench/wishbone/lm32_testsys/sw/main.c
@@ -0,0 +1,31 @@
+#include <stdio.h>
+//#include <stdint.h>
+
+#include "gpio.h"
+
+void _irq_entry(){}
+
+int main(void)
+{
+	uart_init();
+	uart_write_byte('U');
+	uart_write_byte('U');
+	uart_write_byte('U');
+	uart_write_byte('U');
+	uart_write_byte('U');
+	uart_write_byte('U');
+	uart_write_byte('U');
+	uart_write_byte('U');
+
+/*	gpio_dir(1,1);
+	for(;;)
+	{
+		gpio_out(1,0);
+		delay(10);
+		gpio_out(1,1);
+		delay(10);
+	}*/
+}
+
+
+
diff --git a/testbench/wishbone/lm32_testsys/sw/target/lm32/crt0.S b/testbench/wishbone/lm32_testsys/sw/target/lm32/crt0.S
new file mode 100755
index 00000000..de7de225
--- /dev/null
+++ b/testbench/wishbone/lm32_testsys/sw/target/lm32/crt0.S
@@ -0,0 +1,259 @@
+/****************************************************************************
+**
+**  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
+    mvhi    r1, hi(_reset_handler)
+    ori     r1, r1, lo(_reset_handler)
+    wcsr    EBA, r1
+    calli   _crt0
+    nop
+        .size	_reset_handler, .-_reset_handler
+	
+.extern _irq_entry
+.org 0xc0
+        .global _interrupt_handler
+        .type 	_interrupt_handler, @function
+_interrupt_handler:
+    sw      (sp+0), ra
+    calli   _save_all
+    mvi     r1, SIGINT
+#ifndef __MICO_NO_INTERRUPTS__
+    calli  _irq_entry
+#else
+    wcsr    IE, r0
+#endif
+    bi      _restore_all_and_return
+    nop
+    nop
+    nop
+
+.org 0x100
+        .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)
+	
+    mvhi    r1, hi(_fbss)
+    ori     r1, r1, lo(_fbss)
+    mvi     r2, 0
+    mvhi    r3, hi(_ebss)
+    ori     r3, r3, lo(_ebss)
+    sub     r3, r3, r1
+    calli   memset
+    mvi     r1, 0
+    mvi     r2, 0
+    mvi     r3, 0
+    calli   main
+
+loopf:
+	bi loopf
+
+        .global _save_all
+        .type 	_save_all, @function
+_save_all:
+#ifdef MICO32_FULL_CONTEXT_SAVE_RESTORE
+    addi    sp, sp, -128
+#else
+    addi    sp, sp, -60
+#endif
+    sw      (sp+4), r1
+    sw      (sp+8), r2
+    sw      (sp+12), r3
+    sw      (sp+16), r4
+    sw      (sp+20), r5
+    sw      (sp+24), r6
+    sw      (sp+28), r7
+    sw      (sp+32), r8
+    sw      (sp+36), r9
+    sw      (sp+40), r10
+#ifdef MICO32_FULL_CONTEXT_SAVE_RESTORE
+    sw      (sp+44), r11
+    sw      (sp+48), r12
+    sw      (sp+52), r13
+    sw      (sp+56), r14
+    sw      (sp+60), r15
+    sw      (sp+64), r16
+    sw      (sp+68), r17
+    sw      (sp+72), r18
+    sw      (sp+76), r19
+    sw      (sp+80), r20
+    sw      (sp+84), r21
+    sw      (sp+88), r22
+    sw      (sp+92), r23
+    sw      (sp+96), r24
+    sw      (sp+100), r25
+    sw      (sp+104), r26
+    sw      (sp+108), r27
+    sw      (sp+120), ea
+    sw      (sp+124), ba
+    /* ra and sp need special handling, as they have been modified */
+    lw      r1, (sp+128)
+    sw      (sp+116), r1
+    mv      r1, sp
+    addi    r1, r1, 128
+    sw      (sp+112), r1
+#else
+    sw      (sp+52), ea
+    sw      (sp+56), ba
+    /* ra and sp need special handling, as they have been modified */
+    lw      r1, (sp+60)
+    sw      (sp+48), r1
+    mv      r1, sp
+    addi    r1, r1, 60
+    sw      (sp+44), r1
+#endif
+//    xor     r1, r1, r1
+//    wcsr    ie, r1
+    ret
+        .size  	_save_all, .-_save_all
+	
+        .global _restore_all_and_return
+        .type 	_restore_all_and_return, @function
+    /* Restore all registers and return from exception */
+_restore_all_and_return:
+//    addi    r1, r0, 2
+//    wcsr    ie, r1
+    lw      r1, (sp+4)
+    lw      r2, (sp+8) 
+    lw      r3, (sp+12) 
+    lw      r4, (sp+16) 
+    lw      r5, (sp+20) 
+    lw      r6, (sp+24) 
+    lw      r7, (sp+28) 
+    lw      r8, (sp+32) 
+    lw      r9, (sp+36) 
+    lw      r10, (sp+40)
+#ifdef MICO32_FULL_CONTEXT_SAVE_RESTORE
+    lw      r11, (sp+44)
+    lw      r12, (sp+48)
+    lw      r13, (sp+52)
+    lw      r14, (sp+56)
+    lw      r15, (sp+60)
+    lw      r16, (sp+64)
+    lw      r17, (sp+68)
+    lw      r18, (sp+72)
+    lw      r19, (sp+76)
+    lw      r20, (sp+80)
+    lw      r21, (sp+84)
+    lw      r22, (sp+88)
+    lw      r23, (sp+92)
+    lw      r24, (sp+96)
+    lw      r25, (sp+100)
+    lw      r26, (sp+104)
+    lw      r27, (sp+108)
+    lw      ra, (sp+116)
+    lw      ea, (sp+120)
+    lw      ba, (sp+124)
+    /* Stack pointer must be restored last, in case it has been updated */
+    lw      sp, (sp+112)
+#else
+    lw      ra, (sp+48)
+    lw      ea, (sp+52)
+    lw      ba, (sp+56)
+    /* Stack pointer must be restored last, in case it has been updated */
+    lw      sp, (sp+44)
+#endif
+    nop
+    eret
+        .size   _restore_all_and_return, .-_restore_all_and_return
+
diff --git a/testbench/wishbone/lm32_testsys/sw/target/lm32/irq.c b/testbench/wishbone/lm32_testsys/sw/target/lm32/irq.c
new file mode 100644
index 00000000..d1ac86b5
--- /dev/null
+++ b/testbench/wishbone/lm32_testsys/sw/target/lm32/irq.c
@@ -0,0 +1,39 @@
+#include "irq.h"
+
+void disable_irq()
+{
+    unsigned int ie, im;
+    unsigned int Mask = ~1;
+
+    /* disable peripheral interrupts in case they were enabled */
+    asm volatile ("rcsr %0,ie":"=r"(ie));
+    ie &= (~0x1);
+    asm volatile ("wcsr ie, %0"::"r"(ie));
+
+    /* disable mask-bit in im */
+    asm volatile ("rcsr %0, im":"=r"(im));
+    im &= Mask;
+    asm volatile ("wcsr im, %0"::"r"(im));
+
+}
+
+
+void enable_irq()
+{
+    unsigned int ie, im;
+    unsigned int Mask = 1;
+
+
+    /* disable peripheral interrupts in-case they were enabled*/
+    asm volatile ("rcsr %0,ie":"=r"(ie));
+    ie &= (~0x1);
+    asm volatile ("wcsr ie, %0"::"r"(ie));
+
+    /* enable mask-bit in im */
+    asm volatile ("rcsr %0, im":"=r"(im));
+    im |= Mask;
+    asm volatile ("wcsr im, %0"::"r"(im));
+
+    ie |= 0x1;
+    asm volatile ("wcsr ie, %0"::"r"(ie));
+}
diff --git a/testbench/wishbone/lm32_testsys/sw/target/lm32/ram.ld b/testbench/wishbone/lm32_testsys/sw/target/lm32/ram.ld
new file mode 100644
index 00000000..86ec2e94
--- /dev/null
+++ b/testbench/wishbone/lm32_testsys/sw/target/lm32/ram.ld
@@ -0,0 +1,149 @@
+/*
+ * Simulator Link script for Lattice Mico32.
+ * Contributed by Jon Beniston <jon@beniston.com>
+ *
+ * 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.
+ */
+
+OUTPUT_FORMAT("elf32-lm32")
+ENTRY(_start)
+/*INPUT() */
+GROUP(-lgcc -lc)
+
+MEMORY
+{
+    ram : ORIGIN = 0x00000000, LENGTH = 0x10000
+}
+
+SECTIONS
+{
+
+  .boot : { *(.boot) } > ram
+   
+  /* Code */
+  .text           :
+  {
+    . = ALIGN(4);
+    _ftext = .;
+    _ftext_rom = LOADADDR(.text);
+    *(.text .stub .text.* .gnu.linkonce.t.*)
+    *(.gnu.warning)
+    KEEP (*(.init))
+    KEEP (*(.fini))
+    /* Constructors and destructors */
+    KEEP (*crtbegin*.o(.ctors))
+    KEEP (*(EXCLUDE_FILE (*crtend*.o ) .ctors))
+    KEEP (*(SORT(.ctors.*)))
+    KEEP (*(.ctors))
+    KEEP (*crtbegin*.o(.dtors))
+    KEEP (*(EXCLUDE_FILE (*crtend*.o ) .dtors))
+    KEEP (*(SORT(.dtors.*)))
+    KEEP (*(.dtors))
+    KEEP (*(.jcr))
+    _etext = .;
+  } > ram =0 
+
+  /* Exception handlers */
+  .eh_frame_hdr : { *(.eh_frame_hdr) } > ram
+  .eh_frame : { KEEP (*(.eh_frame)) } > ram
+  .gcc_except_table : { *(.gcc_except_table) *(.gcc_except_table.*) } > ram
+    
+  /* Read-only data */
+  .rodata         : 
+  { 
+    . = ALIGN(4);
+    _frodata = .;
+    _frodata_rom = LOADADDR(.rodata);
+    *(.rodata .rodata.* .gnu.linkonce.r.*) 
+    *(.rodata1)
+    _erodata = .;
+  } > ram
+        
+  /* Data */
+  .data           : 
+  {
+    . = ALIGN(4);
+    _fdata = .;
+    _fdata_rom = LOADADDR(.data);
+    *(.data .data.* .gnu.linkonce.d.*)
+    *(.data1)
+    SORT(CONSTRUCTORS)
+    _gp = ALIGN(16) + 0x7ff0;
+    *(.sdata .sdata.* .gnu.linkonce.s.*)
+    _edata = .;
+  } > ram 
+  
+  /* BSS */
+  .bss           :
+  {
+    . = ALIGN(4);
+    _fbss = .;
+    *(.dynsbss)
+    *(.sbss .sbss.* .gnu.linkonce.sb.*)
+    *(.scommon)
+    *(.dynbss)
+    *(.bss .bss.* .gnu.linkonce.b.*)
+    *(COMMON)
+    . = ALIGN(4);
+    _ebss = .;
+    _end = .;
+    PROVIDE (end = .);
+  } > ram
+  
+  /* First location in stack is highest address in RAM */
+  PROVIDE(_fstack = ORIGIN(ram) + LENGTH(ram) - 4);
+  
+  /* Stabs debugging sections.  */
+  .stab          0 : { *(.stab) }
+  .stabstr       0 : { *(.stabstr) }
+  .stab.excl     0 : { *(.stab.excl) }
+  .stab.exclstr  0 : { *(.stab.exclstr) }
+  .stab.index    0 : { *(.stab.index) }
+  .stab.indexstr 0 : { *(.stab.indexstr) }
+  .comment       0 : { *(.comment) }
+  
+  /* DWARF debug sections.
+     Symbols in the DWARF debugging sections are relative to the beginning
+     of the section so we begin them at 0.  */
+  /* DWARF 1 */
+  .debug          0 : { *(.debug) }
+  .line           0 : { *(.line) }
+  /* GNU DWARF 1 extensions */
+  .debug_srcinfo  0 : { *(.debug_srcinfo) }
+  .debug_sfnames  0 : { *(.debug_sfnames) }
+  /* DWARF 1.1 and DWARF 2 */
+  .debug_aranges  0 : { *(.debug_aranges) }
+  .debug_pubnames 0 : { *(.debug_pubnames) }
+  /* DWARF 2 */
+  .debug_info     0 : { *(.debug_info .gnu.linkonce.wi.*) }
+  .debug_abbrev   0 : { *(.debug_abbrev) }
+  .debug_line     0 : { *(.debug_line) }
+  .debug_frame    0 : { *(.debug_frame) }
+  .debug_str      0 : { *(.debug_str) }
+  .debug_loc      0 : { *(.debug_loc) }
+  .debug_macinfo  0 : { *(.debug_macinfo) }
+  /* SGI/MIPS DWARF 2 extensions */
+  .debug_weaknames 0 : { *(.debug_weaknames) }
+  .debug_funcnames 0 : { *(.debug_funcnames) }
+  .debug_typenames 0 : { *(.debug_typenames) }
+  .debug_varnames  0 : { *(.debug_varnames) }
+}
diff --git a/testbench/wishbone/lm32_testsys/sw/uart.c b/testbench/wishbone/lm32_testsys/sw/uart.c
new file mode 100644
index 00000000..20ab3f78
--- /dev/null
+++ b/testbench/wishbone/lm32_testsys/sw/uart.c
@@ -0,0 +1,36 @@
+#include "inttypes.h"
+#include "uart.h"
+
+#define CPU_CLOCK 1000000
+#define UART_BAUDRATE 10000
+#define BASE_UART 0x20000100
+
+#include "wb_uart.h"
+
+#define CALC_BAUD(baudrate) (((((unsigned long long)baudrate*8ULL)<<(16-7))+(CPU_CLOCK>>8))/(CPU_CLOCK>>7))
+ 
+static volatile struct UART_WB *uart = (volatile struct UART_WB *) BASE_UART;
+
+void uart_init()
+{
+	uart->BCR = CALC_BAUD(UART_BAUDRATE);
+}
+
+void uart_write_byte(unsigned char x)
+{
+	while( uart->SR & UART_SR_TX_BUSY);
+
+	uart->TDR = x;
+	if(x == '\n')
+		uart_write_byte('\r');
+}
+
+int uart_poll()
+{
+ 	return uart->SR & UART_SR_RX_RDY;
+}
+
+int uart_read_byte()
+{
+ 	return uart ->RDR & 0xff;
+}
\ No newline at end of file
diff --git a/testbench/wishbone/lm32_testsys/sw/uart.h b/testbench/wishbone/lm32_testsys/sw/uart.h
new file mode 100644
index 00000000..d1f60ad2
--- /dev/null
+++ b/testbench/wishbone/lm32_testsys/sw/uart.h
@@ -0,0 +1,9 @@
+#ifndef __UART_H
+#define __UART_H
+
+int mprintf(char const *format, ...);
+
+void uart_init();
+void uart_write_byte(unsigned char x);
+  
+#endif
diff --git a/testbench/wishbone/lm32_testsys/sw/wb_uart.h b/testbench/wishbone/lm32_testsys/sw/wb_uart.h
new file mode 100644
index 00000000..8de7f8f0
--- /dev/null
+++ b/testbench/wishbone/lm32_testsys/sw/wb_uart.h
@@ -0,0 +1,103 @@
+/*
+  Register definitions for slave core: Simple Wishbone UART
+
+  * File           : wb_uart.h
+  * Author         : auto-generated by wbgen2 from simple_uart_wb.wb
+  * Created        : Tue Oct  4 18:46:41 2011
+  * Standard       : ANSI C
+
+    THIS FILE WAS GENERATED BY wbgen2 FROM SOURCE FILE simple_uart_wb.wb
+    DO NOT HAND-EDIT UNLESS IT'S ABSOLUTELY NECESSARY!
+
+*/
+
+#ifndef __WBGEN2_REGDEFS_SIMPLE_UART_WB_WB
+#define __WBGEN2_REGDEFS_SIMPLE_UART_WB_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)
+
+/* definitions for register: Host VUART Tx register */
+
+/* definitions for field: TX Data in reg: Host VUART Tx register */
+#define UART_HOST_TDR_DATA_MASK               WBGEN2_GEN_MASK(0, 8)
+#define UART_HOST_TDR_DATA_SHIFT              0
+#define UART_HOST_TDR_DATA_W(value)           WBGEN2_GEN_WRITE(value, 0, 8)
+#define UART_HOST_TDR_DATA_R(reg)             WBGEN2_GEN_READ(reg, 0, 8)
+
+/* definitions for field: TX Ready in reg: Host VUART Tx register */
+#define UART_HOST_TDR_RDY                     WBGEN2_GEN_MASK(8, 1)
+
+/* definitions for register: Host VUART Rx register */
+
+/* definitions for field: RX Data in reg: Host VUART Rx register */
+#define UART_HOST_RDR_DATA_MASK               WBGEN2_GEN_MASK(0, 8)
+#define UART_HOST_RDR_DATA_SHIFT              0
+#define UART_HOST_RDR_DATA_W(value)           WBGEN2_GEN_WRITE(value, 0, 8)
+#define UART_HOST_RDR_DATA_R(reg)             WBGEN2_GEN_READ(reg, 0, 8)
+
+/* definitions for field: RX Ready in reg: Host VUART Rx register */
+#define UART_HOST_RDR_RDY                     WBGEN2_GEN_MASK(8, 1)
+
+/* definitions for field: RX FIFO Count in reg: Host VUART Rx register */
+#define UART_HOST_RDR_COUNT_MASK              WBGEN2_GEN_MASK(9, 16)
+#define UART_HOST_RDR_COUNT_SHIFT             9
+#define UART_HOST_RDR_COUNT_W(value)          WBGEN2_GEN_WRITE(value, 9, 16)
+#define UART_HOST_RDR_COUNT_R(reg)            WBGEN2_GEN_READ(reg, 9, 16)
+
+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;
+  /* [0x10]: REG Host VUART Tx register */
+  uint32_t HOST_TDR;
+  /* [0x14]: REG Host VUART Rx register */
+  uint32_t HOST_RDR;
+};
+
+#endif
diff --git a/testbench/wishbone/lm32_testsys/sw/wb_vuart.h b/testbench/wishbone/lm32_testsys/sw/wb_vuart.h
new file mode 100644
index 00000000..51883348
--- /dev/null
+++ b/testbench/wishbone/lm32_testsys/sw/wb_vuart.h
@@ -0,0 +1,67 @@
+/*
+  Register definitions for slave core: Simple Wishbone UART
+
+  * File           : wb_uart.h
+  * Author         : auto-generated by wbgen2 from uart.wb
+  * Created        : Mon Jul 18 01:19:24 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
+#endif
diff --git a/testbench/wishbone/lm32_testsys/wave.do b/testbench/wishbone/lm32_testsys/wave.do
index b2109220..0a0a199e 100644
--- a/testbench/wishbone/lm32_testsys/wave.do
+++ b/testbench/wishbone/lm32_testsys/wave.do
@@ -1,48 +1,21 @@
 onerror {resume}
 quietly WaveActivateNextPane {} 0
-add wave -noupdate /main/DUT/U_UART/U_Wrapped_UART/g_with_virtual_uart
-add wave -noupdate /main/DUT/U_UART/U_Wrapped_UART/g_with_physical_uart
-add wave -noupdate /main/DUT/U_UART/U_Wrapped_UART/g_interface_mode
-add wave -noupdate /main/DUT/U_UART/U_Wrapped_UART/g_address_granularity
-add wave -noupdate /main/DUT/U_UART/U_Wrapped_UART/clk_sys_i
-add wave -noupdate /main/DUT/U_UART/U_Wrapped_UART/rst_n_i
-add wave -noupdate /main/DUT/U_UART/U_Wrapped_UART/wb_adr_i
-add wave -noupdate /main/DUT/U_UART/U_Wrapped_UART/wb_dat_i
-add wave -noupdate /main/DUT/U_UART/U_Wrapped_UART/wb_dat_o
-add wave -noupdate /main/DUT/U_CPU/dwb_o
-add wave -noupdate /main/DUT/U_CPU/dwb_i
-add wave -noupdate /main/DUT/U_CPU/iwb_o
-add wave -noupdate /main/DUT/U_CPU/iwb_i
-add wave -noupdate /main/DUT/U_UART/U_Wrapped_UART/wb_cyc_i
-add wave -noupdate /main/DUT/U_UART/U_Wrapped_UART/wb_sel_i
-add wave -noupdate /main/DUT/U_UART/U_Wrapped_UART/wb_stb_i
-add wave -noupdate /main/DUT/U_UART/U_Wrapped_UART/wb_we_i
-add wave -noupdate /main/DUT/U_UART/U_Wrapped_UART/wb_ack_o
-add wave -noupdate /main/DUT/U_UART/U_Wrapped_UART/wb_stall_o
-add wave -noupdate /main/DUT/U_UART/U_Wrapped_UART/uart_rxd_i
-add wave -noupdate /main/DUT/U_UART/U_Wrapped_UART/uart_txd_o
-add wave -noupdate /main/DUT/U_UART/U_Wrapped_UART/rx_ready_reg
-add wave -noupdate /main/DUT/U_UART/U_Wrapped_UART/rx_ready
-add wave -noupdate /main/DUT/U_UART/U_Wrapped_UART/uart_bcr
-add wave -noupdate /main/DUT/U_UART/U_Wrapped_UART/rdr_rack
-add wave -noupdate /main/DUT/U_UART/U_Wrapped_UART/host_rack
-add wave -noupdate /main/DUT/U_UART/U_Wrapped_UART/baud_tick
-add wave -noupdate /main/DUT/U_UART/U_Wrapped_UART/baud_tick8
-add wave -noupdate /main/DUT/U_UART/U_Wrapped_UART/resized_addr
-add wave -noupdate /main/DUT/U_UART/U_Wrapped_UART/wb_in
-add wave -noupdate /main/DUT/U_UART/U_Wrapped_UART/wb_out
-add wave -noupdate /main/DUT/U_UART/U_Wrapped_UART/regs_in
-add wave -noupdate /main/DUT/U_UART/U_Wrapped_UART/regs_out
-add wave -noupdate /main/DUT/U_UART/U_Wrapped_UART/fifo_empty
-add wave -noupdate /main/DUT/U_UART/U_Wrapped_UART/fifo_full
-add wave -noupdate /main/DUT/U_UART/U_Wrapped_UART/fifo_rd
-add wave -noupdate /main/DUT/U_UART/U_Wrapped_UART/fifo_wr
-add wave -noupdate /main/DUT/U_UART/U_Wrapped_UART/fifo_count
-add wave -noupdate /main/DUT/U_UART/U_Wrapped_UART/phys_rx_ready
-add wave -noupdate /main/DUT/U_UART/U_Wrapped_UART/phys_tx_busy
-add wave -noupdate /main/DUT/U_UART/U_Wrapped_UART/phys_rx_data
+add wave -noupdate /main/DUT/U_Intercon/g_num_masters
+add wave -noupdate /main/DUT/U_Intercon/g_num_slaves
+add wave -noupdate /main/DUT/U_Intercon/g_registered
+add wave -noupdate /main/DUT/U_Intercon/clk_sys_i
+add wave -noupdate /main/DUT/U_Intercon/rst_n_i
+add wave -noupdate /main/DUT/U_Intercon/slave_i
+add wave -noupdate /main/DUT/U_Intercon/slave_o
+add wave -noupdate /main/DUT/U_Intercon/master_i
+add wave -noupdate /main/DUT/U_Intercon/master_o
+add wave -noupdate /main/DUT/U_Intercon/cfg_address_i
+add wave -noupdate /main/DUT/U_Intercon/cfg_mask_i
+add wave -noupdate /main/DUT/U_Intercon/previous
+add wave -noupdate /main/DUT/U_Intercon/granted
+add wave -noupdate /main/DUT/U_Intercon/issue
 TreeUpdate [SetDefaultTree]
-WaveRestoreCursors {{Cursor 1} {5032567 ps} 0}
+WaveRestoreCursors {{Cursor 1} {4093545 ps} 0}
 configure wave -namecolwidth 350
 configure wave -valuecolwidth 100
 configure wave -justifyvalue left
@@ -57,4 +30,4 @@ configure wave -griddelta 40
 configure wave -timeline 0
 configure wave -timelineunits ns
 update
-WaveRestoreZoom {1751287 ps} {8313847 ps}
+WaveRestoreZoom {3879920 ps} {4290080 ps}
-- 
GitLab