Przeglądaj źródła

[bsp] remove hifive1 bsp

liang yongxiang 7 lat temu
rodzic
commit
be27862154

+ 0 - 29
bsp/hifive1/SConstruct

@@ -1,29 +0,0 @@
-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)

+ 0 - 11
bsp/hifive1/applications/SConscript

@@ -1,11 +0,0 @@
-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')

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

@@ -1,59 +0,0 @@
-#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


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

@@ -1,44 +0,0 @@
-#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;
-}

+ 0 - 18
bsp/hifive1/drivers/SConscript

@@ -1,18 +0,0 @@
-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')

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

@@ -1,56 +0,0 @@
-#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


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

@@ -1,55 +0,0 @@
-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


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

@@ -1,90 +0,0 @@
-#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;
-}

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

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

+ 0 - 34
bsp/hifive1/openocd.cfg

@@ -1,34 +0,0 @@
-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

+ 0 - 20
bsp/hifive1/platform/SConscript

@@ -1,20 +0,0 @@
-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')

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

@@ -1,110 +0,0 @@
-#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;
-}

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

@@ -1,12 +0,0 @@
-#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

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

@@ -1,120 +0,0 @@
-#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;
-  
-}

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

@@ -1,47 +0,0 @@
-// 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

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

@@ -1,31 +0,0 @@
-/*
- * 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

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

@@ -1,37 +0,0 @@
-/*
- * 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;
-}

+ 0 - 264
bsp/hifive1/rtconfig.h

@@ -1,264 +0,0 @@
-/* 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

+ 0 - 58
bsp/hifive1/rtconfig.py

@@ -1,58 +0,0 @@
-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   = '/home/zj/risc-v/riscv64-unknown-elf-gcc-20170612-x86_64-linux-centos6/bin'
-
-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 = 'riscv64-unknown-elf-'
-    CC = PREFIX + 'gcc'
-    AS = PREFIX + 'gcc'
-    AR = PREFIX + 'ar'
-    LINK = PREFIX + 'gcc'
-    TARGET_EXT = 'elf'
-    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 '
-    CFLAGS = DEVICE
-    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'

+ 0 - 168
bsp/hifive1/sdram.ld

@@ -1,168 +0,0 @@
-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) }
-
-}

+ 0 - 58
bsp/hifive1/wrap_exit.c

@@ -1,58 +0,0 @@
-#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);
-}