Rework basically the whole sw/matcha tree.
Change-Id: I2f72d4799a5aa14f6eef1a534b91e4cc13e3ccae
diff --git a/platform/.cargo/config.toml b/platform/.cargo/config.toml
new file mode 100644
index 0000000..d92c351
--- /dev/null
+++ b/platform/.cargo/config.toml
@@ -0,0 +1,13 @@
+[build]
+target = "riscv32imc-unknown-none-elf"
+target-dir = "../../../out/matcha"
+rustflags = [
+ "-C", "link-arg=-Tlayout.ld",
+ "-C", "linker=rust-lld",
+ "-C", "linker-flavor=ld.lld",
+ "-C", "relocation-model=dynamic-no-pic",
+ "-C", "link-arg=-zmax-page-size=512",
+ "-C", "link-arg=-icf=all",
+ "-C", "force-frame-pointers=no",
+ "--remap-path-prefix=$(ROOTDIR)/sw/tock/=",
+]
diff --git a/platform/Cargo.toml b/platform/Cargo.toml
new file mode 100644
index 0000000..821688e
--- /dev/null
+++ b/platform/Cargo.toml
@@ -0,0 +1,21 @@
+[package]
+name = "matcha_platform"
+version = "0.1.0"
+authors = ["Tock Project Developers <tock-dev@googlegroups.com>"]
+build = "build.rs"
+edition = "2018"
+
+[dependencies]
+bare-io = "0.2"
+
+components = { path = "../../tock/boards/components" }
+rv32i = { path = "../../tock/arch/rv32i" }
+capsules = { path = "../../tock/capsules" }
+kernel = { path = "../../tock/kernel" }
+lowrisc = { path = "../../tock/chips/lowrisc" }
+
+blob_fs = { path = "../blob_fs" }
+matcha_capsules = { path = "../capsules" }
+matcha_config = { path = "../config" }
+matcha_utils = { path = "../utils" }
+matcha_hal = { path = "../hal" }
\ No newline at end of file
diff --git a/platform/build.rs b/platform/build.rs
new file mode 100644
index 0000000..f05f878
--- /dev/null
+++ b/platform/build.rs
@@ -0,0 +1,4 @@
+fn main() {
+ println!("cargo:rerun-if-changed=layout.ld");
+ println!("cargo:rerun-if-changed=kernel_layout.ld");
+}
diff --git a/platform/kernel_layout.ld b/platform/kernel_layout.ld
new file mode 100644
index 0000000..d11d311
--- /dev/null
+++ b/platform/kernel_layout.ld
@@ -0,0 +1,337 @@
+/*
+ * This is the generic linker script for Tock. For most developers, it should
+ * be sufficient to define {ROM/PROG/RAM}_{ORIGIN/LENGTH} (6 variables, the
+ * start and length for each), MPU_MIN_ALIGN (the minimum alignment
+ * granularity supported by the MPU) and PAGE_SIZE (the size of a flash page).
+ * If undefined, PAGE_SIZE uses the default value of 512 bytes.
+ *
+ * --------------------------------------------------------------------------
+ *
+ * If you wish to create your own linker script from scratch, you must define
+ * the following symbols:
+ *
+ * `_etext`, `_srelocate`, `_erelocate`
+ * The `_etext` symbol marks the end of data stored in flash that should
+ * stay in flash. `_srelocate` and `_erelocate` mark the address range in
+ * SRAM that mutable program data is copied to.
+ *
+ * Tock will copy `_erelocate` - `_srelocate` bytes of data from the
+ * `_etext` pointer to the `_srelocate` pointer.
+ *
+ * `_szero`, `_ezero`
+ *
+ * The `_szero` and `_ezero` symbols define the range of the BSS, SRAM that
+ * Tock will zero on boot.
+ *
+ * `_sapps`, `_eapps`
+ *
+ * The `_sapps` symbol marks the beginning of application memory in flash.
+ * The `_eapps` symbol marks the end of application memory in flash by
+ * pointing to next address after application flash.
+ *
+ * `_sappmem`, `_eappmem`
+ *
+ * The `_sappmem` symbol marks the beginning of application memory in RAM.
+ * The `_eappmem` symbol marks the end of application memory in RAM by
+ * pointing to next address after application RAM.
+ */
+
+PAGE_SIZE = DEFINED(PAGE_SIZE) ? PAGE_SIZE : 512;
+
+SECTIONS
+{
+ .stack (NOLOAD) :
+ {
+ /* Kernel stack.
+ *
+ * Tock places the kernel stack at the bottom of SRAM so that the
+ * kernel will trigger memory fault if it exceeds its stack depth,
+ * rather than silently overwriting valuable data.
+ */
+ . = ALIGN(8);
+ _sstack = .;
+
+ /* For GNU LD, we can just advance the location pointer (".") here to
+ * reserve space for the stack. That, however, doesn't seem to work
+ * for LLVM LLD. The resulting ELF has a stack section that shows the
+ * correct size, but the next section (in our case .relocate) is not
+ * moved down as well, instead it sits at the same address as .stack.
+ * To work around this, we declare a dummy buffer and then insert it
+ * here in the .stack section. This sets the stack size correctly and
+ * places the .relocate section at the correct address. */
+ KEEP(*(.stack_buffer))
+ /*. = . + 0x1000;*/ /*This is the original method. */
+
+ . = ALIGN(8);
+ _estack = .;
+ } > ram
+
+
+ /* STATIC ELEMENTS FOR TOCK KERNEL */
+ .text :
+ {
+ . = ALIGN(4);
+ _textstart = .; /* Symbol expected by some MS build toolchains */
+ _stext = .; /* First of standard s,e (start/end) pair */
+
+ /* Place vector table at the beginning of ROM.
+ *
+ * The first 16 entries in the ARM vector table are defined by ARM and
+ * are common among all ARM chips. The remaining entries are
+ * chip-specific, which Tock defines in a separate .irqs section
+ *
+ * http://infocenter.arm.com/help/index.jsp?topic=/com.arm.doc.dui0553a/BABIFJFG.html
+ */
+ KEEP(*(.vectors .vectors.*))
+ KEEP(*(.irqs))
+
+ /* RISC-V
+ * There is no vector table in RISCV, so .vectors and .irqs will be
+ * empty. Instead, the _start function needs to be first in the binary
+ * for it to correctly be executed. We also need to include the trap
+ * handler assembly function.
+ *
+ * These are expected to just be empty on other platforms so they
+ * shouldn't have any effect.
+ */
+ KEEP(*(.riscv.start));
+ /* For RISC-V we need the `_start_trap` function to be 256 byte aligned,
+ * and that function is at the start of the .riscv.trap section. If that
+ * function does not exist (as for non-RISC-V platforms) then we do not
+ * need any unusual alignment.
+ * The allignment is implementation specific, so we currently use 256 to
+ * work with the lowRISC CPUs.
+ */
+ . = DEFINED(_start_trap) ? ALIGN(256) : ALIGN(1);
+ KEEP(*(.riscv.trap_vectored));
+ KEEP(*(.riscv.trap));
+
+ /* .text and .rodata hold most program code and immutable constants */
+ /* .gnu.linkonce hold C++ elements with vague linkage
+ https://gcc.gnu.org/onlinedocs/gcc/Vague-Linkage.html */
+ *(.text .text.* .gnu.linkonce.t.*)
+ *(.rodata .rodata.* .gnu.linkonce.r.*)
+
+ /* C++ exception unwinding information */
+ *(.ARM.extab* .gnu.linkonce.armextab.*)
+
+ /* glue_7 and glue_7t hold helper functions emitted by the compiler to
+ support interworking (linking between functions in ARM and THUMB
+ mode). Note that Cortex-M's do not support ARM mode, but this is left
+ here to save someone headache if they ever attempt to port Tock to a
+ Cortex-A core. */
+ *(.glue_7t) *(.glue_7)
+
+
+ /* Constructor and destructor sections:
+
+ - init/fini
+ Defined by ELF as sections that hold `process
+ initialization/termination code`
+ - {pre}{init/fini}_array_{start/end}
+ Symbols used by the C runtime for initialization / termination
+ - ctors/dtors
+ Symbols used by the C++ runtime for initialization / termination
+ */
+ . = ALIGN(4);
+ KEEP(*(.init))
+ . = ALIGN(4);
+ __preinit_array_start = .;
+ KEEP (*(.preinit_array))
+ __preinit_array_end = .;
+
+ . = ALIGN(4);
+ __init_array_start = .;
+ KEEP (*(SORT(.init_array.*)))
+ KEEP (*(.init_array))
+ __init_array_end = .;
+
+ . = ALIGN(4);
+ KEEP (*crtbegin.o(.ctors))
+ KEEP (*(EXCLUDE_FILE (*crtend.o) .ctors))
+ KEEP (*(SORT(.ctors.*)))
+ KEEP (*crtend.o(.ctors))
+
+ . = ALIGN(4);
+ KEEP(*(.fini))
+
+ . = ALIGN(4);
+ __fini_array_start = .;
+ KEEP (*(.fini_array))
+ KEEP (*(SORT(.fini_array.*)))
+ __fini_array_end = .;
+
+ KEEP (*crtbegin.o(.dtors))
+ KEEP (*(EXCLUDE_FILE (*crtend.o) .dtors))
+ KEEP (*(SORT(.dtors.*)))
+ KEEP (*crtend.o(.dtors))
+ /* End constructor/destructor */
+ } > rom
+
+
+ /* ARM Exception support
+ *
+ * This contains compiler-generated support for unwinding the stack,
+ * consisting of key-value pairs of function addresses and information on
+ * how to unwind stack frames.
+ * https://wiki.linaro.org/KenWerner/Sandbox/libunwind?action=AttachFile&do=get&target=libunwind-LDS.pdf
+ *
+ * .ARM.exidx is sorted, so has to go in its own output section.
+ */
+ PROVIDE_HIDDEN (__exidx_start = .);
+ .ARM.exidx :
+ {
+ /* (C++) Index entries for section unwinding */
+ *(.ARM.exidx* .gnu.linkonce.armexidx.*)
+ } > rom
+ PROVIDE_HIDDEN (__exidx_end = .);
+
+ /* Region for on-chip kernel non-volatile storage.
+ *
+ * Align on PAGE_SIZE number of bytes. Volumes within this region are
+ * allocated with the storage_volume! macro in utils.rs.
+ */
+ .storage :
+ {
+ . = ALIGN(PAGE_SIZE);
+ _sstorage = .;
+ *(.storage* storage*)
+ _estorage = .;
+ . = ALIGN(PAGE_SIZE);
+ } > rom
+ . = ALIGN(PAGE_SIZE);
+
+ /* Mark the end of static elements */
+ . = ALIGN(4);
+ _etext = .;
+ _textend = .; /* alias for _etext expected by some MS toolchains */
+
+
+ /* Customer configuration is most often located at the end of the rom. It is
+ * conditional, and won't be written if not specified in the board specific
+ * linker file.
+ */
+ .ccfg : {
+ KEEP(*(.ccfg))
+ } > ccfg
+
+
+ /* Section for application binaries in flash.
+ *
+ * This section is put into the "prog" memory, which is reserved for
+ * applications. This section is not used for the kernel, but including it
+ * in the .elf file allows for concatenating application binaries with the
+ * kernel.
+ */
+ .apps :
+ {
+ /* _sapps symbol used by Tock to look for first application. */
+ . = ALIGN(4);
+ _sapps = .;
+
+ /* Include a placeholder byte in this section so that the linker
+ * includes a segment for it. Otherwise the section will be empty and
+ * the linker will ignore it when defining the segments.
+ */
+ BYTE(0)
+ } > prog
+ /* _eapps symbol used by tock to calculate the length of app flash */
+ _eapps = _sapps + LENGTH(prog);
+
+
+
+
+
+
+
+ /* Kernel data that must be relocated. This is program data that is
+ * expected to live in SRAM, but is initialized with a value. This data is
+ * physically placed into flash and is copied into SRAM by Tock. The
+ * symbols here will be defined with addresses in SRAM.
+ *
+ * Tock assumes the relocation section follows all static elements and will
+ * copy (_erelocate - _srelocate) bytes from _etext to _srelocate.
+ */
+ .relocate : AT (_etext)
+ {
+ . = ALIGN(4);
+ _srelocate = .;
+
+ /* The Global Pointer is used by the RISC-V architecture to provide
+ * "gp-relative" addressing. The global pointer is set to the gp
+ * register once on boot, and the linker can then take advantage of this
+ * when emitting instructions by using offsets relative to this known
+ * value. Since RISC-V has only 12 bit immediates, this can help reduce
+ * code size.
+ *
+ * The standard is to set the global pointer to 0x800 past the beginning
+ * of the data section in RAM. This allows instructions to use 12 bit
+ * immediates to access the first 4KB of data memory. In theory the GP
+ * can be set to any value, but it should be placed near actual data for
+ * the compiler to actually be able to use it.
+ *
+ * Per convention, the variable _must_ be called __global_pointer$ for
+ * the linker to actually take advantage of it.
+ */
+ PROVIDE(__global_pointer$ = . + 0x800);
+
+ *(.ramfunc .ramfunc.*);
+ *(.sdata .sdata.* .gnu.linkonce.r.*)
+ *(.data .data.*);
+
+ . = ALIGN(4);
+ _erelocate = .;
+ } > ram
+
+
+ .sram (NOLOAD) :
+ {
+ /* Kernel BSS section. Memory that is expected to be initialized to
+ * zero.
+ *
+ * Elements in this section do not contribute to the binary size. Tock
+ * initialization will write zeros to the memory between _szero and
+ * _ezero.
+ *
+ * Elements placed in the .bss and .COMMON sections are simply used to
+ * measure amount of memory to zero out.
+ */
+ . = ALIGN(4);
+ _szero = .;
+
+ /* In addition to the traditional .bss section, RISC-V splits out a "small data" section
+ * see: https://github.com/riscv/riscv-pk/blob/a3e4ac61d2b1ff37a22b9193b85d3b94273e80cb/pk/pk.lds#L84
+ */
+ *(.sbss .sbss.* .bss .bss.*);
+ *(COMMON)
+
+ . = ALIGN(4);
+ _ezero = .;
+
+
+
+ /* Application Memory.
+ *
+ * Tock uses the remainder of SRAM for application memory.
+ *
+ * Currently, Tock allocates a fixed array of application memories at
+ * compile-time, and that array is simply placed here. A possible
+ * future enhancement may allow the kernel to parcel this memory space
+ * dynamically, requiring changes to this section.
+ */
+ . = ALIGN(MPU_MIN_ALIGN);
+ _sappmem = .;
+ *(.app_memory)
+ } > ram
+ _eappmem = ORIGIN(ram) + LENGTH(ram);
+
+ /* Discard RISC-V relevant .eh_frame, we are not doing unwind on panic
+ so it is not needed. */
+ /DISCARD/ :
+ {
+ *(.eh_frame);
+ }
+}
+
+ASSERT((_etext-_stext) + (_erelocate-_srelocate) < LENGTH(rom), "
+Text plus relocations exceeds the available ROM space.");
diff --git a/platform/layout.ld b/platform/layout.ld
new file mode 100644
index 0000000..4ef628e
--- /dev/null
+++ b/platform/layout.ld
@@ -0,0 +1,25 @@
+MEMORY
+{
+ /*
+ For debugging, use 8M rom, 8M prog, 16M ram.
+ */
+ rom (rx) : ORIGIN = 0x20000000, LENGTH = 0x0800000
+ prog (rx) : ORIGIN = 0x20800000, LENGTH = 0x0800000
+ ram (!rx) : ORIGIN = 0x10000000, LENGTH = 0x1000000
+}
+
+MPU_MIN_ALIGN = 1K;
+SECTIONS {
+ /*
+ * The flash header needs to match what the boot ROM for OpenTitan is
+ * expecting. At the moment, it contains only the entry point, but it
+ * will eventually contain the signature -- and (hopefully?!) some
+ * versioning information to make it slightly easier to debug when the
+ * boot ROM and Tock are out of sync with respect to the definition...
+ */
+ .flash_header : {
+ LONG(_stext)
+ } > rom
+}
+
+INCLUDE kernel_layout.ld
diff --git a/platform/rust-toolchain b/platform/rust-toolchain
new file mode 100644
index 0000000..b18a3f3
--- /dev/null
+++ b/platform/rust-toolchain
@@ -0,0 +1 @@
+nightly-2020-06-03
diff --git a/platform/src/chip.rs b/platform/src/chip.rs
new file mode 100644
index 0000000..b063c46
--- /dev/null
+++ b/platform/src/chip.rs
@@ -0,0 +1,287 @@
+//! High-level setup and interrupt mapping for the chip.
+
+use core::fmt::Write;
+use core::hint::unreachable_unchecked;
+use kernel;
+use kernel::debug;
+use kernel::hil::time::Alarm;
+use rv32i::csr::{mcause, mie::mie, mip::mip, mtvec::mtvec, CSR};
+use rv32i::syscall::SysCall;
+use rv32i::PMPConfigMacro;
+
+use crate::timer;
+use crate::uart;
+use matcha_hal::plic;
+
+PMPConfigMacro!(4);
+
+pub const CHIP_NAME: &str = "sim_verilator";
+pub const CHIP_CPU_FREQ: u32 = 500_000;
+pub const CHIP_PERIPH_FREQ: u32 = 125_000;
+pub const CHIP_UART_BPS: u32 = 9600;
+
+pub const UART0_TX_WATERMARK: u32 = 1;
+pub const UART0_RX_PARITY_ERR: u32 = 8;
+
+pub struct Matcha<A: 'static + Alarm<'static>> {
+ userspace_kernel_boundary: SysCall,
+ pmp: PMP,
+ scheduler_timer: kernel::VirtualSchedulerTimer<A>,
+}
+
+impl<A: 'static + Alarm<'static>> Matcha<A> {
+ pub unsafe fn new(alarm: &'static A) -> Self {
+ Self {
+ userspace_kernel_boundary: SysCall::new(),
+ pmp: PMP::new(),
+ scheduler_timer: kernel::VirtualSchedulerTimer::new(alarm),
+ }
+ }
+
+ pub unsafe fn enable_plic_interrupts(&self) {
+ plic::disable_all();
+ plic::clear_all_pending();
+ plic::enable_all();
+ }
+
+ unsafe fn handle_plic_interrupts(&self) {
+ while let Some(interrupt) = plic::next_pending() {
+ match interrupt {
+ UART0_TX_WATERMARK..=UART0_RX_PARITY_ERR => uart::UART0.handle_interrupt(),
+ _ => debug!("Pidx {}", interrupt),
+ }
+ plic::complete(interrupt);
+ }
+ }
+}
+
+impl<A: 'static + Alarm<'static>> kernel::Chip for Matcha<A> {
+ type MPU = PMP;
+ type UserspaceKernelBoundary = SysCall;
+ type SchedulerTimer = kernel::VirtualSchedulerTimer<A>;
+ type WatchDog = ();
+
+ fn mpu(&self) -> &Self::MPU {
+ &self.pmp
+ }
+
+ fn scheduler_timer(&self) -> &Self::SchedulerTimer {
+ &self.scheduler_timer
+ }
+
+ fn watchdog(&self) -> &Self::WatchDog {
+ &()
+ }
+
+ fn userspace_kernel_boundary(&self) -> &SysCall {
+ &self.userspace_kernel_boundary
+ }
+
+ fn service_pending_interrupts(&self) {
+ loop {
+ let mip = CSR.mip.extract();
+
+ if mip.is_set(mip::mtimer) {
+ unsafe {
+ timer::TIMER.service_interrupt();
+ }
+ }
+ if mip.is_set(mip::mext) {
+ unsafe {
+ self.handle_plic_interrupts();
+ }
+ }
+
+ if !mip.matches_any(mip::mext::SET + mip::mtimer::SET) {
+ break;
+ }
+ }
+
+ // Re-enable all MIE interrupts that we care about. Since we looped
+ // until we handled them all, we can re-enable all of them.
+ CSR.mie.modify(mie::mext::SET + mie::mtimer::SET);
+ }
+
+ fn has_pending_interrupts(&self) -> bool {
+ let mip = CSR.mip.extract();
+ mip.matches_any(mip::mext::SET + mip::mtimer::SET)
+ }
+
+ fn sleep(&self) {
+ unsafe {
+ //pwrmgr::PWRMGR.enable_low_power();
+ //self.check_until_true_or_interrupt(|| pwrmgr::PWRMGR.check_clock_propagation(), None);
+ rv32i::support::wfi();
+ }
+ }
+
+ unsafe fn atomic<F, R>(&self, f: F) -> R
+ where
+ F: FnOnce() -> R,
+ {
+ rv32i::support::atomic(f)
+ }
+
+ unsafe fn print_state(&self, writer: &mut dyn Write) {
+ let _ = writer.write_fmt(format_args!(
+ "\r\n---| Matcha configuration for {} |---",
+ crate::chip::CHIP_NAME
+ ));
+ rv32i::print_riscv_state(writer);
+ }
+}
+
+fn handle_exception(exception: mcause::Exception) {
+ match exception {
+ mcause::Exception::UserEnvCall | mcause::Exception::SupervisorEnvCall => (),
+
+ mcause::Exception::InstructionMisaligned
+ | mcause::Exception::InstructionFault
+ | mcause::Exception::IllegalInstruction
+ | mcause::Exception::Breakpoint
+ | mcause::Exception::LoadMisaligned
+ | mcause::Exception::LoadFault
+ | mcause::Exception::StoreMisaligned
+ | mcause::Exception::StoreFault
+ | mcause::Exception::MachineEnvCall
+ | mcause::Exception::InstructionPageFault
+ | mcause::Exception::LoadPageFault
+ | mcause::Exception::StorePageFault
+ | mcause::Exception::Unknown => {
+ panic!("fatal exception");
+ }
+ }
+}
+
+unsafe fn handle_interrupt(intr: mcause::Interrupt) {
+ match intr {
+ mcause::Interrupt::UserSoft
+ | mcause::Interrupt::UserTimer
+ | mcause::Interrupt::UserExternal => {
+ panic!("unexpected user-mode interrupt");
+ }
+ mcause::Interrupt::SupervisorExternal
+ | mcause::Interrupt::SupervisorTimer
+ | mcause::Interrupt::SupervisorSoft => {
+ panic!("unexpected supervisor-mode interrupt");
+ }
+
+ mcause::Interrupt::MachineSoft => {
+ CSR.mie.modify(mie::msoft::CLEAR);
+ }
+ mcause::Interrupt::MachineTimer => {
+ CSR.mie.modify(mie::mtimer::CLEAR);
+ }
+ mcause::Interrupt::MachineExternal => {
+ CSR.mie.modify(mie::mext::CLEAR);
+ }
+
+ mcause::Interrupt::Unknown => {
+ panic!("interrupt of unknown cause");
+ }
+ }
+}
+
+/// Trap handler for board/chip specific code.
+///
+/// For the Ibex this gets called when an interrupt occurs while the chip is
+/// in kernel mode. All we need to do is check which interrupt occurred and
+/// disable it.
+#[export_name = "_start_trap_rust"]
+pub unsafe extern "C" fn start_trap_rust() {
+ match mcause::Trap::from(CSR.mcause.extract()) {
+ mcause::Trap::Interrupt(interrupt) => {
+ handle_interrupt(interrupt);
+ }
+ mcause::Trap::Exception(exception) => {
+ handle_exception(exception);
+ }
+ }
+}
+
+/// Function that gets called if an interrupt occurs while an app was running.
+/// mcause is passed in, and this function should correctly handle disabling the
+/// interrupt that fired so that it does not trigger again.
+#[export_name = "_disable_interrupt_trap_handler"]
+pub unsafe extern "C" fn disable_interrupt_trap_handler(mcause_val: u32) {
+ match mcause::Trap::from(mcause_val) {
+ mcause::Trap::Interrupt(interrupt) => {
+ handle_interrupt(interrupt);
+ }
+ _ => {
+ panic!("unexpected non-interrupt\n");
+ }
+ }
+}
+
+pub unsafe fn configure_trap_handler() {
+ // The Ibex CPU does not support non-vectored trap entries.
+ CSR.mtvec
+ .write(mtvec::trap_addr.val(_start_trap_vectored as u32 >> 2) + mtvec::mode::Vectored)
+}
+
+// Mock implementation for crate tests that does not include the section
+// specifier, as the test will not use our linker script, and the host
+// compilation environment may not allow the section name.
+#[cfg(not(any(target_arch = "riscv32", target_os = "none")))]
+pub extern "C" fn _start_trap_vectored() {
+ unsafe {
+ unreachable_unchecked();
+ }
+}
+
+#[cfg(all(target_arch = "riscv32", target_os = "none"))]
+#[link_section = ".riscv.trap_vectored"]
+#[export_name = "_start_trap_vectored"]
+#[naked]
+pub extern "C" fn _start_trap_vectored() -> ! {
+ unsafe {
+ // According to the Ibex user manual:
+ // [NMI] has interrupt ID 31, i.e., it has the highest priority of all
+ // interrupts and the core jumps to the trap-handler base address (in
+ // mtvec) plus 0x7C to handle the NMI.
+ //
+ // Below are 32 (non-compressed) jumps to cover the entire possible
+ // range of vectored traps.
+ #[cfg(all(target_arch = "riscv32", target_os = "none"))]
+ llvm_asm!("
+ j _start_trap
+ j _start_trap
+ j _start_trap
+ j _start_trap
+ j _start_trap
+ j _start_trap
+ j _start_trap
+ j _start_trap
+ j _start_trap
+ j _start_trap
+ j _start_trap
+ j _start_trap
+ j _start_trap
+ j _start_trap
+ j _start_trap
+ j _start_trap
+ j _start_trap
+ j _start_trap
+ j _start_trap
+ j _start_trap
+ j _start_trap
+ j _start_trap
+ j _start_trap
+ j _start_trap
+ j _start_trap
+ j _start_trap
+ j _start_trap
+ j _start_trap
+ j _start_trap
+ j _start_trap
+ j _start_trap
+ j _start_trap
+ "
+ :
+ :
+ :
+ : "volatile");
+ unreachable_unchecked()
+ }
+}
diff --git a/platform/src/main.rs b/platform/src/main.rs
new file mode 100644
index 0000000..83f00c8
--- /dev/null
+++ b/platform/src/main.rs
@@ -0,0 +1,227 @@
+//! Board file for Shodan's "Matcha" RISC-V development platform.
+
+#![no_std]
+#![no_main]
+#![feature(llvm_asm)]
+#![feature(const_fn)]
+#![feature(naked_functions)]
+
+use capsules::virtual_alarm::{MuxAlarm, VirtualMuxAlarm};
+use core::panic::PanicInfo;
+use kernel::capabilities;
+use kernel::common::dynamic_deferred_call::{DynamicDeferredCall, DynamicDeferredCallClientState};
+use kernel::component::Component;
+use kernel::hil;
+use kernel::hil::time::Alarm;
+use kernel::Chip;
+use kernel::Platform;
+use kernel::{create_capability, debug, static_init};
+use matcha_capsules::debug_uart::DebugUartCapsule;
+use matcha_capsules::elf_loader::ElfLoaderCapsule;
+use matcha_capsules::storage_manager::StorageManagerCapsule;
+use matcha_config::*;
+use matcha_hal::dprintf;
+use rv32i::csr;
+
+pub mod chip;
+pub mod timer;
+pub mod uart;
+
+/// Panic handler.
+#[cfg(not(test))]
+#[no_mangle]
+#[panic_handler]
+pub unsafe extern "C" fn panic_fmt(_pi: &PanicInfo) -> ! {
+ dprintf!("panic panic panic!\n");
+ loop {}
+}
+
+/// These symbols are defined in the linker script.
+extern "C" {
+ /// Beginning of the ROM region containing app images.
+ static _sapps: u8;
+ /// End of the ROM region containing app images.
+ static _eapps: u8;
+ /// Beginning of the RAM region for app memory.
+ static mut _sappmem: u8;
+ /// End of the RAM region for app memory.
+ static _eappmem: u8;
+}
+
+// Actual memory for holding the active process structures. Need an empty list
+// at least.
+static mut PROCESSES: [Option<&'static dyn kernel::procs::ProcessType>; 4] =
+ [None, None, None, None];
+
+/// Dummy buffer that causes the linker to reserve enough space for the stack.
+/// Must be at least 16k in debug builds (@aappleby - not sure why, what's so large?)
+#[no_mangle]
+#[link_section = ".stack_buffer"]
+pub static mut STACK_MEMORY: [u8; 0x4000] = [0; 0x4000];
+
+/// A structure representing this platform that holds references to all
+/// capsules for this platform. We've included an alarm and console.
+struct MatchaPlatform {
+ console: &'static capsules::console::Console<'static>,
+ alarm: &'static capsules::alarm::AlarmDriver<
+ 'static,
+ VirtualMuxAlarm<'static, crate::timer::RvTimer<'static>>,
+ >,
+ debug_uart: &'static DebugUartCapsule,
+ storage_manager: &'static StorageManagerCapsule,
+ elf_loader: &'static ElfLoaderCapsule,
+}
+
+/// Mapping of integer syscalls to objects that implement syscalls.
+impl Platform for MatchaPlatform {
+ fn with_driver<F, R>(&self, driver_num: usize, f: F) -> R
+ where
+ F: FnOnce(Option<&dyn kernel::Driver>) -> R,
+ {
+ match driver_num {
+ DRIVER_NUM_CONSOLE => f(Some(self.console)),
+ DRIVER_NUM_ALARM => f(Some(self.alarm)),
+ DRIVER_NUM_DEBUG_UART => f(Some(self.debug_uart)),
+ DRIVER_NUM_STORAGE_MANAGER => f(Some(self.storage_manager)),
+ DRIVER_NUM_ELF_LOADER => f(Some(self.elf_loader)),
+ _ => f(None),
+ }
+ }
+}
+
+/// Reset Handler.
+///
+/// This function is called from the arch crate after some very basic RISC-V
+/// setup.
+#[no_mangle]
+pub unsafe fn reset_handler() {
+ // Basic setup of the platform.
+ rv32i::init_memory();
+ // Ibex-specific handler
+ crate::chip::configure_trap_handler();
+
+ dprintf!("sw/matcha/platform/src/main.rs::reset_handler()\n");
+
+ // initialize capabilities
+ let process_mgmt_cap = create_capability!(capabilities::ProcessManagementCapability);
+ let memory_allocation_cap = create_capability!(capabilities::MemoryAllocationCapability);
+
+ let main_loop_cap = create_capability!(capabilities::MainLoopCapability);
+
+ let board_kernel = static_init!(kernel::Kernel, kernel::Kernel::new(&PROCESSES));
+
+ let dynamic_deferred_call_clients =
+ static_init!([DynamicDeferredCallClientState; 1], Default::default());
+ let dynamic_deferred_caller = static_init!(
+ DynamicDeferredCall,
+ DynamicDeferredCall::new(dynamic_deferred_call_clients)
+ );
+ DynamicDeferredCall::set_global_instance(dynamic_deferred_caller);
+
+ // Create a shared UART channel for the console and for kernel debug.
+ let uart_mux = components::console::UartMuxComponent::new(
+ &crate::uart::UART0,
+ crate::uart::UART0_BAUDRATE,
+ dynamic_deferred_caller,
+ )
+ .finalize(());
+
+ let alarm = &crate::timer::TIMER;
+ alarm.setup();
+
+ // Create a shared virtualization mux layer on top of a single hardware
+ // alarm.
+ let mux_alarm = static_init!(
+ MuxAlarm<'static, crate::timer::RvTimer>,
+ MuxAlarm::new(alarm)
+ );
+ hil::time::Alarm::set_alarm_client(&crate::timer::TIMER, mux_alarm);
+
+ // Alarm
+ let virtual_alarm_user = static_init!(
+ VirtualMuxAlarm<'static, crate::timer::RvTimer>,
+ VirtualMuxAlarm::new(mux_alarm)
+ );
+ let scheduler_timer_virtual_alarm = static_init!(
+ VirtualMuxAlarm<'static, crate::timer::RvTimer>,
+ VirtualMuxAlarm::new(mux_alarm)
+ );
+ let alarm = static_init!(
+ capsules::alarm::AlarmDriver<'static, VirtualMuxAlarm<'static, crate::timer::RvTimer>>,
+ capsules::alarm::AlarmDriver::new(
+ virtual_alarm_user,
+ board_kernel.create_grant(&memory_allocation_cap)
+ )
+ );
+ hil::time::Alarm::set_alarm_client(virtual_alarm_user, alarm);
+
+ let chip = static_init!(
+ crate::chip::Matcha<VirtualMuxAlarm<'static, crate::timer::RvTimer>>,
+ crate::chip::Matcha::new(scheduler_timer_virtual_alarm)
+ );
+ scheduler_timer_virtual_alarm.set_alarm_client(chip.scheduler_timer());
+
+ // Need to enable all interrupts for Tock Kernel
+ chip.enable_plic_interrupts();
+ // enable interrupts globally
+ csr::CSR
+ .mie
+ .modify(csr::mie::mie::msoft::SET + csr::mie::mie::mtimer::SET + csr::mie::mie::mext::SET);
+ csr::CSR.mstatus.modify(csr::mstatus::mstatus::mie::SET);
+
+ // Setup the console.
+ let console = components::console::ConsoleComponent::new(board_kernel, uart_mux).finalize(());
+ // Create the debugger object that handles calls to `debug!()`.
+ components::debug_writer::DebugWriterComponent::new(uart_mux).finalize(());
+
+ let debug_uart_capsule = static_init!(
+ DebugUartCapsule,
+ DebugUartCapsule {
+ app_data_grant: board_kernel.create_grant(&memory_allocation_cap)
+ }
+ );
+
+ let storage_manager = static_init!(
+ matcha_capsules::storage_manager::StorageManagerCapsule,
+ matcha_capsules::storage_manager::StorageManagerCapsule::new(
+ board_kernel.create_grant(&memory_allocation_cap)
+ )
+ );
+
+ let elf_loader = static_init!(
+ matcha_capsules::elf_loader::ElfLoaderCapsule,
+ matcha_capsules::elf_loader::ElfLoaderCapsule {}
+ );
+
+ let platform = MatchaPlatform {
+ console: console,
+ alarm: alarm,
+ debug_uart: debug_uart_capsule,
+ storage_manager: storage_manager,
+ elf_loader: elf_loader,
+ };
+
+ kernel::procs::load_processes(
+ board_kernel,
+ chip,
+ core::slice::from_raw_parts(
+ &_sapps as *const u8,
+ &_eapps as *const u8 as usize - &_sapps as *const u8 as usize,
+ ),
+ core::slice::from_raw_parts_mut(
+ &mut _sappmem as *mut u8,
+ &_eappmem as *const u8 as usize - &_sappmem as *const u8 as usize,
+ ),
+ &mut PROCESSES,
+ kernel::procs::FaultResponse::Panic,
+ &process_mgmt_cap,
+ )
+ .unwrap_or_else(|err| {
+ debug!("Error loading processes!");
+ debug!("{:?}", err);
+ });
+ debug!("MatchaPlatform initialisation complete. Entering main loop");
+
+ let scheduler = components::sched::priority::PriorityComponent::new(board_kernel).finalize(());
+ board_kernel.kernel_loop(&platform, chip, None, scheduler, &main_loop_cap);
+}
diff --git a/platform/src/timer.rs b/platform/src/timer.rs
new file mode 100644
index 0000000..362afd5
--- /dev/null
+++ b/platform/src/timer.rs
@@ -0,0 +1,197 @@
+//! Timer driver.
+
+use kernel::common::cells::OptionalCell;
+use kernel::common::registers::{register_bitfields, register_structs, ReadWrite, WriteOnly};
+use kernel::common::StaticRef;
+use kernel::hil::time;
+use kernel::hil::time::{Ticks, Ticks64, Time};
+use kernel::ReturnCode;
+
+const PRESCALE: u16 = ((crate::chip::CHIP_CPU_FREQ / 10_000) - 1) as u16; // 10Khz
+
+/// 10KHz `Frequency`
+#[derive(Debug)]
+pub struct Freq10KHz;
+impl time::Frequency for Freq10KHz {
+ fn frequency() -> u32 {
+ 10_000
+ }
+}
+
+register_structs! {
+ pub TimerRegisters {
+ (0x000 => ctrl: ReadWrite<u32, ctrl::Register>),
+
+ (0x004 => _reserved),
+
+ (0x100 => config: ReadWrite<u32, config::Register>),
+
+ (0x104 => value_low: ReadWrite<u32>),
+ (0x108 => value_high: ReadWrite<u32>),
+
+ (0x10c => compare_low: ReadWrite<u32>),
+ (0x110 => compare_high: ReadWrite<u32>),
+
+ (0x114 => intr_enable: ReadWrite<u32, intr::Register>),
+ (0x118 => intr_state: ReadWrite<u32, intr::Register>),
+ (0x11c => intr_test: WriteOnly<u32, intr::Register>),
+ (0x120 => @END),
+ }
+}
+
+register_bitfields![u32,
+ ctrl [
+ enable OFFSET(0) NUMBITS(1) []
+ ],
+ config [
+ prescale OFFSET(0) NUMBITS(12) [],
+ step OFFSET(16) NUMBITS(8) []
+ ],
+ intr [
+ timer0 OFFSET(0) NUMBITS(1) []
+ ]
+];
+
+pub struct RvTimer<'a> {
+ registers: StaticRef<TimerRegisters>,
+ alarm_client: OptionalCell<&'a dyn time::AlarmClient>,
+ overflow_client: OptionalCell<&'a dyn time::OverflowClient>,
+}
+
+impl<'a> RvTimer<'a> {
+ const fn new(base: StaticRef<TimerRegisters>) -> RvTimer<'a> {
+ RvTimer {
+ registers: base,
+ alarm_client: OptionalCell::empty(),
+ overflow_client: OptionalCell::empty(),
+ }
+ }
+
+ pub fn setup(&self) {
+ let regs = self.registers;
+ // Set proper prescaler and the like
+ regs.config
+ .write(config::prescale.val(PRESCALE as u32) + config::step.val(1u32));
+ regs.compare_high.set(0);
+ regs.value_low.set(0xFFFF_0000);
+ regs.intr_enable.write(intr::timer0::CLEAR);
+ regs.ctrl.write(ctrl::enable::SET);
+ }
+
+ pub fn service_interrupt(&self) {
+ let regs = self.registers;
+ regs.intr_enable.write(intr::timer0::CLEAR);
+ regs.intr_state.write(intr::timer0::SET);
+ self.alarm_client.map(|client| {
+ client.alarm();
+ });
+ }
+}
+
+impl time::Time for RvTimer<'_> {
+ type Frequency = Freq10KHz;
+ type Ticks = Ticks64;
+
+ fn now(&self) -> Ticks64 {
+ // RISC-V has a 64-bit counter but you can only read 32 bits
+ // at once, which creates a race condition if the lower register
+ // wraps between the reads. So the recommended approach is to read
+ // low, read high, read low, and if the second low is lower, re-read
+ // high. -pal 8/6/20
+ let first_low: u32 = self.registers.value_low.get();
+ let mut high: u32 = self.registers.value_high.get();
+ let second_low: u32 = self.registers.value_low.get();
+ if second_low < first_low {
+ // Wraparound
+ high = self.registers.value_high.get();
+ }
+ Ticks64::from(((high as u64) << 32) | second_low as u64)
+ }
+}
+
+impl<'a> time::Counter<'a> for RvTimer<'a> {
+ fn set_overflow_client(&'a self, client: &'a dyn time::OverflowClient) {
+ self.overflow_client.set(client);
+ }
+
+ fn start(&self) -> ReturnCode {
+ ReturnCode::SUCCESS
+ }
+
+ fn stop(&self) -> ReturnCode {
+ // RISCV counter can't be stopped...
+ ReturnCode::EBUSY
+ }
+
+ fn reset(&self) -> ReturnCode {
+ // RISCV counter can't be reset
+ ReturnCode::FAIL
+ }
+
+ fn is_running(&self) -> bool {
+ true
+ }
+}
+
+impl<'a> time::Alarm<'a> for RvTimer<'a> {
+ fn set_alarm_client(&self, client: &'a dyn time::AlarmClient) {
+ self.alarm_client.set(client);
+ }
+
+ fn set_alarm(&self, reference: Self::Ticks, dt: Self::Ticks) {
+ // This does not handle the 64-bit wraparound case.
+ // Because mtimer fires if the counter is >= the compare,
+ // handling wraparound requires setting compare to the
+ // maximum value, issuing a callback on the overflow client
+ // if there is one, spinning until it wraps around to 0, then
+ // setting the compare to the correct value.
+ let regs = self.registers;
+ let now = self.now();
+ let mut expire = reference.wrapping_add(dt);
+
+ if !now.within_range(reference, expire) {
+ expire = now;
+ }
+
+ let val = expire.into_u64();
+ let high = (val >> 32) as u32;
+ let low = (val & 0xffffffff) as u32;
+
+ // Recommended approach for setting the two compare registers
+ // (RISC-V Privileged Architectures 3.1.15) -pal 8/6/20
+ regs.compare_low.set(0xffffffff);
+ regs.compare_high.set(high);
+ regs.compare_low.set(low);
+ //debug!("TIMER: set to {}", expire.into_u64());
+ self.registers.intr_enable.write(intr::timer0::SET);
+ }
+
+ fn get_alarm(&self) -> Self::Ticks {
+ let mut val: u64 = (self.registers.compare_high.get() as u64) << 32;
+ val |= self.registers.compare_low.get() as u64;
+ Ticks64::from(val)
+ }
+
+ fn disarm(&self) -> ReturnCode {
+ // You clear the RISCV mtime interrupt by writing to the compare
+ // registers. Since the only way to do so is to set a new alarm,
+ // and this is also the only way to re-enable the interrupt, disabling
+ // the interrupt is sufficient. Calling set_alarm will clear the
+ // pending interrupt before re-enabling. -pal 8/6/20
+ self.registers.intr_enable.write(intr::timer0::CLEAR);
+ ReturnCode::SUCCESS
+ }
+
+ fn is_armed(&self) -> bool {
+ self.registers.intr_enable.is_set(intr::timer0)
+ }
+
+ fn minimum_dt(&self) -> Self::Ticks {
+ Self::Ticks::from(1 as u64)
+ }
+}
+
+const TIMER_BASE: StaticRef<TimerRegisters> =
+ unsafe { StaticRef::new(0x4010_0000 as *const TimerRegisters) };
+
+pub static mut TIMER: RvTimer = RvTimer::new(TIMER_BASE);
diff --git a/platform/src/uart.rs b/platform/src/uart.rs
new file mode 100644
index 0000000..f9acb19
--- /dev/null
+++ b/platform/src/uart.rs
@@ -0,0 +1,10 @@
+//use crate::chip_config::CONFIG;
+use kernel::common::StaticRef;
+use lowrisc::uart::{Uart, UartRegisters};
+
+pub const UART0_BAUDRATE: u32 = crate::chip::CHIP_UART_BPS;
+
+pub static mut UART0: Uart = Uart::new(UART0_BASE, crate::chip::CHIP_PERIPH_FREQ);
+
+const UART0_BASE: StaticRef<UartRegisters> =
+ unsafe { StaticRef::new(0x4000_0000 as *const UartRegisters) };