summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--bsp/drivers/clic/clic_driver.c90
-rw-r--r--bsp/drivers/clic/clic_driver.h36
-rw-r--r--bsp/env/common.mk2
-rw-r--r--bsp/env/coreip-e2-arty/init.c95
l---------bsp/env/coreip-e2-arty/openocd.cfg (renamed from bsp/env/coreplexip-e21-arty/openocd.cfg)0
-rw-r--r--bsp/env/coreip-e2-arty/platform.h92
l---------bsp/env/coreip-e2-arty/settings.mk (renamed from bsp/env/coreplexip-e21-arty/settings.mk)0
-rw-r--r--bsp/env/coreip-e2-arty/tim-split.lds157
-rw-r--r--bsp/env/coreip-e2-arty/tim.lds161
l---------bsp/env/coreplexip-e21-arty/dhrystone.lds1
l---------bsp/env/coreplexip-e21-arty/flash.lds1
l---------bsp/env/coreplexip-e21-arty/init.c1
l---------bsp/env/coreplexip-e21-arty/platform.h1
l---------bsp/env/coreplexip-e21-arty/scratchpad.lds1
-rw-r--r--bsp/include/sifive/devices/clic.h29
-rw-r--r--software/clic_vectored/Makefile10
-rwxr-xr-xsoftware/clic_vectored/clic_vectoredbin0 -> 73836 bytes
-rw-r--r--software/clic_vectored/clic_vectored.c95
18 files changed, 742 insertions, 30 deletions
diff --git a/bsp/drivers/clic/clic_driver.c b/bsp/drivers/clic/clic_driver.c
new file mode 100644
index 0000000..8acf4d2
--- /dev/null
+++ b/bsp/drivers/clic/clic_driver.c
@@ -0,0 +1,90 @@
+// See LICENSE for license details.
+
+#include "sifive/devices/clic.h"
+#include "clic/clic_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;
+ }
+}
+
+// Note that there are no assertions or bounds checking on these
+// parameter values.
+void clic_init (
+ clic_instance_t * this_clic,
+ uintptr_t hart_addr,
+ interrupt_function_ptr_t* vect_table,
+ interrupt_function_ptr_t default_handler,
+ uint32_t num_irq,
+ uint32_t num_config_bits
+ )
+{
+ this_clic->hart_addr= hart_addr;
+ this_clic->vect_table= vect_table;
+ this_clic->num_config_bits= num_config_bits;
+
+ //initialize vector table
+ for(int i=0;i++;i<num_irq) {
+ this_clic->vect_table[i] = default_handler;
+ }
+
+ //set base vectors
+ write_csr(mtvt, vect_table);
+
+
+ //clear all interrupt enables and pending
+ volatile_memzero((uint8_t*)(this_clic->hart_addr+CLIC_INTIE), num_irq);
+ volatile_memzero((uint8_t*)(this_clic->hart_addr+CLIC_INTIP), num_irq);
+
+ //clear nlbits and nvbits; all interrupts trap to level 15
+ *(volatile uint8_t*)(this_clic->hart_addr+CLIC_CFG)=0;
+
+}
+
+void clic_install_handler (clic_instance_t * this_clic, uint32_t source, interrupt_function_ptr_t handler) {
+ this_clic->vect_table[source] = handler;
+}
+
+void clic_enable_interrupt (clic_instance_t * this_clic, uint32_t source) {
+ *(volatile uint8_t*)(this_clic->hart_addr+CLIC_INTIE+source) = 1;
+}
+
+void clic_disable_interrupt (clic_instance_t * this_clic, uint32_t source){
+ *(volatile uint8_t*)(this_clic->hart_addr+CLIC_INTIE+source) = 0;
+}
+
+void clic_set_pending(clic_instance_t * this_clic, uint32_t source){
+ *(volatile uint8_t*)(this_clic->hart_addr+CLIC_INTIP+source) = 1;
+}
+
+void clic_clear_pending(clic_instance_t * this_clic, uint32_t source){
+ *(volatile uint8_t*)(this_clic->hart_addr+CLIC_INTIP+source) = 0;
+}
+
+//should return max level set. if level set doesn't match requested, check nlbits
+void clic_set_level (clic_instance_t * this_clic, uint32_t source, uint32_t level){
+
+}
+
+void clic_get_level (clic_instance_t * this_clic, uint32_t source, uint32_t level){
+
+}
+
+void clic_set_priority (clic_instance_t * this_clic, uint32_t source, uint32_t priority){
+
+}
+
+void clic_get_priority (clic_instance_t * this_clic, uint32_t source, uint32_t priority){
+
+
+}
+
+
+
+
diff --git a/bsp/drivers/clic/clic_driver.h b/bsp/drivers/clic/clic_driver.h
new file mode 100644
index 0000000..6e8cf0b
--- /dev/null
+++ b/bsp/drivers/clic/clic_driver.h
@@ -0,0 +1,36 @@
+// See LICENSE file for licence details
+
+#ifndef PLIC_DRIVER_H
+#define PLIC_DRIVER_H
+
+
+__BEGIN_DECLS
+
+#include "platform.h"
+
+typedef void (*interrupt_function_ptr_t) (void);
+
+typedef struct __clic_instance_t
+{
+ uintptr_t hart_addr;
+ interrupt_function_ptr_t* vect_table;
+ uint32_t num_config_bits;
+ uint32_t num_sources;
+} clic_instance_t;
+
+// Note that there are no assertions or bounds checking on these
+// parameter values.
+void clic_init (clic_instance_t * this_clic, uintptr_t hart_addr, interrupt_function_ptr_t* vect_table, interrupt_function_ptr_t default_handler, uint32_t num_irq,uint32_t num_config_bits);
+void clic_install_handler (clic_instance_t * this_clic, uint32_t source, interrupt_function_ptr_t handler);
+void clic_enable_interrupt (clic_instance_t * this_clic, uint32_t source);
+void clic_disable_interrupt (clic_instance_t * this_clic, uint32_t source);
+void clic_set_pending(clic_instance_t * this_clic, uint32_t source);
+void clic_clear_pending(clic_instance_t * this_clic, uint32_t source);
+void clic_set_level (clic_instance_t * this_clic, uint32_t source, uint32_t priority);
+void clic_get_level (clic_instance_t * this_clic, uint32_t source, uint32_t priority);
+void clic_set_priority (clic_instance_t * this_clic, uint32_t source, uint32_t priority);
+void clic_get_priority (clic_instance_t * this_clic, uint32_t source, uint32_t priority);
+
+__END_DECLS
+
+#endif
diff --git a/bsp/env/common.mk b/bsp/env/common.mk
index 4566b80..74939a5 100644
--- a/bsp/env/common.mk
+++ b/bsp/env/common.mk
@@ -25,7 +25,7 @@ INCLUDES += -I$(PLATFORM_DIR)
TOOL_DIR = $(BSP_BASE)/../toolchain/bin
LDFLAGS += -T $(LINKER_SCRIPT) -nostartfiles
-LDFLAGS += -L$(ENV_DIR)
+LDFLAGS += -L$(ENV_DIR) --specs=nano.specs
ASM_OBJS := $(ASM_SRCS:.S=.o)
C_OBJS := $(C_SRCS:.c=.o)
diff --git a/bsp/env/coreip-e2-arty/init.c b/bsp/env/coreip-e2-arty/init.c
new file mode 100644
index 0000000..aaf213c
--- /dev/null
+++ b/bsp/env/coreip-e2-arty/init.c
@@ -0,0 +1,95 @@
+//See LICENSE for license details.
+#include <stdint.h>
+#include <stdio.h>
+#include <unistd.h>
+
+#include "platform.h"
+#include "encoding.h"
+
+#define CPU_FREQ 32000000
+#define XSTR(x) #x
+#define STR(x) XSTR(x)
+
+extern int main(int argc, char** argv);
+
+unsigned long get_cpu_freq()
+{
+ return CPU_FREQ;
+}
+
+unsigned long get_timer_freq()
+{
+ return get_cpu_freq();
+}
+
+uint64_t get_timer_value()
+{
+#if __riscv_xlen == 32
+ while (1) {
+ uint32_t hi = read_csr(mcycleh);
+ uint32_t lo = read_csr(mcycle);
+ if (hi == read_csr(mcycleh))
+ return ((uint64_t)hi << 32) | lo;
+ }
+#else
+ return read_csr(mcycle);
+#endif
+}
+
+static void uart_init(size_t baud_rate)
+{
+ UART0_REG(UART_REG_DIV) = (get_cpu_freq() ) / baud_rate - 1;
+ UART0_REG(UART_REG_TXCTRL) |= UART_TXEN;
+}
+
+
+typedef void (*interrupt_function_ptr_t) (void);
+interrupt_function_ptr_t localISR[CLIC_NUM_INTERRUPTS] __attribute__((aligned(64)));
+
+void trap_entry(void) __attribute__((interrupt("SiFive-CLIC-preemptible"), aligned(64)));
+void trap_entry(void)
+{
+ unsigned long mcause = read_csr(mcause);
+ unsigned long mepc = read_csr(mepc);
+ if (mcause & MCAUSE_INT) {
+ localISR[mcause & MCAUSE_CAUSE] ();
+ } else {
+ while(1);
+ }
+}
+
+#ifdef CLIC_DIRECT
+#else
+void default_handler(void)__attribute__((interrupt("SiFive-CLIC-preemptible")));;
+#endif
+void default_handler(void)
+{
+ puts("default handler\n");
+ while(1);
+}
+
+void _init()
+{
+#ifndef NO_INIT
+ uart_init(115200);
+
+ puts("core freq at " STR(CPU_FREQ) " Hz\n");
+
+//initialize vector table
+ for(int i=0;i++;i<CLIC_NUM_INTERRUPTS) {
+ localISR[i] = &default_handler;
+ }
+ write_csr(mtvt, localISR);
+
+#ifdef CLIC_DIRECT
+ write_csr(mtvec, ((unsigned long)&trap_entry | MTVEC_CLIC));
+#else
+ write_csr(mtvec, ((unsigned long)&trap_entry | MTVEC_CLIC_VECT));
+#endif
+
+#endif
+}
+
+void _fini()
+{
+}
diff --git a/bsp/env/coreplexip-e21-arty/openocd.cfg b/bsp/env/coreip-e2-arty/openocd.cfg
index 2f4de8d..2f4de8d 120000
--- a/bsp/env/coreplexip-e21-arty/openocd.cfg
+++ b/bsp/env/coreip-e2-arty/openocd.cfg
diff --git a/bsp/env/coreip-e2-arty/platform.h b/bsp/env/coreip-e2-arty/platform.h
new file mode 100644
index 0000000..8ee0a83
--- /dev/null
+++ b/bsp/env/coreip-e2-arty/platform.h
@@ -0,0 +1,92 @@
+// See LICENSE for license details.
+
+#ifndef _SIFIVE_PLATFORM_H
+#define _SIFIVE_PLATFORM_H
+
+// Some things missing from the official encoding.h
+
+#if __riscv_xlen == 32
+#define MCAUSE_INT 0x80000000UL
+#define MCAUSE_CAUSE 0x000003FFUL
+#else
+#define MCAUSE_INT 0x8000000000000000UL
+#define MCAUSE_CAUSE 0x00000000000003FFUL
+#endif
+
+#define MTVEC_DIRECT 0X00
+#define MTVEC_VECTORED 0x01
+#define MTVEC_CLIC 0x02
+#define MTVEC_CLIC_VECT 0X03
+
+
+#include "sifive/const.h"
+#include "sifive/devices/gpio.h"
+#include "sifive/devices/clic.h"
+#include "sifive/devices/pwm.h"
+#include "sifive/devices/spi.h"
+#include "sifive/devices/uart.h"
+
+/****************************************************************************
+ * Platform definitions
+ *****************************************************************************/
+
+// Memory map
+#define CLINT_CTRL_ADDR _AC(0x02000000,UL)
+#define CLIC_HART0_ADDR _AC(0x02800000, UL)
+#define GPIO_CTRL_ADDR _AC(0x20002000,UL)
+#define PWM0_CTRL_ADDR _AC(0x20005000,UL)
+#define RAM_MEM_ADDR _AC(0x80000000,UL)
+#define RAM_MEM_SIZE _AC(0x10000,UL)
+#define SPI0_CTRL_ADDR _AC(0x20004000,UL)
+#define SPI0_MEM_ADDR _AC(0x40000000,UL)
+#define SPI0_MEM_SIZE _AC(0x20000000,UL)
+#define TESTBENCH_MEM_ADDR _AC(0x20000000,UL)
+#define TESTBENCH_MEM_SIZE _AC(0x10000000,UL)
+//#define TRAPVEC_TABLE_CTRL_ADDR _AC(0x00001010,UL)
+#define UART0_CTRL_ADDR _AC(0x20000000,UL)
+
+// IOF masks
+
+// Interrupt numbers
+#define RESERVED_INT_BASE 0
+#define UART0_INT_BASE 1
+#define EXTERNAL_INT_BASE 2
+#define SPI0_INT_BASE 6
+#define GPIO_INT_BASE 7
+#define PWM0_INT_BASE 23
+
+// Helper functions
+#define _REG64(p, i) (*(volatile uint64_t *)((p) + (i)))
+#define _REG32(p, i) (*(volatile uint32_t *)((p) + (i)))
+#define _REG16(p, i) (*(volatile uint16_t *)((p) + (i)))
+#define SET_BITS(reg, mask, value) if ((value) == 0) { (reg) &= ~(mask); } else { (reg) |= (mask); }
+#define CLINT_REG(offset) _REG32(CLINT_CTRL_ADDR, offset)
+#define CLIC0_REG(offset) _REG32(CLIC_HART0_ADDR, offset)
+#define CLIC0_REG8(offset) (*(volatile uint8_t *)((CLIC_HART0_ADDR) + (offset)))
+#define GPIO_REG(offset) _REG32(GPIO_CTRL_ADDR, offset)
+#define PWM0_REG(offset) _REG32(PWM0_CTRL_ADDR, offset)
+#define SPI0_REG(offset) _REG32(SPI0_CTRL_ADDR, offset)
+#define UART0_REG(offset) _REG32(UART0_CTRL_ADDR, offset)
+#define CLINT_REG(offset) _REG32(CLINT_CTRL_ADDR, offset)
+#define CLIC0_REG64(offset) _REG64(CLIC_HART0_ADDR, offset)
+#define GPIO_REG64(offset) _REG64(GPIO_CTRL_ADDR, offset)
+#define PWM0_REG64(offset) _REG64(PWM0_CTRL_ADDR, offset)
+#define SPI0_REG64(offset) _REG64(SPI0_CTRL_ADDR, offset)
+#define UART0_REG64(offset) _REG64(UART0_CTRL_ADDR, offset)
+
+// Misc
+
+#define NUM_GPIO 16
+
+#define CLIC_NUM_INTERRUPTS 28 + 16
+#define CLIC_NUM_CONFIG_BITS 4 //2 for E20
+
+#define HAS_BOARD_BUTTONS
+
+#include "coreplexip-arty.h"
+
+unsigned long get_cpu_freq(void);
+unsigned long get_timer_freq(void);
+uint64_t get_timer_value(void);
+
+#endif /* _SIFIVE_PLATFORM_H */
diff --git a/bsp/env/coreplexip-e21-arty/settings.mk b/bsp/env/coreip-e2-arty/settings.mk
index 2b2a962..2b2a962 120000
--- a/bsp/env/coreplexip-e21-arty/settings.mk
+++ b/bsp/env/coreip-e2-arty/settings.mk
diff --git a/bsp/env/coreip-e2-arty/tim-split.lds b/bsp/env/coreip-e2-arty/tim-split.lds
new file mode 100644
index 0000000..eab4bd3
--- /dev/null
+++ b/bsp/env/coreip-e2-arty/tim-split.lds
@@ -0,0 +1,157 @@
+OUTPUT_ARCH( "riscv" )
+
+ENTRY( _start )
+
+MEMORY
+{
+ flash (rxai!w) : ORIGIN = 0x80008000, LENGTH = 32K
+ ram (wxa!ri) : ORIGIN = 0x80000000, LENGTH = 32K
+}
+
+PHDRS
+{
+ flash PT_LOAD;
+ ram_init PT_LOAD;
+ ram PT_NULL;
+}
+
+SECTIONS
+{
+ __stack_size = DEFINED(__stack_size) ? __stack_size : 1K;
+
+ .init :
+ {
+ KEEP (*(SORT_NONE(.init)))
+ } >flash AT>flash :flash
+
+ .text :
+ {
+ *(.text.unlikely .text.unlikely.*)
+ *(.text.startup .text.startup.*)
+ *(.text .text.*)
+ *(.gnu.linkonce.t.*)
+ } >flash AT>flash :flash
+
+ .fini :
+ {
+ KEEP (*(SORT_NONE(.fini)))
+ } >flash AT>flash :flash
+
+ PROVIDE (__etext = .);
+ PROVIDE (_etext = .);
+ PROVIDE (etext = .);
+
+ . = ALIGN(4);
+
+ .preinit_array :
+ {
+ PROVIDE_HIDDEN (__preinit_array_start = .);
+ KEEP (*(.preinit_array))
+ PROVIDE_HIDDEN (__preinit_array_end = .);
+ } >flash AT>flash :flash
+
+ .init_array :
+ {
+ PROVIDE_HIDDEN (__init_array_start = .);
+ KEEP (*(SORT_BY_INIT_PRIORITY(.init_array.*) SORT_BY_INIT_PRIORITY(.ctors.*)))
+ KEEP (*(.init_array EXCLUDE_FILE (*crtbegin.o *crtbegin?.o *crtend.o *crtend?.o ) .ctors))
+ PROVIDE_HIDDEN (__init_array_end = .);
+ } >flash AT>flash :flash
+
+ .fini_array :
+ {
+ PROVIDE_HIDDEN (__fini_array_start = .);
+ KEEP (*(SORT_BY_INIT_PRIORITY(.fini_array.*) SORT_BY_INIT_PRIORITY(.dtors.*)))
+ KEEP (*(.fini_array EXCLUDE_FILE (*crtbegin.o *crtbegin?.o *crtend.o *crtend?.o ) .dtors))
+ PROVIDE_HIDDEN (__fini_array_end = .);
+ } >flash AT>flash :flash
+
+ .ctors :
+ {
+ /* gcc uses crtbegin.o to find the start of
+ the constructors, so we make sure it is
+ first. Because this is a wildcard, it
+ doesn't matter if the user does not
+ actually link against crtbegin.o; the
+ linker won't look for a file to match a
+ wildcard. The wildcard also means that it
+ doesn't matter which directory crtbegin.o
+ is in. */
+ KEEP (*crtbegin.o(.ctors))
+ KEEP (*crtbegin?.o(.ctors))
+ /* We don't want to include the .ctor section from
+ the crtend.o file until after the sorted ctors.
+ The .ctor section from the crtend file contains the
+ end of ctors marker and it must be last */
+ KEEP (*(EXCLUDE_FILE (*crtend.o *crtend?.o ) .ctors))
+ KEEP (*(SORT(.ctors.*)))
+ KEEP (*(.ctors))
+ } >flash AT>flash :flash
+
+ .dtors :
+ {
+ KEEP (*crtbegin.o(.dtors))
+ KEEP (*crtbegin?.o(.dtors))
+ KEEP (*(EXCLUDE_FILE (*crtend.o *crtend?.o ) .dtors))
+ KEEP (*(SORT(.dtors.*)))
+ KEEP (*(.dtors))
+ } >flash AT>flash :flash
+
+ .lalign :
+ {
+ . = ALIGN(4);
+ PROVIDE( _data_lma = . );
+ } >flash AT>flash :flash
+
+ .dalign :
+ {
+ . = ALIGN(4);
+ PROVIDE( _data = . );
+ } >ram AT>flash :ram_init
+
+ .data :
+ {
+ *(.rdata)
+ *(.rodata .rodata.*)
+ *(.gnu.linkonce.r.*)
+ *(.data .data.*)
+ *(.gnu.linkonce.d.*)
+ . = ALIGN(8);
+ PROVIDE( __global_pointer$ = . + 0x800 );
+ *(.sdata .sdata.*)
+ *(.gnu.linkonce.s.*)
+ . = ALIGN(8);
+ *(.srodata.cst16)
+ *(.srodata.cst8)
+ *(.srodata.cst4)
+ *(.srodata.cst2)
+ *(.srodata .srodata.*)
+ } >ram AT>flash :ram_init
+
+ . = ALIGN(4);
+ PROVIDE( _edata = . );
+ PROVIDE( edata = . );
+
+ PROVIDE( _fbss = . );
+ PROVIDE( __bss_start = . );
+ .bss :
+ {
+ *(.sbss*)
+ *(.gnu.linkonce.sb.*)
+ *(.bss .bss.*)
+ *(.gnu.linkonce.b.*)
+ *(COMMON)
+ . = ALIGN(4);
+ } >ram AT>ram :ram
+
+ . = ALIGN(8);
+ PROVIDE( _end = . );
+ PROVIDE( end = . );
+
+ .stack ORIGIN(ram) + LENGTH(ram) - __stack_size :
+ {
+ PROVIDE( _heap_end = . );
+ . = __stack_size;
+ PROVIDE( _sp = . );
+ } >ram AT>ram :ram
+}
diff --git a/bsp/env/coreip-e2-arty/tim.lds b/bsp/env/coreip-e2-arty/tim.lds
new file mode 100644
index 0000000..7dfb36b
--- /dev/null
+++ b/bsp/env/coreip-e2-arty/tim.lds
@@ -0,0 +1,161 @@
+OUTPUT_ARCH( "riscv" )
+
+ENTRY( _start )
+
+MEMORY
+{
+ ram (wxa!ri) : ORIGIN = 0x80000000, LENGTH = 64K
+}
+
+PHDRS
+{
+ ram PT_LOAD;
+ ram_init PT_LOAD;
+ ram PT_NULL;
+}
+
+SECTIONS
+{
+ __stack_size = DEFINED(__stack_size) ? __stack_size : 1K;
+
+ .init :
+ {
+ KEEP (*(SORT_NONE(.init)))
+ } >ram AT>ram :ram
+
+ .text :
+ {
+ *(.text.unlikely .text.unlikely.*)
+ *(.text.startup .text.startup.*)
+ *(.text .text.*)
+ *(.gnu.linkonce.t.*)
+ } >ram AT>ram :ram
+
+ .fini :
+ {
+ KEEP (*(SORT_NONE(.fini)))
+ } >ram AT>ram :ram
+
+ PROVIDE (__etext = .);
+ PROVIDE (_etext = .);
+ PROVIDE (etext = .);
+
+ .rodata :
+ {
+ *(.rdata)
+ *(.rodata .rodata.*)
+ *(.gnu.linkonce.r.*)
+ } >ram AT>ram :ram
+
+ . = ALIGN(4);
+
+ .preinit_array :
+ {
+ PROVIDE_HIDDEN (__preinit_array_start = .);
+ KEEP (*(.preinit_array))
+ PROVIDE_HIDDEN (__preinit_array_end = .);
+ } >ram AT>ram :ram
+
+ .init_array :
+ {
+ PROVIDE_HIDDEN (__init_array_start = .);
+ KEEP (*(SORT_BY_INIT_PRIORITY(.init_array.*) SORT_BY_INIT_PRIORITY(.ctors.*)))
+ KEEP (*(.init_array EXCLUDE_FILE (*crtbegin.o *crtbegin?.o *crtend.o *crtend?.o ) .ctors))
+ PROVIDE_HIDDEN (__init_array_end = .);
+ } >ram AT>ram :ram
+
+ .fini_array :
+ {
+ PROVIDE_HIDDEN (__fini_array_start = .);
+ KEEP (*(SORT_BY_INIT_PRIORITY(.fini_array.*) SORT_BY_INIT_PRIORITY(.dtors.*)))
+ KEEP (*(.fini_array EXCLUDE_FILE (*crtbegin.o *crtbegin?.o *crtend.o *crtend?.o ) .dtors))
+ PROVIDE_HIDDEN (__fini_array_end = .);
+ } >ram AT>ram :ram
+
+ .ctors :
+ {
+ /* gcc uses crtbegin.o to find the start of
+ the constructors, so we make sure it is
+ first. Because this is a wildcard, it
+ doesn't matter if the user does not
+ actually link against crtbegin.o; the
+ linker won't look for a file to match a
+ wildcard. The wildcard also means that it
+ doesn't matter which directory crtbegin.o
+ is in. */
+ KEEP (*crtbegin.o(.ctors))
+ KEEP (*crtbegin?.o(.ctors))
+ /* We don't want to include the .ctor section from
+ the crtend.o file until after the sorted ctors.
+ The .ctor section from the crtend file contains the
+ end of ctors marker and it must be last */
+ KEEP (*(EXCLUDE_FILE (*crtend.o *crtend?.o ) .ctors))
+ KEEP (*(SORT(.ctors.*)))
+ KEEP (*(.ctors))
+ } >ram AT>ram :ram
+
+ .dtors :
+ {
+ KEEP (*crtbegin.o(.dtors))
+ KEEP (*crtbegin?.o(.dtors))
+ KEEP (*(EXCLUDE_FILE (*crtend.o *crtend?.o ) .dtors))
+ KEEP (*(SORT(.dtors.*)))
+ KEEP (*(.dtors))
+ } >ram AT>ram :ram
+
+ .lalign :
+ {
+ . = ALIGN(4);
+ PROVIDE( _data_lma = . );
+ } >ram AT>ram :ram
+
+ .dalign :
+ {
+ . = ALIGN(4);
+ PROVIDE( _data = . );
+ } >ram AT>ram :ram_init
+
+ .data :
+ {
+ *(.data .data.*)
+ *(.gnu.linkonce.d.*)
+ . = ALIGN(8);
+ PROVIDE( __global_pointer$ = . + 0x800 );
+ *(.sdata .sdata.*)
+ *(.gnu.linkonce.s.*)
+ . = ALIGN(8);
+ *(.srodata.cst16)
+ *(.srodata.cst8)
+ *(.srodata.cst4)
+ *(.srodata.cst2)
+ *(.srodata .srodata.*)
+ } >ram AT>ram :ram_init
+
+ . = ALIGN(4);
+ PROVIDE( _edata = . );
+ PROVIDE( edata = . );
+
+ PROVIDE( _fbss = . );
+ PROVIDE( __bss_start = . );
+ .bss :
+ {
+ *(.sbss*)
+ *(.gnu.linkonce.sb.*)
+ *(.bss .bss.*)
+ *(.gnu.linkonce.b.*)
+ *(COMMON)
+ . = ALIGN(4);
+ } >ram AT>ram :ram
+
+ . = ALIGN(8);
+ PROVIDE( _end = . );
+ PROVIDE( end = . );
+
+ .stack :
+ {
+ . = ALIGN(8);
+ . += __stack_size;
+ PROVIDE( _sp = . );
+ PROVIDE( _heap_end = . );
+ } >ram AT>ram :ram
+}
diff --git a/bsp/env/coreplexip-e21-arty/dhrystone.lds b/bsp/env/coreplexip-e21-arty/dhrystone.lds
deleted file mode 120000
index 8459e13..0000000
--- a/bsp/env/coreplexip-e21-arty/dhrystone.lds
+++ /dev/null
@@ -1 +0,0 @@
-../coreplexip-e31-arty/dhrystone.lds \ No newline at end of file
diff --git a/bsp/env/coreplexip-e21-arty/flash.lds b/bsp/env/coreplexip-e21-arty/flash.lds
deleted file mode 120000
index 54c1026..0000000
--- a/bsp/env/coreplexip-e21-arty/flash.lds
+++ /dev/null
@@ -1 +0,0 @@
-../coreplexip-e31-arty/flash.lds \ No newline at end of file
diff --git a/bsp/env/coreplexip-e21-arty/init.c b/bsp/env/coreplexip-e21-arty/init.c
deleted file mode 120000
index de048a9..0000000
--- a/bsp/env/coreplexip-e21-arty/init.c
+++ /dev/null
@@ -1 +0,0 @@
-../coreplexip-e31-arty/init.c \ No newline at end of file
diff --git a/bsp/env/coreplexip-e21-arty/platform.h b/bsp/env/coreplexip-e21-arty/platform.h
deleted file mode 120000
index 311ca36..0000000
--- a/bsp/env/coreplexip-e21-arty/platform.h
+++ /dev/null
@@ -1 +0,0 @@
-../coreplexip-e31-arty/platform.h \ No newline at end of file
diff --git a/bsp/env/coreplexip-e21-arty/scratchpad.lds b/bsp/env/coreplexip-e21-arty/scratchpad.lds
deleted file mode 120000
index 7fbe10a..0000000
--- a/bsp/env/coreplexip-e21-arty/scratchpad.lds
+++ /dev/null
@@ -1 +0,0 @@
-../coreplexip-e31-arty/scratchpad.lds \ No newline at end of file
diff --git a/bsp/include/sifive/devices/clic.h b/bsp/include/sifive/devices/clic.h
index b31e1ce..e8dc2df 100644
--- a/bsp/include/sifive/devices/clic.h
+++ b/bsp/include/sifive/devices/clic.h
@@ -3,8 +3,7 @@
#ifndef _SIFIVE_CLIC_H
#define _SIFIVE_CLIC_H
-#define CLIC_CTRL_ADDR _AC(0x2000000,UL)
-
+#define CLIC_HART0 0x00800000
#define CLIC_MSIP 0x0000
#define CLIC_MSIP_size 0x4
#define CLIC_MTIMECMP 0x4000
@@ -12,10 +11,10 @@
#define CLIC_MTIME 0xBFF8
#define CLIC_MTIME_size 0x8
-#define CLIC_INTIP 0x0800000
-#define CLIC_INTIE 0x0800400
-#define CLIC_INTCFG 0x0800800
-#define CLIC_CFG 0x0800c00
+#define CLIC_INTIP 0x000
+#define CLIC_INTIE 0x400
+#define CLIC_INTCFG 0x800
+#define CLIC_CFG 0xc00
// These interrupt IDs are consistent across old and new mtvec modes
#define SSIPID 1
@@ -27,23 +26,5 @@
#define CSIPID 12
#define LOCALINTIDBASE 16
-#define CLIC_REG(offset) _REG32(CLIC_CTRL_ADDR, offset)
-#define CLIC_REG8(offset) (*(volatile uint8_t *)((CLIC_CTRL_ADDR) + (offset)))
-
-#ifndef CLINT_CTRL_ADDR
-#define CLINT_CTRL_ADDR CLIC_CTRL_ADDR
-#endif
-#ifndef CLINT_REG
-#define CLINT_REG CLIC_REG
-#endif
-#ifndef CLINT_MSIP
-#define CLINT_MSIP CLIC_MSIP
-#endif
-#ifndef CLINT_MTIME
-#define CLINT_MTIME CLIC_MTIME
-#endif
-#ifndef CLINT_MTIMECMP
-#define CLINT_MTIMECMP CLIC_MTIMECMP
-#endif
#endif /* _SIFIVE_CLIC_H */
diff --git a/software/clic_vectored/Makefile b/software/clic_vectored/Makefile
new file mode 100644
index 0000000..d6e2342
--- /dev/null
+++ b/software/clic_vectored/Makefile
@@ -0,0 +1,10 @@
+TARGET = clic_vectored
+CFLAGS += -Og -fno-builtin-printf
+
+BSP_BASE = ../../bsp
+
+C_SRCS += clic_vectored.c
+
+C_SRCS += $(BSP_BASE)/drivers/clic/clic_driver.c
+
+include $(BSP_BASE)/env/common.mk
diff --git a/software/clic_vectored/clic_vectored b/software/clic_vectored/clic_vectored
new file mode 100755
index 0000000..df33c93
--- /dev/null
+++ b/software/clic_vectored/clic_vectored
Binary files differ
diff --git a/software/clic_vectored/clic_vectored.c b/software/clic_vectored/clic_vectored.c
new file mode 100644
index 0000000..9ae99e3
--- /dev/null
+++ b/software/clic_vectored/clic_vectored.c
@@ -0,0 +1,95 @@
+// See LICENSE for license details.
+
+#include <stdio.h>
+#include <stdlib.h>
+#include "platform.h"
+#include <string.h>
+#include "encoding.h"
+#include <unistd.h>
+#include "sifive/devices/clic.h"
+#include "clic/clic_driver.h"
+
+#ifndef _SIFIVE_COREPLEXIP_ARTY_H
+#error 'local_interrupts' demo only supported for Core IP Eval Kits
+#endif
+
+// Global Variable used to show
+// software interrupts.
+volatile uint32_t g_debouncing;
+
+// vector table defined in init.c
+typedef void (*interrupt_function_ptr_t) (void);
+extern interrupt_function_ptr_t localISR[CLIC_NUM_INTERRUPTS];
+extern void default_handler(void);
+
+//clic data structure
+clic_instance_t clic;
+
+const char * instructions_msg = " \
+\n\
+ SiFive, Inc\n\
+ E21 Core IP Eval Kit 'clic_interrupts' demo.\n\
+\n\
+The Buttons 0-3 and Switch 3 are enabled as local\n\
+interrupts sources. A .5 s 'debounce' timer is used \n\
+between these interrupts. Software interrupts are\n\
+used to print a message while debouncing.\n\
+Note the priority of the interrupts sources.\n\
+\n";
+
+void print_instructions() {
+
+ //write (STDERR_FILENO, instructions_msg, strlen(instructions_msg));
+ printf(instructions_msg);
+
+}
+
+void button_0_isr(void)__attribute__((interrupt("SiFive-CLIC-preemptible")));
+void button_0_isr(void) {
+ // Toggle Red LED
+ const char button_0_msg[] = "Button 0 was pressed. Toggle Red.\n";
+ write (STDOUT_FILENO, button_0_msg, strlen(button_0_msg));
+ GPIO_REG(GPIO_OUTPUT_VAL) = GPIO_REG(GPIO_OUTPUT_VAL) ^ (0x1 << RED_LED_OFFSET);
+ clic_clear_pending(&clic, (LOCALINTIDBASE + LOCAL_INT_BTN_0));
+ clic_enable_interrupt(&clic, (LOCALINTIDBASE + LOCAL_INT_BTN_0));
+}
+
+void button_0_setup(void) {
+ clic_install_handler(&clic, (LOCALINTIDBASE + LOCAL_INT_BTN_0), button_0_isr);
+ clic_enable_interrupt(&clic, (LOCALINTIDBASE + LOCAL_INT_BTN_0));
+}
+
+void config_gpio() {
+ // Configure LEDs as outputs.
+ 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<< RED_LED_OFFSET) | (0x1<< GREEN_LED_OFFSET)| (0x1 << BLUE_LED_OFFSET)) ;
+}
+
+int main(int argc, char **argv)
+{
+ clear_csr(mstatus, MSTATUS_MIE);
+ clear_csr(mie, IRQ_M_SOFT);
+ clear_csr(mie, IRQ_M_TIMER);
+
+
+ clic_init(&clic, CLIC_HART0_ADDR,
+ (interrupt_function_ptr_t*)localISR,
+ default_handler,
+ CLIC_NUM_INTERRUPTS,
+ CLIC_NUM_CONFIG_BITS);
+
+
+ config_gpio();
+ button_0_setup();
+
+ // Enable all global interrupts
+ set_csr(mstatus, MSTATUS_MIE);
+
+
+ print_instructions();
+ while(1);
+
+ return 0;
+
+}