diff --git a/sw/device/silicon_owner/tock/kernel/BUILD b/sw/device/silicon_owner/tock/kernel/BUILD new file mode 100644 index 0000000000000..337299add657a --- /dev/null +++ b/sw/device/silicon_owner/tock/kernel/BUILD @@ -0,0 +1,73 @@ +# Copyright lowRISC contributors. +# Licensed under the Apache License, Version 2.0, see LICENSE for details. +# SPDX-License-Identifier: Apache-2.0 + +load("@rules_rust//rust:defs.bzl", "rust_binary") +load("//rules:linker.bzl", "ld_library") +load("//rules:opentitan.bzl", "elf_to_disassembly", "obj_transform") + +package(default_visibility = ["//visibility:public"]) + +ld_library( + name = "kernel_layout", + includes = [ + "@tock//boards:kernel_layout", + ], +) + +ld_library( + name = "layout", + script = "layout.ld", + deps = [ + ":kernel_layout", + ], +) + +cc_library( + name = "nostartfiles", + linkopts = [ + "-nostartfiles", + ], +) + +rust_binary( + name = "kernel", + srcs = [ + "src/io.rs", + "src/main.rs", + "src/otbn.rs", + ], + rustc_flags = [ + "-g", + # TODO(cfrantz): determine the appropriate set of linker flags. + #"-Clinker=rust-lld", + #"-Clinker-flavor=ld.lld", + #"-Crelocation-model=static", + #"-Clink-arg=-nmagic", + #"-Clink-arg=-icf=all", + #"-Cforce-frame-pointers=no", + ], + # We don't want to build the kernel automatically if matched + # by a bazel wildcard because the kernel will not fit in the allocated + # space if built in `fastbuild` or `dbg` modes. + tags = ["manual"], + deps = [ + ":layout", + ":nostartfiles", + "@tock//arch/rv32i", + "@tock//boards/components", + "@tock//capsules/aes_gcm:capsules-aes-gcm", + "@tock//capsules/core:capsules-core", + "@tock//capsules/extra:capsules-extra", + "@tock//chips/earlgrey", + "@tock//chips/lowrisc", + "@tock//kernel", + "@tock//libraries/tock-tbf", + ], +) + +obj_transform( + name = "raw_kernel", + srcs = [":kernel"], + tags = ["manual"], +) diff --git a/sw/device/silicon_owner/tock/kernel/layout.ld b/sw/device/silicon_owner/tock/kernel/layout.ld new file mode 100644 index 0000000000000..4b4b3dff17200 --- /dev/null +++ b/sw/device/silicon_owner/tock/kernel/layout.ld @@ -0,0 +1,57 @@ +/* Copyright lowRISC contributors. */ +/* Licensed under the Apache License, Version 2.0, see LICENSE for details. */ +/* SPDX-License-Identifier: Apache-2.0 */ + + +/* Licensed under the Apache License, Version 2.0 or the MIT License. */ +/* SPDX-License-Identifier: Apache-2.0 OR MIT */ +/* Copyright Tock Contributors 2023. */ + +MEMORY +{ + rom (rx) : ORIGIN = 0x20000000, LENGTH = 0x40000 + /* Support up to 0x2009_0000 for apps + * and 0x2009_0000 to 0x2010_0000 is for flash storage. + */ + prog (rx) : ORIGIN = 0x20040000, LENGTH = 0x60000 + ram (!rx) : ORIGIN = 0x10000000, LENGTH = 0x20000 +} + +SECTIONS { + .manifest ORIGIN(rom): + { + _manifest = .; + /* see: sw/device/silicon_creator/lib/manifest.h */ + . += 384; /* rsa_signature */ + . += 4; /* usage_constraints.selector_bits */ + . += 32; /* usage_constraints.device_id */ + . += 4; /* usage_constraints.manuf_state_creator */ + . += 4; /* usage_constraints.manuf_state_owner */ + . += 4; /* usage_constraints.life_cycle_state */ + . += 384; /* rsa_modulus */ + . += 4; /* address_translation */ + . += 4; /* identifier */ + . += 4; /* manifest_version */ + . += 4; /* signed_region_end */ + . += 4; /* length */ + . += 4; /* version_major */ + . += 4; /* version_minor */ + . += 4; /* security_version */ + . += 8; /* timestamp */ + . += 32; /* binding_value */ + . += 4; /* max_key_version */ + . += 4; /* code_start */ + . += 4; /* code_end */ + LONG(_stext - ORIGIN(rom)); /* . = . + 4; entry_point */ + /* manifest extension table */ + /* see: sw/device/silicon_creator/lib/base/chip.h */ + /* CHIP_MANIFEST_EXT_TABLE_COUNT = 15 */ + /* sizeof(manifest_ext_table_entry) = 8 */ + . += 120; /* manifest_ext_table */ + } > rom +} + +ASSERT (((_etext - _manifest) > 0), "Error: PMP and Flash protection setup assumes _etext follows _manifest"); +/* TODO(cfrantz): Fix the ld_library rule to allow include paths and avoid */ +/* having to specify an `external` path here */ +INCLUDE external/tock/boards/kernel_layout.ld diff --git a/sw/device/silicon_owner/tock/kernel/src/io.rs b/sw/device/silicon_owner/tock/kernel/src/io.rs new file mode 100644 index 0000000000000..a3bdf137e1ae8 --- /dev/null +++ b/sw/device/silicon_owner/tock/kernel/src/io.rs @@ -0,0 +1,102 @@ +// Copyright lowRISC contributors. +// Licensed under the Apache License, Version 2.0, see LICENSE for details. +// SPDX-License-Identifier: Apache-2.0 + +use core::fmt::Write; +use core::panic::PanicInfo; +use core::str; +use kernel::debug; +use kernel::debug::IoWrite; + +use crate::CHIP; +use crate::PROCESSES; +use crate::PROCESS_PRINTER; + +struct Writer {} + +static mut WRITER: Writer = Writer {}; + +impl Write for Writer { + fn write_str(&mut self, s: &str) -> ::core::fmt::Result { + self.write(s.as_bytes()); + Ok(()) + } +} + +impl IoWrite for Writer { + fn write(&mut self, buf: &[u8]) -> usize { + // This creates a second instance of the UART peripheral, and should only be used + // during panic. + earlgrey::uart::Uart::new( + earlgrey::uart::UART0_BASE, + earlgrey::chip_config::CONFIG.peripheral_freq, + ) + .transmit_sync(buf); + buf.len() + } +} + +#[cfg(not(test))] +use kernel::hil::gpio::Configure; +#[cfg(not(test))] +use kernel::hil::led; + +/// Panic handler. +#[cfg(not(test))] +#[no_mangle] +#[panic_handler] +pub unsafe extern "C" fn panic_fmt(pi: &PanicInfo) -> ! { + let first_led_pin = &mut earlgrey::gpio::GpioPin::new( + earlgrey::gpio::GPIO0_BASE, + earlgrey::gpio::PADCTRL_BASE, + earlgrey::gpio::pins::pin7, + ); + first_led_pin.make_output(); + let first_led = &mut led::LedLow::new(first_led_pin); + let writer = &mut WRITER; + + #[cfg(feature = "sim_verilator")] + debug::panic( + &mut [first_led], + writer, + pi, + &|| {}, + &PROCESSES, + &CHIP, + &PROCESS_PRINTER, + ); + + #[cfg(not(feature = "sim_verilator"))] + debug::panic( + &mut [first_led], + writer, + pi, + &rv32i::support::nop, + &PROCESSES, + &CHIP, + &PROCESS_PRINTER, + ); +} + +#[cfg(test)] +#[no_mangle] +#[panic_handler] +pub unsafe extern "C" fn panic_fmt(pi: &PanicInfo) -> ! { + let writer = &mut WRITER; + + #[cfg(feature = "sim_verilator")] + debug::panic_print(writer, pi, &|| {}, &PROCESSES, &CHIP, &PROCESS_PRINTER); + #[cfg(not(feature = "sim_verilator"))] + debug::panic_print( + writer, + pi, + &rv32i::support::nop, + &PROCESSES, + &CHIP, + &PROCESS_PRINTER, + ); + + let _ = writeln!(writer, "{}", pi); + // Exit QEMU with a return code of 1 + crate::tests::semihost_command_exit_failure(); +} diff --git a/sw/device/silicon_owner/tock/kernel/src/main.rs b/sw/device/silicon_owner/tock/kernel/src/main.rs new file mode 100644 index 0000000000000..a817464422125 --- /dev/null +++ b/sw/device/silicon_owner/tock/kernel/src/main.rs @@ -0,0 +1,809 @@ +// Copyright lowRISC contributors. +// Licensed under the Apache License, Version 2.0, see LICENSE for details. +// SPDX-License-Identifier: Apache-2.0 + +//! Board file for LowRISC OpenTitan RISC-V development platform. +//! +//! - + +#![no_std] +// Disable this attribute when documenting, as a workaround for +// https://github.com/rust-lang/rust/issues/62184. +#![cfg_attr(not(doc), no_main)] +#![feature(custom_test_frameworks)] +#![test_runner(test_runner)] +#![reexport_test_harness_main = "test_main"] + +use crate::hil::symmetric_encryption::AES128_BLOCK_SIZE; +use crate::otbn::OtbnComponent; +use capsules_aes_gcm::aes_gcm; +use capsules_core::virtualizers::virtual_aes_ccm; +use capsules_core::virtualizers::virtual_alarm::{MuxAlarm, VirtualMuxAlarm}; +use earlgrey::chip::EarlGreyDefaultPeripherals; +use kernel::capabilities; +use kernel::component::Component; +use kernel::hil; +use kernel::hil::entropy::Entropy32; +use kernel::hil::hasher::Hasher; +use kernel::hil::i2c::I2CMaster; +use kernel::hil::led::LedHigh; +use kernel::hil::rng::Rng; +use kernel::hil::symmetric_encryption::AES128; +use kernel::platform::mpu; +use kernel::platform::mpu::KernelMPU; +use kernel::platform::scheduler_timer::VirtualSchedulerTimer; +use kernel::platform::{KernelResources, SyscallDriverLookup, TbfHeaderFilterDefaultAllow}; +use kernel::scheduler::priority::PrioritySched; +use kernel::utilities::registers::interfaces::ReadWriteable; +use kernel::{create_capability, debug, static_init}; +use lowrisc::flash_ctrl::FlashMPConfig; +use rv32i::csr; + +pub mod io; +mod otbn; +#[cfg(test)] +mod tests; + +const NUM_PROCS: usize = 4; + +// +// Actual memory for holding the active process structures. Need an empty list +// at least. +static mut PROCESSES: [Option<&'static dyn kernel::process::Process>; 4] = [None; NUM_PROCS]; + +// Test access to the peripherals +#[cfg(test)] +static mut PERIPHERALS: Option<&'static EarlGreyDefaultPeripherals> = None; +// Test access to board +#[cfg(test)] +static mut BOARD: Option<&'static kernel::Kernel> = None; +// Test access to platform +#[cfg(test)] +static mut PLATFORM: Option<&'static EarlGrey> = None; +// Test access to main loop capability +#[cfg(test)] +static mut MAIN_CAP: Option<&dyn kernel::capabilities::MainLoopCapability> = None; +// Test access to alarm +static mut ALARM: Option<&'static MuxAlarm<'static, earlgrey::timer::RvTimer<'static>>> = None; +// Test access to TicKV +static mut TICKV: Option< + &capsules_extra::tickv::TicKVStore< + 'static, + capsules_core::virtualizers::virtual_flash::FlashUser< + 'static, + lowrisc::flash_ctrl::FlashCtrl<'static>, + >, + capsules_extra::sip_hash::SipHasher24<'static>, + 2048, + >, +> = None; +// Test access to AES +static mut AES: Option< + &aes_gcm::Aes128Gcm< + 'static, + virtual_aes_ccm::VirtualAES128CCM<'static, earlgrey::aes::Aes<'static>>, + >, +> = None; +// Test access to SipHash +static mut SIPHASH: Option<&capsules_extra::sip_hash::SipHasher24<'static>> = None; +// Test access to RSA +static mut RSA_HARDWARE: Option<&lowrisc::rsa::OtbnRsa<'static>> = None; + +// Test access to a software SHA256 +#[cfg(test)] +static mut SHA256SOFT: Option<&capsules_extra::sha256::Sha256Software<'static>> = None; + +static mut CHIP: Option<&'static earlgrey::chip::EarlGrey> = None; +static mut PROCESS_PRINTER: Option<&'static kernel::process::ProcessPrinterText> = None; + +// How should the kernel respond when a process faults. +const FAULT_RESPONSE: kernel::process::PanicFaultPolicy = kernel::process::PanicFaultPolicy {}; + +/// Dummy buffer that causes the linker to reserve enough space for the stack. +#[no_mangle] +#[link_section = ".stack_buffer"] +pub static mut STACK_MEMORY: [u8; 0x1400] = [0; 0x1400]; + +/// A structure representing this platform that holds references to all +/// capsules for this platform. We've included an alarm and console. +struct EarlGrey { + led: &'static capsules_core::led::LedDriver< + 'static, + LedHigh<'static, earlgrey::gpio::GpioPin<'static>>, + 8, + >, + gpio: &'static capsules_core::gpio::GPIO<'static, earlgrey::gpio::GpioPin<'static>>, + console: &'static capsules_core::console::Console<'static>, + alarm: &'static capsules_core::alarm::AlarmDriver< + 'static, + VirtualMuxAlarm<'static, earlgrey::timer::RvTimer<'static>>, + >, + hmac: &'static capsules_extra::hmac::HmacDriver<'static, lowrisc::hmac::Hmac<'static>, 32>, + lldb: &'static capsules_core::low_level_debug::LowLevelDebug< + 'static, + capsules_core::virtualizers::virtual_uart::UartDevice<'static>, + >, + i2c_master: + &'static capsules_core::i2c_master::I2CMasterDriver<'static, lowrisc::i2c::I2c<'static>>, + spi_controller: &'static capsules_core::spi_controller::Spi< + 'static, + capsules_core::virtualizers::virtual_spi::VirtualSpiMasterDevice< + 'static, + lowrisc::spi_host::SpiHost<'static>, + >, + >, + rng: &'static capsules_core::rng::RngDriver<'static>, + aes: &'static capsules_extra::symmetric_encryption::aes::AesDriver< + 'static, + aes_gcm::Aes128Gcm< + 'static, + virtual_aes_ccm::VirtualAES128CCM<'static, earlgrey::aes::Aes<'static>>, + >, + >, + kv_driver: &'static capsules_extra::kv_driver::KVStoreDriver< + 'static, + capsules_extra::tickv::TicKVStore< + 'static, + capsules_core::virtualizers::virtual_flash::FlashUser< + 'static, + lowrisc::flash_ctrl::FlashCtrl<'static>, + >, + capsules_extra::sip_hash::SipHasher24<'static>, + 2048, + >, + [u8; 8], + >, + syscall_filter: &'static TbfHeaderFilterDefaultAllow, + scheduler: &'static PrioritySched, + scheduler_timer: + &'static VirtualSchedulerTimer>>, + watchdog: &'static lowrisc::aon_timer::AonTimer, +} + +/// Mapping of integer syscalls to objects that implement syscalls. +impl SyscallDriverLookup for EarlGrey { + fn with_driver(&self, driver_num: usize, f: F) -> R + where + F: FnOnce(Option<&dyn kernel::syscall::SyscallDriver>) -> R, + { + match driver_num { + capsules_core::led::DRIVER_NUM => f(Some(self.led)), + capsules_extra::hmac::DRIVER_NUM => f(Some(self.hmac)), + capsules_core::gpio::DRIVER_NUM => f(Some(self.gpio)), + capsules_core::console::DRIVER_NUM => f(Some(self.console)), + capsules_core::alarm::DRIVER_NUM => f(Some(self.alarm)), + capsules_core::low_level_debug::DRIVER_NUM => f(Some(self.lldb)), + capsules_core::i2c_master::DRIVER_NUM => f(Some(self.i2c_master)), + capsules_core::spi_controller::DRIVER_NUM => f(Some(self.spi_controller)), + capsules_core::rng::DRIVER_NUM => f(Some(self.rng)), + capsules_extra::symmetric_encryption::aes::DRIVER_NUM => f(Some(self.aes)), + capsules_extra::kv_driver::DRIVER_NUM => f(Some(self.kv_driver)), + _ => f(None), + } + } +} + +impl KernelResources>> + for EarlGrey +{ + type SyscallDriverLookup = Self; + type SyscallFilter = TbfHeaderFilterDefaultAllow; + type ProcessFault = (); + type CredentialsCheckingPolicy = (); + type Scheduler = PrioritySched; + type SchedulerTimer = + VirtualSchedulerTimer>>; + type WatchDog = lowrisc::aon_timer::AonTimer; + type ContextSwitchCallback = (); + + fn syscall_driver_lookup(&self) -> &Self::SyscallDriverLookup { + &self + } + fn syscall_filter(&self) -> &Self::SyscallFilter { + &self.syscall_filter + } + fn process_fault(&self) -> &Self::ProcessFault { + &() + } + fn credentials_checking_policy(&self) -> &'static Self::CredentialsCheckingPolicy { + &() + } + fn scheduler(&self) -> &Self::Scheduler { + self.scheduler + } + fn scheduler_timer(&self) -> &Self::SchedulerTimer { + &self.scheduler_timer + } + fn watchdog(&self) -> &Self::WatchDog { + &self.watchdog + } + fn context_switch_callback(&self) -> &Self::ContextSwitchCallback { + &() + } +} + +unsafe fn setup() -> ( + &'static kernel::Kernel, + &'static EarlGrey, + &'static earlgrey::chip::EarlGrey<'static, EarlGreyDefaultPeripherals<'static>>, + &'static EarlGreyDefaultPeripherals<'static>, +) { + // Ibex-specific handler + earlgrey::chip::configure_trap_handler(); + + // initialize capabilities + let process_mgmt_cap = create_capability!(capabilities::ProcessManagementCapability); + let memory_allocation_cap = create_capability!(capabilities::MemoryAllocationCapability); + + let board_kernel = static_init!(kernel::Kernel, kernel::Kernel::new(&PROCESSES)); + + let peripherals = static_init!( + EarlGreyDefaultPeripherals, + EarlGreyDefaultPeripherals::new() + ); + peripherals.init(); + + // Configure kernel debug gpios as early as possible + kernel::debug::assign_gpios( + Some(&peripherals.gpio_port[7]), // First LED + None, + None, + ); + + // Create a shared UART channel for the console and for kernel debug. + let uart_mux = components::console::UartMuxComponent::new( + &peripherals.uart0, + earlgrey::uart::UART0_BAUDRATE, + ) + .finalize(components::uart_mux_component_static!()); + + // LEDs + // Start with half on and half off + let led = components::led::LedsComponent::new().finalize(components::led_component_static!( + LedHigh<'static, earlgrey::gpio::GpioPin>, + LedHigh::new(&peripherals.gpio_port[8]), + LedHigh::new(&peripherals.gpio_port[9]), + LedHigh::new(&peripherals.gpio_port[10]), + LedHigh::new(&peripherals.gpio_port[11]), + LedHigh::new(&peripherals.gpio_port[12]), + LedHigh::new(&peripherals.gpio_port[13]), + LedHigh::new(&peripherals.gpio_port[14]), + LedHigh::new(&peripherals.gpio_port[15]), + )); + + let gpio = components::gpio::GpioComponent::new( + board_kernel, + capsules_core::gpio::DRIVER_NUM, + components::gpio_component_helper!( + earlgrey::gpio::GpioPin, + 0 => &peripherals.gpio_port[0], + 1 => &peripherals.gpio_port[1], + 2 => &peripherals.gpio_port[2], + 3 => &peripherals.gpio_port[3], + 4 => &peripherals.gpio_port[4], + 5 => &peripherals.gpio_port[5], + 6 => &peripherals.gpio_port[6], + 7 => &peripherals.gpio_port[15] + ), + ) + .finalize(components::gpio_component_static!(earlgrey::gpio::GpioPin)); + + let hardware_alarm = static_init!(earlgrey::timer::RvTimer, earlgrey::timer::RvTimer::new()); + hardware_alarm.setup(); + + // Create a shared virtualization mux layer on top of a single hardware + // alarm. + let mux_alarm = static_init!( + MuxAlarm<'static, earlgrey::timer::RvTimer>, + MuxAlarm::new(hardware_alarm) + ); + hil::time::Alarm::set_alarm_client(hardware_alarm, mux_alarm); + + ALARM = Some(mux_alarm); + + // Alarm + let virtual_alarm_user = static_init!( + VirtualMuxAlarm<'static, earlgrey::timer::RvTimer>, + VirtualMuxAlarm::new(mux_alarm) + ); + virtual_alarm_user.setup(); + + let scheduler_timer_virtual_alarm = static_init!( + VirtualMuxAlarm<'static, earlgrey::timer::RvTimer>, + VirtualMuxAlarm::new(mux_alarm) + ); + scheduler_timer_virtual_alarm.setup(); + + let alarm = static_init!( + capsules_core::alarm::AlarmDriver< + 'static, + VirtualMuxAlarm<'static, earlgrey::timer::RvTimer>, + >, + capsules_core::alarm::AlarmDriver::new( + virtual_alarm_user, + board_kernel.create_grant(capsules_core::alarm::DRIVER_NUM, &memory_allocation_cap) + ) + ); + hil::time::Alarm::set_alarm_client(virtual_alarm_user, alarm); + + let scheduler_timer = static_init!( + VirtualSchedulerTimer>>, + VirtualSchedulerTimer::new(scheduler_timer_virtual_alarm) + ); + + let chip = static_init!( + earlgrey::chip::EarlGrey< + EarlGreyDefaultPeripherals, + >, + earlgrey::chip::EarlGrey::new(peripherals, hardware_alarm) + ); + CHIP = Some(chip); + + // 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::CLEAR + 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, + capsules_core::console::DRIVER_NUM, + uart_mux, + ) + .finalize(components::console_component_static!()); + // Create the debugger object that handles calls to `debug!()`. + components::debug_writer::DebugWriterComponent::new(uart_mux) + .finalize(components::debug_writer_component_static!()); + + let lldb = components::lldb::LowLevelDebugComponent::new( + board_kernel, + capsules_core::low_level_debug::DRIVER_NUM, + uart_mux, + ) + .finalize(components::low_level_debug_component_static!()); + + let hmac = components::hmac::HmacComponent::new( + board_kernel, + capsules_extra::hmac::DRIVER_NUM, + &peripherals.hmac, + ) + .finalize(components::hmac_component_static!(lowrisc::hmac::Hmac, 32)); + + let i2c_master_buffer = static_init!( + [u8; capsules_core::i2c_master::BUFFER_LENGTH], + [0; capsules_core::i2c_master::BUFFER_LENGTH] + ); + let i2c_master = static_init!( + capsules_core::i2c_master::I2CMasterDriver<'static, lowrisc::i2c::I2c<'static>>, + capsules_core::i2c_master::I2CMasterDriver::new( + &peripherals.i2c0, + i2c_master_buffer, + board_kernel.create_grant( + capsules_core::i2c_master::DRIVER_NUM, + &memory_allocation_cap + ) + ) + ); + + peripherals.i2c0.set_master_client(i2c_master); + + //SPI + let mux_spi = components::spi::SpiMuxComponent::new(&peripherals.spi_host0).finalize( + components::spi_mux_component_static!(lowrisc::spi_host::SpiHost), + ); + + let spi_controller = components::spi::SpiSyscallComponent::new( + board_kernel, + mux_spi, + 0, + capsules_core::spi_controller::DRIVER_NUM, + ) + .finalize(components::spi_syscall_component_static!( + lowrisc::spi_host::SpiHost + )); + + let process_printer = components::process_printer::ProcessPrinterTextComponent::new() + .finalize(components::process_printer_text_component_static!()); + PROCESS_PRINTER = Some(process_printer); + + // USB support is currently broken in the OpenTitan hardware + // See https://github.com/lowRISC/opentitan/issues/2598 for more details + // let usb = components::usb::UsbComponent::new( + // board_kernel, + // capsules_extra::usb::usb_user::DRIVER_NUM, + // &peripherals.usb, + // ) + // .finalize(components::usb_component_static!(earlgrey::usbdev::Usb)); + + // Kernel storage region, allocated with the storage_volume! + // macro in common/utils.rs + extern "C" { + /// Beginning on the ROM region containing app images. + static _sstorage: u8; + static _estorage: u8; + } + + // Flash setup memory protection for the ROM/Kernel + // Only allow reads for this region, any other ops will cause an MP fault + let mp_cfg = FlashMPConfig { + read_en: true, + write_en: false, + erase_en: false, + scramble_en: false, + ecc_en: false, + he_en: false, + }; + + // Allocate a flash protection region (associated cfg number: 0), for the code section. + if let Err(e) = peripherals.flash_ctrl.mp_set_region_perms( + &_manifest as *const u8 as usize, + &_etext as *const u8 as usize, + 0, + &mp_cfg, + ) { + debug!("Failed to set flash memory protection: {:?}", e); + } else { + // Lock region 0, until next system reset. + if let Err(e) = peripherals.flash_ctrl.mp_lock_region_cfg(0) { + debug!("Failed to lock memory protection config: {:?}", e); + } + } + + // Flash + let flash_ctrl_read_buf = static_init!( + [u8; lowrisc::flash_ctrl::PAGE_SIZE], + [0; lowrisc::flash_ctrl::PAGE_SIZE] + ); + let page_buffer = static_init!( + lowrisc::flash_ctrl::LowRiscPage, + lowrisc::flash_ctrl::LowRiscPage::default() + ); + + let mux_flash = components::flash::FlashMuxComponent::new(&peripherals.flash_ctrl).finalize( + components::flash_mux_component_static!(lowrisc::flash_ctrl::FlashCtrl), + ); + + // SipHash + let sip_hash = static_init!( + capsules_extra::sip_hash::SipHasher24, + capsules_extra::sip_hash::SipHasher24::new() + ); + kernel::deferred_call::DeferredCallClient::register(sip_hash); + SIPHASH = Some(sip_hash); + + // TicKV + let tickv = components::tickv::TicKVComponent::new( + sip_hash, + &mux_flash, // Flash controller + lowrisc::flash_ctrl::FLASH_PAGES_PER_BANK - 1, // Region offset (End of Bank0/Use Bank1) + // Region Size + lowrisc::flash_ctrl::FLASH_PAGES_PER_BANK * lowrisc::flash_ctrl::PAGE_SIZE, + flash_ctrl_read_buf, // Buffer used internally in TicKV + page_buffer, // Buffer used with the flash controller + ) + .finalize(components::tickv_component_static!( + lowrisc::flash_ctrl::FlashCtrl, + capsules_extra::sip_hash::SipHasher24, + 2048 + )); + hil::flash::HasClient::set_client(&peripherals.flash_ctrl, mux_flash); + sip_hash.set_client(tickv); + TICKV = Some(tickv); + + let mux_kv = components::kv_system::KVStoreMuxComponent::new(tickv).finalize( + components::kv_store_mux_component_static!( + capsules_extra::tickv::TicKVStore< + capsules_core::virtualizers::virtual_flash::FlashUser< + lowrisc::flash_ctrl::FlashCtrl, + >, + capsules_extra::sip_hash::SipHasher24<'static>, + 2048, + >, + capsules_extra::tickv::TicKVKeyType, + ), + ); + + let kv_store = components::kv_system::KVStoreComponent::new(mux_kv).finalize( + components::kv_store_component_static!( + capsules_extra::tickv::TicKVStore< + capsules_core::virtualizers::virtual_flash::FlashUser< + lowrisc::flash_ctrl::FlashCtrl, + >, + capsules_extra::sip_hash::SipHasher24<'static>, + 2048, + >, + capsules_extra::tickv::TicKVKeyType, + ), + ); + + let kv_driver = components::kv_system::KVDriverComponent::new( + kv_store, + board_kernel, + capsules_extra::kv_driver::DRIVER_NUM, + ) + .finalize(components::kv_driver_component_static!( + capsules_extra::tickv::TicKVStore< + capsules_core::virtualizers::virtual_flash::FlashUser, + capsules_extra::sip_hash::SipHasher24<'static>, + 2048, + >, + capsules_extra::tickv::TicKVKeyType, + )); + + let mux_otbn = crate::otbn::AccelMuxComponent::new(&peripherals.otbn) + .finalize(otbn_mux_component_static!()); + + let otbn = OtbnComponent::new(&mux_otbn).finalize(crate::otbn_component_static!()); + + let otbn_rsa_internal_buf = static_init!([u8; 512], [0; 512]); + + // Use the OTBN to create an RSA engine + if let Ok((rsa_imem_start, rsa_imem_length, rsa_dmem_start, rsa_dmem_length)) = + crate::otbn::find_app( + "otbn-rsa", + core::slice::from_raw_parts( + &_sapps as *const u8, + &_eapps as *const u8 as usize - &_sapps as *const u8 as usize, + ), + ) + { + let rsa_hardware = static_init!( + lowrisc::rsa::OtbnRsa<'static>, + lowrisc::rsa::OtbnRsa::new( + otbn, + lowrisc::rsa::AppAddresses { + imem_start: rsa_imem_start, + imem_size: rsa_imem_length, + dmem_start: rsa_dmem_start, + dmem_size: rsa_dmem_length + }, + otbn_rsa_internal_buf, + ) + ); + peripherals.otbn.set_client(rsa_hardware); + RSA_HARDWARE = Some(rsa_hardware); + } else { + debug!("Unable to find otbn-rsa, disabling RSA support"); + } + + // Convert hardware RNG to the Random interface. + let entropy_to_random = static_init!( + capsules_core::rng::Entropy32ToRandom<'static>, + capsules_core::rng::Entropy32ToRandom::new(&peripherals.rng) + ); + peripherals.rng.set_client(entropy_to_random); + // Setup RNG for userspace + let rng = static_init!( + capsules_core::rng::RngDriver<'static>, + capsules_core::rng::RngDriver::new( + entropy_to_random, + board_kernel.create_grant(capsules_core::rng::DRIVER_NUM, &memory_allocation_cap) + ) + ); + entropy_to_random.set_client(rng); + + const CRYPT_SIZE: usize = 7 * AES128_BLOCK_SIZE; + + let ccm_mux = static_init!( + virtual_aes_ccm::MuxAES128CCM<'static, earlgrey::aes::Aes<'static>>, + virtual_aes_ccm::MuxAES128CCM::new(&peripherals.aes) + ); + kernel::deferred_call::DeferredCallClient::register(ccm_mux); + peripherals.aes.set_client(ccm_mux); + + let ccm_client = components::aes::AesVirtualComponent::new(ccm_mux).finalize( + components::aes_virtual_component_static!(earlgrey::aes::Aes<'static>), + ); + + let crypt_buf2 = static_init!([u8; CRYPT_SIZE], [0x00; CRYPT_SIZE]); + let gcm_client = static_init!( + aes_gcm::Aes128Gcm< + 'static, + virtual_aes_ccm::VirtualAES128CCM<'static, earlgrey::aes::Aes<'static>>, + >, + aes_gcm::Aes128Gcm::new(ccm_client, crypt_buf2) + ); + ccm_client.set_client(gcm_client); + + let aes = components::aes::AesDriverComponent::new( + board_kernel, + capsules_extra::symmetric_encryption::aes::DRIVER_NUM, + gcm_client, + ) + .finalize(components::aes_driver_component_static!( + aes_gcm::Aes128Gcm< + 'static, + virtual_aes_ccm::VirtualAES128CCM<'static, earlgrey::aes::Aes<'static>>, + >, + )); + + AES = Some(gcm_client); + + #[cfg(test)] + { + use capsules_extra::sha256::Sha256Software; + + let sha_soft = static_init!(Sha256Software<'static>, Sha256Software::new()); + kernel::deferred_call::DeferredCallClient::register(sha_soft); + + SHA256SOFT = Some(sha_soft); + } + + hil::symmetric_encryption::AES128GCM::set_client(gcm_client, aes); + hil::symmetric_encryption::AES128::set_client(gcm_client, ccm_client); + + // 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; + /// The start of the kernel stack (Included only for kernel PMP) + static _sstack: u8; + /// The end of the kernel stack (Included only for kernel PMP) + static _estack: u8; + /// The start of the kernel text (Included only for kernel PMP) + static _stext: u8; + /// The end of the kernel text (Included only for kernel PMP) + static _etext: u8; + /// The start of the kernel relocation region + /// (Included only for kernel PMP) + static _srelocate: u8; + /// The end of the kernel relocation region + /// (Included only for kernel PMP) + static _erelocate: u8; + /// The start of the kernel BSS (Included only for kernel PMP) + static _szero: u8; + /// The end of the kernel BSS (Included only for kernel PMP) + static _ezero: u8; + /// The start of the OpenTitan manifest + static _manifest: u8; + } + + let syscall_filter = static_init!(TbfHeaderFilterDefaultAllow, TbfHeaderFilterDefaultAllow {}); + let scheduler = components::sched::priority::PriorityComponent::new(board_kernel) + .finalize(components::priority_component_static!()); + let watchdog = &peripherals.watchdog; + + let earlgrey = static_init!( + EarlGrey, + EarlGrey { + gpio, + led, + console, + alarm, + hmac, + rng, + lldb: lldb, + i2c_master, + spi_controller, + aes, + kv_driver, + syscall_filter, + scheduler, + scheduler_timer, + watchdog, + } + ); + + let mut mpu_config = rv32i::epmp::PMPConfig::kernel_default(); + + // The kernel stack, BSS and relocation data + chip.pmp + .allocate_kernel_region( + &_sstack as *const u8, + &_ezero as *const u8 as usize - &_sstack as *const u8 as usize, + mpu::Permissions::ReadWriteOnly, + &mut mpu_config, + ) + .unwrap(); + // The kernel text, Manifest and vectors + chip.pmp + .allocate_kernel_region( + &_manifest as *const u8, + &_etext as *const u8 as usize - &_manifest as *const u8 as usize, + mpu::Permissions::ReadExecuteOnly, + &mut mpu_config, + ) + .unwrap(); + // The app locations + chip.pmp.allocate_kernel_region( + &_sapps as *const u8, + &_eapps as *const u8 as usize - &_sapps as *const u8 as usize, + mpu::Permissions::ReadWriteOnly, + &mut mpu_config, + ); + // The app memory locations + chip.pmp.allocate_kernel_region( + &_sappmem as *const u8, + &_eappmem as *const u8 as usize - &_sappmem as *const u8 as usize, + mpu::Permissions::ReadWriteOnly, + &mut mpu_config, + ); + // Access to the MMIO devices + chip.pmp + .allocate_kernel_region( + 0x4000_0000 as *const u8, + 0x900_0000, + mpu::Permissions::ReadWriteOnly, + &mut mpu_config, + ) + .unwrap(); + + chip.pmp.enable_kernel_mpu(&mut mpu_config); + + kernel::process::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, + &FAULT_RESPONSE, + &process_mgmt_cap, + ) + .unwrap_or_else(|err| { + debug!("Error loading processes!"); + debug!("{:?}", err); + }); + debug!("OpenTitan (downstream) initialisation complete. Entering main loop"); + + (board_kernel, earlgrey, chip, peripherals) +} + +/// Main function. +/// +/// This function is called from the arch crate after some very basic RISC-V +/// setup and RAM initialization. +#[no_mangle] +pub unsafe fn main() { + #[cfg(test)] + test_main(); + + #[cfg(not(test))] + { + let (board_kernel, earlgrey, chip, _peripherals) = setup(); + + let main_loop_cap = create_capability!(capabilities::MainLoopCapability); + + board_kernel.kernel_loop(earlgrey, chip, None::<&kernel::ipc::IPC<0>>, &main_loop_cap); + } +} + +#[cfg(test)] +use kernel::platform::watchdog::WatchDog; + +#[cfg(test)] +fn test_runner(tests: &[&dyn Fn()]) { + unsafe { + let (board_kernel, earlgrey, _chip, peripherals) = setup(); + + BOARD = Some(board_kernel); + PLATFORM = Some(&earlgrey); + PERIPHERALS = Some(peripherals); + MAIN_CAP = Some(&create_capability!(capabilities::MainLoopCapability)); + + PLATFORM.map(|p| { + p.watchdog().setup(); + }); + + for test in tests { + test(); + } + } + + // Exit QEMU with a return code of 0 + crate::tests::semihost_command_exit_success() +} diff --git a/sw/device/silicon_owner/tock/kernel/src/otbn.rs b/sw/device/silicon_owner/tock/kernel/src/otbn.rs new file mode 100644 index 0000000000000..ecbcab10c87ed --- /dev/null +++ b/sw/device/silicon_owner/tock/kernel/src/otbn.rs @@ -0,0 +1,184 @@ +// Copyright lowRISC contributors. +// Licensed under the Apache License, Version 2.0, see LICENSE for details. +// SPDX-License-Identifier: Apache-2.0 + +//! Components for collections of Hardware Accelerators. +//! +//! Usage +//! ----- +//! ```rust +//! let _mux_otbn = crate::otbn::AccelMuxComponent::new(&peripherals.otbn) +//! .finalize(otbn_mux_component_static!()); +//! +//! peripherals.otbn.initialise( +//! dynamic_deferred_caller +//! .register(&peripherals.otbn) +//! .unwrap(), // Unwrap fail = dynamic deferred caller out of slots +//! ); +//! ``` + +use core::mem::MaybeUninit; +use kernel::component::Component; +use lowrisc::otbn::Otbn; +use lowrisc::virtual_otbn::{MuxAccel, VirtualMuxAccel}; + +#[macro_export] +macro_rules! otbn_mux_component_static { + () => {{ + kernel::static_buf!(lowrisc::virtual_otbn::MuxAccel<'static>) + }}; +} + +#[macro_export] +macro_rules! otbn_component_static { + () => {{ + kernel::static_buf!(lowrisc::virtual_otbn::VirtualMuxAccel<'static>) + }}; +} + +pub struct AccelMuxComponent { + otbn: &'static Otbn<'static>, +} + +impl AccelMuxComponent { + pub fn new(otbn: &'static Otbn<'static>) -> AccelMuxComponent { + AccelMuxComponent { otbn } + } +} + +impl Component for AccelMuxComponent { + type StaticInput = &'static mut MaybeUninit>; + type Output = &'static MuxAccel<'static>; + + fn finalize(self, s: Self::StaticInput) -> Self::Output { + s.write(MuxAccel::new(self.otbn)) + } +} + +pub struct OtbnComponent { + mux_otbn: &'static MuxAccel<'static>, +} + +impl OtbnComponent { + pub fn new(mux_otbn: &'static MuxAccel<'static>) -> OtbnComponent { + OtbnComponent { mux_otbn } + } +} + +impl Component for OtbnComponent { + type StaticInput = &'static mut MaybeUninit>; + + type Output = &'static VirtualMuxAccel<'static>; + + fn finalize(self, s: Self::StaticInput) -> Self::Output { + let virtual_otbn_user = s.write(VirtualMuxAccel::new(self.mux_otbn)); + + virtual_otbn_user + } +} + +/// Find the OTBN app in the Tock process list +/// +/// This will iterate through the app list inside the `app_flash` looking +/// for a disabled app with the same name as `name`. +/// On success this function will return the following information: +/// * OTBN imem start address +/// * OTBN imem size +/// * OTBN dmem start address +/// * OTBN dmem size +/// +/// This function is based on the Tock process loading code +#[allow(dead_code)] +pub fn find_app(name: &str, app_flash: &'static [u8]) -> Result<(usize, usize, usize, usize), ()> { + let mut remaining_flash = app_flash; + + loop { + // Get the first eight bytes of flash to check if there is another + // app. + let test_header_slice = match remaining_flash.get(0..8) { + Some(s) => s, + None => { + // Not enough flash to test for another app. This just means + // we are at the end of flash, and there are no more apps to + // load. + return Err(()); + } + }; + + // Pass the first eight bytes to tbfheader to parse out the length of + // the tbf header and app. We then use those values to see if we have + // enough flash remaining to parse the remainder of the header. + let (version, header_length, entry_length) = match tock_tbf::parse::parse_tbf_header_lengths( + test_header_slice.try_into().or(Err(()))?, + ) { + Ok((v, hl, el)) => (v, hl, el), + Err(tock_tbf::types::InitialTbfParseError::InvalidHeader(entry_length)) => { + // If we could not parse the header, then we want to skip over + // this app and look for the next one. + (0, 0, entry_length) + } + Err(tock_tbf::types::InitialTbfParseError::UnableToParse) => { + // Since Tock apps use a linked list, it is very possible the + // header we started to parse is intentionally invalid to signal + // the end of apps. This is ok and just means we have finished + // loading apps. + return Err(()); + } + }; + + // Now we can get a slice which only encompasses the length of flash + // described by this tbf header. We will either parse this as an actual + // app, or skip over this region. + let entry_flash = remaining_flash.get(0..entry_length as usize).ok_or(())?; + + // Advance the flash slice for process discovery beyond this last entry. + // This will be the start of where we look for a new process since Tock + // processes are allocated back-to-back in flash. + remaining_flash = remaining_flash.get(entry_flash.len()..).ok_or(())?; + + if header_length > 0 { + // If we found an actual app header, try to create a `Process` + // object. We also need to shrink the amount of remaining memory + // based on whatever is assigned to the new process if one is + // created. + + // Get a slice for just the app header. + let header_flash = entry_flash.get(0..header_length as usize).ok_or(())?; + + // Parse the full TBF header to see if this is a valid app. If the + // header can't parse, we will error right here. + if let Ok(tbf_header) = tock_tbf::parse::parse_tbf_header(header_flash, version) { + let process_name = tbf_header.get_package_name().unwrap(); + + // If the app is enabled, it's a real app and not what we are looking for. + if tbf_header.enabled() { + continue; + } + + if name != process_name { + continue; + } + + let dmem_length = tbf_header.get_minimum_app_ram_size(); + + let imem_start = + unsafe { entry_flash.as_ptr().offset(header_length as isize) as usize }; + let imem_length = entry_length - dmem_length - header_length as u32 - 4; + + let dmem_start = unsafe { + entry_flash + .as_ptr() + .offset(header_length as isize + imem_length as isize) + as usize + }; + + return Ok(( + imem_start, + imem_length as usize, + dmem_start, + dmem_length as usize, + )); + } + }; + } +}