Browse Source

Merge pull request #784 from zhangjun1996/master

[BSP] add bsp for sifive(risc-v e310).
Bernard Xiong 8 years ago
parent
commit
4626b19ead
46 changed files with 4346 additions and 0 deletions
  1. 18 0
      bsp/hifive1/SConscript
  2. 29 0
      bsp/hifive1/SConstruct
  3. 11 0
      bsp/hifive1/applications/SConscript
  4. 59 0
      bsp/hifive1/applications/applications.c
  5. 0 0
      bsp/hifive1/applications/cmd.c
  6. 44 0
      bsp/hifive1/applications/startup.c
  7. 18 0
      bsp/hifive1/drivers/SConscript
  8. 56 0
      bsp/hifive1/drivers/board.c
  9. 0 0
      bsp/hifive1/drivers/board.h
  10. 55 0
      bsp/hifive1/drivers/led.c
  11. 0 0
      bsp/hifive1/drivers/led.h
  12. 90 0
      bsp/hifive1/drivers/usart.c
  13. 1 0
      bsp/hifive1/drivers/usart.h
  14. 34 0
      bsp/hifive1/openocd.cfg
  15. 20 0
      bsp/hifive1/platform/SConscript
  16. 110 0
      bsp/hifive1/platform/interrupt.c
  17. 12 0
      bsp/hifive1/platform/interrupt.h
  18. 120 0
      bsp/hifive1/platform/plic_driver.c
  19. 47 0
      bsp/hifive1/platform/plic_driver.h
  20. 31 0
      bsp/hifive1/platform/rt_low_level_gcc.inc
  21. 37 0
      bsp/hifive1/platform/rt_low_level_init.c
  22. 264 0
      bsp/hifive1/rtconfig.h
  23. 142 0
      bsp/hifive1/rtconfig.py
  24. 168 0
      bsp/hifive1/sdram.ld
  25. 58 0
      bsp/hifive1/wrap_exit.c
  26. 236 0
      libcpu/risc-v/e310/context_gcc.S
  27. 1313 0
      libcpu/risc-v/e310/encoding.h
  28. 81 0
      libcpu/risc-v/e310/hifive1.h
  29. 210 0
      libcpu/risc-v/e310/init.c
  30. 133 0
      libcpu/risc-v/e310/platform.h
  31. 36 0
      libcpu/risc-v/e310/sifive/bits.h
  32. 18 0
      libcpu/risc-v/e310/sifive/const.h
  33. 88 0
      libcpu/risc-v/e310/sifive/devices/aon.h
  34. 14 0
      libcpu/risc-v/e310/sifive/devices/clint.h
  35. 24 0
      libcpu/risc-v/e310/sifive/devices/gpio.h
  36. 23 0
      libcpu/risc-v/e310/sifive/devices/otp.h
  37. 31 0
      libcpu/risc-v/e310/sifive/devices/plic.h
  38. 56 0
      libcpu/risc-v/e310/sifive/devices/prci.h
  39. 37 0
      libcpu/risc-v/e310/sifive/devices/pwm.h
  40. 80 0
      libcpu/risc-v/e310/sifive/devices/spi.h
  41. 27 0
      libcpu/risc-v/e310/sifive/devices/uart.h
  42. 17 0
      libcpu/risc-v/e310/sifive/sections.h
  43. 65 0
      libcpu/risc-v/e310/sifive/smp.h
  44. 81 0
      libcpu/risc-v/e310/stack.c
  45. 297 0
      libcpu/risc-v/e310/start_gcc.S
  46. 55 0
      libcpu/risc-v/e310/trap.c

+ 18 - 0
bsp/hifive1/SConscript

@@ -0,0 +1,18 @@
+# for module compiling
+import os
+Import('RTT_ROOT')
+from building import *
+
+cwd = str(Dir('#'))
+src = Glob('*.c')
+objs = []
+list = os.listdir(cwd)
+
+for d in list:
+    path = os.path.join(cwd, d)
+    if os.path.isfile(os.path.join(path, 'SConscript')):
+        objs = objs + SConscript(os.path.join(d, 'SConscript'))
+
+group = DefineGroup('', src, depend = [''], CPPPATH = [])
+#objs += group
+Return('objs')

+ 29 - 0
bsp/hifive1/SConstruct

@@ -0,0 +1,29 @@
+import os
+import sys
+import rtconfig
+
+if os.getenv('RTT_ROOT'):
+    RTT_ROOT = os.getenv('RTT_ROOT')
+else:
+    RTT_ROOT = os.path.normpath(os.getcwd() + '/../..')
+
+sys.path = sys.path + [os.path.join(RTT_ROOT, 'tools')]
+from building import *
+
+TARGET = 'rtthread.' + rtconfig.TARGET_EXT
+
+env = Environment(tools = ['mingw'],
+	AS = rtconfig.AS, ASFLAGS = rtconfig.AFLAGS,
+	CC = rtconfig.CC, CCFLAGS = rtconfig.CFLAGS,
+	AR = rtconfig.AR, ARFLAGS = '-rc',
+	LINK = rtconfig.LINK, LINKFLAGS = rtconfig.LFLAGS)
+env.PrependENVPath('PATH', rtconfig.EXEC_PATH)
+
+Export('RTT_ROOT')
+Export('rtconfig')
+
+# prepare building environment
+objs = PrepareBuilding(env, RTT_ROOT)
+
+# make a building
+DoBuilding(TARGET, objs)

+ 11 - 0
bsp/hifive1/applications/SConscript

@@ -0,0 +1,11 @@
+Import('RTT_ROOT')
+Import('rtconfig')
+from building import *
+
+cwd     = os.path.join(str(Dir('#')), 'applications')
+src	= Glob('*.c')
+CPPPATH = [cwd, str(Dir('#'))]
+
+group = DefineGroup('Applications', src, depend = [''], CPPPATH = CPPPATH)
+
+Return('group')

+ 59 - 0
bsp/hifive1/applications/applications.c

@@ -0,0 +1,59 @@
+#include <rtthread.h>
+
+static void rt_init_thread_entry(void* parameter)
+{
+#ifdef RT_USING_COMPONENTS_INIT
+    /* initialization RT-Thread Components */
+    rt_components_init();
+#endif
+    rt_thread_delay( RT_TIMER_TICK_PER_SECOND*2 ); /* sleep 0.5 second and switch to other thread */
+}
+#include <encoding.h>
+#include <platform.h>
+static void led_thread_entry(void* parameter)
+{
+    unsigned int count=0;
+
+    rt_hw_led_init();
+    while (0)
+    {
+/*        rt_hw_led_on(0);*/
+        rt_thread_delay( RT_TIMER_TICK_PER_SECOND/2 ); /* sleep 0.5 second and switch to other thread */
+
+        /* led1 off */
+        rt_hw_led_off(0);
+
+        rt_thread_delay( RT_TIMER_TICK_PER_SECOND*2);
+    }
+}
+static rt_uint8_t led_stack[ 1024];
+static struct rt_thread led_thread;
+void rt_application_init()
+{
+    rt_thread_t init_thread;
+
+    rt_err_t result;
+	/* init led thread */
+	result = rt_thread_init(&led_thread,
+			"led",
+			led_thread_entry,
+			RT_NULL,
+			(rt_uint8_t*)&led_stack[0],
+			sizeof(led_stack),
+			20,
+			5);
+	if (result == RT_EOK)
+	{
+		rt_thread_startup(&led_thread);
+	}
+
+	init_thread = rt_thread_create("init",
+			rt_init_thread_entry,
+		       	RT_NULL,
+			512,
+		       	8,
+		       	20);
+	if (init_thread != RT_NULL)
+		rt_thread_startup(init_thread);
+	return;
+}

+ 0 - 0
bsp/hifive1/applications/cmd.c


+ 44 - 0
bsp/hifive1/applications/startup.c

@@ -0,0 +1,44 @@
+#include <rtthread.h>
+
+extern  void *__bss_end__;
+extern  void *_heap_end;
+#define HEAP_BEGIN &__bss_end__
+#define HEAP_END   &_heap_end
+static void rtthread_startup(void)
+{
+	/* initialize board */
+	rt_hw_board_init();
+
+	/* show version */
+	rt_show_version();
+
+#ifdef RT_USING_HEAP
+	rt_system_heap_init((void *)HEAP_BEGIN, (void *)HEAP_END);
+#endif
+
+	/* initialize scheduler system */
+	rt_system_scheduler_init();
+	/* initialize system timer*/
+	rt_system_timer_init();
+	/* initialize application */
+	rt_application_init();
+
+	/* initialize timer thread */
+	rt_system_timer_thread_init();
+
+	/* initialize idle thread */
+	rt_thread_idle_init();
+
+	/* start scheduler */
+	rt_system_scheduler_start();
+
+	/* never reach here */
+	return;
+}
+#include "encoding.h"
+#include <platform.h>
+int main(void)
+{
+	rtthread_startup();
+	return 0;
+}

+ 18 - 0
bsp/hifive1/drivers/SConscript

@@ -0,0 +1,18 @@
+Import('RTT_ROOT')
+Import('rtconfig')
+from building import *
+
+cwd = os.path.join(str(Dir('#')), 'drivers')
+
+# add the general drvers.
+src = Glob("*.c")
+
+# add Ethernet drvers.
+#if GetDepend('RT_USING_LED'):
+#    src += ['led.c']
+
+CPPPATH = [cwd]
+
+group = DefineGroup('Drivers', src, depend = [''], CPPPATH = CPPPATH)
+
+Return('group')

+ 56 - 0
bsp/hifive1/drivers/board.c

@@ -0,0 +1,56 @@
+#include <interrupt.h>
+#include <rthw.h>
+#include <platform.h>
+#if 0
+static struct mem_desc hw_mem_desc[] =
+{
+    { 0x00000000, 0xFFFFFFFF, 0x00000000, RW_NCNB },/* None cached for 4G memory */
+//  visual start, visual end, phy start , props
+    { 0x00000000, 0x000FFFFF, 0x20000000, RW_CB },  /* ISR Vector table */
+    { 0x00200000, 0x00001FFF, 0x40000000, RW_CB },  /* 8K cached SRAM 0/1 */
+    { 0x20000000, 0x21FFFFFF, 0x20000000, RW_CB },  /* 32M cached SDRAM */
+    { 0x90000000, 0x90001FFF, 0x40000000, RW_NCNB },/* 4K SRAM0 + 4k SRAM1 */
+    { 0xA0000000, 0xA1FFFFFF, 0x20000000, RW_NCNB },/* 32M none-cached SDRAM */
+};
+#endif
+
+#include <encoding.h>
+static void rt_hw_timer_init(void)
+{
+	GPIO_REG(GPIO_INPUT_EN)    &= ~((0x1<< RED_LED_OFFSET) | (0x1<< GREEN_LED_OFFSET) | (0x1 << BLUE_LED_OFFSET)) ;
+	GPIO_REG(GPIO_OUTPUT_EN)   |=  ((0x1<< RED_LED_OFFSET)| (0x1<< GREEN_LED_OFFSET) | (0x1 << BLUE_LED_OFFSET)) ;
+	GPIO_REG(GPIO_OUTPUT_VAL)  |=   (0x1 << BLUE_LED_OFFSET) ;
+	GPIO_REG(GPIO_OUTPUT_VAL)  &=  ~((0x1<< RED_LED_OFFSET) | (0x1<< GREEN_LED_OFFSET)) ;
+	
+/*	enable timer interrupt*/
+ 	set_csr(mie, MIP_MTIP);	
+	volatile uint64_t * mtimecmp    = (uint64_t*) (CLINT_CTRL_ADDR + CLINT_MTIMECMP);
+	CLINT_REG(CLINT_MTIME) = 0x0;
+/*	CLINT_REG(CLINT_MTIMECMP) = 0x10000;*/
+	*mtimecmp = 0x20000;
+	return;
+}
+void rt_hw_board_init(void)
+{
+	/* initialize mmu */
+/*	rt_hw_mmu_init(hw_mem_desc, sizeof(hw_mem_desc)/sizeof(hw_mem_desc[0]));*/
+	/* initialize hardware interrupt */
+	rt_hw_interrupt_init();
+
+	/* initialize the system clock */
+	//rt_hw_clock_init(); //set each pll etc.
+
+	/* initialize uart */
+	rt_hw_uart_init();
+	rt_console_set_device(RT_CONSOLE_DEVICE_NAME);
+
+	/* initialize timer0 */
+	rt_hw_timer_init();
+
+#ifdef RT_USING_COMPONENTS_INIT
+	rt_components_board_init();
+#endif
+
+	return;
+}
+

+ 0 - 0
bsp/hifive1/drivers/board.h


+ 55 - 0
bsp/hifive1/drivers/led.c

@@ -0,0 +1,55 @@
+void rt_hw_led_init(void)
+{
+	return;
+}
+#include <stdint.h>
+#include "platform.h"
+
+void rt_hw_led_on(int led)
+{
+
+
+	uint16_t r=0xFF;
+	uint16_t g=0;
+	uint16_t b=0;
+	char c = 0;
+
+	// Set up RGB PWM
+
+	/* 
+	   PWM1_REG(PWM_CFG)   = 0;
+	// To balance the power consumption, make one left, one right, and one center aligned.
+	PWM1_REG(PWM_CFG)   = (PWM_CFG_ENALWAYS) | (PWM_CFG_CMP2CENTER);
+	PWM1_REG(PWM_COUNT) = 0;
+
+	// Period is approximately 244 Hz
+	// the LEDs are intentionally left somewhat dim, 
+	// as the full brightness can be painful to look at.
+	PWM1_REG(PWM_CMP0)  = 0;
+	*/
+	if(r > 0 && b == 0){
+		r--;
+		g++;
+	}
+	if(g > 0 && r == 0){
+		g--;
+		b++;
+	}
+	if(b > 0 && g == 0){
+		r++;
+		b--;
+	}
+
+	uint32_t G = g;
+	uint32_t R = r;
+	uint32_t B = b;
+
+	PWM1_REG(PWM_CMP1)  = G << 4;            // PWM is low on the left, GPIO is low on the left side, LED is ON on the left.
+	PWM1_REG(PWM_CMP2)  = (B << 1) << 4;     // PWM is high on the middle, GPIO is low in the middle, LED is ON in the middle.
+	PWM1_REG(PWM_CMP3)  = 0xFFFF - (R << 4); // PWM is low on the left, GPIO is low on the right, LED is on on the right.
+	return;
+}
+void rt_hw_led_off(int led)
+{
+	return;
+}

+ 0 - 0
bsp/hifive1/drivers/led.h


+ 90 - 0
bsp/hifive1/drivers/usart.c

@@ -0,0 +1,90 @@
+#include <rtdevice.h>
+#include "usart.h"
+#include <encoding.h>
+#include <platform.h>
+/**
+ * @brief set uartdbg buard 
+ *
+ * @param buard
+ */
+static void usart_init(int buard)
+{
+	GPIO_REG(GPIO_IOF_SEL) &= ~IOF0_UART0_MASK;
+	GPIO_REG(GPIO_IOF_EN) |= IOF0_UART0_MASK;
+	UART0_REG(UART_REG_DIV) = get_cpu_freq() / buard - 1;
+	UART0_REG(UART_REG_TXCTRL) |= UART_TXEN;
+}
+static void usart_handler(int vector, void *param)
+{
+	rt_hw_serial_isr((struct rt_serial_device*)param, RT_SERIAL_EVENT_RX_IND);
+	return;
+}
+static rt_err_t usart_configure(struct rt_serial_device *serial,
+                                struct serial_configure *cfg)
+{
+	GPIO_REG(GPIO_IOF_SEL) &= ~IOF0_UART0_MASK;
+	GPIO_REG(GPIO_IOF_EN) |= IOF0_UART0_MASK;
+	UART0_REG(UART_REG_DIV) = get_cpu_freq() / 115200 - 1;
+	UART0_REG(UART_REG_TXCTRL) |= UART_TXEN;
+	UART0_REG(UART_REG_RXCTRL) |= UART_RXEN;
+	UART0_REG(UART_REG_IE) = UART_IP_RXWM;
+		return RT_EOK;
+}
+static rt_err_t usart_control(struct rt_serial_device *serial,
+                              int cmd, void *arg)
+{
+	RT_ASSERT(serial != RT_NULL);
+	switch(cmd){
+	case RT_DEVICE_CTRL_CLR_INT:
+		break;
+	case RT_DEVICE_CTRL_SET_INT:
+		break;
+	}
+	return RT_EOK;
+}
+static int usart_putc(struct rt_serial_device *serial, char c)
+{
+	while (UART0_REG(UART_REG_TXFIFO) & 0x80000000) ;
+	UART0_REG(UART_REG_TXFIFO) = c;
+	return 0;
+}
+static int usart_getc(struct rt_serial_device *serial)
+{
+	rt_int32_t val = UART0_REG(UART_REG_RXFIFO);
+	if (val > 0)
+		return (rt_uint8_t)val;
+	else
+		return -1;
+}
+static struct rt_uart_ops ops = {
+	usart_configure,
+	usart_control,
+	usart_putc,
+	usart_getc,
+};
+static struct rt_serial_device serial = {
+	.ops = &ops,
+	.config.baud_rate = BAUD_RATE_115200,
+	.config.bit_order = BIT_ORDER_LSB,
+	.config.data_bits = DATA_BITS_8,
+	.config.parity    = PARITY_NONE,
+	.config.stop_bits = STOP_BITS_1,
+	.config.invert    = NRZ_NORMAL,
+	.config.bufsz     = RT_SERIAL_RB_BUFSZ,
+};
+void rt_hw_uart_init(void)
+{
+	rt_hw_serial_register(
+			&serial, 
+			"dusart", 
+			RT_DEVICE_FLAG_STREAM
+		       	| RT_DEVICE_FLAG_RDWR
+			| RT_DEVICE_FLAG_INT_RX, RT_NULL);
+	rt_hw_interrupt_install(
+			INT_UART0_BASE,
+		       	usart_handler,
+		       	(void*)&(serial.parent),
+		       	"uart interrupt");
+	rt_hw_interrupt_unmask(INT_UART0_BASE);
+	return;
+}

+ 1 - 0
bsp/hifive1/drivers/usart.h

@@ -0,0 +1 @@
+#define UARTCLK 24e6

+ 34 - 0
bsp/hifive1/openocd.cfg

@@ -0,0 +1,34 @@
+adapter_khz     10000
+
+interface ftdi
+ftdi_device_desc "Dual RS232-HS"
+ftdi_vid_pid 0x0403 0x6010
+
+ftdi_layout_init 0x0008 0x001b
+ftdi_layout_signal nSRST -oe 0x0020 -data 0x0020
+
+#Reset Stretcher logic on FE310 is ~1 second long
+#This doesn't apply if you use
+# ftdi_set_signal, but still good to document
+#adapter_nsrst_delay 1500
+
+set _CHIPNAME riscv
+jtag newtap $_CHIPNAME cpu -irlen 5 -expected-id 0x10e31913
+
+set _TARGETNAME $_CHIPNAME.cpu
+target create $_TARGETNAME riscv -chain-position $_TARGETNAME
+$_TARGETNAME configure -work-area-phys 0x80000000 -work-area-size 10000 -work-area-backup 1
+
+flash bank onboard_spi_flash fespi 0x20000000 0 0 0 $_TARGETNAME
+init
+#reset -- This type of reset is not implemented yet
+if {[ info exists pulse_srst]} {
+  ftdi_set_signal nSRST 0
+  ftdi_set_signal nSRST z
+  #Wait for the reset stretcher
+  #It will work without this, but
+  #will incur lots of delays for later commands.
+  sleep 1500
+}	
+halt
+flash protect 0 64 last off

+ 20 - 0
bsp/hifive1/platform/SConscript

@@ -0,0 +1,20 @@
+Import('RTT_ROOT')
+Import('rtconfig')
+from building import *
+
+cwd  = GetCurrentDir()
+CPPPATH = [cwd]
+objs = []
+list = os.listdir(cwd)
+
+for d in list:
+    path = os.path.join(cwd, d)
+    if os.path.isfile(os.path.join(path, 'SConscript')):
+        objs = objs + SConscript(os.path.join(d, 'SConscript'))
+
+
+# The set of source files associated with this SConscript file.
+src = Glob('*.c')
+
+group = DefineGroup('platform', src, depend = [''], CPPPATH = CPPPATH)
+Return('group')

+ 110 - 0
bsp/hifive1/platform/interrupt.c

@@ -0,0 +1,110 @@
+#include <rthw.h>
+#include "plic_driver.h"
+#include "platform.h"
+
+#define MAX_HANDLERS    PLIC_NUM_INTERRUPTS
+extern rt_uint32_t rt_interrupt_nest;
+
+/* exception and interrupt handler table */
+struct rt_irq_desc irq_desc[MAX_HANDLERS];
+
+rt_uint32_t rt_interrupt_from_thread;
+rt_uint32_t rt_interrupt_to_thread;
+rt_uint32_t rt_thread_switch_interrupt_flag;
+volatile plic_instance_t g_plic;
+/**
+ * This function will mask a interrupt.
+ * @param vector the interrupt number
+ */
+void rt_hw_interrupt_mask(int irq)
+{
+	PLIC_disable_interrupt(&g_plic, irq);
+	return;
+}
+
+/**
+ * This function will un-mask a interrupt.
+ * @param vector the interrupt number
+ */
+void rt_hw_interrupt_unmask(int irq)
+{
+	PLIC_enable_interrupt(&g_plic, irq);
+	PLIC_set_priority(&g_plic, irq, 1);
+	return;
+}
+rt_isr_handler_t rt_hw_interrupt_handle(rt_uint32_t vector, void *param)
+{
+    rt_kprintf("UN-handled interrupt %d occurred!!!\n", vector);
+    return RT_NULL;
+}
+void rt_hw_interrupt_init(void)
+{
+	int idx;
+/*	config interrupt vector*/
+	asm volatile(
+		"la t0, trap_entry\n"
+		"csrw mtvec, t0"
+	);
+/*	enable global interrupt*/
+	PLIC_init(&g_plic,
+			PLIC_CTRL_ADDR,
+			PLIC_NUM_INTERRUPTS,
+			PLIC_NUM_PRIORITIES);
+
+	/* init exceptions table */
+	for(idx=0; idx < MAX_HANDLERS; idx++)
+	{
+		rt_hw_interrupt_mask(idx);
+		irq_desc[idx].handler = (rt_isr_handler_t)rt_hw_interrupt_handle;
+		irq_desc[idx].param = RT_NULL;
+#ifdef RT_USING_INTERRUPT_INFO
+		rt_snprintf(irq_desc[idx].name, RT_NAME_MAX - 1, "default");
+		irq_desc[idx].counter = 0;
+#endif
+	}
+	/* init interrupt nest, and context in thread sp */
+	rt_interrupt_nest = 0;
+	rt_interrupt_from_thread = 0;
+	rt_interrupt_to_thread = 0;
+	rt_thread_switch_interrupt_flag = 0;
+}
+rt_uint32_t rt_hw_interrupt_get_active(rt_uint32_t fiq_irq)
+{
+	//volatile rt_uint32_t irqstat;
+	rt_uint32_t id = PLIC_claim_interrupt(&g_plic);
+	return id;
+}
+void rt_hw_interrupt_ack(rt_uint32_t fiq_irq, rt_uint32_t id)
+{
+	PLIC_complete_interrupt(&g_plic, id);
+	return;
+}
+/**
+ * This function will install a interrupt service routine to a interrupt.
+ * @param vector the interrupt number
+ * @param handler the interrupt service routine to be installed
+ * @param param the interrupt service function parameter
+ * @param name the interrupt name
+ * @return old handler
+ */
+rt_isr_handler_t rt_hw_interrupt_install(int vector, rt_isr_handler_t handler,
+        void *param, char *name)
+{
+    rt_isr_handler_t old_handler = RT_NULL;
+
+    if(vector < MAX_HANDLERS)
+    {
+        old_handler = irq_desc[vector].handler;
+        if (handler != RT_NULL)
+        {
+            irq_desc[vector].handler = (rt_isr_handler_t)handler;
+            irq_desc[vector].param = param;
+#ifdef RT_USING_INTERRUPT_INFO
+            rt_snprintf(irq_desc[vector].name, RT_NAME_MAX - 1, "%s", name);
+            irq_desc[vector].counter = 0;
+#endif
+        }
+    }
+
+    return old_handler;
+}

+ 12 - 0
bsp/hifive1/platform/interrupt.h

@@ -0,0 +1,12 @@
+#ifndef __INTERRUPT_H__
+#define __INTERRUPT_H__
+#include <rthw.h>
+void rt_hw_interrupt_mask(int irq);
+void rt_hw_interrupt_unmask(int irq);
+rt_isr_handler_t rt_hw_interrupt_handle(rt_uint32_t vector, void *param);
+void rt_hw_interrupt_init(void);
+rt_uint32_t rt_hw_interrupt_get_active(rt_uint32_t fiq_irq);
+void rt_hw_interrupt_ack(rt_uint32_t fiq_irq, rt_uint32_t id);
+rt_isr_handler_t rt_hw_interrupt_install(int vector, rt_isr_handler_t handler,
+        void *param, char *name);
+#endif

+ 120 - 0
bsp/hifive1/platform/plic_driver.c

@@ -0,0 +1,120 @@
+#include "sifive/devices/plic.h"
+#include "plic_driver.h"
+#include "platform.h"
+#include "encoding.h"
+#include <string.h>
+
+void volatile_memzero(uint8_t * base, unsigned int size)
+{
+  volatile uint8_t * ptr;
+  for (ptr = base; ptr < (base + size); ptr++){
+    *ptr = 0;
+  }
+}
+
+void PLIC_init (
+                plic_instance_t * this_plic,
+                uintptr_t         base_addr,
+                uint32_t num_sources,
+                uint32_t num_priorities
+                )
+{
+  
+  this_plic->base_addr = base_addr;
+  this_plic->num_sources = num_sources;
+  this_plic->num_priorities = num_priorities;
+  
+  // Disable all interrupts (don't assume that these registers are reset).
+  unsigned long hart_id = read_csr(mhartid);
+  volatile_memzero((uint8_t*) (this_plic->base_addr +
+                               PLIC_ENABLE_OFFSET +
+                               (hart_id << PLIC_ENABLE_SHIFT_PER_TARGET)),
+                   (num_sources + 8) / 8);
+  
+  // Set all priorities to 0 (equal priority -- don't assume that these are reset).
+  volatile_memzero ((uint8_t *)(this_plic->base_addr +
+                                PLIC_PRIORITY_OFFSET),
+                    (num_sources + 1) << PLIC_PRIORITY_SHIFT_PER_SOURCE);
+
+  // Set the threshold to 0.
+  volatile plic_threshold* threshold = (plic_threshold*)
+    (this_plic->base_addr +
+     PLIC_THRESHOLD_OFFSET +
+     (hart_id << PLIC_THRESHOLD_SHIFT_PER_TARGET));
+
+  *threshold = 0;
+  
+}
+
+void PLIC_set_threshold (plic_instance_t * this_plic,
+			 plic_threshold threshold){
+
+  unsigned long hart_id = read_csr(mhartid);  
+  volatile plic_threshold* threshold_ptr = (plic_threshold*) (this_plic->base_addr +
+                                                              PLIC_THRESHOLD_OFFSET +
+                                                              (hart_id << PLIC_THRESHOLD_SHIFT_PER_TARGET));
+
+  *threshold_ptr = threshold;
+
+}
+  
+
+void PLIC_enable_interrupt (plic_instance_t * this_plic, plic_source source){
+
+  unsigned long hart_id = read_csr(mhartid);
+  volatile uint8_t * current_ptr = (volatile uint8_t *)(this_plic->base_addr +
+                                                        PLIC_ENABLE_OFFSET +
+                                                        (hart_id << PLIC_ENABLE_SHIFT_PER_TARGET) +
+                                                        (source >> 3));
+  uint8_t current = *current_ptr;
+  current = current | ( 1 << (source & 0x7));
+  *current_ptr = current;
+
+}
+
+void PLIC_disable_interrupt (plic_instance_t * this_plic, plic_source source){
+  
+  unsigned long hart_id = read_csr(mhartid);
+  volatile uint8_t * current_ptr = (volatile uint8_t *) (this_plic->base_addr +
+                                                         PLIC_ENABLE_OFFSET +
+                                                         (hart_id << PLIC_ENABLE_SHIFT_PER_TARGET) +
+                                                         (source >> 3));
+  uint8_t current = *current_ptr;
+  current = current & ~(( 1 << (source & 0x7)));
+  *current_ptr = current;
+  
+}
+
+void PLIC_set_priority (plic_instance_t * this_plic, plic_source source, plic_priority priority){
+
+  if (this_plic->num_priorities > 0) {
+    volatile plic_priority * priority_ptr = (volatile plic_priority *)
+      (this_plic->base_addr +
+       PLIC_PRIORITY_OFFSET +
+       (source << PLIC_PRIORITY_SHIFT_PER_SOURCE));
+    *priority_ptr = priority;
+  }
+}
+
+plic_source PLIC_claim_interrupt(plic_instance_t * this_plic){
+  
+  unsigned long hart_id = read_csr(mhartid);
+
+  volatile plic_source * claim_addr = (volatile plic_source * )
+    (this_plic->base_addr +
+     PLIC_CLAIM_OFFSET +
+     (hart_id << PLIC_CLAIM_SHIFT_PER_TARGET));
+
+  return  *claim_addr;
+  
+}
+
+void PLIC_complete_interrupt(plic_instance_t * this_plic, plic_source source){
+  
+  unsigned long hart_id = read_csr(mhartid);
+  volatile plic_source * claim_addr = (volatile plic_source *) (this_plic->base_addr +
+                                                                PLIC_CLAIM_OFFSET +
+                                                                (hart_id << PLIC_CLAIM_SHIFT_PER_TARGET));
+  *claim_addr = source;
+  
+}

+ 47 - 0
bsp/hifive1/platform/plic_driver.h

@@ -0,0 +1,47 @@
+// See LICENSE file for licence details
+
+#ifndef PLIC_DRIVER_H
+#define PLIC_DRIVER_H
+
+#include "platform.h"
+
+typedef struct __plic_instance_t
+{
+  uintptr_t base_addr;
+
+  uint32_t num_sources;
+  uint32_t num_priorities;
+  
+} plic_instance_t;
+
+typedef uint32_t plic_source;
+typedef uint32_t plic_priority;
+typedef uint32_t plic_threshold;
+
+void PLIC_init (
+                plic_instance_t * this_plic,
+                uintptr_t         base_addr,
+                uint32_t num_sources,
+                uint32_t num_priorities
+                );
+
+void PLIC_set_threshold (plic_instance_t * this_plic,
+			 plic_threshold threshold);
+  
+void PLIC_enable_interrupt (plic_instance_t * this_plic,
+			    plic_source source);
+
+void PLIC_disable_interrupt (plic_instance_t * this_plic,
+			     plic_source source);
+  
+void PLIC_set_priority (plic_instance_t * this_plic,
+			plic_source source,
+			plic_priority priority);
+
+plic_source PLIC_claim_interrupt(plic_instance_t * this_plic);
+
+void PLIC_complete_interrupt(plic_instance_t * this_plic,
+			     plic_source source);
+
+
+#endif

+ 31 - 0
bsp/hifive1/platform/rt_low_level_gcc.inc

@@ -0,0 +1,31 @@
+/*
+ * File      : rt_low_level_gcc.inc
+ * This file is part of RT-Thread RTOS
+ * COPYRIGHT (C) 2006 - 2015, RT-Thread Development Team
+ *
+ *  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 program is distributed in the hope that it will be useful,
+ *  but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ *  GNU General Public License for more details.
+ *
+ *  You should have received a copy of the GNU General Public License along
+ *  with this program; if not, write to the Free Software Foundation, Inc.,
+ *  51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
+ *
+ * Change Logs:
+ * Date           Author       Notes
+ * 2015-04-14     ArdaFu      first version
+ */
+
+/*--------- Stack size of CPU modes ------------------------------------------*/
+.equ UND_STK_SIZE,    2048
+.equ SVC_STK_SIZE,    4096
+.equ ABT_STK_SIZE,    2048
+.equ IRQ_STK_SIZE,    4096
+.equ FIQ_STK_SIZE,    4096
+.equ SYS_STK_SIZE,    2048

+ 37 - 0
bsp/hifive1/platform/rt_low_level_init.c

@@ -0,0 +1,37 @@
+/*
+ * File      : rt_low_level_init.c
+ * This file is part of RT-Thread RTOS
+ * COPYRIGHT (C) 2006 - 2015, RT-Thread Development Team
+ *
+ *  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 program is distributed in the hope that it will be useful,
+ *  but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ *  GNU General Public License for more details.
+ *
+ *  You should have received a copy of the GNU General Public License along
+ *  with this program; if not, write to the Free Software Foundation, Inc.,
+ *  51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
+ *
+ * Change Logs:
+ * Date           Author       Notes
+ * 2015-04-14     ArdaFu      first version
+ * 2015-04-27     ArdaFu      Port bsp from at91sam9260 to asm9260t
+ */
+
+void rt_low_level_init(void)
+{
+
+}
+void machine_reset(void)
+{
+	return;
+}
+void machine_shutdown(void)
+{
+	return;
+}

+ 264 - 0
bsp/hifive1/rtconfig.h

@@ -0,0 +1,264 @@
+/* RT-Thread config file */
+#ifndef __RTTHREAD_CFG_H__
+#define __RTTHREAD_CFG_H__
+
+/* RT_NAME_MAX*/
+#define RT_NAME_MAX	32
+
+/* RT_ALIGN_SIZE*/
+#define RT_ALIGN_SIZE	4
+
+/* PRIORITY_MAX */
+#define RT_THREAD_PRIORITY_MAX	255
+
+/* Tick per Second */
+#define RT_TICK_PER_SECOND	100
+
+/* SECTION: RT_DEBUG */
+/* Thread Debug */
+#define RT_DEBUG
+#define RT_DEBUG_TIMER 0
+/*#define RT_DEBUG_IRQ 1*/
+#define RT_DEBUG_SCHEDULER 0
+#define RT_DEBUG_THREAD 0
+
+#define RT_USING_OVERFLOW_CHECK
+
+#define RT_USING_INTERRUPT_INFO
+
+/* Using Hook */
+#define RT_USING_HOOK
+
+/* Using Software Timer */
+#define RT_USING_TIMER_SOFT
+#define RT_TIMER_THREAD_PRIO		8
+#define RT_TIMER_THREAD_STACK_SIZE	512
+#define RT_TIMER_TICK_PER_SECOND	50
+
+/* SECTION: IPC */
+/* Using Semaphore */
+#define RT_USING_SEMAPHORE
+
+/* Using Mutex */
+#define RT_USING_MUTEX
+
+/* Using Event */
+#define RT_USING_EVENT
+
+/* Using MailBox */
+#define RT_USING_MAILBOX
+
+/* Using Message Queue */
+#define RT_USING_MESSAGEQUEUE
+
+/* SECTION: Memory Management */
+/* Using Memory Pool Management*/
+#define RT_USING_MEMPOOL
+
+/* Using Dynamic Heap Management */
+#define RT_USING_HEAP
+
+/* Using Small MM */
+ #define RT_USING_SMALL_MEM 
+
+/* Using SLAB Allocator */
+/*#define RT_USING_SLAB*/
+
+/* SECTION: the runtime libc library */
+/* the runtime libc library */
+#define RT_USING_LIBC
+//#define RT_USING_PTHREADS
+
+/* Using Module System */
+//#define RT_USING_MODULE
+//#define RT_USING_LIBDL
+
+/* SECTION: Device System */
+/* Using Device System */
+#define RT_USING_DEVICE
+
+#define RT_USING_DEVICE_IPC
+#define RT_USING_SERIAL
+
+/* SECTION: Console options */
+#define RT_USING_CONSOLE
+/* the buffer size of console */
+#define RT_CONSOLEBUF_SIZE	128
+#define RT_CONSOLE_DEVICE_NAME "dusart"
+
+/* SECTION: finsh, a C-Express shell */
+/* Using FinSH as Shell*/
+#define RT_USING_FINSH
+/* Using symbol table */
+#define FINSH_USING_SYMTAB
+#define FINSH_USING_DESCRIPTION
+#define FINSH_THREAD_STACK_SIZE 1024
+#define FINSH_USING_MSH
+#define FINSH_USING_MSH_ONLY
+
+/* SECTION: C++ support */
+/* Using C++ support */
+/* #define RT_USING_CPLUSPLUS */
+
+/* SECTION: Device filesystem support */
+/* using DFS support */
+//#define RT_USING_DFS
+#define RT_USING_DFS_ELMFAT
+/* use long file name feature */
+#define RT_DFS_ELM_USE_LFN			2
+#define RT_DFS_ELM_REENTRANT
+/* define OEM code page */
+#define RT_DFS_ELM_CODE_PAGE	936
+/* Using OEM code page file */
+// #define RT_DFS_ELM_CODE_PAGE_FILE
+/* the max number of file length */
+#define RT_DFS_ELM_MAX_LFN			128
+/* #define RT_USING_DFS_YAFFS2 */
+//#define RT_USING_DFS_DEVFS
+
+#define RT_USING_DFS_NFS
+#define RT_NFS_HOST_EXPORT		"192.168.1.5:/"
+
+#define DFS_USING_WORKDIR
+
+/* the max number of mounted filesystem */
+#define DFS_FILESYSTEMS_MAX		4
+/* the max number of opened files */
+#define DFS_FD_MAX					16
+/* the max number of cached sector */
+#define DFS_CACHE_MAX_NUM   		4
+
+/* Enable freemodbus protocol stack*/
+/* #define RT_USING_MODBUS */
+
+/*#define RT_USING_LED*/
+/*#define RT_USING_SPI*/
+/*#define RT_USING_SDIO*/
+/*#define RT_USING_I2C*/
+#define RT_USING_I2C_BITOPS
+
+/*#define RT_USING_DBGU*/
+ #define RT_USING_UART0
+/* #define RT_USING_UART1 */
+
+
+/* SECTION: lwip, a lightweight TCP/IP protocol stack */
+/* Using lightweight TCP/IP protocol stack */
+//#define RT_USING_LWIP
+#define RT_LWIP_DNS
+
+/* Trace LwIP protocol */
+// #define RT_LWIP_DEBUG 
+
+/* Enable ICMP protocol */
+#define RT_LWIP_ICMP
+
+/* Enable IGMP protocol */
+#define RT_LWIP_IGMP
+
+/* Enable UDP protocol */
+#define RT_LWIP_UDP
+
+/* Enable TCP protocol */
+#define RT_LWIP_TCP
+
+/* the number of simulatenously active TCP connections*/
+#define RT_LWIP_TCP_PCB_NUM	5
+
+/* TCP sender buffer space */
+#define RT_LWIP_TCP_SND_BUF	1024*10
+
+/* TCP receive window. */
+#define RT_LWIP_TCP_WND	1024*8
+
+/* Enable SNMP protocol */
+/* #define RT_LWIP_SNMP */
+
+/* Using DHCP */
+/* #define RT_LWIP_DHCP */
+
+/* ip address of target */
+#define RT_LWIP_IPADDR0	192
+#define RT_LWIP_IPADDR1	168
+#define RT_LWIP_IPADDR2	1
+#define RT_LWIP_IPADDR3	30
+
+/* gateway address of target */
+#define RT_LWIP_GWADDR0	192
+#define RT_LWIP_GWADDR1	168
+#define RT_LWIP_GWADDR2	1
+#define RT_LWIP_GWADDR3	1
+
+/* mask address of target */
+#define RT_LWIP_MSKADDR0	255
+#define RT_LWIP_MSKADDR1	255
+#define RT_LWIP_MSKADDR2	255
+#define RT_LWIP_MSKADDR3	0
+
+/* the number of blocks for pbuf */
+#define RT_LWIP_PBUF_NUM	16
+
+/* the number of simultaneously queued TCP */
+#define RT_LWIP_TCP_SEG_NUM    40
+
+/* thread priority of tcpip thread */
+#define RT_LWIP_TCPTHREAD_PRIORITY	128
+
+/* mail box size of tcpip thread to wait for */
+#define RT_LWIP_TCPTHREAD_MBOX_SIZE	32
+
+/* thread stack size of tcpip thread */
+#define RT_LWIP_TCPTHREAD_STACKSIZE	4096
+
+/* thread priority of ethnetif thread */
+#define RT_LWIP_ETHTHREAD_PRIORITY	144
+
+/* mail box size of ethnetif thread to wait for */
+#define RT_LWIP_ETHTHREAD_MBOX_SIZE	32
+
+/* thread stack size of ethnetif thread */
+#define RT_LWIP_ETHTHREAD_STACKSIZE	1024
+
+
+/* SECTION: RTGUI support */
+/* using RTGUI support */
+/* #define RT_USING_RTGUI */
+
+/* name length of RTGUI object */
+//#define RTGUI_NAME_MAX		16
+/* support 16 weight font */
+//#define RTGUI_USING_FONT16
+/* support 16 weight font */
+//#define RTGUI_USING_FONT12
+/* support Chinese font */
+//#define RTGUI_USING_FONTHZ
+/* use DFS as file interface */
+//#define RTGUI_USING_DFS_FILERW
+/* use font file as Chinese font */
+/* #define RTGUI_USING_HZ_FILE */
+/* use Chinese bitmap font */
+//#define RTGUI_USING_HZ_BMP
+/* use small size in RTGUI */
+/* #define RTGUI_USING_SMALL_SIZE */
+/* use mouse cursor */
+/* #define RTGUI_USING_MOUSE_CURSOR */
+
+/* SECTION: FTK support */
+/* using FTK support */
+/* #define RT_USING_FTK */
+
+/*
+ * Note on FTK:
+ * 
+ * FTK depends :
+ * #define RT_USING_NEWLIB
+ * #define DFS_USING_WORKDIR
+ * 
+ * And the maximal length must great than 64
+ * #define RT_DFS_ELM_MAX_LFN	128
+ */
+//#define RT_USING_CPU_FFS
+#define RT_USING_COMPONENTS_INIT
+
+#define IDLE_THREAD_STACK_SIZE 1024
+#endif

+ 142 - 0
bsp/hifive1/rtconfig.py

@@ -0,0 +1,142 @@
+import os
+ARCH     = 'risc-v'
+CPU      = 'e310'
+# toolchains options
+CROSS_TOOL  = 'gcc'
+
+#------- toolchains path -------------------------------------------------------
+if os.getenv('RTT_CC'):
+    CROSS_TOOL = os.getenv('RTT_CC')
+
+if  CROSS_TOOL == 'gcc':
+    PLATFORM    = 'gcc'
+   # EXEC_PATH  = 'D:/ArdaArmTools/Sourcery_Lite/bin'
+    EXEC_PATH   = '/home/zj/risc-v/riscv64-unknown-elf-gcc-20170612-x86_64-linux-centos6/bin'
+elif CROSS_TOOL == 'keil':
+    PLATFORM    = 'armcc'
+    EXEC_PATH   = 'C:/Keil_v5'
+elif CROSS_TOOL == 'iar':
+    PLATFORM    = 'iar'
+    IAR_PATH    = 'C:/Program Files (x86)/IAR Systems/Embedded Workbench 7.0'
+
+if os.getenv('RTT_EXEC_PATH'):
+    EXEC_PATH = os.getenv('RTT_EXEC_PATH')
+
+BUILD = 'debug'
+#BUILD = 'release'
+
+CORE = 'risc-v'
+MAP_FILE = 'rtthread.map'
+LINK_FILE = 'sdram'
+TARGET_NAME = 'rtthread.bin'
+
+#------- GCC settings ----------------------------------------------------------
+if PLATFORM == 'gcc':
+    # toolchains
+    PREFIX = '/home/zj/risc-v/riscv64-unknown-elf-gcc-20170612-x86_64-linux-centos6/bin/riscv64-unknown-elf-'
+    #PREFIX = 'arm-none-linux-gnueabi-'
+    CC = PREFIX + 'gcc'
+    AS = PREFIX + 'gcc'
+    AR = PREFIX + 'ar'
+    LINK = PREFIX + 'gcc'
+    TARGET_EXT = 'axf'
+    SIZE = PREFIX + 'size'
+    OBJDUMP = PREFIX + 'objdump'
+    OBJCPY = PREFIX + 'objcopy'
+
+    DEVICE = ' -march=rv32imac -mabi=ilp32 -DUSE_PLIC -DUSE_M_TIME -mcmodel=medany -msmall-data-limit=8  -g -L.  -nostartfiles  -lc '
+#    DEVICE += '-Wl,--wrap=malloc -Wl,--wrap=free -Wl,--wrap=open -Wl,--wrap=lseek -Wl,--wrap=read -Wl,--wrap=write -Wl,--wrap=fstat -Wl,--wrap=stat -Wl,--wrap=close -Wl,--wrap=link -Wl,--wrap=unlink -Wl,--wrap=execve -Wl,--wrap=fork -Wl,--wrap=getpid -Wl,--wrap=kill -Wl,--wrap=wait -Wl,--wrap=isatty -Wl,--wrap=times -Wl,--wrap=sbrk -Wl,--wrap=_exit'
+    CFLAGS = DEVICE
+#    CFLAGS += ' -I ./mx28_registers/'
+    CFLAGS += ''
+    AFLAGS = '-c'+ DEVICE + ' -x assembler-with-cpp'
+    AFLAGS += ' -Iplatform'
+    LFLAGS = DEVICE 
+    LFLAGS += ' -Wl,--gc-sections,-cref,-Map=' + MAP_FILE
+    LFLAGS += ' -T ' + LINK_FILE + '.ld'
+
+    CPATH = ''
+    LPATH = ''
+
+    if BUILD == 'debug':
+        CFLAGS += ' -O0 -gdwarf-2'
+        AFLAGS += ' -gdwarf-2'
+    else:
+        CFLAGS += ' -O2'
+
+    POST_ACTION = OBJCPY + ' -O binary $TARGET ' + TARGET_NAME + '\n' 
+    POST_ACTION += SIZE + ' $TARGET\n'
+#------- Keil settings ---------------------------------------------------------
+elif PLATFORM == 'armcc':
+    # toolchains
+    CC = 'armcc'
+    AS = 'armasm'
+    AR = 'armar'
+    LINK = 'armlink'
+    TARGET_EXT = 'axf'
+    EXEC_PATH += '/arm/armcc/bin/'
+
+    DEVICE = ' --cpu=' + CORE
+    CFLAGS = DEVICE + ' --apcs=interwork --diag_suppress=870'
+    AFLAGS = DEVICE + ' -Iplatform'
+    LFLAGS = DEVICE + ' --strict'
+    LFLAGS += ' --info sizes --info totals --info unused --info veneers'
+    LFLAGS += ' --list ' + MAP_FILE
+    LFLAGS += ' --scatter  ' + LINK_FILE + '.scat'
+
+    if BUILD == 'debug':
+        CFLAGS += ' -g -O0'
+        AFLAGS += ' -g'
+    else:
+        CFLAGS += ' -O2'
+
+    POST_ACTION = 'fromelf --bin $TARGET --output ' + TARGET_NAME + ' \n'
+    POST_ACTION += 'fromelf -z $TARGET\n'
+#------- IAR settings ----------------------------------------------------------
+elif PLATFORM == 'iar':
+    # toolchains
+    CC = 'iccarm'
+    AS = 'iasmarm'
+    AR = 'iarchive'
+    LINK = 'ilinkarm'
+    TARGET_EXT = 'axf'
+
+    DEVICE = CORE
+
+    CFLAGS = '--cpu=' + DEVICE
+    CFLAGS += ' --diag_suppress Pa050'
+    CFLAGS += ' --no_cse'
+    CFLAGS += ' --no_unroll'
+    CFLAGS += ' --no_inline'
+    CFLAGS += ' --no_code_motion'
+    CFLAGS += ' --no_tbaa'
+    CFLAGS += ' --no_clustering'
+    CFLAGS += ' --no_scheduling'
+
+    CFLAGS += ' --endian=little'
+    CFLAGS += ' -e'
+    CFLAGS += ' --fpu=none'
+    CFLAGS += ' --dlib_config "' + IAR_PATH + '/arm/INC/c/DLib_Config_Normal.h"'
+    CFLAGS += ' --silent'
+
+    AFLAGS = '--cpu '+ DEVICE
+    AFLAGS += ' -s+'
+    AFLAGS += ' -w+'
+    AFLAGS += ' -r'
+    AFLAGS += ' --fpu none'
+    AFLAGS += ' -S'
+    AFLAGS += ' -Iplatform'
+    
+    if BUILD == 'debug':
+        CFLAGS += ' --debug'
+        CFLAGS += ' -On'
+    else:
+        CFLAGS += ' -Oh'
+
+    LFLAGS = '--config ' + LINK_FILE +'.icf'
+    LFLAGS += ' --entry __iar_program_start'
+    LFLAGS += ' --map ' + MAP_FILE
+    LFLAGS += ' --silent'
+
+    EXEC_PATH = IAR_PATH + '/arm/bin/'
+    POST_ACTION = 'ielftool  --silent --bin $TARGET ' + TARGET_NAME

+ 168 - 0
bsp/hifive1/sdram.ld

@@ -0,0 +1,168 @@
+OUTPUT_ARCH( "riscv" )
+
+ENTRY( _start )
+
+MEMORY
+{
+  flash (rxai!w) : ORIGIN = 0x20400000, LENGTH = 16M
+  ram (wxa!ri) : ORIGIN = 0x80000000, LENGTH = 16K
+}
+
+PHDRS
+{
+  flash PT_LOAD;
+  ram_init PT_LOAD;
+  ram PT_NULL;
+}
+
+
+SECTIONS
+{
+    __stack_size = DEFINED(__stack_size) ? __stack_size : 512;
+    . = 0x20400000;
+
+    . = ALIGN(4);
+    .init           :
+    {
+	    KEEP (*(SORT_NONE(.init)))
+    } >flash AT>flash :flash
+
+    .text : 
+    {
+        *(.init)
+	__init_end__ = .;
+        *(.text)
+        *(.gnu.linkonce.t*)
+        
+        /* section information for finsh shell */
+        . = ALIGN(4);
+        __fsymtab_start = .;
+        KEEP(*(FSymTab))
+        __fsymtab_end = .;
+        . = ALIGN(4);
+        __vsymtab_start = .;
+        KEEP(*(VSymTab))
+        __vsymtab_end = .;
+        . = ALIGN(4);   
+
+        . = ALIGN(4);
+        __rt_init_start = .;
+        KEEP(*(SORT(.rti_fn*)))
+        __rt_init_end = .;
+        . = ALIGN(4);
+
+        /* section information for modules */
+        . = ALIGN(4);
+        __rtmsymtab_start = .;
+        KEEP(*(RTMSymTab))
+        __rtmsymtab_end = .;
+    }>flash AT>flash :flash
+
+    .fini           :
+    {
+	    KEEP (*(SORT_NONE(.fini)))
+    } >flash AT>flash :flash
+
+    PROVIDE (__etext = .);
+    PROVIDE (_etext = .);
+    PROVIDE (etext = .);
+
+
+    . = ALIGN(4);
+    .rodata : { 
+	    *(.rodata) ;
+	    *(.rodata.*) ;
+	    *(.gnu.linkonce.r*) ;
+	    *(.eh_frame) 
+    }>flash AT>flash :flash
+
+    . = ALIGN(4);
+    .ctors :
+    {
+        PROVIDE(__ctors_start__ = .);
+        KEEP(*(SORT(.ctors.*)))
+        KEEP(*(.ctors))
+        PROVIDE(__ctors_end__ = .);
+    }>flash AT>flash :flash
+
+    .dtors :
+    {
+        PROVIDE(__dtors_start__ = .);
+        KEEP(*(SORT(.dtors.*)))
+        KEEP(*(.dtors))
+        PROVIDE(__dtors_end__ = .);
+    }>flash AT>flash :flash
+
+    .lalign         :
+    {
+	    . = ALIGN(4);
+	    PROVIDE( _data_lma = . );
+    } >flash AT>flash :flash
+
+    .dalign         :
+    {
+	    . = ALIGN(4);
+	    PROVIDE( _data = . );
+    } >ram AT>flash :ram_init
+
+    . = ALIGN(4);
+    .data :
+    {
+        *(.data)
+        *(.data.*)
+	. = ALIGN(8);
+	PROVIDE( __global_pointer$ = . + 0x800 );
+	*(.sdata .sdata.*)
+	*(.gnu.linkonce.s.*)
+	. = ALIGN(8);
+	*(.srodata.cst16)
+	*(.srodata.cst8)
+	*(.srodata.cst4)
+	*(.srodata.cst2)
+	*(.srodata .srodata.*)
+        *(.gnu.linkonce.d*)
+    }>ram AT>flash :ram_init
+
+    . = ALIGN(4);
+    .nobss : { *(.nobss) }
+    
+    . = ALIGN(4);
+    PROVIDE( _edata = . );
+    PROVIDE( edata = . );
+
+    PROVIDE( _fbss = . );
+    PROVIDE( __bss_start = . );
+    __bss_start__ = .;
+    .bss : { 
+	    *(.bss)
+	    *(.sbss*)
+	    *(.gnu.linkonce.sb.*)
+	    *(.bss .bss.*)
+	    *(.gnu.linkonce.b.*)
+	    *(COMMON)
+    	    . = ALIGN(4);
+    }>ram AT>flash :ram
+    _end = .;
+    __bss_end__ = .;
+
+    .stack ORIGIN(ram) + LENGTH(ram) - __stack_size :
+    {
+	    PROVIDE( _heap_end = . );
+	    . = __stack_size;
+	    PROVIDE( _sp = . );
+    } >ram AT>ram :ram
+    /* 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) }
+    .debug_abbrev 0 : { *(.debug_abbrev) }
+    .debug_info 0 : { *(.debug_info) }
+    .debug_line 0 : { *(.debug_line) }
+    .debug_pubnames 0 : { *(.debug_pubnames) }
+    .debug_aranges 0 : { *(.debug_aranges) }
+
+}

+ 58 - 0
bsp/hifive1/wrap_exit.c

@@ -0,0 +1,58 @@
+#include <reent.h>
+#include <sys/errno.h>
+#include <sys/time.h>
+#include <rtthread.h>
+
+#ifdef RT_USING_DFS
+#include <dfs_posix.h>
+#endif
+
+#ifdef RT_USING_PTHREADS 
+#include <pthread.h>
+#endif
+
+
+void
+__wrap__exit (int status)
+{
+#ifdef RT_USING_MODULE
+	rt_module_t module;
+
+	module = rt_module_self();
+	if (module != RT_NULL)
+	{
+		struct rt_list_node *list;
+		struct rt_object *object;
+
+		rt_enter_critical();
+		
+        /* delete all threads in the module */
+        list = &module->module_object[RT_Object_Class_Thread].object_list;
+        while (list->next != list)
+        {
+            object = rt_list_entry(list->next, struct rt_object, list);
+            if (rt_object_is_systemobject(object) == RT_TRUE)
+            {
+                /* detach static object */
+                rt_thread_detach((rt_thread_t)object);
+            }
+            else
+            {
+                /* delete dynamic object */
+                rt_thread_delete((rt_thread_t)object);
+            }
+        }
+		/* delete main thread */
+		rt_thread_delete(module->module_thread);
+		rt_exit_critical();
+
+		/* re-schedule */
+		rt_schedule();
+	}
+#endif
+	
+	rt_kprintf("thread:%s exit with %d\n", rt_thread_self()->name, status);
+	RT_ASSERT(0);
+
+	while (1);
+}

+ 236 - 0
libcpu/risc-v/e310/context_gcc.S

@@ -0,0 +1,236 @@
+;/*
+; * File      : context_gcc.S
+; * This file is part of RT-Thread RTOS
+; * COPYRIGHT (C) 2006, RT-Thread Development Team
+; *
+; *  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 program is distributed in the hope that it will be useful,
+; *  but WITHOUT ANY WARRANTY; without even the implied warranty of
+; *  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+; *  GNU General Public License for more details.
+; *
+; *  You should have received a copy of the GNU General Public License along
+; *  with this program; if not, write to the Free Software Foundation, Inc.,
+; *  51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
+; *
+; * Change Logs:
+; * Date           Author       Notes
+; * 2017-07-16     zhangjun    for hifive1
+; */
+
+#include "encoding.h"
+#include "sifive/bits.h"
+
+/*
+ * rt_base_t rt_hw_interrupt_disable();
+ */
+    .globl rt_hw_interrupt_disable
+rt_hw_interrupt_disable:
+  addi sp, sp, -12
+  sw a5, (sp)
+  li a5, 0x800
+  csrr a0, mie
+  blt a0, a5, 1f
+/*  interrupt is enable before disable it*/
+  addi a0, a0, 1
+
+  li a5, 0x1
+  addi a5, a5, -2048
+  csrrc a5, mie, a5
+/*  csrrc a5, mie, 128*/
+  j 2f
+/*  interrupt is disabled before disable it*/
+1:
+  li a0, 0
+2:
+  lw a5, (sp)
+  addi sp, sp, 12
+  ret
+
+/*
+ * void rt_hw_interrupt_enable(rt_base_t level);
+ */
+    .globl rt_hw_interrupt_enable
+rt_hw_interrupt_enable:
+  addi sp, sp, -12
+  sw a5, (sp)
+  beqz a0, 1f
+  li a5, 0x1
+  addi a5, a5, -2048
+  csrrs a5, mie, a5
+/*  csrrs a5, mie, 128*/
+1:
+  lw a5, (sp)
+  addi sp, sp, 12
+  ret
+
+/*
+ * void rt_hw_context_switch(rt_uint32 from, rt_uint32 to);
+ * a0 --> from
+ * a1 --> to
+ */
+    .globl rt_hw_context_switch
+rt_hw_context_switch:
+  addi  sp,  sp, -32*REGBYTES
+
+  STORE sp,  (a0)
+  STORE x30, 1*REGBYTES(sp)
+  STORE x31, 2*REGBYTES(sp)
+  STORE x3,  3*REGBYTES(sp)
+  STORE x4,  4*REGBYTES(sp)
+  STORE x5,  5*REGBYTES(sp)
+  STORE x6,  6*REGBYTES(sp)
+  STORE x7,  7*REGBYTES(sp)
+  STORE x8,  8*REGBYTES(sp)
+  STORE x9,  9*REGBYTES(sp)
+  STORE x10, 10*REGBYTES(sp)
+  STORE x11, 11*REGBYTES(sp)
+  STORE x12, 12*REGBYTES(sp)
+  STORE x13, 13*REGBYTES(sp)
+  STORE x14, 14*REGBYTES(sp)
+  STORE x15, 15*REGBYTES(sp)
+  STORE x16, 16*REGBYTES(sp)
+  STORE x17, 17*REGBYTES(sp)
+  STORE x18, 18*REGBYTES(sp)
+  STORE x19, 19*REGBYTES(sp)
+  STORE x20, 20*REGBYTES(sp)
+  STORE x21, 21*REGBYTES(sp)
+  STORE x22, 22*REGBYTES(sp)
+  STORE x23, 23*REGBYTES(sp)
+  STORE x24, 24*REGBYTES(sp)
+  STORE x25, 25*REGBYTES(sp)
+  STORE x26, 26*REGBYTES(sp)
+  STORE x27, 27*REGBYTES(sp)
+  STORE x28, 28*REGBYTES(sp)
+  STORE x10, 29*REGBYTES(sp)
+  STORE x1,  30*REGBYTES(sp)
+  STORE x1,  31*REGBYTES(sp)
+  csrr  x10, mie
+  STORE x10, 0*REGBYTES(sp)
+/*
+ *Remain in M-mode after mret
+ *enable interrupt in M-mode
+ */
+  li t0, 136
+  csrrs t0, mstatus, t0
+
+  LOAD sp,  (a1)
+  LOAD x30, 1*REGBYTES(sp)
+  LOAD x31, 2*REGBYTES(sp)
+  LOAD x3,  3*REGBYTES(sp)
+  LOAD x4,  4*REGBYTES(sp)
+  LOAD x5,  5*REGBYTES(sp)
+  LOAD x6,  6*REGBYTES(sp)
+  LOAD x7,  7*REGBYTES(sp)
+  LOAD x8,  8*REGBYTES(sp)
+  LOAD x9,  9*REGBYTES(sp)
+  LOAD x29, 10*REGBYTES(sp)
+  LOAD x11, 11*REGBYTES(sp)
+  LOAD x12, 12*REGBYTES(sp)
+  LOAD x13, 13*REGBYTES(sp)
+  LOAD x14, 14*REGBYTES(sp)
+  LOAD x15, 15*REGBYTES(sp)
+  LOAD x16, 16*REGBYTES(sp)
+  LOAD x17, 17*REGBYTES(sp)
+  LOAD x18, 18*REGBYTES(sp)
+  LOAD x19, 19*REGBYTES(sp)
+  LOAD x20, 20*REGBYTES(sp)
+  LOAD x21, 21*REGBYTES(sp)
+  LOAD x22, 22*REGBYTES(sp)
+  LOAD x23, 23*REGBYTES(sp)
+  LOAD x24, 24*REGBYTES(sp)
+  LOAD x25, 25*REGBYTES(sp)
+  LOAD x26, 26*REGBYTES(sp)
+  LOAD x27, 27*REGBYTES(sp)
+  LOAD x28, 28*REGBYTES(sp)
+  LOAD x10, 31*REGBYTES(sp)
+  csrw mepc,x10
+  LOAD x10, 0*REGBYTES(sp)
+  csrw mie, x10
+  LOAD x10, 29*REGBYTES(sp)
+  LOAD x1,  30*REGBYTES(sp)
+  
+  addi sp,  sp, 32*REGBYTES
+  mret
+	
+/*
+ * void rt_hw_context_switch_to(rt_uint32 to);
+ * a0 --> to
+ */
+    .globl rt_hw_context_switch_to
+rt_hw_context_switch_to:
+  LOAD sp,  (a0)
+  LOAD x30, 1*REGBYTES(sp)
+  LOAD x31, 2*REGBYTES(sp)
+  LOAD x3,  3*REGBYTES(sp)
+  LOAD x4,  4*REGBYTES(sp)
+  LOAD x5,  5*REGBYTES(sp)
+  LOAD x6,  6*REGBYTES(sp)
+  LOAD x7,  7*REGBYTES(sp)
+  LOAD x8,  8*REGBYTES(sp)
+  LOAD x9,  9*REGBYTES(sp)
+  LOAD x29, 10*REGBYTES(sp)
+  LOAD x11, 11*REGBYTES(sp)
+  LOAD x12, 12*REGBYTES(sp)
+  LOAD x13, 13*REGBYTES(sp)
+  LOAD x14, 14*REGBYTES(sp)
+  LOAD x15, 15*REGBYTES(sp)
+  LOAD x16, 16*REGBYTES(sp)
+  LOAD x17, 17*REGBYTES(sp)
+  LOAD x18, 18*REGBYTES(sp)
+  LOAD x19, 19*REGBYTES(sp)
+  LOAD x20, 20*REGBYTES(sp)
+  LOAD x21, 21*REGBYTES(sp)
+  LOAD x22, 22*REGBYTES(sp)
+  LOAD x23, 23*REGBYTES(sp)
+  LOAD x24, 24*REGBYTES(sp)
+  LOAD x25, 25*REGBYTES(sp)
+  LOAD x26, 26*REGBYTES(sp)
+  LOAD x27, 27*REGBYTES(sp)
+  LOAD x28, 28*REGBYTES(sp)
+  LOAD x10, 31*REGBYTES(sp)
+  csrw mepc,a0
+  LOAD x10, 29*REGBYTES(sp)
+  LOAD x1,  30*REGBYTES(sp)
+  
+
+  addi sp,  sp, 32*REGBYTES
+  mret
+	
+
+/*
+ * void rt_hw_context_switch_interrupt(rt_uint32 from, rt_uint32 to);
+ */
+    .globl rt_thread_switch_interrupt_flag
+    .globl rt_interrupt_from_thread
+    .globl rt_interrupt_to_thread
+    .globl rt_hw_context_switch_interrupt
+rt_hw_context_switch_interrupt:
+  addi sp, sp, -16
+  sw   s0, 12(sp)
+  sw   a0, 8(sp)
+  sw   a5, 4(sp)
+
+  la   a0, rt_thread_switch_interrupt_flag
+  lw   a5, (a0)
+  bnez a5, _reswitch
+  li   a5, 1
+  sw   a5, (a0)
+
+  la   a5, rt_interrupt_from_thread
+  lw   a0, 8(sp)
+  sw   a0, (a5)
+
+_reswitch:
+  la   a5, rt_interrupt_to_thread
+  sw   a1, (a5)
+
+  lw   a5, 4(sp)
+  lw   a0, 8(sp)
+  lw   s0, 12(sp)
+  addi sp, sp, 16
+  ret

+ 1313 - 0
libcpu/risc-v/e310/encoding.h

@@ -0,0 +1,1313 @@
+// See LICENSE for license details.
+
+#ifndef RISCV_CSR_ENCODING_H
+#define RISCV_CSR_ENCODING_H
+
+#define MSTATUS_UIE         0x00000001
+#define MSTATUS_SIE         0x00000002
+#define MSTATUS_HIE         0x00000004
+#define MSTATUS_MIE         0x00000008
+#define MSTATUS_UPIE        0x00000010
+#define MSTATUS_SPIE        0x00000020
+#define MSTATUS_HPIE        0x00000040
+#define MSTATUS_MPIE        0x00000080
+#define MSTATUS_SPP         0x00000100
+#define MSTATUS_HPP         0x00000600
+#define MSTATUS_MPP         0x00001800
+#define MSTATUS_FS          0x00006000
+#define MSTATUS_XS          0x00018000
+#define MSTATUS_MPRV        0x00020000
+#define MSTATUS_PUM         0x00040000
+#define MSTATUS_MXR         0x00080000
+#define MSTATUS_VM          0x1F000000
+#define MSTATUS32_SD        0x80000000
+#define MSTATUS64_SD        0x8000000000000000
+
+#define SSTATUS_UIE         0x00000001
+#define SSTATUS_SIE         0x00000002
+#define SSTATUS_UPIE        0x00000010
+#define SSTATUS_SPIE        0x00000020
+#define SSTATUS_SPP         0x00000100
+#define SSTATUS_FS          0x00006000
+#define SSTATUS_XS          0x00018000
+#define SSTATUS_PUM         0x00040000
+#define SSTATUS32_SD        0x80000000
+#define SSTATUS64_SD        0x8000000000000000
+
+#define DCSR_XDEBUGVER      (3U<<30)
+#define DCSR_NDRESET        (1<<29)
+#define DCSR_FULLRESET      (1<<28)
+#define DCSR_EBREAKM        (1<<15)
+#define DCSR_EBREAKH        (1<<14)
+#define DCSR_EBREAKS        (1<<13)
+#define DCSR_EBREAKU        (1<<12)
+#define DCSR_STOPCYCLE      (1<<10)
+#define DCSR_STOPTIME       (1<<9)
+#define DCSR_CAUSE          (7<<6)
+#define DCSR_DEBUGINT       (1<<5)
+#define DCSR_HALT           (1<<3)
+#define DCSR_STEP           (1<<2)
+#define DCSR_PRV            (3<<0)
+
+#define DCSR_CAUSE_NONE     0
+#define DCSR_CAUSE_SWBP     1
+#define DCSR_CAUSE_HWBP     2
+#define DCSR_CAUSE_DEBUGINT 3
+#define DCSR_CAUSE_STEP     4
+#define DCSR_CAUSE_HALT     5
+
+#define MCONTROL_TYPE(xlen)    (0xfULL<<((xlen)-4))
+#define MCONTROL_DMODE(xlen)   (1ULL<<((xlen)-5))
+#define MCONTROL_MASKMAX(xlen) (0x3fULL<<((xlen)-11))
+
+#define MCONTROL_SELECT     (1<<19)
+#define MCONTROL_TIMING     (1<<18)
+#define MCONTROL_ACTION     (0x3f<<12)
+#define MCONTROL_CHAIN      (1<<11)
+#define MCONTROL_MATCH      (0xf<<7)
+#define MCONTROL_M          (1<<6)
+#define MCONTROL_H          (1<<5)
+#define MCONTROL_S          (1<<4)
+#define MCONTROL_U          (1<<3)
+#define MCONTROL_EXECUTE    (1<<2)
+#define MCONTROL_STORE      (1<<1)
+#define MCONTROL_LOAD       (1<<0)
+
+#define MCONTROL_TYPE_NONE      0
+#define MCONTROL_TYPE_MATCH     2
+
+#define MCONTROL_ACTION_DEBUG_EXCEPTION   0
+#define MCONTROL_ACTION_DEBUG_MODE        1
+#define MCONTROL_ACTION_TRACE_START       2
+#define MCONTROL_ACTION_TRACE_STOP        3
+#define MCONTROL_ACTION_TRACE_EMIT        4
+
+#define MCONTROL_MATCH_EQUAL     0
+#define MCONTROL_MATCH_NAPOT     1
+#define MCONTROL_MATCH_GE        2
+#define MCONTROL_MATCH_LT        3
+#define MCONTROL_MATCH_MASK_LOW  4
+#define MCONTROL_MATCH_MASK_HIGH 5
+
+#define MIP_SSIP            (1 << IRQ_S_SOFT)
+#define MIP_HSIP            (1 << IRQ_H_SOFT)
+#define MIP_MSIP            (1 << IRQ_M_SOFT)
+#define MIP_STIP            (1 << IRQ_S_TIMER)
+#define MIP_HTIP            (1 << IRQ_H_TIMER)
+#define MIP_MTIP            (1 << IRQ_M_TIMER)
+#define MIP_SEIP            (1 << IRQ_S_EXT)
+#define MIP_HEIP            (1 << IRQ_H_EXT)
+#define MIP_MEIP            (1 << IRQ_M_EXT)
+
+#define SIP_SSIP MIP_SSIP
+#define SIP_STIP MIP_STIP
+
+#define PRV_U 0
+#define PRV_S 1
+#define PRV_H 2
+#define PRV_M 3
+
+#define VM_MBARE 0
+#define VM_MBB   1
+#define VM_MBBID 2
+#define VM_SV32  8
+#define VM_SV39  9
+#define VM_SV48  10
+
+#define IRQ_S_SOFT   1
+#define IRQ_H_SOFT   2
+#define IRQ_M_SOFT   3
+#define IRQ_S_TIMER  5
+#define IRQ_H_TIMER  6
+#define IRQ_M_TIMER  7
+#define IRQ_S_EXT    9
+#define IRQ_H_EXT    10
+#define IRQ_M_EXT    11
+#define IRQ_COP      12
+#define IRQ_HOST     13
+
+#define DEFAULT_RSTVEC     0x00001000
+#define DEFAULT_NMIVEC     0x00001004
+#define DEFAULT_MTVEC      0x00001010
+#define CONFIG_STRING_ADDR 0x0000100C
+#define EXT_IO_BASE        0x40000000
+#define DRAM_BASE          0x80000000
+
+// page table entry (PTE) fields
+#define PTE_V     0x001 // Valid
+#define PTE_R     0x002 // Read
+#define PTE_W     0x004 // Write
+#define PTE_X     0x008 // Execute
+#define PTE_U     0x010 // User
+#define PTE_G     0x020 // Global
+#define PTE_A     0x040 // Accessed
+#define PTE_D     0x080 // Dirty
+#define PTE_SOFT  0x300 // Reserved for Software
+
+#define PTE_PPN_SHIFT 10
+
+#define PTE_TABLE(PTE) (((PTE) & (PTE_V | PTE_R | PTE_W | PTE_X)) == PTE_V)
+
+#ifdef __riscv
+
+#ifdef __riscv64
+# define MSTATUS_SD MSTATUS64_SD
+# define SSTATUS_SD SSTATUS64_SD
+# define RISCV_PGLEVEL_BITS 9
+#else
+# define MSTATUS_SD MSTATUS32_SD
+# define SSTATUS_SD SSTATUS32_SD
+# define RISCV_PGLEVEL_BITS 10
+#endif
+#define RISCV_PGSHIFT 12
+#define RISCV_PGSIZE (1 << RISCV_PGSHIFT)
+
+#ifndef __ASSEMBLER__
+
+#ifdef __GNUC__
+
+#define read_csr(reg) ({ unsigned long __tmp; \
+  asm volatile ("csrr %0, " #reg : "=r"(__tmp)); \
+  __tmp; })
+
+#define write_csr(reg, val) ({ \
+  if (__builtin_constant_p(val) && (unsigned long)(val) < 32) \
+    asm volatile ("csrw " #reg ", %0" :: "i"(val)); \
+  else \
+    asm volatile ("csrw " #reg ", %0" :: "r"(val)); })
+
+#define swap_csr(reg, val) ({ unsigned long __tmp; \
+  if (__builtin_constant_p(val) && (unsigned long)(val) < 32) \
+    asm volatile ("csrrw %0, " #reg ", %1" : "=r"(__tmp) : "i"(val)); \
+  else \
+    asm volatile ("csrrw %0, " #reg ", %1" : "=r"(__tmp) : "r"(val)); \
+  __tmp; })
+
+#define set_csr(reg, bit) ({ unsigned long __tmp; \
+  if (__builtin_constant_p(bit) && (unsigned long)(bit) < 32) \
+    asm volatile ("csrrs %0, " #reg ", %1" : "=r"(__tmp) : "i"(bit)); \
+  else \
+    asm volatile ("csrrs %0, " #reg ", %1" : "=r"(__tmp) : "r"(bit)); \
+  __tmp; })
+
+#define clear_csr(reg, bit) ({ unsigned long __tmp; \
+  if (__builtin_constant_p(bit) && (unsigned long)(bit) < 32) \
+    asm volatile ("csrrc %0, " #reg ", %1" : "=r"(__tmp) : "i"(bit)); \
+  else \
+    asm volatile ("csrrc %0, " #reg ", %1" : "=r"(__tmp) : "r"(bit)); \
+  __tmp; })
+
+#define rdtime() read_csr(time)
+#define rdcycle() read_csr(cycle)
+#define rdinstret() read_csr(instret)
+
+#endif
+
+#endif
+
+#endif
+
+#endif
+/* Automatically generated by parse-opcodes */
+#ifndef RISCV_ENCODING_H
+#define RISCV_ENCODING_H
+#define MATCH_BEQ 0x63
+#define MASK_BEQ  0x707f
+#define MATCH_BNE 0x1063
+#define MASK_BNE  0x707f
+#define MATCH_BLT 0x4063
+#define MASK_BLT  0x707f
+#define MATCH_BGE 0x5063
+#define MASK_BGE  0x707f
+#define MATCH_BLTU 0x6063
+#define MASK_BLTU  0x707f
+#define MATCH_BGEU 0x7063
+#define MASK_BGEU  0x707f
+#define MATCH_JALR 0x67
+#define MASK_JALR  0x707f
+#define MATCH_JAL 0x6f
+#define MASK_JAL  0x7f
+#define MATCH_LUI 0x37
+#define MASK_LUI  0x7f
+#define MATCH_AUIPC 0x17
+#define MASK_AUIPC  0x7f
+#define MATCH_ADDI 0x13
+#define MASK_ADDI  0x707f
+#define MATCH_SLLI 0x1013
+#define MASK_SLLI  0xfc00707f
+#define MATCH_SLTI 0x2013
+#define MASK_SLTI  0x707f
+#define MATCH_SLTIU 0x3013
+#define MASK_SLTIU  0x707f
+#define MATCH_XORI 0x4013
+#define MASK_XORI  0x707f
+#define MATCH_SRLI 0x5013
+#define MASK_SRLI  0xfc00707f
+#define MATCH_SRAI 0x40005013
+#define MASK_SRAI  0xfc00707f
+#define MATCH_ORI 0x6013
+#define MASK_ORI  0x707f
+#define MATCH_ANDI 0x7013
+#define MASK_ANDI  0x707f
+#define MATCH_ADD 0x33
+#define MASK_ADD  0xfe00707f
+#define MATCH_SUB 0x40000033
+#define MASK_SUB  0xfe00707f
+#define MATCH_SLL 0x1033
+#define MASK_SLL  0xfe00707f
+#define MATCH_SLT 0x2033
+#define MASK_SLT  0xfe00707f
+#define MATCH_SLTU 0x3033
+#define MASK_SLTU  0xfe00707f
+#define MATCH_XOR 0x4033
+#define MASK_XOR  0xfe00707f
+#define MATCH_SRL 0x5033
+#define MASK_SRL  0xfe00707f
+#define MATCH_SRA 0x40005033
+#define MASK_SRA  0xfe00707f
+#define MATCH_OR 0x6033
+#define MASK_OR  0xfe00707f
+#define MATCH_AND 0x7033
+#define MASK_AND  0xfe00707f
+#define MATCH_ADDIW 0x1b
+#define MASK_ADDIW  0x707f
+#define MATCH_SLLIW 0x101b
+#define MASK_SLLIW  0xfe00707f
+#define MATCH_SRLIW 0x501b
+#define MASK_SRLIW  0xfe00707f
+#define MATCH_SRAIW 0x4000501b
+#define MASK_SRAIW  0xfe00707f
+#define MATCH_ADDW 0x3b
+#define MASK_ADDW  0xfe00707f
+#define MATCH_SUBW 0x4000003b
+#define MASK_SUBW  0xfe00707f
+#define MATCH_SLLW 0x103b
+#define MASK_SLLW  0xfe00707f
+#define MATCH_SRLW 0x503b
+#define MASK_SRLW  0xfe00707f
+#define MATCH_SRAW 0x4000503b
+#define MASK_SRAW  0xfe00707f
+#define MATCH_LB 0x3
+#define MASK_LB  0x707f
+#define MATCH_LH 0x1003
+#define MASK_LH  0x707f
+#define MATCH_LW 0x2003
+#define MASK_LW  0x707f
+#define MATCH_LD 0x3003
+#define MASK_LD  0x707f
+#define MATCH_LBU 0x4003
+#define MASK_LBU  0x707f
+#define MATCH_LHU 0x5003
+#define MASK_LHU  0x707f
+#define MATCH_LWU 0x6003
+#define MASK_LWU  0x707f
+#define MATCH_SB 0x23
+#define MASK_SB  0x707f
+#define MATCH_SH 0x1023
+#define MASK_SH  0x707f
+#define MATCH_SW 0x2023
+#define MASK_SW  0x707f
+#define MATCH_SD 0x3023
+#define MASK_SD  0x707f
+#define MATCH_FENCE 0xf
+#define MASK_FENCE  0x707f
+#define MATCH_FENCE_I 0x100f
+#define MASK_FENCE_I  0x707f
+#define MATCH_MUL 0x2000033
+#define MASK_MUL  0xfe00707f
+#define MATCH_MULH 0x2001033
+#define MASK_MULH  0xfe00707f
+#define MATCH_MULHSU 0x2002033
+#define MASK_MULHSU  0xfe00707f
+#define MATCH_MULHU 0x2003033
+#define MASK_MULHU  0xfe00707f
+#define MATCH_DIV 0x2004033
+#define MASK_DIV  0xfe00707f
+#define MATCH_DIVU 0x2005033
+#define MASK_DIVU  0xfe00707f
+#define MATCH_REM 0x2006033
+#define MASK_REM  0xfe00707f
+#define MATCH_REMU 0x2007033
+#define MASK_REMU  0xfe00707f
+#define MATCH_MULW 0x200003b
+#define MASK_MULW  0xfe00707f
+#define MATCH_DIVW 0x200403b
+#define MASK_DIVW  0xfe00707f
+#define MATCH_DIVUW 0x200503b
+#define MASK_DIVUW  0xfe00707f
+#define MATCH_REMW 0x200603b
+#define MASK_REMW  0xfe00707f
+#define MATCH_REMUW 0x200703b
+#define MASK_REMUW  0xfe00707f
+#define MATCH_AMOADD_W 0x202f
+#define MASK_AMOADD_W  0xf800707f
+#define MATCH_AMOXOR_W 0x2000202f
+#define MASK_AMOXOR_W  0xf800707f
+#define MATCH_AMOOR_W 0x4000202f
+#define MASK_AMOOR_W  0xf800707f
+#define MATCH_AMOAND_W 0x6000202f
+#define MASK_AMOAND_W  0xf800707f
+#define MATCH_AMOMIN_W 0x8000202f
+#define MASK_AMOMIN_W  0xf800707f
+#define MATCH_AMOMAX_W 0xa000202f
+#define MASK_AMOMAX_W  0xf800707f
+#define MATCH_AMOMINU_W 0xc000202f
+#define MASK_AMOMINU_W  0xf800707f
+#define MATCH_AMOMAXU_W 0xe000202f
+#define MASK_AMOMAXU_W  0xf800707f
+#define MATCH_AMOSWAP_W 0x800202f
+#define MASK_AMOSWAP_W  0xf800707f
+#define MATCH_LR_W 0x1000202f
+#define MASK_LR_W  0xf9f0707f
+#define MATCH_SC_W 0x1800202f
+#define MASK_SC_W  0xf800707f
+#define MATCH_AMOADD_D 0x302f
+#define MASK_AMOADD_D  0xf800707f
+#define MATCH_AMOXOR_D 0x2000302f
+#define MASK_AMOXOR_D  0xf800707f
+#define MATCH_AMOOR_D 0x4000302f
+#define MASK_AMOOR_D  0xf800707f
+#define MATCH_AMOAND_D 0x6000302f
+#define MASK_AMOAND_D  0xf800707f
+#define MATCH_AMOMIN_D 0x8000302f
+#define MASK_AMOMIN_D  0xf800707f
+#define MATCH_AMOMAX_D 0xa000302f
+#define MASK_AMOMAX_D  0xf800707f
+#define MATCH_AMOMINU_D 0xc000302f
+#define MASK_AMOMINU_D  0xf800707f
+#define MATCH_AMOMAXU_D 0xe000302f
+#define MASK_AMOMAXU_D  0xf800707f
+#define MATCH_AMOSWAP_D 0x800302f
+#define MASK_AMOSWAP_D  0xf800707f
+#define MATCH_LR_D 0x1000302f
+#define MASK_LR_D  0xf9f0707f
+#define MATCH_SC_D 0x1800302f
+#define MASK_SC_D  0xf800707f
+#define MATCH_ECALL 0x73
+#define MASK_ECALL  0xffffffff
+#define MATCH_EBREAK 0x100073
+#define MASK_EBREAK  0xffffffff
+#define MATCH_URET 0x200073
+#define MASK_URET  0xffffffff
+#define MATCH_SRET 0x10200073
+#define MASK_SRET  0xffffffff
+#define MATCH_HRET 0x20200073
+#define MASK_HRET  0xffffffff
+#define MATCH_MRET 0x30200073
+#define MASK_MRET  0xffffffff
+#define MATCH_DRET 0x7b200073
+#define MASK_DRET  0xffffffff
+#define MATCH_SFENCE_VM 0x10400073
+#define MASK_SFENCE_VM  0xfff07fff
+#define MATCH_WFI 0x10500073
+#define MASK_WFI  0xffffffff
+#define MATCH_CSRRW 0x1073
+#define MASK_CSRRW  0x707f
+#define MATCH_CSRRS 0x2073
+#define MASK_CSRRS  0x707f
+#define MATCH_CSRRC 0x3073
+#define MASK_CSRRC  0x707f
+#define MATCH_CSRRWI 0x5073
+#define MASK_CSRRWI  0x707f
+#define MATCH_CSRRSI 0x6073
+#define MASK_CSRRSI  0x707f
+#define MATCH_CSRRCI 0x7073
+#define MASK_CSRRCI  0x707f
+#define MATCH_FADD_S 0x53
+#define MASK_FADD_S  0xfe00007f
+#define MATCH_FSUB_S 0x8000053
+#define MASK_FSUB_S  0xfe00007f
+#define MATCH_FMUL_S 0x10000053
+#define MASK_FMUL_S  0xfe00007f
+#define MATCH_FDIV_S 0x18000053
+#define MASK_FDIV_S  0xfe00007f
+#define MATCH_FSGNJ_S 0x20000053
+#define MASK_FSGNJ_S  0xfe00707f
+#define MATCH_FSGNJN_S 0x20001053
+#define MASK_FSGNJN_S  0xfe00707f
+#define MATCH_FSGNJX_S 0x20002053
+#define MASK_FSGNJX_S  0xfe00707f
+#define MATCH_FMIN_S 0x28000053
+#define MASK_FMIN_S  0xfe00707f
+#define MATCH_FMAX_S 0x28001053
+#define MASK_FMAX_S  0xfe00707f
+#define MATCH_FSQRT_S 0x58000053
+#define MASK_FSQRT_S  0xfff0007f
+#define MATCH_FADD_D 0x2000053
+#define MASK_FADD_D  0xfe00007f
+#define MATCH_FSUB_D 0xa000053
+#define MASK_FSUB_D  0xfe00007f
+#define MATCH_FMUL_D 0x12000053
+#define MASK_FMUL_D  0xfe00007f
+#define MATCH_FDIV_D 0x1a000053
+#define MASK_FDIV_D  0xfe00007f
+#define MATCH_FSGNJ_D 0x22000053
+#define MASK_FSGNJ_D  0xfe00707f
+#define MATCH_FSGNJN_D 0x22001053
+#define MASK_FSGNJN_D  0xfe00707f
+#define MATCH_FSGNJX_D 0x22002053
+#define MASK_FSGNJX_D  0xfe00707f
+#define MATCH_FMIN_D 0x2a000053
+#define MASK_FMIN_D  0xfe00707f
+#define MATCH_FMAX_D 0x2a001053
+#define MASK_FMAX_D  0xfe00707f
+#define MATCH_FCVT_S_D 0x40100053
+#define MASK_FCVT_S_D  0xfff0007f
+#define MATCH_FCVT_D_S 0x42000053
+#define MASK_FCVT_D_S  0xfff0007f
+#define MATCH_FSQRT_D 0x5a000053
+#define MASK_FSQRT_D  0xfff0007f
+#define MATCH_FLE_S 0xa0000053
+#define MASK_FLE_S  0xfe00707f
+#define MATCH_FLT_S 0xa0001053
+#define MASK_FLT_S  0xfe00707f
+#define MATCH_FEQ_S 0xa0002053
+#define MASK_FEQ_S  0xfe00707f
+#define MATCH_FLE_D 0xa2000053
+#define MASK_FLE_D  0xfe00707f
+#define MATCH_FLT_D 0xa2001053
+#define MASK_FLT_D  0xfe00707f
+#define MATCH_FEQ_D 0xa2002053
+#define MASK_FEQ_D  0xfe00707f
+#define MATCH_FCVT_W_S 0xc0000053
+#define MASK_FCVT_W_S  0xfff0007f
+#define MATCH_FCVT_WU_S 0xc0100053
+#define MASK_FCVT_WU_S  0xfff0007f
+#define MATCH_FCVT_L_S 0xc0200053
+#define MASK_FCVT_L_S  0xfff0007f
+#define MATCH_FCVT_LU_S 0xc0300053
+#define MASK_FCVT_LU_S  0xfff0007f
+#define MATCH_FMV_X_S 0xe0000053
+#define MASK_FMV_X_S  0xfff0707f
+#define MATCH_FCLASS_S 0xe0001053
+#define MASK_FCLASS_S  0xfff0707f
+#define MATCH_FCVT_W_D 0xc2000053
+#define MASK_FCVT_W_D  0xfff0007f
+#define MATCH_FCVT_WU_D 0xc2100053
+#define MASK_FCVT_WU_D  0xfff0007f
+#define MATCH_FCVT_L_D 0xc2200053
+#define MASK_FCVT_L_D  0xfff0007f
+#define MATCH_FCVT_LU_D 0xc2300053
+#define MASK_FCVT_LU_D  0xfff0007f
+#define MATCH_FMV_X_D 0xe2000053
+#define MASK_FMV_X_D  0xfff0707f
+#define MATCH_FCLASS_D 0xe2001053
+#define MASK_FCLASS_D  0xfff0707f
+#define MATCH_FCVT_S_W 0xd0000053
+#define MASK_FCVT_S_W  0xfff0007f
+#define MATCH_FCVT_S_WU 0xd0100053
+#define MASK_FCVT_S_WU  0xfff0007f
+#define MATCH_FCVT_S_L 0xd0200053
+#define MASK_FCVT_S_L  0xfff0007f
+#define MATCH_FCVT_S_LU 0xd0300053
+#define MASK_FCVT_S_LU  0xfff0007f
+#define MATCH_FMV_S_X 0xf0000053
+#define MASK_FMV_S_X  0xfff0707f
+#define MATCH_FCVT_D_W 0xd2000053
+#define MASK_FCVT_D_W  0xfff0007f
+#define MATCH_FCVT_D_WU 0xd2100053
+#define MASK_FCVT_D_WU  0xfff0007f
+#define MATCH_FCVT_D_L 0xd2200053
+#define MASK_FCVT_D_L  0xfff0007f
+#define MATCH_FCVT_D_LU 0xd2300053
+#define MASK_FCVT_D_LU  0xfff0007f
+#define MATCH_FMV_D_X 0xf2000053
+#define MASK_FMV_D_X  0xfff0707f
+#define MATCH_FLW 0x2007
+#define MASK_FLW  0x707f
+#define MATCH_FLD 0x3007
+#define MASK_FLD  0x707f
+#define MATCH_FSW 0x2027
+#define MASK_FSW  0x707f
+#define MATCH_FSD 0x3027
+#define MASK_FSD  0x707f
+#define MATCH_FMADD_S 0x43
+#define MASK_FMADD_S  0x600007f
+#define MATCH_FMSUB_S 0x47
+#define MASK_FMSUB_S  0x600007f
+#define MATCH_FNMSUB_S 0x4b
+#define MASK_FNMSUB_S  0x600007f
+#define MATCH_FNMADD_S 0x4f
+#define MASK_FNMADD_S  0x600007f
+#define MATCH_FMADD_D 0x2000043
+#define MASK_FMADD_D  0x600007f
+#define MATCH_FMSUB_D 0x2000047
+#define MASK_FMSUB_D  0x600007f
+#define MATCH_FNMSUB_D 0x200004b
+#define MASK_FNMSUB_D  0x600007f
+#define MATCH_FNMADD_D 0x200004f
+#define MASK_FNMADD_D  0x600007f
+#define MATCH_C_NOP 0x1
+#define MASK_C_NOP  0xffff
+#define MATCH_C_ADDI16SP 0x6101
+#define MASK_C_ADDI16SP  0xef83
+#define MATCH_C_JR 0x8002
+#define MASK_C_JR  0xf07f
+#define MATCH_C_JALR 0x9002
+#define MASK_C_JALR  0xf07f
+#define MATCH_C_EBREAK 0x9002
+#define MASK_C_EBREAK  0xffff
+#define MATCH_C_LD 0x6000
+#define MASK_C_LD  0xe003
+#define MATCH_C_SD 0xe000
+#define MASK_C_SD  0xe003
+#define MATCH_C_ADDIW 0x2001
+#define MASK_C_ADDIW  0xe003
+#define MATCH_C_LDSP 0x6002
+#define MASK_C_LDSP  0xe003
+#define MATCH_C_SDSP 0xe002
+#define MASK_C_SDSP  0xe003
+#define MATCH_C_ADDI4SPN 0x0
+#define MASK_C_ADDI4SPN  0xe003
+#define MATCH_C_FLD 0x2000
+#define MASK_C_FLD  0xe003
+#define MATCH_C_LW 0x4000
+#define MASK_C_LW  0xe003
+#define MATCH_C_FLW 0x6000
+#define MASK_C_FLW  0xe003
+#define MATCH_C_FSD 0xa000
+#define MASK_C_FSD  0xe003
+#define MATCH_C_SW 0xc000
+#define MASK_C_SW  0xe003
+#define MATCH_C_FSW 0xe000
+#define MASK_C_FSW  0xe003
+#define MATCH_C_ADDI 0x1
+#define MASK_C_ADDI  0xe003
+#define MATCH_C_JAL 0x2001
+#define MASK_C_JAL  0xe003
+#define MATCH_C_LI 0x4001
+#define MASK_C_LI  0xe003
+#define MATCH_C_LUI 0x6001
+#define MASK_C_LUI  0xe003
+#define MATCH_C_SRLI 0x8001
+#define MASK_C_SRLI  0xec03
+#define MATCH_C_SRAI 0x8401
+#define MASK_C_SRAI  0xec03
+#define MATCH_C_ANDI 0x8801
+#define MASK_C_ANDI  0xec03
+#define MATCH_C_SUB 0x8c01
+#define MASK_C_SUB  0xfc63
+#define MATCH_C_XOR 0x8c21
+#define MASK_C_XOR  0xfc63
+#define MATCH_C_OR 0x8c41
+#define MASK_C_OR  0xfc63
+#define MATCH_C_AND 0x8c61
+#define MASK_C_AND  0xfc63
+#define MATCH_C_SUBW 0x9c01
+#define MASK_C_SUBW  0xfc63
+#define MATCH_C_ADDW 0x9c21
+#define MASK_C_ADDW  0xfc63
+#define MATCH_C_J 0xa001
+#define MASK_C_J  0xe003
+#define MATCH_C_BEQZ 0xc001
+#define MASK_C_BEQZ  0xe003
+#define MATCH_C_BNEZ 0xe001
+#define MASK_C_BNEZ  0xe003
+#define MATCH_C_SLLI 0x2
+#define MASK_C_SLLI  0xe003
+#define MATCH_C_FLDSP 0x2002
+#define MASK_C_FLDSP  0xe003
+#define MATCH_C_LWSP 0x4002
+#define MASK_C_LWSP  0xe003
+#define MATCH_C_FLWSP 0x6002
+#define MASK_C_FLWSP  0xe003
+#define MATCH_C_MV 0x8002
+#define MASK_C_MV  0xf003
+#define MATCH_C_ADD 0x9002
+#define MASK_C_ADD  0xf003
+#define MATCH_C_FSDSP 0xa002
+#define MASK_C_FSDSP  0xe003
+#define MATCH_C_SWSP 0xc002
+#define MASK_C_SWSP  0xe003
+#define MATCH_C_FSWSP 0xe002
+#define MASK_C_FSWSP  0xe003
+#define MATCH_CUSTOM0 0xb
+#define MASK_CUSTOM0  0x707f
+#define MATCH_CUSTOM0_RS1 0x200b
+#define MASK_CUSTOM0_RS1  0x707f
+#define MATCH_CUSTOM0_RS1_RS2 0x300b
+#define MASK_CUSTOM0_RS1_RS2  0x707f
+#define MATCH_CUSTOM0_RD 0x400b
+#define MASK_CUSTOM0_RD  0x707f
+#define MATCH_CUSTOM0_RD_RS1 0x600b
+#define MASK_CUSTOM0_RD_RS1  0x707f
+#define MATCH_CUSTOM0_RD_RS1_RS2 0x700b
+#define MASK_CUSTOM0_RD_RS1_RS2  0x707f
+#define MATCH_CUSTOM1 0x2b
+#define MASK_CUSTOM1  0x707f
+#define MATCH_CUSTOM1_RS1 0x202b
+#define MASK_CUSTOM1_RS1  0x707f
+#define MATCH_CUSTOM1_RS1_RS2 0x302b
+#define MASK_CUSTOM1_RS1_RS2  0x707f
+#define MATCH_CUSTOM1_RD 0x402b
+#define MASK_CUSTOM1_RD  0x707f
+#define MATCH_CUSTOM1_RD_RS1 0x602b
+#define MASK_CUSTOM1_RD_RS1  0x707f
+#define MATCH_CUSTOM1_RD_RS1_RS2 0x702b
+#define MASK_CUSTOM1_RD_RS1_RS2  0x707f
+#define MATCH_CUSTOM2 0x5b
+#define MASK_CUSTOM2  0x707f
+#define MATCH_CUSTOM2_RS1 0x205b
+#define MASK_CUSTOM2_RS1  0x707f
+#define MATCH_CUSTOM2_RS1_RS2 0x305b
+#define MASK_CUSTOM2_RS1_RS2  0x707f
+#define MATCH_CUSTOM2_RD 0x405b
+#define MASK_CUSTOM2_RD  0x707f
+#define MATCH_CUSTOM2_RD_RS1 0x605b
+#define MASK_CUSTOM2_RD_RS1  0x707f
+#define MATCH_CUSTOM2_RD_RS1_RS2 0x705b
+#define MASK_CUSTOM2_RD_RS1_RS2  0x707f
+#define MATCH_CUSTOM3 0x7b
+#define MASK_CUSTOM3  0x707f
+#define MATCH_CUSTOM3_RS1 0x207b
+#define MASK_CUSTOM3_RS1  0x707f
+#define MATCH_CUSTOM3_RS1_RS2 0x307b
+#define MASK_CUSTOM3_RS1_RS2  0x707f
+#define MATCH_CUSTOM3_RD 0x407b
+#define MASK_CUSTOM3_RD  0x707f
+#define MATCH_CUSTOM3_RD_RS1 0x607b
+#define MASK_CUSTOM3_RD_RS1  0x707f
+#define MATCH_CUSTOM3_RD_RS1_RS2 0x707b
+#define MASK_CUSTOM3_RD_RS1_RS2  0x707f
+#define CSR_FFLAGS 0x1
+#define CSR_FRM 0x2
+#define CSR_FCSR 0x3
+#define CSR_CYCLE 0xc00
+#define CSR_TIME 0xc01
+#define CSR_INSTRET 0xc02
+#define CSR_HPMCOUNTER3 0xc03
+#define CSR_HPMCOUNTER4 0xc04
+#define CSR_HPMCOUNTER5 0xc05
+#define CSR_HPMCOUNTER6 0xc06
+#define CSR_HPMCOUNTER7 0xc07
+#define CSR_HPMCOUNTER8 0xc08
+#define CSR_HPMCOUNTER9 0xc09
+#define CSR_HPMCOUNTER10 0xc0a
+#define CSR_HPMCOUNTER11 0xc0b
+#define CSR_HPMCOUNTER12 0xc0c
+#define CSR_HPMCOUNTER13 0xc0d
+#define CSR_HPMCOUNTER14 0xc0e
+#define CSR_HPMCOUNTER15 0xc0f
+#define CSR_HPMCOUNTER16 0xc10
+#define CSR_HPMCOUNTER17 0xc11
+#define CSR_HPMCOUNTER18 0xc12
+#define CSR_HPMCOUNTER19 0xc13
+#define CSR_HPMCOUNTER20 0xc14
+#define CSR_HPMCOUNTER21 0xc15
+#define CSR_HPMCOUNTER22 0xc16
+#define CSR_HPMCOUNTER23 0xc17
+#define CSR_HPMCOUNTER24 0xc18
+#define CSR_HPMCOUNTER25 0xc19
+#define CSR_HPMCOUNTER26 0xc1a
+#define CSR_HPMCOUNTER27 0xc1b
+#define CSR_HPMCOUNTER28 0xc1c
+#define CSR_HPMCOUNTER29 0xc1d
+#define CSR_HPMCOUNTER30 0xc1e
+#define CSR_HPMCOUNTER31 0xc1f
+#define CSR_SSTATUS 0x100
+#define CSR_SIE 0x104
+#define CSR_STVEC 0x105
+#define CSR_SSCRATCH 0x140
+#define CSR_SEPC 0x141
+#define CSR_SCAUSE 0x142
+#define CSR_SBADADDR 0x143
+#define CSR_SIP 0x144
+#define CSR_SPTBR 0x180
+#define CSR_MSTATUS 0x300
+#define CSR_MISA 0x301
+#define CSR_MEDELEG 0x302
+#define CSR_MIDELEG 0x303
+#define CSR_MIE 0x304
+#define CSR_MTVEC 0x305
+#define CSR_MSCRATCH 0x340
+#define CSR_MEPC 0x341
+#define CSR_MCAUSE 0x342
+#define CSR_MBADADDR 0x343
+#define CSR_MIP 0x344
+#define CSR_TSELECT 0x7a0
+#define CSR_TDATA1 0x7a1
+#define CSR_TDATA2 0x7a2
+#define CSR_TDATA3 0x7a3
+#define CSR_DCSR 0x7b0
+#define CSR_DPC 0x7b1
+#define CSR_DSCRATCH 0x7b2
+#define CSR_MCYCLE 0xb00
+#define CSR_MINSTRET 0xb02
+#define CSR_MHPMCOUNTER3 0xb03
+#define CSR_MHPMCOUNTER4 0xb04
+#define CSR_MHPMCOUNTER5 0xb05
+#define CSR_MHPMCOUNTER6 0xb06
+#define CSR_MHPMCOUNTER7 0xb07
+#define CSR_MHPMCOUNTER8 0xb08
+#define CSR_MHPMCOUNTER9 0xb09
+#define CSR_MHPMCOUNTER10 0xb0a
+#define CSR_MHPMCOUNTER11 0xb0b
+#define CSR_MHPMCOUNTER12 0xb0c
+#define CSR_MHPMCOUNTER13 0xb0d
+#define CSR_MHPMCOUNTER14 0xb0e
+#define CSR_MHPMCOUNTER15 0xb0f
+#define CSR_MHPMCOUNTER16 0xb10
+#define CSR_MHPMCOUNTER17 0xb11
+#define CSR_MHPMCOUNTER18 0xb12
+#define CSR_MHPMCOUNTER19 0xb13
+#define CSR_MHPMCOUNTER20 0xb14
+#define CSR_MHPMCOUNTER21 0xb15
+#define CSR_MHPMCOUNTER22 0xb16
+#define CSR_MHPMCOUNTER23 0xb17
+#define CSR_MHPMCOUNTER24 0xb18
+#define CSR_MHPMCOUNTER25 0xb19
+#define CSR_MHPMCOUNTER26 0xb1a
+#define CSR_MHPMCOUNTER27 0xb1b
+#define CSR_MHPMCOUNTER28 0xb1c
+#define CSR_MHPMCOUNTER29 0xb1d
+#define CSR_MHPMCOUNTER30 0xb1e
+#define CSR_MHPMCOUNTER31 0xb1f
+#define CSR_MUCOUNTEREN 0x320
+#define CSR_MSCOUNTEREN 0x321
+#define CSR_MHPMEVENT3 0x323
+#define CSR_MHPMEVENT4 0x324
+#define CSR_MHPMEVENT5 0x325
+#define CSR_MHPMEVENT6 0x326
+#define CSR_MHPMEVENT7 0x327
+#define CSR_MHPMEVENT8 0x328
+#define CSR_MHPMEVENT9 0x329
+#define CSR_MHPMEVENT10 0x32a
+#define CSR_MHPMEVENT11 0x32b
+#define CSR_MHPMEVENT12 0x32c
+#define CSR_MHPMEVENT13 0x32d
+#define CSR_MHPMEVENT14 0x32e
+#define CSR_MHPMEVENT15 0x32f
+#define CSR_MHPMEVENT16 0x330
+#define CSR_MHPMEVENT17 0x331
+#define CSR_MHPMEVENT18 0x332
+#define CSR_MHPMEVENT19 0x333
+#define CSR_MHPMEVENT20 0x334
+#define CSR_MHPMEVENT21 0x335
+#define CSR_MHPMEVENT22 0x336
+#define CSR_MHPMEVENT23 0x337
+#define CSR_MHPMEVENT24 0x338
+#define CSR_MHPMEVENT25 0x339
+#define CSR_MHPMEVENT26 0x33a
+#define CSR_MHPMEVENT27 0x33b
+#define CSR_MHPMEVENT28 0x33c
+#define CSR_MHPMEVENT29 0x33d
+#define CSR_MHPMEVENT30 0x33e
+#define CSR_MHPMEVENT31 0x33f
+#define CSR_MVENDORID 0xf11
+#define CSR_MARCHID 0xf12
+#define CSR_MIMPID 0xf13
+#define CSR_MHARTID 0xf14
+#define CSR_CYCLEH 0xc80
+#define CSR_TIMEH 0xc81
+#define CSR_INSTRETH 0xc82
+#define CSR_HPMCOUNTER3H 0xc83
+#define CSR_HPMCOUNTER4H 0xc84
+#define CSR_HPMCOUNTER5H 0xc85
+#define CSR_HPMCOUNTER6H 0xc86
+#define CSR_HPMCOUNTER7H 0xc87
+#define CSR_HPMCOUNTER8H 0xc88
+#define CSR_HPMCOUNTER9H 0xc89
+#define CSR_HPMCOUNTER10H 0xc8a
+#define CSR_HPMCOUNTER11H 0xc8b
+#define CSR_HPMCOUNTER12H 0xc8c
+#define CSR_HPMCOUNTER13H 0xc8d
+#define CSR_HPMCOUNTER14H 0xc8e
+#define CSR_HPMCOUNTER15H 0xc8f
+#define CSR_HPMCOUNTER16H 0xc90
+#define CSR_HPMCOUNTER17H 0xc91
+#define CSR_HPMCOUNTER18H 0xc92
+#define CSR_HPMCOUNTER19H 0xc93
+#define CSR_HPMCOUNTER20H 0xc94
+#define CSR_HPMCOUNTER21H 0xc95
+#define CSR_HPMCOUNTER22H 0xc96
+#define CSR_HPMCOUNTER23H 0xc97
+#define CSR_HPMCOUNTER24H 0xc98
+#define CSR_HPMCOUNTER25H 0xc99
+#define CSR_HPMCOUNTER26H 0xc9a
+#define CSR_HPMCOUNTER27H 0xc9b
+#define CSR_HPMCOUNTER28H 0xc9c
+#define CSR_HPMCOUNTER29H 0xc9d
+#define CSR_HPMCOUNTER30H 0xc9e
+#define CSR_HPMCOUNTER31H 0xc9f
+#define CSR_MCYCLEH 0xb80
+#define CSR_MINSTRETH 0xb82
+#define CSR_MHPMCOUNTER3H 0xb83
+#define CSR_MHPMCOUNTER4H 0xb84
+#define CSR_MHPMCOUNTER5H 0xb85
+#define CSR_MHPMCOUNTER6H 0xb86
+#define CSR_MHPMCOUNTER7H 0xb87
+#define CSR_MHPMCOUNTER8H 0xb88
+#define CSR_MHPMCOUNTER9H 0xb89
+#define CSR_MHPMCOUNTER10H 0xb8a
+#define CSR_MHPMCOUNTER11H 0xb8b
+#define CSR_MHPMCOUNTER12H 0xb8c
+#define CSR_MHPMCOUNTER13H 0xb8d
+#define CSR_MHPMCOUNTER14H 0xb8e
+#define CSR_MHPMCOUNTER15H 0xb8f
+#define CSR_MHPMCOUNTER16H 0xb90
+#define CSR_MHPMCOUNTER17H 0xb91
+#define CSR_MHPMCOUNTER18H 0xb92
+#define CSR_MHPMCOUNTER19H 0xb93
+#define CSR_MHPMCOUNTER20H 0xb94
+#define CSR_MHPMCOUNTER21H 0xb95
+#define CSR_MHPMCOUNTER22H 0xb96
+#define CSR_MHPMCOUNTER23H 0xb97
+#define CSR_MHPMCOUNTER24H 0xb98
+#define CSR_MHPMCOUNTER25H 0xb99
+#define CSR_MHPMCOUNTER26H 0xb9a
+#define CSR_MHPMCOUNTER27H 0xb9b
+#define CSR_MHPMCOUNTER28H 0xb9c
+#define CSR_MHPMCOUNTER29H 0xb9d
+#define CSR_MHPMCOUNTER30H 0xb9e
+#define CSR_MHPMCOUNTER31H 0xb9f
+#define CAUSE_MISALIGNED_FETCH 0x0
+#define CAUSE_FAULT_FETCH 0x1
+#define CAUSE_ILLEGAL_INSTRUCTION 0x2
+#define CAUSE_BREAKPOINT 0x3
+#define CAUSE_MISALIGNED_LOAD 0x4
+#define CAUSE_FAULT_LOAD 0x5
+#define CAUSE_MISALIGNED_STORE 0x6
+#define CAUSE_FAULT_STORE 0x7
+#define CAUSE_USER_ECALL 0x8
+#define CAUSE_SUPERVISOR_ECALL 0x9
+#define CAUSE_HYPERVISOR_ECALL 0xa
+#define CAUSE_MACHINE_ECALL 0xb
+#endif
+#ifdef DECLARE_INSN
+DECLARE_INSN(beq, MATCH_BEQ, MASK_BEQ)
+DECLARE_INSN(bne, MATCH_BNE, MASK_BNE)
+DECLARE_INSN(blt, MATCH_BLT, MASK_BLT)
+DECLARE_INSN(bge, MATCH_BGE, MASK_BGE)
+DECLARE_INSN(bltu, MATCH_BLTU, MASK_BLTU)
+DECLARE_INSN(bgeu, MATCH_BGEU, MASK_BGEU)
+DECLARE_INSN(jalr, MATCH_JALR, MASK_JALR)
+DECLARE_INSN(jal, MATCH_JAL, MASK_JAL)
+DECLARE_INSN(lui, MATCH_LUI, MASK_LUI)
+DECLARE_INSN(auipc, MATCH_AUIPC, MASK_AUIPC)
+DECLARE_INSN(addi, MATCH_ADDI, MASK_ADDI)
+DECLARE_INSN(slli, MATCH_SLLI, MASK_SLLI)
+DECLARE_INSN(slti, MATCH_SLTI, MASK_SLTI)
+DECLARE_INSN(sltiu, MATCH_SLTIU, MASK_SLTIU)
+DECLARE_INSN(xori, MATCH_XORI, MASK_XORI)
+DECLARE_INSN(srli, MATCH_SRLI, MASK_SRLI)
+DECLARE_INSN(srai, MATCH_SRAI, MASK_SRAI)
+DECLARE_INSN(ori, MATCH_ORI, MASK_ORI)
+DECLARE_INSN(andi, MATCH_ANDI, MASK_ANDI)
+DECLARE_INSN(add, MATCH_ADD, MASK_ADD)
+DECLARE_INSN(sub, MATCH_SUB, MASK_SUB)
+DECLARE_INSN(sll, MATCH_SLL, MASK_SLL)
+DECLARE_INSN(slt, MATCH_SLT, MASK_SLT)
+DECLARE_INSN(sltu, MATCH_SLTU, MASK_SLTU)
+DECLARE_INSN(xor, MATCH_XOR, MASK_XOR)
+DECLARE_INSN(srl, MATCH_SRL, MASK_SRL)
+DECLARE_INSN(sra, MATCH_SRA, MASK_SRA)
+DECLARE_INSN(or, MATCH_OR, MASK_OR)
+DECLARE_INSN(and, MATCH_AND, MASK_AND)
+DECLARE_INSN(addiw, MATCH_ADDIW, MASK_ADDIW)
+DECLARE_INSN(slliw, MATCH_SLLIW, MASK_SLLIW)
+DECLARE_INSN(srliw, MATCH_SRLIW, MASK_SRLIW)
+DECLARE_INSN(sraiw, MATCH_SRAIW, MASK_SRAIW)
+DECLARE_INSN(addw, MATCH_ADDW, MASK_ADDW)
+DECLARE_INSN(subw, MATCH_SUBW, MASK_SUBW)
+DECLARE_INSN(sllw, MATCH_SLLW, MASK_SLLW)
+DECLARE_INSN(srlw, MATCH_SRLW, MASK_SRLW)
+DECLARE_INSN(sraw, MATCH_SRAW, MASK_SRAW)
+DECLARE_INSN(lb, MATCH_LB, MASK_LB)
+DECLARE_INSN(lh, MATCH_LH, MASK_LH)
+DECLARE_INSN(lw, MATCH_LW, MASK_LW)
+DECLARE_INSN(ld, MATCH_LD, MASK_LD)
+DECLARE_INSN(lbu, MATCH_LBU, MASK_LBU)
+DECLARE_INSN(lhu, MATCH_LHU, MASK_LHU)
+DECLARE_INSN(lwu, MATCH_LWU, MASK_LWU)
+DECLARE_INSN(sb, MATCH_SB, MASK_SB)
+DECLARE_INSN(sh, MATCH_SH, MASK_SH)
+DECLARE_INSN(sw, MATCH_SW, MASK_SW)
+DECLARE_INSN(sd, MATCH_SD, MASK_SD)
+DECLARE_INSN(fence, MATCH_FENCE, MASK_FENCE)
+DECLARE_INSN(fence_i, MATCH_FENCE_I, MASK_FENCE_I)
+DECLARE_INSN(mul, MATCH_MUL, MASK_MUL)
+DECLARE_INSN(mulh, MATCH_MULH, MASK_MULH)
+DECLARE_INSN(mulhsu, MATCH_MULHSU, MASK_MULHSU)
+DECLARE_INSN(mulhu, MATCH_MULHU, MASK_MULHU)
+DECLARE_INSN(div, MATCH_DIV, MASK_DIV)
+DECLARE_INSN(divu, MATCH_DIVU, MASK_DIVU)
+DECLARE_INSN(rem, MATCH_REM, MASK_REM)
+DECLARE_INSN(remu, MATCH_REMU, MASK_REMU)
+DECLARE_INSN(mulw, MATCH_MULW, MASK_MULW)
+DECLARE_INSN(divw, MATCH_DIVW, MASK_DIVW)
+DECLARE_INSN(divuw, MATCH_DIVUW, MASK_DIVUW)
+DECLARE_INSN(remw, MATCH_REMW, MASK_REMW)
+DECLARE_INSN(remuw, MATCH_REMUW, MASK_REMUW)
+DECLARE_INSN(amoadd_w, MATCH_AMOADD_W, MASK_AMOADD_W)
+DECLARE_INSN(amoxor_w, MATCH_AMOXOR_W, MASK_AMOXOR_W)
+DECLARE_INSN(amoor_w, MATCH_AMOOR_W, MASK_AMOOR_W)
+DECLARE_INSN(amoand_w, MATCH_AMOAND_W, MASK_AMOAND_W)
+DECLARE_INSN(amomin_w, MATCH_AMOMIN_W, MASK_AMOMIN_W)
+DECLARE_INSN(amomax_w, MATCH_AMOMAX_W, MASK_AMOMAX_W)
+DECLARE_INSN(amominu_w, MATCH_AMOMINU_W, MASK_AMOMINU_W)
+DECLARE_INSN(amomaxu_w, MATCH_AMOMAXU_W, MASK_AMOMAXU_W)
+DECLARE_INSN(amoswap_w, MATCH_AMOSWAP_W, MASK_AMOSWAP_W)
+DECLARE_INSN(lr_w, MATCH_LR_W, MASK_LR_W)
+DECLARE_INSN(sc_w, MATCH_SC_W, MASK_SC_W)
+DECLARE_INSN(amoadd_d, MATCH_AMOADD_D, MASK_AMOADD_D)
+DECLARE_INSN(amoxor_d, MATCH_AMOXOR_D, MASK_AMOXOR_D)
+DECLARE_INSN(amoor_d, MATCH_AMOOR_D, MASK_AMOOR_D)
+DECLARE_INSN(amoand_d, MATCH_AMOAND_D, MASK_AMOAND_D)
+DECLARE_INSN(amomin_d, MATCH_AMOMIN_D, MASK_AMOMIN_D)
+DECLARE_INSN(amomax_d, MATCH_AMOMAX_D, MASK_AMOMAX_D)
+DECLARE_INSN(amominu_d, MATCH_AMOMINU_D, MASK_AMOMINU_D)
+DECLARE_INSN(amomaxu_d, MATCH_AMOMAXU_D, MASK_AMOMAXU_D)
+DECLARE_INSN(amoswap_d, MATCH_AMOSWAP_D, MASK_AMOSWAP_D)
+DECLARE_INSN(lr_d, MATCH_LR_D, MASK_LR_D)
+DECLARE_INSN(sc_d, MATCH_SC_D, MASK_SC_D)
+DECLARE_INSN(ecall, MATCH_ECALL, MASK_ECALL)
+DECLARE_INSN(ebreak, MATCH_EBREAK, MASK_EBREAK)
+DECLARE_INSN(uret, MATCH_URET, MASK_URET)
+DECLARE_INSN(sret, MATCH_SRET, MASK_SRET)
+DECLARE_INSN(hret, MATCH_HRET, MASK_HRET)
+DECLARE_INSN(mret, MATCH_MRET, MASK_MRET)
+DECLARE_INSN(dret, MATCH_DRET, MASK_DRET)
+DECLARE_INSN(sfence_vm, MATCH_SFENCE_VM, MASK_SFENCE_VM)
+DECLARE_INSN(wfi, MATCH_WFI, MASK_WFI)
+DECLARE_INSN(csrrw, MATCH_CSRRW, MASK_CSRRW)
+DECLARE_INSN(csrrs, MATCH_CSRRS, MASK_CSRRS)
+DECLARE_INSN(csrrc, MATCH_CSRRC, MASK_CSRRC)
+DECLARE_INSN(csrrwi, MATCH_CSRRWI, MASK_CSRRWI)
+DECLARE_INSN(csrrsi, MATCH_CSRRSI, MASK_CSRRSI)
+DECLARE_INSN(csrrci, MATCH_CSRRCI, MASK_CSRRCI)
+DECLARE_INSN(fadd_s, MATCH_FADD_S, MASK_FADD_S)
+DECLARE_INSN(fsub_s, MATCH_FSUB_S, MASK_FSUB_S)
+DECLARE_INSN(fmul_s, MATCH_FMUL_S, MASK_FMUL_S)
+DECLARE_INSN(fdiv_s, MATCH_FDIV_S, MASK_FDIV_S)
+DECLARE_INSN(fsgnj_s, MATCH_FSGNJ_S, MASK_FSGNJ_S)
+DECLARE_INSN(fsgnjn_s, MATCH_FSGNJN_S, MASK_FSGNJN_S)
+DECLARE_INSN(fsgnjx_s, MATCH_FSGNJX_S, MASK_FSGNJX_S)
+DECLARE_INSN(fmin_s, MATCH_FMIN_S, MASK_FMIN_S)
+DECLARE_INSN(fmax_s, MATCH_FMAX_S, MASK_FMAX_S)
+DECLARE_INSN(fsqrt_s, MATCH_FSQRT_S, MASK_FSQRT_S)
+DECLARE_INSN(fadd_d, MATCH_FADD_D, MASK_FADD_D)
+DECLARE_INSN(fsub_d, MATCH_FSUB_D, MASK_FSUB_D)
+DECLARE_INSN(fmul_d, MATCH_FMUL_D, MASK_FMUL_D)
+DECLARE_INSN(fdiv_d, MATCH_FDIV_D, MASK_FDIV_D)
+DECLARE_INSN(fsgnj_d, MATCH_FSGNJ_D, MASK_FSGNJ_D)
+DECLARE_INSN(fsgnjn_d, MATCH_FSGNJN_D, MASK_FSGNJN_D)
+DECLARE_INSN(fsgnjx_d, MATCH_FSGNJX_D, MASK_FSGNJX_D)
+DECLARE_INSN(fmin_d, MATCH_FMIN_D, MASK_FMIN_D)
+DECLARE_INSN(fmax_d, MATCH_FMAX_D, MASK_FMAX_D)
+DECLARE_INSN(fcvt_s_d, MATCH_FCVT_S_D, MASK_FCVT_S_D)
+DECLARE_INSN(fcvt_d_s, MATCH_FCVT_D_S, MASK_FCVT_D_S)
+DECLARE_INSN(fsqrt_d, MATCH_FSQRT_D, MASK_FSQRT_D)
+DECLARE_INSN(fle_s, MATCH_FLE_S, MASK_FLE_S)
+DECLARE_INSN(flt_s, MATCH_FLT_S, MASK_FLT_S)
+DECLARE_INSN(feq_s, MATCH_FEQ_S, MASK_FEQ_S)
+DECLARE_INSN(fle_d, MATCH_FLE_D, MASK_FLE_D)
+DECLARE_INSN(flt_d, MATCH_FLT_D, MASK_FLT_D)
+DECLARE_INSN(feq_d, MATCH_FEQ_D, MASK_FEQ_D)
+DECLARE_INSN(fcvt_w_s, MATCH_FCVT_W_S, MASK_FCVT_W_S)
+DECLARE_INSN(fcvt_wu_s, MATCH_FCVT_WU_S, MASK_FCVT_WU_S)
+DECLARE_INSN(fcvt_l_s, MATCH_FCVT_L_S, MASK_FCVT_L_S)
+DECLARE_INSN(fcvt_lu_s, MATCH_FCVT_LU_S, MASK_FCVT_LU_S)
+DECLARE_INSN(fmv_x_s, MATCH_FMV_X_S, MASK_FMV_X_S)
+DECLARE_INSN(fclass_s, MATCH_FCLASS_S, MASK_FCLASS_S)
+DECLARE_INSN(fcvt_w_d, MATCH_FCVT_W_D, MASK_FCVT_W_D)
+DECLARE_INSN(fcvt_wu_d, MATCH_FCVT_WU_D, MASK_FCVT_WU_D)
+DECLARE_INSN(fcvt_l_d, MATCH_FCVT_L_D, MASK_FCVT_L_D)
+DECLARE_INSN(fcvt_lu_d, MATCH_FCVT_LU_D, MASK_FCVT_LU_D)
+DECLARE_INSN(fmv_x_d, MATCH_FMV_X_D, MASK_FMV_X_D)
+DECLARE_INSN(fclass_d, MATCH_FCLASS_D, MASK_FCLASS_D)
+DECLARE_INSN(fcvt_s_w, MATCH_FCVT_S_W, MASK_FCVT_S_W)
+DECLARE_INSN(fcvt_s_wu, MATCH_FCVT_S_WU, MASK_FCVT_S_WU)
+DECLARE_INSN(fcvt_s_l, MATCH_FCVT_S_L, MASK_FCVT_S_L)
+DECLARE_INSN(fcvt_s_lu, MATCH_FCVT_S_LU, MASK_FCVT_S_LU)
+DECLARE_INSN(fmv_s_x, MATCH_FMV_S_X, MASK_FMV_S_X)
+DECLARE_INSN(fcvt_d_w, MATCH_FCVT_D_W, MASK_FCVT_D_W)
+DECLARE_INSN(fcvt_d_wu, MATCH_FCVT_D_WU, MASK_FCVT_D_WU)
+DECLARE_INSN(fcvt_d_l, MATCH_FCVT_D_L, MASK_FCVT_D_L)
+DECLARE_INSN(fcvt_d_lu, MATCH_FCVT_D_LU, MASK_FCVT_D_LU)
+DECLARE_INSN(fmv_d_x, MATCH_FMV_D_X, MASK_FMV_D_X)
+DECLARE_INSN(flw, MATCH_FLW, MASK_FLW)
+DECLARE_INSN(fld, MATCH_FLD, MASK_FLD)
+DECLARE_INSN(fsw, MATCH_FSW, MASK_FSW)
+DECLARE_INSN(fsd, MATCH_FSD, MASK_FSD)
+DECLARE_INSN(fmadd_s, MATCH_FMADD_S, MASK_FMADD_S)
+DECLARE_INSN(fmsub_s, MATCH_FMSUB_S, MASK_FMSUB_S)
+DECLARE_INSN(fnmsub_s, MATCH_FNMSUB_S, MASK_FNMSUB_S)
+DECLARE_INSN(fnmadd_s, MATCH_FNMADD_S, MASK_FNMADD_S)
+DECLARE_INSN(fmadd_d, MATCH_FMADD_D, MASK_FMADD_D)
+DECLARE_INSN(fmsub_d, MATCH_FMSUB_D, MASK_FMSUB_D)
+DECLARE_INSN(fnmsub_d, MATCH_FNMSUB_D, MASK_FNMSUB_D)
+DECLARE_INSN(fnmadd_d, MATCH_FNMADD_D, MASK_FNMADD_D)
+DECLARE_INSN(c_nop, MATCH_C_NOP, MASK_C_NOP)
+DECLARE_INSN(c_addi16sp, MATCH_C_ADDI16SP, MASK_C_ADDI16SP)
+DECLARE_INSN(c_jr, MATCH_C_JR, MASK_C_JR)
+DECLARE_INSN(c_jalr, MATCH_C_JALR, MASK_C_JALR)
+DECLARE_INSN(c_ebreak, MATCH_C_EBREAK, MASK_C_EBREAK)
+DECLARE_INSN(c_ld, MATCH_C_LD, MASK_C_LD)
+DECLARE_INSN(c_sd, MATCH_C_SD, MASK_C_SD)
+DECLARE_INSN(c_addiw, MATCH_C_ADDIW, MASK_C_ADDIW)
+DECLARE_INSN(c_ldsp, MATCH_C_LDSP, MASK_C_LDSP)
+DECLARE_INSN(c_sdsp, MATCH_C_SDSP, MASK_C_SDSP)
+DECLARE_INSN(c_addi4spn, MATCH_C_ADDI4SPN, MASK_C_ADDI4SPN)
+DECLARE_INSN(c_fld, MATCH_C_FLD, MASK_C_FLD)
+DECLARE_INSN(c_lw, MATCH_C_LW, MASK_C_LW)
+DECLARE_INSN(c_flw, MATCH_C_FLW, MASK_C_FLW)
+DECLARE_INSN(c_fsd, MATCH_C_FSD, MASK_C_FSD)
+DECLARE_INSN(c_sw, MATCH_C_SW, MASK_C_SW)
+DECLARE_INSN(c_fsw, MATCH_C_FSW, MASK_C_FSW)
+DECLARE_INSN(c_addi, MATCH_C_ADDI, MASK_C_ADDI)
+DECLARE_INSN(c_jal, MATCH_C_JAL, MASK_C_JAL)
+DECLARE_INSN(c_li, MATCH_C_LI, MASK_C_LI)
+DECLARE_INSN(c_lui, MATCH_C_LUI, MASK_C_LUI)
+DECLARE_INSN(c_srli, MATCH_C_SRLI, MASK_C_SRLI)
+DECLARE_INSN(c_srai, MATCH_C_SRAI, MASK_C_SRAI)
+DECLARE_INSN(c_andi, MATCH_C_ANDI, MASK_C_ANDI)
+DECLARE_INSN(c_sub, MATCH_C_SUB, MASK_C_SUB)
+DECLARE_INSN(c_xor, MATCH_C_XOR, MASK_C_XOR)
+DECLARE_INSN(c_or, MATCH_C_OR, MASK_C_OR)
+DECLARE_INSN(c_and, MATCH_C_AND, MASK_C_AND)
+DECLARE_INSN(c_subw, MATCH_C_SUBW, MASK_C_SUBW)
+DECLARE_INSN(c_addw, MATCH_C_ADDW, MASK_C_ADDW)
+DECLARE_INSN(c_j, MATCH_C_J, MASK_C_J)
+DECLARE_INSN(c_beqz, MATCH_C_BEQZ, MASK_C_BEQZ)
+DECLARE_INSN(c_bnez, MATCH_C_BNEZ, MASK_C_BNEZ)
+DECLARE_INSN(c_slli, MATCH_C_SLLI, MASK_C_SLLI)
+DECLARE_INSN(c_fldsp, MATCH_C_FLDSP, MASK_C_FLDSP)
+DECLARE_INSN(c_lwsp, MATCH_C_LWSP, MASK_C_LWSP)
+DECLARE_INSN(c_flwsp, MATCH_C_FLWSP, MASK_C_FLWSP)
+DECLARE_INSN(c_mv, MATCH_C_MV, MASK_C_MV)
+DECLARE_INSN(c_add, MATCH_C_ADD, MASK_C_ADD)
+DECLARE_INSN(c_fsdsp, MATCH_C_FSDSP, MASK_C_FSDSP)
+DECLARE_INSN(c_swsp, MATCH_C_SWSP, MASK_C_SWSP)
+DECLARE_INSN(c_fswsp, MATCH_C_FSWSP, MASK_C_FSWSP)
+DECLARE_INSN(custom0, MATCH_CUSTOM0, MASK_CUSTOM0)
+DECLARE_INSN(custom0_rs1, MATCH_CUSTOM0_RS1, MASK_CUSTOM0_RS1)
+DECLARE_INSN(custom0_rs1_rs2, MATCH_CUSTOM0_RS1_RS2, MASK_CUSTOM0_RS1_RS2)
+DECLARE_INSN(custom0_rd, MATCH_CUSTOM0_RD, MASK_CUSTOM0_RD)
+DECLARE_INSN(custom0_rd_rs1, MATCH_CUSTOM0_RD_RS1, MASK_CUSTOM0_RD_RS1)
+DECLARE_INSN(custom0_rd_rs1_rs2, MATCH_CUSTOM0_RD_RS1_RS2, MASK_CUSTOM0_RD_RS1_RS2)
+DECLARE_INSN(custom1, MATCH_CUSTOM1, MASK_CUSTOM1)
+DECLARE_INSN(custom1_rs1, MATCH_CUSTOM1_RS1, MASK_CUSTOM1_RS1)
+DECLARE_INSN(custom1_rs1_rs2, MATCH_CUSTOM1_RS1_RS2, MASK_CUSTOM1_RS1_RS2)
+DECLARE_INSN(custom1_rd, MATCH_CUSTOM1_RD, MASK_CUSTOM1_RD)
+DECLARE_INSN(custom1_rd_rs1, MATCH_CUSTOM1_RD_RS1, MASK_CUSTOM1_RD_RS1)
+DECLARE_INSN(custom1_rd_rs1_rs2, MATCH_CUSTOM1_RD_RS1_RS2, MASK_CUSTOM1_RD_RS1_RS2)
+DECLARE_INSN(custom2, MATCH_CUSTOM2, MASK_CUSTOM2)
+DECLARE_INSN(custom2_rs1, MATCH_CUSTOM2_RS1, MASK_CUSTOM2_RS1)
+DECLARE_INSN(custom2_rs1_rs2, MATCH_CUSTOM2_RS1_RS2, MASK_CUSTOM2_RS1_RS2)
+DECLARE_INSN(custom2_rd, MATCH_CUSTOM2_RD, MASK_CUSTOM2_RD)
+DECLARE_INSN(custom2_rd_rs1, MATCH_CUSTOM2_RD_RS1, MASK_CUSTOM2_RD_RS1)
+DECLARE_INSN(custom2_rd_rs1_rs2, MATCH_CUSTOM2_RD_RS1_RS2, MASK_CUSTOM2_RD_RS1_RS2)
+DECLARE_INSN(custom3, MATCH_CUSTOM3, MASK_CUSTOM3)
+DECLARE_INSN(custom3_rs1, MATCH_CUSTOM3_RS1, MASK_CUSTOM3_RS1)
+DECLARE_INSN(custom3_rs1_rs2, MATCH_CUSTOM3_RS1_RS2, MASK_CUSTOM3_RS1_RS2)
+DECLARE_INSN(custom3_rd, MATCH_CUSTOM3_RD, MASK_CUSTOM3_RD)
+DECLARE_INSN(custom3_rd_rs1, MATCH_CUSTOM3_RD_RS1, MASK_CUSTOM3_RD_RS1)
+DECLARE_INSN(custom3_rd_rs1_rs2, MATCH_CUSTOM3_RD_RS1_RS2, MASK_CUSTOM3_RD_RS1_RS2)
+#endif
+#ifdef DECLARE_CSR
+DECLARE_CSR(fflags, CSR_FFLAGS)
+DECLARE_CSR(frm, CSR_FRM)
+DECLARE_CSR(fcsr, CSR_FCSR)
+DECLARE_CSR(cycle, CSR_CYCLE)
+DECLARE_CSR(time, CSR_TIME)
+DECLARE_CSR(instret, CSR_INSTRET)
+DECLARE_CSR(hpmcounter3, CSR_HPMCOUNTER3)
+DECLARE_CSR(hpmcounter4, CSR_HPMCOUNTER4)
+DECLARE_CSR(hpmcounter5, CSR_HPMCOUNTER5)
+DECLARE_CSR(hpmcounter6, CSR_HPMCOUNTER6)
+DECLARE_CSR(hpmcounter7, CSR_HPMCOUNTER7)
+DECLARE_CSR(hpmcounter8, CSR_HPMCOUNTER8)
+DECLARE_CSR(hpmcounter9, CSR_HPMCOUNTER9)
+DECLARE_CSR(hpmcounter10, CSR_HPMCOUNTER10)
+DECLARE_CSR(hpmcounter11, CSR_HPMCOUNTER11)
+DECLARE_CSR(hpmcounter12, CSR_HPMCOUNTER12)
+DECLARE_CSR(hpmcounter13, CSR_HPMCOUNTER13)
+DECLARE_CSR(hpmcounter14, CSR_HPMCOUNTER14)
+DECLARE_CSR(hpmcounter15, CSR_HPMCOUNTER15)
+DECLARE_CSR(hpmcounter16, CSR_HPMCOUNTER16)
+DECLARE_CSR(hpmcounter17, CSR_HPMCOUNTER17)
+DECLARE_CSR(hpmcounter18, CSR_HPMCOUNTER18)
+DECLARE_CSR(hpmcounter19, CSR_HPMCOUNTER19)
+DECLARE_CSR(hpmcounter20, CSR_HPMCOUNTER20)
+DECLARE_CSR(hpmcounter21, CSR_HPMCOUNTER21)
+DECLARE_CSR(hpmcounter22, CSR_HPMCOUNTER22)
+DECLARE_CSR(hpmcounter23, CSR_HPMCOUNTER23)
+DECLARE_CSR(hpmcounter24, CSR_HPMCOUNTER24)
+DECLARE_CSR(hpmcounter25, CSR_HPMCOUNTER25)
+DECLARE_CSR(hpmcounter26, CSR_HPMCOUNTER26)
+DECLARE_CSR(hpmcounter27, CSR_HPMCOUNTER27)
+DECLARE_CSR(hpmcounter28, CSR_HPMCOUNTER28)
+DECLARE_CSR(hpmcounter29, CSR_HPMCOUNTER29)
+DECLARE_CSR(hpmcounter30, CSR_HPMCOUNTER30)
+DECLARE_CSR(hpmcounter31, CSR_HPMCOUNTER31)
+DECLARE_CSR(sstatus, CSR_SSTATUS)
+DECLARE_CSR(sie, CSR_SIE)
+DECLARE_CSR(stvec, CSR_STVEC)
+DECLARE_CSR(sscratch, CSR_SSCRATCH)
+DECLARE_CSR(sepc, CSR_SEPC)
+DECLARE_CSR(scause, CSR_SCAUSE)
+DECLARE_CSR(sbadaddr, CSR_SBADADDR)
+DECLARE_CSR(sip, CSR_SIP)
+DECLARE_CSR(sptbr, CSR_SPTBR)
+DECLARE_CSR(mstatus, CSR_MSTATUS)
+DECLARE_CSR(misa, CSR_MISA)
+DECLARE_CSR(medeleg, CSR_MEDELEG)
+DECLARE_CSR(mideleg, CSR_MIDELEG)
+DECLARE_CSR(mie, CSR_MIE)
+DECLARE_CSR(mtvec, CSR_MTVEC)
+DECLARE_CSR(mscratch, CSR_MSCRATCH)
+DECLARE_CSR(mepc, CSR_MEPC)
+DECLARE_CSR(mcause, CSR_MCAUSE)
+DECLARE_CSR(mbadaddr, CSR_MBADADDR)
+DECLARE_CSR(mip, CSR_MIP)
+DECLARE_CSR(tselect, CSR_TSELECT)
+DECLARE_CSR(tdata1, CSR_TDATA1)
+DECLARE_CSR(tdata2, CSR_TDATA2)
+DECLARE_CSR(tdata3, CSR_TDATA3)
+DECLARE_CSR(dcsr, CSR_DCSR)
+DECLARE_CSR(dpc, CSR_DPC)
+DECLARE_CSR(dscratch, CSR_DSCRATCH)
+DECLARE_CSR(mcycle, CSR_MCYCLE)
+DECLARE_CSR(minstret, CSR_MINSTRET)
+DECLARE_CSR(mhpmcounter3, CSR_MHPMCOUNTER3)
+DECLARE_CSR(mhpmcounter4, CSR_MHPMCOUNTER4)
+DECLARE_CSR(mhpmcounter5, CSR_MHPMCOUNTER5)
+DECLARE_CSR(mhpmcounter6, CSR_MHPMCOUNTER6)
+DECLARE_CSR(mhpmcounter7, CSR_MHPMCOUNTER7)
+DECLARE_CSR(mhpmcounter8, CSR_MHPMCOUNTER8)
+DECLARE_CSR(mhpmcounter9, CSR_MHPMCOUNTER9)
+DECLARE_CSR(mhpmcounter10, CSR_MHPMCOUNTER10)
+DECLARE_CSR(mhpmcounter11, CSR_MHPMCOUNTER11)
+DECLARE_CSR(mhpmcounter12, CSR_MHPMCOUNTER12)
+DECLARE_CSR(mhpmcounter13, CSR_MHPMCOUNTER13)
+DECLARE_CSR(mhpmcounter14, CSR_MHPMCOUNTER14)
+DECLARE_CSR(mhpmcounter15, CSR_MHPMCOUNTER15)
+DECLARE_CSR(mhpmcounter16, CSR_MHPMCOUNTER16)
+DECLARE_CSR(mhpmcounter17, CSR_MHPMCOUNTER17)
+DECLARE_CSR(mhpmcounter18, CSR_MHPMCOUNTER18)
+DECLARE_CSR(mhpmcounter19, CSR_MHPMCOUNTER19)
+DECLARE_CSR(mhpmcounter20, CSR_MHPMCOUNTER20)
+DECLARE_CSR(mhpmcounter21, CSR_MHPMCOUNTER21)
+DECLARE_CSR(mhpmcounter22, CSR_MHPMCOUNTER22)
+DECLARE_CSR(mhpmcounter23, CSR_MHPMCOUNTER23)
+DECLARE_CSR(mhpmcounter24, CSR_MHPMCOUNTER24)
+DECLARE_CSR(mhpmcounter25, CSR_MHPMCOUNTER25)
+DECLARE_CSR(mhpmcounter26, CSR_MHPMCOUNTER26)
+DECLARE_CSR(mhpmcounter27, CSR_MHPMCOUNTER27)
+DECLARE_CSR(mhpmcounter28, CSR_MHPMCOUNTER28)
+DECLARE_CSR(mhpmcounter29, CSR_MHPMCOUNTER29)
+DECLARE_CSR(mhpmcounter30, CSR_MHPMCOUNTER30)
+DECLARE_CSR(mhpmcounter31, CSR_MHPMCOUNTER31)
+DECLARE_CSR(mucounteren, CSR_MUCOUNTEREN)
+DECLARE_CSR(mscounteren, CSR_MSCOUNTEREN)
+DECLARE_CSR(mhpmevent3, CSR_MHPMEVENT3)
+DECLARE_CSR(mhpmevent4, CSR_MHPMEVENT4)
+DECLARE_CSR(mhpmevent5, CSR_MHPMEVENT5)
+DECLARE_CSR(mhpmevent6, CSR_MHPMEVENT6)
+DECLARE_CSR(mhpmevent7, CSR_MHPMEVENT7)
+DECLARE_CSR(mhpmevent8, CSR_MHPMEVENT8)
+DECLARE_CSR(mhpmevent9, CSR_MHPMEVENT9)
+DECLARE_CSR(mhpmevent10, CSR_MHPMEVENT10)
+DECLARE_CSR(mhpmevent11, CSR_MHPMEVENT11)
+DECLARE_CSR(mhpmevent12, CSR_MHPMEVENT12)
+DECLARE_CSR(mhpmevent13, CSR_MHPMEVENT13)
+DECLARE_CSR(mhpmevent14, CSR_MHPMEVENT14)
+DECLARE_CSR(mhpmevent15, CSR_MHPMEVENT15)
+DECLARE_CSR(mhpmevent16, CSR_MHPMEVENT16)
+DECLARE_CSR(mhpmevent17, CSR_MHPMEVENT17)
+DECLARE_CSR(mhpmevent18, CSR_MHPMEVENT18)
+DECLARE_CSR(mhpmevent19, CSR_MHPMEVENT19)
+DECLARE_CSR(mhpmevent20, CSR_MHPMEVENT20)
+DECLARE_CSR(mhpmevent21, CSR_MHPMEVENT21)
+DECLARE_CSR(mhpmevent22, CSR_MHPMEVENT22)
+DECLARE_CSR(mhpmevent23, CSR_MHPMEVENT23)
+DECLARE_CSR(mhpmevent24, CSR_MHPMEVENT24)
+DECLARE_CSR(mhpmevent25, CSR_MHPMEVENT25)
+DECLARE_CSR(mhpmevent26, CSR_MHPMEVENT26)
+DECLARE_CSR(mhpmevent27, CSR_MHPMEVENT27)
+DECLARE_CSR(mhpmevent28, CSR_MHPMEVENT28)
+DECLARE_CSR(mhpmevent29, CSR_MHPMEVENT29)
+DECLARE_CSR(mhpmevent30, CSR_MHPMEVENT30)
+DECLARE_CSR(mhpmevent31, CSR_MHPMEVENT31)
+DECLARE_CSR(mvendorid, CSR_MVENDORID)
+DECLARE_CSR(marchid, CSR_MARCHID)
+DECLARE_CSR(mimpid, CSR_MIMPID)
+DECLARE_CSR(mhartid, CSR_MHARTID)
+DECLARE_CSR(cycleh, CSR_CYCLEH)
+DECLARE_CSR(timeh, CSR_TIMEH)
+DECLARE_CSR(instreth, CSR_INSTRETH)
+DECLARE_CSR(hpmcounter3h, CSR_HPMCOUNTER3H)
+DECLARE_CSR(hpmcounter4h, CSR_HPMCOUNTER4H)
+DECLARE_CSR(hpmcounter5h, CSR_HPMCOUNTER5H)
+DECLARE_CSR(hpmcounter6h, CSR_HPMCOUNTER6H)
+DECLARE_CSR(hpmcounter7h, CSR_HPMCOUNTER7H)
+DECLARE_CSR(hpmcounter8h, CSR_HPMCOUNTER8H)
+DECLARE_CSR(hpmcounter9h, CSR_HPMCOUNTER9H)
+DECLARE_CSR(hpmcounter10h, CSR_HPMCOUNTER10H)
+DECLARE_CSR(hpmcounter11h, CSR_HPMCOUNTER11H)
+DECLARE_CSR(hpmcounter12h, CSR_HPMCOUNTER12H)
+DECLARE_CSR(hpmcounter13h, CSR_HPMCOUNTER13H)
+DECLARE_CSR(hpmcounter14h, CSR_HPMCOUNTER14H)
+DECLARE_CSR(hpmcounter15h, CSR_HPMCOUNTER15H)
+DECLARE_CSR(hpmcounter16h, CSR_HPMCOUNTER16H)
+DECLARE_CSR(hpmcounter17h, CSR_HPMCOUNTER17H)
+DECLARE_CSR(hpmcounter18h, CSR_HPMCOUNTER18H)
+DECLARE_CSR(hpmcounter19h, CSR_HPMCOUNTER19H)
+DECLARE_CSR(hpmcounter20h, CSR_HPMCOUNTER20H)
+DECLARE_CSR(hpmcounter21h, CSR_HPMCOUNTER21H)
+DECLARE_CSR(hpmcounter22h, CSR_HPMCOUNTER22H)
+DECLARE_CSR(hpmcounter23h, CSR_HPMCOUNTER23H)
+DECLARE_CSR(hpmcounter24h, CSR_HPMCOUNTER24H)
+DECLARE_CSR(hpmcounter25h, CSR_HPMCOUNTER25H)
+DECLARE_CSR(hpmcounter26h, CSR_HPMCOUNTER26H)
+DECLARE_CSR(hpmcounter27h, CSR_HPMCOUNTER27H)
+DECLARE_CSR(hpmcounter28h, CSR_HPMCOUNTER28H)
+DECLARE_CSR(hpmcounter29h, CSR_HPMCOUNTER29H)
+DECLARE_CSR(hpmcounter30h, CSR_HPMCOUNTER30H)
+DECLARE_CSR(hpmcounter31h, CSR_HPMCOUNTER31H)
+DECLARE_CSR(mcycleh, CSR_MCYCLEH)
+DECLARE_CSR(minstreth, CSR_MINSTRETH)
+DECLARE_CSR(mhpmcounter3h, CSR_MHPMCOUNTER3H)
+DECLARE_CSR(mhpmcounter4h, CSR_MHPMCOUNTER4H)
+DECLARE_CSR(mhpmcounter5h, CSR_MHPMCOUNTER5H)
+DECLARE_CSR(mhpmcounter6h, CSR_MHPMCOUNTER6H)
+DECLARE_CSR(mhpmcounter7h, CSR_MHPMCOUNTER7H)
+DECLARE_CSR(mhpmcounter8h, CSR_MHPMCOUNTER8H)
+DECLARE_CSR(mhpmcounter9h, CSR_MHPMCOUNTER9H)
+DECLARE_CSR(mhpmcounter10h, CSR_MHPMCOUNTER10H)
+DECLARE_CSR(mhpmcounter11h, CSR_MHPMCOUNTER11H)
+DECLARE_CSR(mhpmcounter12h, CSR_MHPMCOUNTER12H)
+DECLARE_CSR(mhpmcounter13h, CSR_MHPMCOUNTER13H)
+DECLARE_CSR(mhpmcounter14h, CSR_MHPMCOUNTER14H)
+DECLARE_CSR(mhpmcounter15h, CSR_MHPMCOUNTER15H)
+DECLARE_CSR(mhpmcounter16h, CSR_MHPMCOUNTER16H)
+DECLARE_CSR(mhpmcounter17h, CSR_MHPMCOUNTER17H)
+DECLARE_CSR(mhpmcounter18h, CSR_MHPMCOUNTER18H)
+DECLARE_CSR(mhpmcounter19h, CSR_MHPMCOUNTER19H)
+DECLARE_CSR(mhpmcounter20h, CSR_MHPMCOUNTER20H)
+DECLARE_CSR(mhpmcounter21h, CSR_MHPMCOUNTER21H)
+DECLARE_CSR(mhpmcounter22h, CSR_MHPMCOUNTER22H)
+DECLARE_CSR(mhpmcounter23h, CSR_MHPMCOUNTER23H)
+DECLARE_CSR(mhpmcounter24h, CSR_MHPMCOUNTER24H)
+DECLARE_CSR(mhpmcounter25h, CSR_MHPMCOUNTER25H)
+DECLARE_CSR(mhpmcounter26h, CSR_MHPMCOUNTER26H)
+DECLARE_CSR(mhpmcounter27h, CSR_MHPMCOUNTER27H)
+DECLARE_CSR(mhpmcounter28h, CSR_MHPMCOUNTER28H)
+DECLARE_CSR(mhpmcounter29h, CSR_MHPMCOUNTER29H)
+DECLARE_CSR(mhpmcounter30h, CSR_MHPMCOUNTER30H)
+DECLARE_CSR(mhpmcounter31h, CSR_MHPMCOUNTER31H)
+#endif
+#ifdef DECLARE_CAUSE
+DECLARE_CAUSE("misaligned fetch", CAUSE_MISALIGNED_FETCH)
+DECLARE_CAUSE("fault fetch", CAUSE_FAULT_FETCH)
+DECLARE_CAUSE("illegal instruction", CAUSE_ILLEGAL_INSTRUCTION)
+DECLARE_CAUSE("breakpoint", CAUSE_BREAKPOINT)
+DECLARE_CAUSE("misaligned load", CAUSE_MISALIGNED_LOAD)
+DECLARE_CAUSE("fault load", CAUSE_FAULT_LOAD)
+DECLARE_CAUSE("misaligned store", CAUSE_MISALIGNED_STORE)
+DECLARE_CAUSE("fault store", CAUSE_FAULT_STORE)
+DECLARE_CAUSE("user_ecall", CAUSE_USER_ECALL)
+DECLARE_CAUSE("supervisor_ecall", CAUSE_SUPERVISOR_ECALL)
+DECLARE_CAUSE("hypervisor_ecall", CAUSE_HYPERVISOR_ECALL)
+DECLARE_CAUSE("machine_ecall", CAUSE_MACHINE_ECALL)
+#endif

+ 81 - 0
libcpu/risc-v/e310/hifive1.h

@@ -0,0 +1,81 @@
+// See LICENSE for license details.
+
+#ifndef _SIFIVE_HIFIVE1_H
+#define _SIFIVE_HIFIVE1_H
+
+#include <stdint.h>
+
+/****************************************************************************
+ * GPIO Connections
+ *****************************************************************************/
+
+// These are the GPIO bit offsets for the RGB LED on HiFive1 Board.
+// These are also mapped to RGB LEDs on the Freedom E300 Arty
+// FPGA
+// Dev Kit.
+
+#define RED_LED_OFFSET   22
+#define GREEN_LED_OFFSET 19
+#define BLUE_LED_OFFSET  21
+
+// These are the GPIO bit offsets for the differen digital pins
+// on the headers for both the HiFive1 Board and the Freedom E300 Arty FPGA Dev Kit.
+#define PIN_0_OFFSET 16
+#define PIN_1_OFFSET 17
+#define PIN_2_OFFSET 18
+#define PIN_3_OFFSET 19
+#define PIN_4_OFFSET 20
+#define PIN_5_OFFSET 21
+#define PIN_6_OFFSET 22
+#define PIN_7_OFFSET 23
+#define PIN_8_OFFSET 0
+#define PIN_9_OFFSET 1
+#define PIN_10_OFFSET 2
+#define PIN_11_OFFSET 3
+#define PIN_12_OFFSET 4
+#define PIN_13_OFFSET 5
+//#define PIN_14_OFFSET 8 //This pin is not connected on either board.
+#define PIN_15_OFFSET 9
+#define PIN_16_OFFSET 10
+#define PIN_17_OFFSET 11
+#define PIN_18_OFFSET 12
+#define PIN_19_OFFSET 13
+
+// These are *PIN* numbers, not
+// GPIO Offset Numbers.
+#define PIN_SPI1_SCK    (13u)
+#define PIN_SPI1_MISO   (12u)
+#define PIN_SPI1_MOSI   (11u)
+#define PIN_SPI1_SS0    (10u)
+#define PIN_SPI1_SS1    (14u) 
+#define PIN_SPI1_SS2    (15u)
+#define PIN_SPI1_SS3    (16u)
+
+#define SS_PIN_TO_CS_ID(x) \
+  ((x==PIN_SPI1_SS0 ? 0 :		 \
+    (x==PIN_SPI1_SS1 ? 1 :		 \
+     (x==PIN_SPI1_SS2 ? 2 :		 \
+      (x==PIN_SPI1_SS3 ? 3 :		 \
+       -1))))) 
+
+
+// These buttons are present only on the Freedom E300 Arty Dev Kit.
+#ifdef HAS_BOARD_BUTTONS
+#define BUTTON_0_OFFSET 15
+#define BUTTON_1_OFFSET 30
+#define BUTTON_2_OFFSET 31
+
+#define INT_DEVICE_BUTTON_0 (INT_GPIO_BASE + BUTTON_0_OFFSET)
+#define INT_DEVICE_BUTTON_1 (INT_GPIO_BASE + BUTTON_1_OFFSET)
+#define INT_DEVICE_BUTTON_2 (INT_GPIO_BASE + BUTTON_2_OFFSET)
+
+#endif
+
+#define HAS_HFXOSC 1
+#define HAS_LFROSC_BYPASS 1
+
+#define RTC_FREQ 32768
+
+void write_hex(int fd, unsigned long int hex);
+
+#endif /* _SIFIVE_HIFIVE1_H */

+ 210 - 0
libcpu/risc-v/e310/init.c

@@ -0,0 +1,210 @@
+#include <stdint.h>
+#include <stdio.h>
+#include <unistd.h>
+
+#include "platform.h"
+#include "encoding.h"
+
+extern int main(int argc, char** argv);
+extern void trap_entry();
+
+static unsigned long mtime_lo(void)
+{
+  return *(volatile unsigned long *)(CLINT_CTRL_ADDR + CLINT_MTIME);
+}
+
+#ifdef __riscv32
+
+static uint32_t mtime_hi(void)
+{
+  return *(volatile uint32_t *)(CLINT_CTRL_ADDR + CLINT_MTIME + 4);
+}
+
+uint64_t get_timer_value()
+{
+  while (1) {
+    uint32_t hi = mtime_hi();
+    uint32_t lo = mtime_lo();
+    if (hi == mtime_hi())
+      return ((uint64_t)hi << 32) | lo;
+  }
+}
+
+#else /* __riscv32 */
+
+uint64_t get_timer_value()
+{
+  return mtime_lo();
+}
+
+#endif
+
+unsigned long get_timer_freq()
+{
+  return 32768;
+}
+
+static void use_hfrosc(int div, int trim)
+{
+  // Make sure the HFROSC is running at its default setting
+  PRCI_REG(PRCI_HFROSCCFG) = (ROSC_DIV(div) | ROSC_TRIM(trim) | ROSC_EN(1));
+  while ((PRCI_REG(PRCI_HFROSCCFG) & ROSC_RDY(1)) == 0) ;
+  PRCI_REG(PRCI_PLLCFG) &= ~PLL_SEL(1);
+}
+
+static void use_pll(int refsel, int bypass, int r, int f, int q)
+{
+  // Ensure that we aren't running off the PLL before we mess with it.
+  if (PRCI_REG(PRCI_PLLCFG) & PLL_SEL(1)) {
+    // Make sure the HFROSC is running at its default setting
+    use_hfrosc(4, 16);
+  }
+
+  // Set PLL Source to be HFXOSC if available.
+  uint32_t config_value = 0;
+
+  config_value |= PLL_REFSEL(refsel);
+
+  if (bypass) {
+    // Bypass
+    config_value |= PLL_BYPASS(1);
+
+    PRCI_REG(PRCI_PLLCFG) = config_value;
+
+    // If we don't have an HFXTAL, this doesn't really matter.
+    // Set our Final output divide to divide-by-1:
+    PRCI_REG(PRCI_PLLDIV) = (PLL_FINAL_DIV_BY_1(1) | PLL_FINAL_DIV(0));
+  } else {
+    // In case we are executing from QSPI,
+    // (which is quite likely) we need to
+    // set the QSPI clock divider appropriately
+    // before boosting the clock frequency.
+
+    // Div = f_sck/2
+    SPI0_REG(SPI_REG_SCKDIV) = 8;
+
+    // Set DIV Settings for PLL
+    // Both HFROSC and HFXOSC are modeled as ideal
+    // 16MHz sources (assuming dividers are set properly for
+    // HFROSC).
+    // (Legal values of f_REF are 6-48MHz)
+
+    // Set DIVR to divide-by-2 to get 8MHz frequency
+    // (legal values of f_R are 6-12 MHz)
+
+    config_value |= PLL_BYPASS(1);
+    config_value |= PLL_R(r);
+
+    // Set DIVF to get 512Mhz frequncy
+    // There is an implied multiply-by-2, 16Mhz.
+    // So need to write 32-1
+    // (legal values of f_F are 384-768 MHz)
+    config_value |= PLL_F(f);
+
+    // Set DIVQ to divide-by-2 to get 256 MHz frequency
+    // (legal values of f_Q are 50-400Mhz)
+    config_value |= PLL_Q(q);
+
+    // Set our Final output divide to divide-by-1:
+    PRCI_REG(PRCI_PLLDIV) = (PLL_FINAL_DIV_BY_1(1) | PLL_FINAL_DIV(0));
+
+    PRCI_REG(PRCI_PLLCFG) = config_value;
+
+    // Un-Bypass the PLL.
+    PRCI_REG(PRCI_PLLCFG) &= ~PLL_BYPASS(1);
+
+    // Wait for PLL Lock
+    // Note that the Lock signal can be glitchy.
+    // Need to wait 100 us
+    // RTC is running at 32kHz.
+    // So wait 4 ticks of RTC.
+    uint32_t now = mtime_lo();
+    while (mtime_lo() - now < 4) ;
+
+    // Now it is safe to check for PLL Lock
+    while ((PRCI_REG(PRCI_PLLCFG) & PLL_LOCK(1)) == 0) ;
+  }
+
+  // Switch over to PLL Clock source
+  PRCI_REG(PRCI_PLLCFG) |= PLL_SEL(1);
+}
+
+static void use_default_clocks()
+{
+  // Turn off the LFROSC
+  AON_REG(AON_LFROSC) &= ~ROSC_EN(1);
+
+  // Use HFROSC
+  use_hfrosc(4, 16);
+}
+
+static unsigned long __attribute__((noinline)) measure_cpu_freq(size_t n)
+{
+  unsigned long start_mtime, delta_mtime;
+  unsigned long mtime_freq = get_timer_freq();
+
+  // Don't start measuruing until we see an mtime tick
+  unsigned long tmp = mtime_lo();
+  do {
+    start_mtime = mtime_lo();
+  } while (start_mtime == tmp);
+
+  unsigned long start_mcycle = read_csr(mcycle);
+
+  do {
+    delta_mtime = mtime_lo() - start_mtime;
+  } while (delta_mtime < n);
+
+  unsigned long delta_mcycle = read_csr(mcycle) - start_mcycle;
+
+  return (delta_mcycle / delta_mtime) * mtime_freq
+         + ((delta_mcycle % delta_mtime) * mtime_freq) / delta_mtime;
+}
+
+unsigned long get_cpu_freq()
+{
+  static uint32_t cpu_freq;
+
+  if (!cpu_freq) {
+    // warm up I$
+    measure_cpu_freq(1);
+    // measure for real
+    cpu_freq = measure_cpu_freq(10);
+  }
+
+  return cpu_freq;
+}
+
+
+
+
+
+#ifdef USE_PLIC
+extern void handle_m_ext_interrupt();
+#endif
+
+#ifdef USE_M_TIME
+extern void handle_m_time_interrupt();
+#endif
+
+
+void _init()
+{
+  
+  #ifndef NO_INIT
+  use_default_clocks();
+  use_pll(0, 0, 1, 31, 1);
+
+
+  write_csr(mtvec, &trap_entry);
+  if (read_csr(misa) & (1 << ('F' - 'A'))) { // if F extension is present
+    write_csr(mstatus, MSTATUS_FS); // allow FPU instructions without trapping
+    write_csr(fcsr, 0); // initialize rounding mode, undefined at reset
+  }
+  #endif
+  
+}
+
+void _fini()
+{
+}

+ 133 - 0
libcpu/risc-v/e310/platform.h

@@ -0,0 +1,133 @@
+// See LICENSE for license details.
+
+#ifndef _SIFIVE_PLATFORM_H
+#define _SIFIVE_PLATFORM_H
+
+// Some things missing from the official encoding.h
+#define MCAUSE_INT         0x80000000
+#define MCAUSE_CAUSE       0x7FFFFFFF
+
+#include "sifive/const.h"
+#include "sifive/devices/aon.h"
+#include "sifive/devices/clint.h"
+#include "sifive/devices/gpio.h"
+#include "sifive/devices/otp.h"
+#include "sifive/devices/plic.h"
+#include "sifive/devices/prci.h"
+#include "sifive/devices/pwm.h"
+#include "sifive/devices/spi.h"
+#include "sifive/devices/uart.h"
+
+/****************************************************************************
+ * Platform definitions
+ *****************************************************************************/
+
+// Memory map
+#define MASKROM_MEM_ADDR _AC(0x00001000,UL)
+#define TRAPVEC_TABLE_CTRL_ADDR _AC(0x00001010,UL)
+#define OTP_MEM_ADDR _AC(0x00020000,UL)
+#define CLINT_CTRL_ADDR _AC(0x02000000,UL)
+#define PLIC_CTRL_ADDR _AC(0x0C000000,UL)
+#define AON_CTRL_ADDR _AC(0x10000000,UL)
+#define PRCI_CTRL_ADDR _AC(0x10008000,UL)
+#define OTP_CTRL_ADDR _AC(0x10010000,UL)
+#define GPIO_CTRL_ADDR _AC(0x10012000,UL)
+#define UART0_CTRL_ADDR _AC(0x10013000,UL)
+#define SPI0_CTRL_ADDR _AC(0x10014000,UL)
+#define PWM0_CTRL_ADDR _AC(0x10015000,UL)
+#define UART1_CTRL_ADDR _AC(0x10023000,UL)
+#define SPI1_CTRL_ADDR _AC(0x10024000,UL)
+#define PWM1_CTRL_ADDR _AC(0x10025000,UL)
+#define SPI2_CTRL_ADDR _AC(0x10034000,UL)
+#define PWM2_CTRL_ADDR _AC(0x10035000,UL)
+#define SPI0_MEM_ADDR _AC(0x20000000,UL)
+#define MEM_CTRL_ADDR _AC(0x80000000,UL)
+
+// IOF masks
+#define IOF0_SPI1_MASK          _AC(0x000007FC,UL)
+#define SPI11_NUM_SS     (4)
+#define IOF_SPI1_SS0          (2u)
+#define IOF_SPI1_SS1          (8u)
+#define IOF_SPI1_SS2          (9u)
+#define IOF_SPI1_SS3          (10u)
+#define IOF_SPI1_MOSI         (3u)
+#define IOF_SPI1_MISO         (4u)
+#define IOF_SPI1_SCK          (5u)
+#define IOF_SPI1_DQ0          (3u)
+#define IOF_SPI1_DQ1          (4u)
+#define IOF_SPI1_DQ2          (6u)
+#define IOF_SPI1_DQ3          (7u)
+
+#define IOF0_SPI2_MASK          _AC(0xFC000000,UL)
+#define SPI2_NUM_SS       (1)
+#define IOF_SPI2_SS0          (26u)
+#define IOF_SPI2_MOSI         (27u)
+#define IOF_SPI2_MISO         (28u)
+#define IOF_SPI2_SCK          (29u)
+#define IOF_SPI2_DQ0          (27u)
+#define IOF_SPI2_DQ1          (28u)
+#define IOF_SPI2_DQ2          (30u)
+#define IOF_SPI2_DQ3          (31u)
+
+//#define IOF0_I2C_MASK          _AC(0x00003000,UL)
+
+#define IOF0_UART0_MASK         _AC(0x00030000, UL)
+#define IOF_UART0_RX   (16u)
+#define IOF_UART0_TX   (17u)
+
+#define IOF0_UART1_MASK         _AC(0x03000000, UL)
+#define IOF_UART1_RX (24u)
+#define IOF_UART1_TX (25u)
+
+#define IOF1_PWM0_MASK          _AC(0x0000000F, UL)
+#define IOF1_PWM1_MASK          _AC(0x00780000, UL)
+#define IOF1_PWM2_MASK          _AC(0x00003C00, UL)
+
+// Interrupt numbers
+#define INT_RESERVED 0
+#define INT_WDOGCMP 1
+#define INT_RTCCMP 2
+#define INT_UART0_BASE 3
+#define INT_UART1_BASE 4
+#define INT_SPI0_BASE 5
+#define INT_SPI1_BASE 6
+#define INT_SPI2_BASE 7
+#define INT_GPIO_BASE 8
+#define INT_PWM0_BASE 40
+#define INT_PWM1_BASE 44
+#define INT_PWM2_BASE 48
+
+// Helper functions
+#define _REG32(p, i) (*(volatile uint32_t *) ((p) + (i)))
+#define _REG32P(p, i) ((volatile uint32_t *) ((p) + (i)))
+#define AON_REG(offset) _REG32(AON_CTRL_ADDR, offset)
+#define CLINT_REG(offset) _REG32(CLINT_CTRL_ADDR, offset)
+#define GPIO_REG(offset) _REG32(GPIO_CTRL_ADDR, offset)
+#define OTP_REG(offset)  _REG32(OTP_CTRL_ADDR, offset)
+#define PLIC_REG(offset) _REG32(PLIC_CTRL_ADDR, offset)
+#define PRCI_REG(offset) _REG32(PRCI_CTRL_ADDR, offset)
+#define PWM0_REG(offset) _REG32(PWM0_CTRL_ADDR, offset)
+#define PWM1_REG(offset) _REG32(PWM1_CTRL_ADDR, offset)
+#define PWM2_REG(offset) _REG32(PWM2_CTRL_ADDR, offset)
+#define SPI0_REG(offset) _REG32(SPI0_CTRL_ADDR, offset)
+#define SPI1_REG(offset) _REG32(SPI1_CTRL_ADDR, offset)
+#define SPI2_REG(offset) _REG32(SPI2_CTRL_ADDR, offset)
+#define UART0_REG(offset) _REG32(UART0_CTRL_ADDR, offset)
+#define UART1_REG(offset) _REG32(UART1_CTRL_ADDR, offset)
+
+// Misc
+
+#include <stdint.h>
+
+#define NUM_GPIO 32
+
+#define PLIC_NUM_INTERRUPTS 52
+#define PLIC_NUM_PRIORITIES 7
+
+#include "hifive1.h"
+
+unsigned long get_cpu_freq(void);
+unsigned long get_timer_freq(void);
+uint64_t get_timer_value(void);
+
+#endif /* _SIFIVE_PLATFORM_H */

+ 36 - 0
libcpu/risc-v/e310/sifive/bits.h

@@ -0,0 +1,36 @@
+// See LICENSE for license details.
+#ifndef _RISCV_BITS_H
+#define _RISCV_BITS_H
+
+#define likely(x) __builtin_expect((x), 1)
+#define unlikely(x) __builtin_expect((x), 0)
+
+#define ROUNDUP(a, b) ((((a)-1)/(b)+1)*(b))
+#define ROUNDDOWN(a, b) ((a)/(b)*(b))
+
+#define MAX(a, b) ((a) > (b) ? (a) : (b))
+#define MIN(a, b) ((a) < (b) ? (a) : (b))
+#define CLAMP(a, lo, hi) MIN(MAX(a, lo), hi)
+
+#define EXTRACT_FIELD(val, which) (((val) & (which)) / ((which) & ~((which)-1)))
+#define INSERT_FIELD(val, which, fieldval) (((val) & ~(which)) | ((fieldval) * ((which) & ~((which)-1))))
+
+#define STR(x) XSTR(x)
+#define XSTR(x) #x
+
+#if __riscv_xlen == 64
+# define SLL32    sllw
+# define STORE    sd
+# define LOAD     ld
+# define LWU      lwu
+# define LOG_REGBYTES 3
+#else
+# define SLL32    sll
+# define STORE    sw
+# define LOAD     lw
+# define LWU      lw
+# define LOG_REGBYTES 2
+#endif
+#define REGBYTES (1 << LOG_REGBYTES)
+
+#endif

+ 18 - 0
libcpu/risc-v/e310/sifive/const.h

@@ -0,0 +1,18 @@
+// See LICENSE for license details.
+/* Derived from <linux/const.h> */
+
+#ifndef _SIFIVE_CONST_H
+#define _SIFIVE_CONST_H
+
+#ifdef __ASSEMBLER__
+#define _AC(X,Y)        X
+#define _AT(T,X)        X
+#else
+#define _AC(X,Y)        (X##Y)
+#define _AT(T,X)        ((T)(X))
+#endif /* !__ASSEMBLER__*/
+
+#define _BITUL(x)       (_AC(1,UL) << (x))
+#define _BITULL(x)      (_AC(1,ULL) << (x))
+
+#endif /* _SIFIVE_CONST_H */

+ 88 - 0
libcpu/risc-v/e310/sifive/devices/aon.h

@@ -0,0 +1,88 @@
+// See LICENSE for license details.
+
+#ifndef _SIFIVE_AON_H
+#define _SIFIVE_AON_H
+
+/* Register offsets */
+
+#define AON_WDOGCFG     0x000
+#define AON_WDOGCOUNT   0x008
+#define AON_WDOGS       0x010
+#define AON_WDOGFEED    0x018
+#define AON_WDOGKEY     0x01C
+#define AON_WDOGCMP     0x020
+
+#define AON_RTCCFG      0x040
+#define AON_RTCLO       0x048
+#define AON_RTCHI       0x04C
+#define AON_RTCS        0x050
+#define AON_RTCCMP      0x060
+
+#define AON_BACKUP0     0x080
+#define AON_BACKUP1     0x084
+#define AON_BACKUP2     0x088
+#define AON_BACKUP3     0x08C
+#define AON_BACKUP4     0x090
+#define AON_BACKUP5     0x094
+#define AON_BACKUP6     0x098
+#define AON_BACKUP7     0x09C
+#define AON_BACKUP8     0x0A0
+#define AON_BACKUP9     0x0A4
+#define AON_BACKUP10    0x0A8
+#define AON_BACKUP11    0x0AC
+#define AON_BACKUP12    0x0B0
+#define AON_BACKUP13    0x0B4
+#define AON_BACKUP14    0x0B8
+#define AON_BACKUP15    0x0BC
+
+#define AON_PMUWAKEUPI0 0x100
+#define AON_PMUWAKEUPI1 0x104
+#define AON_PMUWAKEUPI2 0x108
+#define AON_PMUWAKEUPI3 0x10C
+#define AON_PMUWAKEUPI4 0x110
+#define AON_PMUWAKEUPI5 0x114
+#define AON_PMUWAKEUPI6 0x118
+#define AON_PMUWAKEUPI7 0x11C
+#define AON_PMUSLEEPI0  0x120
+#define AON_PMUSLEEPI1  0x124
+#define AON_PMUSLEEPI2  0x128
+#define AON_PMUSLEEPI3  0x12C
+#define AON_PMUSLEEPI4  0x130
+#define AON_PMUSLEEPI5  0x134
+#define AON_PMUSLEEPI6  0x138
+#define AON_PMUSLEEPI7  0x13C
+#define AON_PMUIE       0x140
+#define AON_PMUCAUSE    0x144
+#define AON_PMUSLEEP    0x148
+#define AON_PMUKEY      0x14C
+
+#define AON_LFROSC      0x070
+/* Constants */
+
+#define AON_WDOGKEY_VALUE  0x51F15E
+#define AON_WDOGFEED_VALUE 0xD09F00D
+
+#define AON_WDOGCFG_SCALE       0x0000000F
+#define AON_WDOGCFG_RSTEN       0x00000100
+#define AON_WDOGCFG_ZEROCMP     0x00000200
+#define AON_WDOGCFG_ENALWAYS    0x00001000
+#define AON_WDOGCFG_ENCOREAWAKE 0x00002000
+#define AON_WDOGCFG_CMPIP       0x10000000
+
+#define AON_RTCCFG_SCALE     0x0000000F
+#define AON_RTCCFG_ENALWAYS  0x00001000
+#define AON_RTCCFG_CMPIP     0x10000000
+
+#define AON_WAKEUPCAUSE_RESET   0x00
+#define AON_WAKEUPCAUSE_RTC     0x01
+#define AON_WAKEUPCAUSE_DWAKEUP 0x02
+#define AON_WAKEUPCAUSE_AWAKEUP 0x03
+
+#define AON_RESETCAUSE_POWERON  0x0000
+#define AON_RESETCAUSE_EXTERNAL 0x0100
+#define AON_RESETCAUSE_WATCHDOG 0x0200
+
+#define AON_PMUCAUSE_WAKEUPCAUSE 0x00FF
+#define AON_PMUCAUSE_RESETCAUSE  0xFF00
+
+#endif /* _SIFIVE_AON_H */

+ 14 - 0
libcpu/risc-v/e310/sifive/devices/clint.h

@@ -0,0 +1,14 @@
+// See LICENSE for license details
+
+#ifndef _SIFIVE_CLINT_H
+#define _SIFIVE_CLINT_H
+
+
+#define CLINT_MSIP 0x0000
+#define CLINT_MSIP_size   0x4
+#define CLINT_MTIMECMP 0x4000
+#define CLINT_MTIMECMP_size 0x8
+#define CLINT_MTIME 0xBFF8
+#define CLINT_MTIME_size 0x8
+
+#endif /* _SIFIVE_CLINT_H */ 

+ 24 - 0
libcpu/risc-v/e310/sifive/devices/gpio.h

@@ -0,0 +1,24 @@
+// See LICENSE for license details.
+
+#ifndef _SIFIVE_GPIO_H
+#define _SIFIVE_GPIO_H
+
+#define GPIO_INPUT_VAL  (0x00)
+#define GPIO_INPUT_EN   (0x04)
+#define GPIO_OUTPUT_EN  (0x08)
+#define GPIO_OUTPUT_VAL (0x0C)
+#define GPIO_PULLUP_EN  (0x10)
+#define GPIO_DRIVE      (0x14)
+#define GPIO_RISE_IE    (0x18)
+#define GPIO_RISE_IP    (0x1C)
+#define GPIO_FALL_IE    (0x20)
+#define GPIO_FALL_IP    (0x24)
+#define GPIO_HIGH_IE    (0x28)
+#define GPIO_HIGH_IP    (0x2C)
+#define GPIO_LOW_IE     (0x30)
+#define GPIO_LOW_IP     (0x34)
+#define GPIO_IOF_EN     (0x38)
+#define GPIO_IOF_SEL    (0x3C)
+#define GPIO_OUTPUT_XOR    (0x40)
+
+#endif /* _SIFIVE_GPIO_H */

+ 23 - 0
libcpu/risc-v/e310/sifive/devices/otp.h

@@ -0,0 +1,23 @@
+// See LICENSE for license details.
+
+#ifndef _SIFIVE_OTP_H
+#define _SIFIVE_OTP_H
+
+/* Register offsets */
+
+#define OTP_LOCK         0x00
+#define OTP_CK           0x04
+#define OTP_OE           0x08
+#define OTP_SEL          0x0C
+#define OTP_WE           0x10
+#define OTP_MR           0x14
+#define OTP_MRR          0x18
+#define OTP_MPP          0x1C
+#define OTP_VRREN        0x20
+#define OTP_VPPEN        0x24
+#define OTP_A            0x28
+#define OTP_D            0x2C
+#define OTP_Q            0x30
+#define OTP_READ_TIMINGS 0x34
+
+#endif

+ 31 - 0
libcpu/risc-v/e310/sifive/devices/plic.h

@@ -0,0 +1,31 @@
+// See LICENSE for license details.
+
+#ifndef PLIC_H
+#define PLIC_H
+
+#include <sifive/const.h>
+
+// 32 bits per source
+#define PLIC_PRIORITY_OFFSET            _AC(0x0000,UL)
+#define PLIC_PRIORITY_SHIFT_PER_SOURCE  2
+// 1 bit per source (1 address)
+#define PLIC_PENDING_OFFSET             _AC(0x1000,UL)
+#define PLIC_PENDING_SHIFT_PER_SOURCE   0
+
+//0x80 per target
+#define PLIC_ENABLE_OFFSET              _AC(0x2000,UL)
+#define PLIC_ENABLE_SHIFT_PER_TARGET    7
+
+
+#define PLIC_THRESHOLD_OFFSET           _AC(0x200000,UL)
+#define PLIC_CLAIM_OFFSET               _AC(0x200004,UL)
+#define PLIC_THRESHOLD_SHIFT_PER_TARGET 12
+#define PLIC_CLAIM_SHIFT_PER_TARGET     12
+
+#define PLIC_MAX_SOURCE                 1023
+#define PLIC_SOURCE_MASK                0x3FF
+
+#define PLIC_MAX_TARGET                 15871
+#define PLIC_TARGET_MASK                0x3FFF
+
+#endif /* PLIC_H */

+ 56 - 0
libcpu/risc-v/e310/sifive/devices/prci.h

@@ -0,0 +1,56 @@
+// See LICENSE for license details.
+
+#ifndef _SIFIVE_PRCI_H
+#define _SIFIVE_PRCI_H
+
+/* Register offsets */
+
+#define PRCI_HFROSCCFG   (0x0000)
+#define PRCI_HFXOSCCFG   (0x0004)
+#define PRCI_PLLCFG      (0x0008)
+#define PRCI_PLLDIV      (0x000C)
+#define PRCI_PROCMONCFG  (0x00F0)
+
+/* Fields */
+#define ROSC_DIV(x)    (((x) & 0x2F) << 0 ) 
+#define ROSC_TRIM(x)   (((x) & 0x1F) << 16)
+#define ROSC_EN(x)     (((x) & 0x1 ) << 30) 
+#define ROSC_RDY(x)    (((x) & 0x1 ) << 31)
+
+#define XOSC_EN(x)     (((x) & 0x1) << 30)
+#define XOSC_RDY(x)    (((x) & 0x1) << 31)
+
+#define PLL_R(x)       (((x) & 0x7)  << 0)
+// single reserved bit for F LSB.
+#define PLL_F(x)       (((x) & 0x3F) << 4)
+#define PLL_Q(x)       (((x) & 0x3)  << 10)
+#define PLL_SEL(x)     (((x) & 0x1)  << 16)
+#define PLL_REFSEL(x)  (((x) & 0x1)  << 17)
+#define PLL_BYPASS(x)  (((x) & 0x1)  << 18)
+#define PLL_LOCK(x)    (((x) & 0x1)  << 31)
+
+#define PLL_R_default 0x1
+#define PLL_F_default 0x1F
+#define PLL_Q_default 0x3
+
+#define PLL_REFSEL_HFROSC 0x0
+#define PLL_REFSEL_HFXOSC 0x1
+
+#define PLL_SEL_HFROSC 0x0
+#define PLL_SEL_PLL    0x1
+
+#define PLL_FINAL_DIV(x)      (((x) & 0x3F) << 0)
+#define PLL_FINAL_DIV_BY_1(x) (((x) & 0x1 ) << 8)
+
+#define PROCMON_DIV(x)   (((x) & 0x1F) << 0)
+#define PROCMON_TRIM(x)  (((x) & 0x1F) << 8)
+#define PROCMON_EN(x)    (((x) & 0x1)  << 16)
+#define PROCMON_SEL(x)   (((x) & 0x3)  << 24)
+#define PROCMON_NT_EN(x) (((x) & 0x1)  << 28)
+
+#define PROCMON_SEL_HFCLK     0
+#define PROCMON_SEL_HFXOSCIN  1
+#define PROCMON_SEL_PLLOUTDIV 2
+#define PROCMON_SEL_PROCMON   3
+
+#endif // _SIFIVE_PRCI_H

+ 37 - 0
libcpu/risc-v/e310/sifive/devices/pwm.h

@@ -0,0 +1,37 @@
+// See LICENSE for license details.
+
+#ifndef _SIFIVE_PWM_H
+#define _SIFIVE_PWM_H
+
+/* Register offsets */
+
+#define PWM_CFG   0x00
+#define PWM_COUNT 0x08
+#define PWM_S     0x10
+#define PWM_CMP0  0x20
+#define PWM_CMP1  0x24
+#define PWM_CMP2  0x28
+#define PWM_CMP3  0x2C
+
+/* Constants */
+
+#define PWM_CFG_SCALE       0x0000000F
+#define PWM_CFG_STICKY      0x00000100
+#define PWM_CFG_ZEROCMP     0x00000200
+#define PWM_CFG_DEGLITCH    0x00000400
+#define PWM_CFG_ENALWAYS    0x00001000
+#define PWM_CFG_ONESHOT     0x00002000
+#define PWM_CFG_CMP0CENTER  0x00010000
+#define PWM_CFG_CMP1CENTER  0x00020000
+#define PWM_CFG_CMP2CENTER  0x00040000
+#define PWM_CFG_CMP3CENTER  0x00080000
+#define PWM_CFG_CMP0GANG    0x01000000
+#define PWM_CFG_CMP1GANG    0x02000000
+#define PWM_CFG_CMP2GANG    0x04000000
+#define PWM_CFG_CMP3GANG    0x08000000
+#define PWM_CFG_CMP0IP      0x10000000
+#define PWM_CFG_CMP1IP      0x20000000
+#define PWM_CFG_CMP2IP      0x40000000
+#define PWM_CFG_CMP3IP      0x80000000
+
+#endif /* _SIFIVE_PWM_H */

+ 80 - 0
libcpu/risc-v/e310/sifive/devices/spi.h

@@ -0,0 +1,80 @@
+// See LICENSE for license details.
+
+#ifndef _SIFIVE_SPI_H
+#define _SIFIVE_SPI_H
+
+/* Register offsets */
+
+#define SPI_REG_SCKDIV          0x00
+#define SPI_REG_SCKMODE         0x04
+#define SPI_REG_CSID            0x10
+#define SPI_REG_CSDEF           0x14
+#define SPI_REG_CSMODE          0x18
+
+#define SPI_REG_DCSSCK          0x28
+#define SPI_REG_DSCKCS          0x2a
+#define SPI_REG_DINTERCS        0x2c
+#define SPI_REG_DINTERXFR       0x2e
+
+#define SPI_REG_FMT             0x40
+#define SPI_REG_TXFIFO          0x48
+#define SPI_REG_RXFIFO          0x4c
+#define SPI_REG_TXCTRL          0x50
+#define SPI_REG_RXCTRL          0x54
+
+#define SPI_REG_FCTRL           0x60
+#define SPI_REG_FFMT            0x64
+
+#define SPI_REG_IE              0x70
+#define SPI_REG_IP              0x74
+
+/* Fields */
+
+#define SPI_SCK_POL             0x1
+#define SPI_SCK_PHA             0x2
+
+#define SPI_FMT_PROTO(x)        ((x) & 0x3)
+#define SPI_FMT_ENDIAN(x)       (((x) & 0x1) << 2)
+#define SPI_FMT_DIR(x)          (((x) & 0x1) << 3)
+#define SPI_FMT_LEN(x)          (((x) & 0xf) << 16)
+
+/* TXCTRL register */
+#define SPI_TXWM(x)             ((x) & 0xffff)
+/* RXCTRL register */
+#define SPI_RXWM(x)             ((x) & 0xffff)
+
+#define SPI_IP_TXWM             0x1
+#define SPI_IP_RXWM             0x2
+
+#define SPI_FCTRL_EN            0x1
+
+#define SPI_INSN_CMD_EN         0x1
+#define SPI_INSN_ADDR_LEN(x)    (((x) & 0x7) << 1)
+#define SPI_INSN_PAD_CNT(x)     (((x) & 0xf) << 4)
+#define SPI_INSN_CMD_PROTO(x)   (((x) & 0x3) << 8)
+#define SPI_INSN_ADDR_PROTO(x)  (((x) & 0x3) << 10)
+#define SPI_INSN_DATA_PROTO(x)  (((x) & 0x3) << 12)
+#define SPI_INSN_CMD_CODE(x)    (((x) & 0xff) << 16)
+#define SPI_INSN_PAD_CODE(x)    (((x) & 0xff) << 24)
+
+#define SPI_TXFIFO_FULL  (1 << 31)   
+#define SPI_RXFIFO_EMPTY (1 << 31)   
+
+/* Values */
+
+#define SPI_CSMODE_AUTO         0
+#define SPI_CSMODE_HOLD         2
+#define SPI_CSMODE_OFF          3
+
+#define SPI_DIR_RX              0
+#define SPI_DIR_TX              1
+
+#define SPI_PROTO_S             0
+#define SPI_PROTO_D             1
+#define SPI_PROTO_Q             2
+
+#define SPI_ENDIAN_MSB          0
+#define SPI_ENDIAN_LSB          1
+
+
+#endif /* _SIFIVE_SPI_H */

+ 27 - 0
libcpu/risc-v/e310/sifive/devices/uart.h

@@ -0,0 +1,27 @@
+// See LICENSE for license details.
+
+#ifndef _SIFIVE_UART_H
+#define _SIFIVE_UART_H
+
+/* Register offsets */
+#define UART_REG_TXFIFO         0x00
+#define UART_REG_RXFIFO         0x04
+#define UART_REG_TXCTRL         0x08
+#define UART_REG_RXCTRL         0x0c
+#define UART_REG_IE             0x10
+#define UART_REG_IP             0x14
+#define UART_REG_DIV            0x18
+
+/* TXCTRL register */
+#define UART_TXEN               0x1
+#define UART_TXWM(x)            (((x) & 0xffff) << 16)
+
+/* RXCTRL register */
+#define UART_RXEN               0x1
+#define UART_RXWM(x)            (((x) & 0xffff) << 16)
+
+/* IP register */
+#define UART_IP_TXWM            0x1
+#define UART_IP_RXWM            0x2
+
+#endif /* _SIFIVE_UART_H */

+ 17 - 0
libcpu/risc-v/e310/sifive/sections.h

@@ -0,0 +1,17 @@
+// See LICENSE for license details.
+#ifndef _SECTIONS_H
+#define _SECTIONS_H
+
+extern unsigned char _rom[];
+extern unsigned char _rom_end[];
+
+extern unsigned char _ram[];
+extern unsigned char _ram_end[];
+
+extern unsigned char _ftext[];
+extern unsigned char _etext[];
+extern unsigned char _fbss[];
+extern unsigned char _ebss[];
+extern unsigned char _end[];
+
+#endif /* _SECTIONS_H */

+ 65 - 0
libcpu/risc-v/e310/sifive/smp.h

@@ -0,0 +1,65 @@
+#ifndef SIFIVE_SMP
+#define SIFIVE_SMP
+
+// The maximum number of HARTs this code supports
+#ifndef MAX_HARTS
+#define MAX_HARTS 32
+#endif
+#define CLINT_END_HART_IPI CLINT_CTRL_ADDR + (MAX_HARTS*4)
+
+// The hart that non-SMP tests should run on
+#ifndef NONSMP_HART
+#define NONSMP_HART 0
+#endif
+
+/* If your test cannot handle multiple-threads, use this: 
+ *   smp_disable(reg1)
+ */
+#define smp_disable(reg1, reg2)			 \
+  csrr reg1, mhartid				;\
+  li   reg2, NONSMP_HART			;\
+  beq  reg1, reg2, hart0_entry			;\
+42:						;\
+  wfi    					;\
+  j 42b						;\
+hart0_entry:
+
+/* If your test needs to temporarily block multiple-threads, do this:
+ *    smp_pause(reg1, reg2)
+ *    ... single-threaded work ...
+ *    smp_resume(reg1, reg2)
+ *    ... multi-threaded work ...
+ */
+
+#define smp_pause(reg1, reg2)	 \
+  li reg2, 0x8			;\
+  csrw mie, reg2		;\
+  csrr reg2, mhartid		;\
+  bnez reg2, 42f
+
+#define smp_resume(reg1, reg2)	 \
+  li reg1, CLINT_CTRL_ADDR	;\
+41:				;\
+  li reg2, 1			;\
+  sw reg2, 0(reg1)		;\
+  addi reg1, reg1, 4		;\
+  li reg2, CLINT_END_HART_IPI	;\
+  blt reg1, reg2, 41b		;\
+42:				;\
+  wfi    			;\
+  csrr reg2, mip		;\
+  andi reg2, reg2, 0x8		;\
+  beqz reg2, 42b		;\
+  li reg1, CLINT_CTRL_ADDR	;\
+  csrr reg2, mhartid		;\
+  slli reg2, reg2, 2		;\
+  add reg2, reg2, reg1		;\
+  sw zero, 0(reg2)		;\
+41:				;\
+  lw reg2, 0(reg1)		;\
+  bnez reg2, 41b		;\
+  addi reg1, reg1, 4		;\
+  li reg2, CLINT_END_HART_IPI	;\
+  blt reg1, reg2, 41b
+
+#endif

+ 81 - 0
libcpu/risc-v/e310/stack.c

@@ -0,0 +1,81 @@
+/*
+ * File      : stack.c
+ * This file is part of RT-Thread RTOS
+ * COPYRIGHT (C) 2006, RT-Thread Development Team
+ *
+ *  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 program is distributed in the hope that it will be useful,
+ *  but WITHOUT ANY WARRANTY; without even the implied warranty of
+ *  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ *  GNU General Public License for more details.
+ *
+ *  You should have received a copy of the GNU General Public License along
+ *  with this program; if not, write to the Free Software Foundation, Inc.,
+ *  51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
+ *
+ * Change Logs:
+ * Date           Author       Notes
+ * 2017-07-31     zhangjun      copy from mini2440
+ */
+#include <rtthread.h>
+
+/**
+ * This function will initialize thread stack
+ *
+ * @param tentry the entry of thread
+ * @param parameter the parameter of entry
+ * @param stack_addr the beginning stack address
+ * @param texit the function will be called when thread exit
+ *
+ * @return stack address
+ */
+rt_uint8_t *rt_hw_stack_init(void *tentry, void *parameter,
+                             rt_uint8_t *stack_addr, void *texit)
+{
+    rt_uint32_t *stk;
+
+    //stk      = (rt_uint32_t*)stack_addr;
+    stack_addr += sizeof(rt_uint32_t);
+    stack_addr  = (rt_uint8_t *)RT_ALIGN_DOWN((rt_uint32_t)stack_addr, 8);
+    stk  = (rt_uint32_t *)stack_addr;
+
+    *(--stk) = (rt_uint32_t)tentry;         /* entry point */
+    *(--stk) = (rt_uint32_t)texit;          /* ra */
+    *(--stk) = (rt_uint32_t)parameter;      /* a0 */
+    *(--stk) = 0xffffffff;          	    /* a1 */
+    *(--stk) = 0xffffffff;          	    /* a2 */
+    *(--stk) = 0xffffffff;          	    /* a3 */
+    *(--stk) = 0xffffffff;          	    /* a4 */
+    *(--stk) = 0xffffffff;          	    /* a5 */
+    *(--stk) = 0xffffffff;          	    /* a6 */
+    *(--stk) = 0xffffffff;          	    /* a7 */
+    *(--stk) = 0xffffffff;          	    /* s0/fp */
+    *(--stk) = 0xffffffff;          	    /* s1 */
+    *(--stk) = 0xffffffff;          	    /* s2 */
+    *(--stk) = 0xffffffff;          	    /* s3 */
+    *(--stk) = 0xffffffff;          	    /* s4 */
+    *(--stk) = 0xffffffff;          	    /* s5 */
+    *(--stk) = 0xffffffff;          	    /* s6 */
+    *(--stk) = 0xffffffff;          	    /* s7 */
+    *(--stk) = 0xffffffff;          	    /* s8 */
+    *(--stk) = 0xffffffff;          	    /* s9 */
+    *(--stk) = 0xffffffff;          	    /* s10*/
+    *(--stk) = 0xffffffff;          	    /* s11*/
+    *(--stk) = 0xffffffff;          	    /* t0 */
+    *(--stk) = 0xffffffff;          	    /* t1 */
+    *(--stk) = 0xffffffff;          	    /* t2 */
+    *(--stk) = 0xffffffff;          	    /* t3 */
+    *(--stk) = 0xffffffff;          	    /* t4 */
+    *(--stk) = 0xffffffff;          	    /* t5 */
+    *(--stk) = 0xffffffff;          	    /* t6 */
+    *(--stk) = 0xffffffff;          	    /* tp */
+    *(--stk) = 0xffffffff;          	    /* gp */
+    *(--stk) = 0x880;          	            /* mie */
+//    *(--stk) = (rt_uint32_t)parameter;      /* r0 : argument */
+    /* return task's current stack address */
+    return (rt_uint8_t *)stk;
+}

+ 297 - 0
libcpu/risc-v/e310/start_gcc.S

@@ -0,0 +1,297 @@
+;/*
+; * File      : start_gcc.S
+; * This file is part of RT-Thread RTOS
+; * COPYRIGHT (C) 2006, RT-Thread Development Team
+; *
+; *  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 program is distributed in the hope that it will be useful,
+; *  but WITHOUT ANY WARRANTY; without even the implied warranty of
+; *  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+; *  GNU General Public License for more details.
+; *
+; *  You should have received a copy of the GNU General Public License along
+; *  with this program; if not, write to the Free Software Foundation, Inc.,
+; *  51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
+; *
+; * Change Logs:
+; * Date           Author       Notes
+; * 2017-07-16     zhangjun    for hifive1
+; */
+#include <sifive/smp.h>
+#define CLINT_CTRL_ADDR 0x02000000
+
+.section .init
+.globl _start
+.type _start,@function
+
+_start:
+	.cfi_startproc
+	.cfi_undefined ra
+.option push
+.option norelax
+	la gp, __global_pointer$
+.option pop
+	la sp, _sp
+/*
+ *disable all interrupt at startup
+ */
+	csrrc a5, mstatus, 0xb
+
+#if defined(ENABLE_SMP)
+	smp_pause(t0, t1)
+#endif
+
+	/* Load data section */
+	la a0, _data_lma
+	la a1, _data
+	la a2, _edata
+	bgeu a1, a2, 2f
+1:
+	lw t0, (a0)
+	sw t0, (a1)
+	addi a0, a0, 4
+	addi a1, a1, 4
+	bltu a1, a2, 1b
+2:
+
+	/* Clear bss section */
+	la a0, __bss_start
+	la a1, _end
+	bgeu a0, a1, 2f
+1:
+	sw zero, (a0)
+	addi a0, a0, 4
+	bltu a0, a1, 1b
+2:
+
+	/* Call global constructors */
+	la a0, __libc_fini_array
+	call atexit
+	call __libc_init_array
+	/*call _init directly in rt-thread*/
+        call _init
+
+#ifndef __riscv_float_abi_soft
+	/* Enable FPU */
+	li t0, MSTATUS_FS
+	csrs mstatus, t0
+	csrr t1, mstatus
+	and t1, t1, t0
+	beqz t1, 1f
+	fssr x0
+1:
+#endif
+
+#if defined(ENABLE_SMP)
+	smp_resume(t0, t1)
+
+	csrr a0, mhartid
+	bnez a0, 2f
+#endif
+
+	auipc ra, 0
+	addi sp, sp, -16
+#if __riscv_xlen == 32
+	sw ra, 8(sp)
+#else
+	sd ra, 8(sp)
+#endif
+
+	/* argc = argv = 0 */
+	li a0, 0
+	li a1, 0
+	call main
+	tail exit
+1:
+	j 1b
+
+#if defined(ENABLE_SMP)
+2:
+	la t0, trap_entry
+	csrw mtvec, t0
+
+	csrr a0, mhartid
+	la t1, _sp
+	slli t0, a0, 10
+	sub sp, t1, t0
+
+	auipc ra, 0
+	addi sp, sp, -16
+#if __riscv_xlen == 32
+	sw ra, 8(sp)
+#else
+	sd ra, 8(sp)
+#endif
+
+	call secondary_main
+	tail exit
+
+1:
+	j 1b
+#endif
+	.cfi_endproc
+
+#include "encoding.h"
+#include "sifive/bits.h"
+
+  .section      .text.entry	
+  .align 2
+  .global trap_entry
+trap_entry:
+  addi  sp,  sp, -32*REGBYTES
+
+  STORE x30, 1*REGBYTES(sp)
+  STORE x31, 2*REGBYTES(sp)
+  STORE x3,  3*REGBYTES(sp)
+  STORE x4,  4*REGBYTES(sp)
+  STORE x5,  5*REGBYTES(sp)
+  STORE x6,  6*REGBYTES(sp)
+  STORE x7,  7*REGBYTES(sp)
+  STORE x8,  8*REGBYTES(sp)
+  STORE x9,  9*REGBYTES(sp)
+  STORE x10, 10*REGBYTES(sp)
+  STORE x11, 11*REGBYTES(sp)
+  STORE x12, 12*REGBYTES(sp)
+  STORE x13, 13*REGBYTES(sp)
+  STORE x14, 14*REGBYTES(sp)
+  STORE x15, 15*REGBYTES(sp)
+  STORE x16, 16*REGBYTES(sp)
+  STORE x17, 17*REGBYTES(sp)
+  STORE x18, 18*REGBYTES(sp)
+  STORE x19, 19*REGBYTES(sp)
+  STORE x20, 20*REGBYTES(sp)
+  STORE x21, 21*REGBYTES(sp)
+  STORE x22, 22*REGBYTES(sp)
+  STORE x23, 23*REGBYTES(sp)
+  STORE x24, 24*REGBYTES(sp)
+  STORE x25, 25*REGBYTES(sp)
+  STORE x26, 26*REGBYTES(sp)
+  STORE x27, 27*REGBYTES(sp)
+  STORE x28, 28*REGBYTES(sp)
+  STORE x10, 29*REGBYTES(sp)
+  STORE x1,  30*REGBYTES(sp)
+  csrr  x10, mepc
+  STORE x10, 31*REGBYTES(sp)
+  csrr  x10, mie
+  STORE x10, 0*REGBYTES(sp)
+
+
+/*
+ *Remain in M-mode after mret
+ *enable interrupt in M-mode
+ */
+  li    t0, MSTATUS_MPP
+  csrrs t0, mstatus, t0
+
+  call rt_interrupt_enter
+  csrr a0, mcause
+  lui  a5, 0x80000 
+  not  a5, a5
+  and  a5, a5, a0
+  li   a4, 11
+  mv   s1, a1
+  /*Machine external interrupt*/
+  bne  a5, a4, 1f
+  call rt_hw_trap_irq
+1:
+  /*Machine timer interrupt*/
+  li   a4, 7
+  bne  a5, a4, 2f
+  call rt_systick_handler
+2:
+  call rt_interrupt_leave
+
+  la   a0, rt_thread_switch_interrupt_flag
+  lw   a1, (a0)
+  bnez a1, rt_hw_context_switch_interrupt_do
+
+
+  LOAD x30, 1*REGBYTES(sp)
+  LOAD x31, 2*REGBYTES(sp)
+  LOAD x3,  3*REGBYTES(sp)
+  LOAD x4,  4*REGBYTES(sp)
+  LOAD x5,  5*REGBYTES(sp)
+  LOAD x6,  6*REGBYTES(sp)
+  LOAD x7,  7*REGBYTES(sp)
+  LOAD x8,  8*REGBYTES(sp)
+  LOAD x9,  9*REGBYTES(sp)
+  LOAD x29, 10*REGBYTES(sp)
+  LOAD x11, 11*REGBYTES(sp)
+  LOAD x12, 12*REGBYTES(sp)
+  LOAD x13, 13*REGBYTES(sp)
+  LOAD x14, 14*REGBYTES(sp)
+  LOAD x15, 15*REGBYTES(sp)
+  LOAD x16, 16*REGBYTES(sp)
+  LOAD x17, 17*REGBYTES(sp)
+  LOAD x18, 18*REGBYTES(sp)
+  LOAD x19, 19*REGBYTES(sp)
+  LOAD x20, 20*REGBYTES(sp)
+  LOAD x21, 21*REGBYTES(sp)
+  LOAD x22, 22*REGBYTES(sp)
+  LOAD x23, 23*REGBYTES(sp)
+  LOAD x24, 24*REGBYTES(sp)
+  LOAD x25, 25*REGBYTES(sp)
+  LOAD x26, 26*REGBYTES(sp)
+  LOAD x27, 27*REGBYTES(sp)
+  LOAD x28, 28*REGBYTES(sp)
+  LOAD x10, 31*REGBYTES(sp)
+  csrw mepc,x10
+  LOAD x10, 0*REGBYTES(sp)
+  csrw mie, x10
+  LOAD x10, 29*REGBYTES(sp)
+  LOAD x1,  30*REGBYTES(sp)
+
+  addi sp,  sp, 32*REGBYTES
+  mret
+
+rt_hw_context_switch_interrupt_do:
+  /*clear rt_thread_switch_interrupt_flag*/
+  la   a0, rt_thread_switch_interrupt_flag
+  li   a5, 0
+  sw   a5, (a0)
+
+  LOAD a0,  rt_interrupt_from_thread
+  STORE sp,  (a0)
+  LOAD a0,  rt_interrupt_to_thread
+  LOAD sp,  (a0)
+  LOAD x30, 1*REGBYTES(sp)
+  LOAD x31, 2*REGBYTES(sp)
+  LOAD x3,  3*REGBYTES(sp)
+  LOAD x4,  4*REGBYTES(sp)
+  LOAD x5,  5*REGBYTES(sp)
+  LOAD x6,  6*REGBYTES(sp)
+  LOAD x7,  7*REGBYTES(sp)
+  LOAD x8,  8*REGBYTES(sp)
+  LOAD x9,  9*REGBYTES(sp)
+  LOAD x29, 10*REGBYTES(sp)
+  LOAD x11, 11*REGBYTES(sp)
+  LOAD x12, 12*REGBYTES(sp)
+  LOAD x13, 13*REGBYTES(sp)
+  LOAD x14, 14*REGBYTES(sp)
+  LOAD x15, 15*REGBYTES(sp)
+  LOAD x16, 16*REGBYTES(sp)
+  LOAD x17, 17*REGBYTES(sp)
+  LOAD x18, 18*REGBYTES(sp)
+  LOAD x19, 19*REGBYTES(sp)
+  LOAD x20, 20*REGBYTES(sp)
+  LOAD x21, 21*REGBYTES(sp)
+  LOAD x22, 22*REGBYTES(sp)
+  LOAD x23, 23*REGBYTES(sp)
+  LOAD x24, 24*REGBYTES(sp)
+  LOAD x25, 25*REGBYTES(sp)
+  LOAD x26, 26*REGBYTES(sp)
+  LOAD x27, 27*REGBYTES(sp)
+  LOAD x28, 28*REGBYTES(sp)
+  LOAD x10, 31*REGBYTES(sp)
+  csrw mepc,x10
+  LOAD x10, 0*REGBYTES(sp)
+  csrw mie, x10
+  LOAD x10, 29*REGBYTES(sp)
+  LOAD x1,  30*REGBYTES(sp)
+  
+  addi sp, sp, 32*REGBYTES
+  mret

+ 55 - 0
libcpu/risc-v/e310/trap.c

@@ -0,0 +1,55 @@
+#include <rtthread.h>
+#include <rthw.h>
+#include <platform.h>
+#include <encoding.h>
+#include "interrupt.h"
+extern struct rt_irq_desc irq_desc[];
+extern rt_uint32_t rt_hw_interrupt_get_active(rt_uint32_t fiq_irq);
+void rt_hw_trap_irq()
+{
+    rt_isr_handler_t isr_func;
+    rt_uint32_t irq;
+    void *param;
+
+    /* get irq number */
+    irq = rt_hw_interrupt_get_active(0);
+
+    /* get interrupt service routine */
+    isr_func = irq_desc[irq].handler;
+    param = irq_desc[irq].param;
+
+    /* turn to interrupt service routine */
+    isr_func(irq, param);
+    rt_hw_interrupt_ack(0, irq);
+
+#ifdef RT_USING_INTERRUPT_INFO
+    irq_desc[irq].counter ++;
+#endif
+}
+void handle_m_ext_interrupt()
+{
+}
+void rt_systick_handler(void)
+{
+    clear_csr(mie, MIP_MTIP);
+
+    // Reset the timer for 3s in the future.
+    // This also clears the existing timer interrupt.
+
+    volatile uint64_t * mtime       = (uint64_t*) (CLINT_CTRL_ADDR + CLINT_MTIME);
+    volatile uint64_t * mtimecmp    = (uint64_t*) (CLINT_CTRL_ADDR + CLINT_MTIMECMP);
+    uint64_t now = *mtime;
+    uint64_t then = now + 2 * RTC_FREQ/RT_TICK_PER_SECOND;
+    *mtimecmp = then;
+    rt_tick_increase();
+
+    // read the current value of the LEDS and invert them.
+/*
+    GPIO_REG(GPIO_OUTPUT_VAL) ^= ((0x1 << RED_LED_OFFSET)   |
+		    (0x1 << GREEN_LED_OFFSET) |
+		    (0x1 << BLUE_LED_OFFSET));
+		    */
+
+    // Re-enable the timer interrupt.
+    set_csr(mie, MIP_MTIP);
+}