Port Zephyr support to 2.4 and update instructions

This commit is contained in:
Olof Kindgren 2020-12-16 22:52:36 +01:00
parent 731ca8bb45
commit acab804a31
31 changed files with 690 additions and 43 deletions

4
.gitmodules vendored
View file

@ -1,4 +0,0 @@
[submodule "zephyr"]
path = zephyr
url = https://github.com/olofk/zephyr
branch = serv

114
README.md
View file

@ -11,70 +11,83 @@ There's also an official [SERV user manual](https://serv.readthedocs.io/en/lates
## Prerequisites
Create a directory to keep all the different parts of the project together. We
will refer to this directory as `$SERV` from now on.
Download the main serv repo
`cd $SERV && git clone https://github.com/olofk/serv`
will refer to this directory as `$WORKSPACE` from now on. All commands will be run from this directory unless otherwise stated.
Install FuseSoC
`pip install fusesoc`
Initialize the FuseSoC standard libraries
Add the FuseSoC standard library
`fusesoc init`
`fusesoc library add fusesoc_cores https://github.com/fusesoc/fusesoc_cores`
Create a workspace directory for FuseSoC
The FuseSoC standard library already contain a version of SERV, but if we want to make changes to SERV, run the bundled example or use the Zephyr support, it is better to add SERV as a separate library into the workspace
`mkdir $SERV/workspace`
`fusesoc library add serv https://github.com/olofk/serv`
Register the serv repo as a core library
The SERV repo will now be available in $WORKSPACE/fusesoc_libraries/serv. To save some typing, we will refer to that directory as `$SERV`.
`cd $SERV/workspace && fusesoc library add serv $SERV`
We are now ready to do our first exercises with SERV
Check that the CPU passes the linter
If [Verilator](https://www.veripool.org/wiki/verilator) is installed, we can use that as a linter to check the SERV source code
`cd $SERV/workspace && fusesoc run --target=lint serv`
`fusesoc run --target=lint serv`
## Running test software
If everything worked, the output should look like
INFO: Preparing ::serv:1.0.2
INFO: Setting up project
INFO: Building simulation model
verilator -f serv_1.0.2.vc
INFO: Running
## Running pre-built test software
Build and run the single threaded zephyr hello world example with verilator (should be stopped with Ctrl-C):
cd $SERV/workspace
fusesoc run --target=verilator_tb servant --uart_baudrate=57600 --firmware=$SERV/serv/sw/zephyr_hello.hex
fusesoc run --target=verilator_tb servant --uart_baudrate=57600 --firmware=$SERV/sw/zephyr_hello.hex
..or... the multithreaded version
fusesoc run --target=verilator_tb servant --uart_baudrate=57600 --firmware=$SERV/serv/sw/zephyr_hello_mt.hex --memsize=16384
fusesoc run --target=verilator_tb servant --uart_baudrate=57600 --firmware=$SERV/sw/zephyr_hello_mt.hex --memsize=16384
...or... the philosophers example
Both should yield an output ending with
fusesoc run --target=verilator_tb servant --uart_baudrate=57600 --firmware=$SERV/serv/sw/zephyr_phil.hex --memsize=32768
***** Booting Zephyr OS zephyr-v1.14.1-4-gc7c2d62513fe *****
Hello World! service
For a more advanced example, we can also run the Dining philosophers demo
fusesoc run --target=verilator_tb servant --uart_baudrate=57600 --firmware=$SERV/sw/zephyr_phil.hex --memsize=32768
...or... the synchronization example
fusesoc run --target=verilator_tb servant --uart_baudrate=57600 --firmware=$SERV/serv/sw/zephyr_sync.hex --memsize=16384
fusesoc run --target=verilator_tb servant --uart_baudrate=57600 --firmware=$SERV/sw/zephyr_sync.hex --memsize=16384
Other applications can be tested by compiling and converting to bin and then hex e.g. with makehex.py found in `$SERV/serv/riscv-target/serv`
Other applications can be tested by compiling and converting to bin and then hex e.g. with makehex.py found in `$SERV/sw`
## Run the compliance tests
## Run RISC-V compliance tests
Build the verilator model (if not already done)
`cd $SERV/workspace && fusesoc run --target=verilator_tb --setup --build servant`
fusesoc run --target=verilator_tb --build servant
Download the tests repo
`cd $SERV && git clone https://github.com/riscv/riscv-compliance`
git clone https://github.com/riscv/riscv-compliance
To run the RISC-V compliance tests, we need to supply the SERV-specific support files and point the test suite to where it can find a target to run (i.e. the previously built Verilator model)
Run the compliance tests
`cd $SERV/riscv-compliance && make TARGETDIR=$SERV/serv/riscv-target RISCV_TARGET=serv RISCV_DECICE=rv32i RISCV_ISA=rv32i TARGET_SIM=$SERV/workspace/build/servant_1.0.1/verilator_tb-verilator/Vservant_sim`
cd riscv-compliance && make TARGETDIR=$SERV/riscv-target RISCV_TARGET=serv RISCV_DECICE=rv32i RISCV_ISA=rv32i TARGET_SIM=$SERV/build/servant_1.0.2/verilator_tb-verilator/Vservant_sim
The above will run all tests in the rv32i test suite. Since SERV also implement the `rv32Zicsr` and `rv32Zifencei` extensions, these can also be tested by choosing any of them instead of rv32i as the `RISCV_ISA` variable.
## Run on hardware
The servant SoC has been ported to a number of different FPGA boards. To see all currently supported targets run
The servant SoC has been ported to an increasing number of different FPGA boards. To see all currently supported targets run
fusesoc core show servant
@ -86,14 +99,12 @@ Some targets also depend on functionality in the FuseSoC base library (fusesoc-c
Now we're ready to build. Note, for all the cases below, it's possible to run with `--memfile=$SERV/sw/blinky.hex`
(or any other suitable program) as the last argument to preload the LED blink example
instead of hello world. If the `--memfile` option doesn't work, try upgrading
FuseSOC with `pip install --upgrade fusesoc`.
instead of hello world.
### TinyFPGA BX
Pin A6 is used for UART output with 115200 baud rate.
cd $SERV/workspace
fusesoc run --target=tinyfpga_bx servant
tinyprog --program build/servant_1.0.1/tinyfpga_bx-icestorm/servant_1.0.1.bin
@ -101,7 +112,6 @@ Pin A6 is used for UART output with 115200 baud rate.
Pin 9 is used for UART output with 57600 baud rate.
cd $SERV/workspace
fusesoc run --target=icebreaker servant
### iCESugar
@ -110,14 +120,12 @@ Pin 6 is used for UART output with 115200 baud rate. Thanks to the onboard
debugger, you can just connect the USB Type-C connector to the PC, and a
serial console will show up.
cd $SERV/workspace
fusesoc run --target=icesugar servant
### OrangeCrab R0.2
Pin D1 is used for UART output with 115200 baud rate.
cd $SERV/workspace
fusesoc run --target=orangecrab_r0.2 servant
dfu-util -d 1209:5af0 -D build/servant_1.0.2/orangecrab_r0.2-trellis/servant_1.0.2.bit
@ -126,14 +134,12 @@ Pin D1 is used for UART output with 115200 baud rate.
Pin D10 (uart_rxd_out) is used for UART output with 57600 baud rate (to use
blinky.hex change D10 to H5 (led[4]) in data/arty_a7_35t.xdc).
cd $SERV/workspace
fusesoc run --target=arty_a7_35t servant
### DE0 Nano
FPGA Pin D11 (Connector JP1, pin 38) is used for UART output with 57600 baud rate. DE0 Nano needs an external 3.3V UART to connect to this pin
cd $SERV/workspace
fusesoc run --target=de0_nano servant
### Saanlima Pipistrello (Spartan6 LX45)
@ -141,14 +147,12 @@ FPGA Pin D11 (Connector JP1, pin 38) is used for UART output with 57600 baud rat
Pin A10 (usb_data<1>) is used for UART output with 57600 baud rate (to use
blinky.hex change A10 to V16 (led[0]) in data/pipistrello.ucf).
cd $SERV/workspace
fusesoc run --target=pipistrello servant
### Alhambra II
Pin 61 is used for UART output with 115200 baud rate. This pin is connected to a FT2232H chip in board, that manages the communications between the FPGA and the computer.
cd $SERV/workspace
fusesoc run --target=alhambra servant
iceprog -d i:0x0403:0x6010:0 build/servant_1.0.1/alhambra-icestorm/servant_1.0.1.bin
@ -156,7 +160,6 @@ Pin 61 is used for UART output with 115200 baud rate. This pin is connected to a
Pin 95 is used as the GPIO output which is connected to the board's green LED. Due to this board's limited Embedded BRAM, programs with a maximum of 7168 bytes can be loaded. The default program for this board is blinky.hex.
cd $SERV/workspace
fusesoc run --target=icestick servant
iceprog build/servant_1.0.2/icestick-icestorm/servant_1.0.2.bin
@ -178,6 +181,42 @@ This will synthesize for the default Vivado part. To synthesise for a specific d
fusesoc run --tool=vivado serv --pnr=none --part=xc7a100tcsg324-1
## Zephyr support
SERV, or rather the Servant SoC, can run the [Zephyr RTOS](https://www.zephyrproject.org). The Servant-specific drivers and BSP is located in the zephyr subdirectory of the SERV repository. In order to use Zephyr on Servant, a project directory structure must be set up that allows Zephyr to load the Servant-specific files as a module.
First, the Zephyr SDK and the "west" build too must be installed. The [Zephyr getting started guide](https://docs.zephyrproject.org/latest/getting_started/index.html) describes these steps in more detail.
Assuming that SERV was installed into `$WORKSPACE/fusesoc_libraries/serv` as per the prerequisites, run the following command to make the workspace also work as a Zephyr workspace.
west init
Specify the SERV repository as the manifest repository, meaning it will be the main entry point when Zephyr is looking for modules.
west config manifest.path $SERV
Get the right versions of all Zephyr submodules
west update
It should now be possible to build Zephyr applications for the Servant SoC within the workspace. This can be tested e.g. by building the Zephyr Hello world samples application
cd zephyr/samples/hello_world
west build -b service
After a successful build, Zephyr will create an elf and a bin file of the application in `build/zephyr/zephyr.{elf,bin}`. The bin file can be converted to a verilog hex file, which in turn can be preloaded to FPGA on-chip memories and run on a target board, or loaded into simulated RAM model when running simulations.
To convert the newly built hello world example into a Verilog hex file, run
python3 $SERV/sw/makehex.py zephyr/samples/hello_world/build/zephyr/zephyr.bin 4096 > hello.hex
4096 is the number of 32-bit words to write and must be at least the size of the application binary. `hello.hex` is the resulting hex file. Running a simulation can now be done as described in [Running pre-built test software](#running-pre-built-test-software), e.g.
fusesoc run --target=verilator_tb servant --uart_baudrate=57600 --firmware=/path/to/hello.hex
Or to create an FPGA image with the application preloaded to on-chip RAM, e.g. for a Nexys A7 board, run
fusesoc run --target=nexys_a7 servant --memfile=/path/to/hello.hex
## Good to know
@ -190,5 +229,4 @@ Don't go changing the clock frequency on a whim when running Zephyr. Or well, it
## TODO
- Applications have to be preloaded to RAM at compile-time
- Store bootloader and register file together in a RAM
- Make it faster and smaller

9
west.yml Normal file
View file

@ -0,0 +1,9 @@
manifest:
remotes:
- name: zephyrproject-rtos
url-base: https://github.com/zephyrproject-rtos
projects:
- name: zephyr
remote: zephyrproject-rtos
revision: v2.4.0
import: true

1
zephyr

@ -1 +0,0 @@
Subproject commit a690d52fa69f812924aa38f20c45f707c64fa16f

4
zephyr/CMakeLists.txt Normal file
View file

@ -0,0 +1,4 @@
# Copyright (c) 2020 Olof Kindgren <olof.kindgren@gmail.com>
# SPDX-License-Identifier: Apache-2.0
add_subdirectory(drivers)

8
zephyr/Kconfig Normal file
View file

@ -0,0 +1,8 @@
# Copyright (c) 2020 Olof Kindgren <olof.kindgren@gmail.com>
# SPDX-License-Identifier: Apache-2.0
menu "SweRVolf"
rsource "drivers/Kconfig"
endmenu

View file

@ -0,0 +1,7 @@
# Copyright (c) 2020 Olof Kindgren <olof.kindgren@gmail.com>
#
# SPDX-License-Identifier: Apache-2.0
config BOARD_SERVICE
bool "servant SoC for iCE40"
depends on SOC_RISCV32_SERVANT

View file

@ -0,0 +1,7 @@
# Copyright (c) 2020 Olof Kindgren <olof.kindgren@gmail.com>
#
# SPDX-License-Identifier: Apache-2.0
config BOARD
default "service"
depends on BOARD_SERVICE

View file

@ -0,0 +1,12 @@
/*
* Copyright (c) 2020 Olof Kindgren <olof.kindgren@gmail.com>
*
* SPDX-License-Identifier: Apache-2.0
*/
#ifndef __INC_BOARD_H
#define __INC_BOARD_H
#include <soc.h>
#endif /* __INC_BOARD_H */

View file

@ -0,0 +1,21 @@
/*
* Copyright (c) 2020 Olof Kindgren <olof.kindgren@gmail.com>
*
* SPDX-License-Identifier: Apache-2.0
*/
/dts-v1/;
#include <serv.dtsi>
/ {
chosen {
zephyr,sram = &ram;
};
ram: memory@0 {
compatible = "mmio-sram";
reg = <0x0 0x8000>;
};
};

View file

@ -0,0 +1,15 @@
# Copyright (c) 2020 Olof Kindgren <olof.kindgren@gmail.com>
#
# SPDX-License-Identifier: Apache-2.0
identifier: service
name: servant SoC for iCE40
type: mcu
arch: riscv32
toolchain:
- zephyr
ram: 32
testing:
ignore_tags:
- net
- bluetooth

View file

@ -0,0 +1,13 @@
# Copyright (c) 2020 Olof Kindgren <olof.kindgren@gmail.com>
#
# SPDX-License-Identifier: Apache-2.0
CONFIG_BOARD_SERVICE=y
CONFIG_CONSOLE=y
CONFIG_SERIAL=y
CONFIG_UART_BITBANG=y
CONFIG_UART_CONSOLE=y
CONFIG_UART_CONSOLE_ON_DEV_NAME="uart0"
CONFIG_XIP=n

View file

@ -0,0 +1,6 @@
# Copyright (c) 2020 Olof Kindgren <olof.kindgren@gmail.com>
# SPDX-License-Identifier: Apache-2.0
add_subdirectory_ifdef(CONFIG_SERIAL_HAS_DRIVER serial)
add_subdirectory_ifdef(CONFIG_SYS_CLOCK_EXISTS timer)

10
zephyr/drivers/Kconfig Normal file
View file

@ -0,0 +1,10 @@
# Copyright (c) 2020 Olof Kindgren <olof.kindgren@gmail.com>
# SPDX-License-Identifier: Apache-2.0
menu "Device Drivers"
rsource "serial/Kconfig"
rsource "timer/Kconfig"
endmenu

View file

@ -0,0 +1,6 @@
# Copyright (c) 2020 Olof Kindgren <olof.kindgren@gmail.com>
# SPDX-License-Identifier: Apache-2.0
set(ZEPHYR_CURRENT_LIBRARY drivers__serial)
zephyr_library_sources_ifdef(CONFIG_UART_BITBANG uart_bitbang.c)

View file

@ -0,0 +1,13 @@
# Copyright (c) 2020 Olof Kindgren <olof.kindgren@gmail.com>
# SPDX-License-Identifier: Apache-2.0
if SERIAL
menuconfig UART_BITBANG
bool "SERV bitbang serial driver"
select SERIAL_HAS_DRIVER
help
Enables the SERV bitbang serial driver.
Hardcoded to send at ~57600 baud rate with a 16MHz clock
endif

View file

@ -0,0 +1,57 @@
/*
* Copyright (c) 2020 Olof Kindgren <olof.kindgren@gmail.com>
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <kernel.h>
#include <arch/cpu.h>
#include <drivers/uart.h>
#define reg_uart_data (*(volatile uint32_t*)UART_BITBANG_BASE)
static struct k_spinlock lock;
static void uart_bitbang_poll_out(const struct device *dev, unsigned char c)
{
ARG_UNUSED(dev);
k_spinlock_key_t key = k_spin_lock(&lock);
int cout = (c|0x100) << 1;
do {
reg_uart_data = cout;
cout >>= 1;
__asm__ __volatile__ ("nop");
__asm__ __volatile__ ("nop");
} while (cout);
k_spin_unlock(&lock, key);
}
static int uart_bitbang_poll_in(const struct device *dev, unsigned char *c)
{
ARG_UNUSED(dev);
*c = reg_uart_data;
return 0;
}
static int uart_bitbang_init(const struct device *dev)
{
ARG_UNUSED(dev);
reg_uart_data = 1;
return 0;
}
static const struct uart_driver_api uart_bitbang_driver_api = {
.poll_in = uart_bitbang_poll_in,
.poll_out = uart_bitbang_poll_out,
.err_check = NULL,
};
DEVICE_AND_API_INIT(uart_bitbang, "uart0", &uart_bitbang_init,
NULL, NULL,
PRE_KERNEL_1, CONFIG_KERNEL_INIT_PRIORITY_DEVICE,
&uart_bitbang_driver_api);

View file

@ -0,0 +1,5 @@
# Copyright (c) 2020 Olof Kindgren <olof.kindgren@gmail.com>
# SPDX-License-Identifier: Apache-2.0
zephyr_library_sources_ifdef(CONFIG_SERV_TIMER serv_timer.c)

View file

@ -0,0 +1,9 @@
# Copyright (c) 2020 Olof Kindgren <olof.kindgren@gmail.com>
# SPDX-License-Identifier: Apache-2.0
config SERV_TIMER
bool "SERV Timer"
# select TICKLESS_CAPABLE
help
This module implements a kernel device driver for the SERV
timer driver. It provides the standard "system clock driver" interfaces.

View file

@ -0,0 +1,125 @@
/*
* Copyright (c) 2020 Olof Kindgren <olof.kindgren@gmail.com>
*
* SPDX-License-Identifier: Apache-2.0
*/
/*
This is basically a 32-bit version of riscv_machine_timer.c fro Zephyr
*/
#include <drivers/timer/system_timer.h>
#include <sys_clock.h>
#include <spinlock.h>
#include <soc.h>
#define CYC_PER_TICK ((uint32_t)((uint32_t)sys_clock_hw_cycles_per_sec() \
/ (uint32_t)CONFIG_SYS_CLOCK_TICKS_PER_SEC))
#define MAX_CYC 0xffffffffu
#define MAX_TICKS ((MAX_CYC - CYC_PER_TICK) / CYC_PER_TICK)
#define MIN_DELAY 1000
#define TICKLESS IS_ENABLED(CONFIG_TICKLESS_KERNEL)
static struct k_spinlock lock;
static uint32_t last_count;
static ALWAYS_INLINE void set_mtimecmp(uint32_t time)
{
sys_write32(time, SERV_TIMER_BASE);
}
static ALWAYS_INLINE uint32_t mtime(void)
{
return sys_read32(SERV_TIMER_BASE);
}
static void timer_isr(void *arg)
{
ARG_UNUSED(arg);
k_spinlock_key_t key = k_spin_lock(&lock);
uint32_t now = mtime();
uint32_t dticks = ((now - last_count) / CYC_PER_TICK);
last_count += dticks * CYC_PER_TICK;
if (!TICKLESS) {
uint32_t next = last_count + CYC_PER_TICK;
if ((int32_t)(next - now) < MIN_DELAY) {
next += CYC_PER_TICK;
}
set_mtimecmp(next);
}
k_spin_unlock(&lock, key);
z_clock_announce(IS_ENABLED(CONFIG_TICKLESS_KERNEL) ? dticks : 1);
}
int z_clock_driver_init(const struct device *device)
{
ARG_UNUSED(device);
IRQ_CONNECT(RISCV_MACHINE_TIMER_IRQ, 0, timer_isr, NULL, 0);
set_mtimecmp(mtime() + (uint32_t)CYC_PER_TICK);
irq_enable(RISCV_MACHINE_TIMER_IRQ);
return 0;
}
void z_clock_set_timeout(int32_t ticks, bool idle)
{
ARG_UNUSED(idle);
#if defined(CONFIG_TICKLESS_KERNEL)
/* RISCV has no idle handler yet, so if we try to spin on the
* logic below to reset the comparator, we'll always bump it
* forward to the "next tick" due to MIN_DELAY handling and
* the interrupt will never fire! Just rely on the fact that
* the OS gave us the proper timeout already.
*/
if (idle) {
return;
}
ticks = ticks == K_TICKS_FOREVER ? MAX_TICKS : ticks;
ticks = MAX(MIN(ticks - 1, (int32_t)MAX_TICKS), 0);
k_spinlock_key_t key = k_spin_lock(&lock);
uint32_t now = mtime();
uint32_t adj, cyc = ticks * CYC_PER_TICK;
/* Round up to next tick boundary. */
adj = (now - last_count) + (CYC_PER_TICK - 1);
if (cyc <= MAX_CYC - adj) {
cyc += adj;
} else {
cyc = MAX_CYC;
}
cyc = (cyc / CYC_PER_TICK) * CYC_PER_TICK;
if ((int32_t)(cyc + last_count - now) < MIN_DELAY) {
cyc += CYC_PER_TICK;
}
set_mtimecmp(cyc + last_count);
k_spin_unlock(&lock, key);
#endif
}
uint32_t z_clock_elapsed(void)
{
if (!IS_ENABLED(CONFIG_TICKLESS_KERNEL)) {
return 0;
}
k_spinlock_key_t key = k_spin_lock(&lock);
uint32_t ret = (mtime() - last_count) / CYC_PER_TICK;
k_spin_unlock(&lock, key);
return ret;
}
uint32_t z_timer_cycle_get_32(void)
{
return mtime();
}

View file

@ -0,0 +1,11 @@
/*
* Copyright (c) 2020 Olof Kindgren <olof.kindgren@gmail.com>
*
* SPDX-License-Identifier: Apache-2.0
*/
/ {
#address-cells = <1>;
#size-cells = <1>;
compatible = "olofk,servant";
};

5
zephyr/module.yml Normal file
View file

@ -0,0 +1,5 @@
build:
settings:
board_root: zephyr
dts_root: zephyr
soc_root: zephyr

View file

@ -0,0 +1,7 @@
# Copyright (c) 2020 Olof Kindgren <olof.kindgren@gmail.com>
# SPDX-License-Identifier: Apache-2.0
zephyr_sources(
soc_irq.S
vector.S
irq.c)

View file

@ -0,0 +1,26 @@
# Copyright (c) 2020 Olof Kindgren <olof.kindgren@gmail.com>
# SPDX-License-Identifier: Apache-2.0
if SOC_RISCV32_SERVANT
config SOC
string
default "servant"
config SYS_CLOCK_HW_CYCLES_PER_SEC
int
default 16000000
config RISCV_SOC_INTERRUPT_INIT
bool
default y
config NUM_IRQS
int
default 8
config SERV_TIMER
bool
default y
endif # SOC_RISCV32_SERVANT

View file

@ -0,0 +1,7 @@
# Copyright (c) 2020 Olof Kindgren <olof.kindgren@gmail.com>
# SPDX-License-Identifier: Apache-2.0
config SOC_RISCV32_SERVANT
bool "servant SoC"
select RISCV
select ATOMIC_OPERATIONS_C

View file

@ -0,0 +1,58 @@
/*
* Copyright (c) 2017 Jean-Paul Etienne <fractalclone@gmail.com>
*
* SPDX-License-Identifier: Apache-2.0
*/
/**
* @file
* @brief interrupt management code for riscv SOCs supporting the riscv
privileged architecture specification
*/
#include <irq.h>
void arch_irq_enable(unsigned int irq)
{
uint32_t mie;
/*
* CSR mie register is updated using atomic instruction csrrs
* (atomic read and set bits in CSR register)
*/
__asm__ volatile ("csrrs %0, mie, %1\n"
: "=r" (mie)
: "r" (1 << irq));
}
void arch_irq_disable(unsigned int irq)
{
uint32_t mie;
/*
* Use atomic instruction csrrc to disable device interrupt in mie CSR.
* (atomic read and clear bits in CSR register)
*/
__asm__ volatile ("csrrc %0, mie, %1\n"
: "=r" (mie)
: "r" (1 << irq));
};
int arch_irq_is_enabled(unsigned int irq)
{
uint32_t mie;
__asm__ volatile ("csrr %0, mie" : "=r" (mie));
return !!(mie & (1 << irq));
}
#if defined(CONFIG_RISCV_SOC_INTERRUPT_INIT)
void soc_interrupt_init(void)
{
/* ensure that all interrupts are disabled */
(void)irq_lock();
__asm__ volatile ("csrwi mie, 0\n"
"csrwi mip, 0\n");
}
#endif

View file

@ -0,0 +1,7 @@
/*
* Copyright (c) 2018 Antmicro <www.antmicro.com>
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <arch/riscv/common/linker.ld>

View file

@ -0,0 +1,24 @@
/*
* Copyright (c) 2020 Olof Kindgren <olof.kindgren@gmail.com>
*
* SPDX-License-Identifier: Apache-2.0
*/
#ifndef __RISCV32_SERVANT_SOC_H_
#define __RISCV32_SERVANT_SOC_H_
#include <soc_common.h>
#include <devicetree.h>
/* Bitbang UART configuration */
#define UART_BITBANG_BASE 0x40000000
/* Timer configuration */
#define SERV_TIMER_BASE 0x80000000
#define SERV_TIMER_IRQ 7
/* lib-c hooks required RAM defined variables */
#define RISCV_RAM_BASE DT_SRAM_BASE_ADDR_ADDRESS
#define RISCV_RAM_SIZE DT_SRAM_SIZE
#endif /* __RISCV32_SERVANT_SOC_H_ */

View file

@ -0,0 +1,56 @@
/*
* Copyright (c) 2017 Jean-Paul Etienne <fractalclone@gmail.com>
*
* SPDX-License-Identifier: Apache-2.0
*/
/**
* @file configuration macros for riscv SOCs supporting the riscv
* privileged architecture specification
*/
#ifndef __SOC_COMMON_H_
#define __SOC_COMMON_H_
/* IRQ numbers */
#define RISCV_MACHINE_SOFT_IRQ 3 /* Machine Software Interrupt */
#define RISCV_MACHINE_TIMER_IRQ 7 /* Machine Timer Interrupt */
#define RISCV_MACHINE_EXT_IRQ 11 /* Machine External Interrupt */
/* ECALL Exception numbers */
#define SOC_MCAUSE_ECALL_EXP 11 /* Machine ECALL instruction */
#define SOC_MCAUSE_USER_ECALL_EXP 8 /* User ECALL instruction */
/* SOC-specific MCAUSE bitfields */
#ifdef CONFIG_64BIT
/* Interrupt Mask */
#define SOC_MCAUSE_IRQ_MASK (1 << 63)
/* Exception code Mask */
#define SOC_MCAUSE_EXP_MASK 0x7FFFFFFFFFFFFFFF
#else
/* Interrupt Mask */
#define SOC_MCAUSE_IRQ_MASK (1 << 31)
/* Exception code Mask */
#define SOC_MCAUSE_EXP_MASK 0x7FFFFFFF
#endif
/* SOC-Specific EXIT ISR command */
#define SOC_ERET mret
#ifndef _ASMLANGUAGE
#if defined(CONFIG_RISCV_SOC_INTERRUPT_INIT)
void soc_interrupt_init(void);
#endif
#if defined(CONFIG_RISCV_HAS_PLIC)
void riscv_plic_irq_enable(uint32_t irq);
void riscv_plic_irq_disable(uint32_t irq);
int riscv_plic_irq_is_enabled(uint32_t irq);
void riscv_plic_set_priority(uint32_t irq, uint32_t priority);
int riscv_plic_get_irq(void);
#endif
#endif /* !_ASMLANGUAGE */
#endif /* __SOC_COMMON_H_ */

View file

@ -0,0 +1,58 @@
/*
* Copyright (c) 2017 Jean-Paul Etienne <fractalclone@gmail.com>
*
* SPDX-License-Identifier: Apache-2.0
*/
/*
* common interrupt management code for riscv SOCs supporting the riscv
* privileged architecture specification
*/
#include <kernel_structs.h>
#include <offsets.h>
#include <toolchain.h>
#include <linker/sections.h>
#include <soc.h>
/* exports */
GTEXT(__soc_handle_irq)
/*
* SOC-specific function to handle pending IRQ number generating the interrupt.
* Exception number is given as parameter via register a0.
*/
SECTION_FUNC(exception.other, __soc_handle_irq)
/* Clear exception number from CSR mip register */
li t1, 1
sll t0, t1, a0
csrrc t1, mip, t0
/* Return */
jalr x0, ra
/*
* __soc_is_irq is defined as .weak to allow re-implementation by
* SOCs that does not truly follow the riscv privilege specification.
*/
WTEXT(__soc_is_irq)
/*
* SOC-specific function to determine if the exception is the result of a
* an interrupt or an exception
* return 1 (interrupt) or 0 (exception)
*
*/
SECTION_FUNC(exception.other, __soc_is_irq)
/* Read mcause and check if interrupt bit is set */
csrr t0, mcause
li t1, SOC_MCAUSE_IRQ_MASK
and t0, t0, t1
/* If interrupt bit is not set, return with 0 */
addi a0, x0, 0
beqz t0, not_interrupt
addi a0, a0, 1
not_interrupt:
/* return */
jalr x0, ra

View file

@ -0,0 +1,28 @@
/*
* Copyright (c) 2017 Jean-Paul Etienne <fractalclone@gmail.com>
* Contributors: 2018 Antmicro <www.antmicro.com>
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <toolchain.h>
/* exports */
GTEXT(__start)
/* imports */
GTEXT(__initialize)
GTEXT(__irq_wrapper)
SECTION_FUNC(vectors, __start)
.option norvc;
/*
* Set mtvec (Machine Trap-Vector Base-Address Register)
* to __irq_wrapper.
*/
la t0, __irq_wrapper
csrw mtvec, t0
/* Jump to __initialize */
tail __initialize