Refactor tutorial 09

pull/51/head
Andre Richter 4 years ago
parent 353cc4b6d5
commit 7e583dc923
No known key found for this signature in database
GPG Key ID: 2116C1AB102F615E

@ -21,7 +21,7 @@ ifeq ($(BSP),rpi3)
QEMU_RELEASE_ARGS = -serial stdio -display none QEMU_RELEASE_ARGS = -serial stdio -display none
OPENOCD_ARG = -f /openocd/tcl/interface/ftdi/olimex-arm-usb-tiny-h.cfg -f /openocd/rpi3.cfg OPENOCD_ARG = -f /openocd/tcl/interface/ftdi/olimex-arm-usb-tiny-h.cfg -f /openocd/rpi3.cfg
JTAG_BOOT_IMAGE = jtag_boot_rpi3.img JTAG_BOOT_IMAGE = jtag_boot_rpi3.img
LINKER_FILE = src/bsp/rpi/link.ld LINKER_FILE = src/bsp/raspberrypi/link.ld
RUSTC_MISC_ARGS = -C target-cpu=cortex-a53 RUSTC_MISC_ARGS = -C target-cpu=cortex-a53
else ifeq ($(BSP),rpi4) else ifeq ($(BSP),rpi4)
TARGET = aarch64-unknown-none-softfloat TARGET = aarch64-unknown-none-softfloat
@ -31,7 +31,7 @@ else ifeq ($(BSP),rpi4)
# QEMU_RELEASE_ARGS = -serial stdio -display none # QEMU_RELEASE_ARGS = -serial stdio -display none
OPENOCD_ARG = -f /openocd/tcl/interface/ftdi/olimex-arm-usb-tiny-h.cfg -f /openocd/rpi4.cfg OPENOCD_ARG = -f /openocd/tcl/interface/ftdi/olimex-arm-usb-tiny-h.cfg -f /openocd/rpi4.cfg
JTAG_BOOT_IMAGE = jtag_boot_rpi4.img JTAG_BOOT_IMAGE = jtag_boot_rpi4.img
LINKER_FILE = src/bsp/rpi/link.ld LINKER_FILE = src/bsp/raspberrypi/link.ld
RUSTC_MISC_ARGS = -C target-cpu=cortex-a72 RUSTC_MISC_ARGS = -C target-cpu=cortex-a72
endif endif
@ -74,8 +74,7 @@ $(OUTPUT): $(CARGO_OUTPUT)
$(OBJCOPY_CMD) $< $(OUTPUT) $(OBJCOPY_CMD) $< $(OUTPUT)
doc: doc:
cargo xdoc --target=$(TARGET) --features bsp_$(BSP) --document-private-items cargo xdoc --target=$(TARGET) --features bsp_$(BSP) --document-private-items --open
xdg-open target/$(TARGET)/doc/kernel/index.html
ifeq ($(QEMU_MACHINE_TYPE),) ifeq ($(QEMU_MACHINE_TYPE),)
qemu: qemu:

@ -61,12 +61,12 @@ enable_jtag_gpio=1
## Hardware Setup ## Hardware Setup
Unlike microcontroller boards like the `STM32F3DISCOVERY`, which is used in our WG's [Embedded Rust Unlike microcontroller boards like the `STM32F3DISCOVERY`, which is used in our WG's [Embedded Rust
Book](https://rust-embedded.github.io/book/start/hardware.html), the Raspberry Pi does not have an Book], the Raspberry Pi does not have an embedded debugger on its board. Hence, you need to buy one.
embedded debugger on its board. Hence, you need to buy one.
For this tutorial, we will use the [ARM-USB-TINY-H] from OLIMEX. It has a standard [ARM JTAG 20 For this tutorial, we will use the [ARM-USB-TINY-H] from OLIMEX. It has a standard [ARM JTAG 20
connector]. Unfortunately, the RPi does not, so we have to connect it via jumper wires. connector]. Unfortunately, the RPi does not, so we have to connect it via jumper wires.
[Embedded Rust Book]: https://rust-embedded.github.io/book/start/hardware.html
[ARM-USB-TINY-H]: https://www.olimex.com/Products/ARM/JTAG/ARM-USB-TINY-H [ARM-USB-TINY-H]: https://www.olimex.com/Products/ARM/JTAG/ARM-USB-TINY-H
[ARM JTAG 20 connector]: http://infocenter.arm.com/help/index.jsp?topic=/com.arm.doc.dui0499dj/BEHEIHCE.html [ARM JTAG 20 connector]: http://infocenter.arm.com/help/index.jsp?topic=/com.arm.doc.dui0499dj/BEHEIHCE.html
@ -147,11 +147,13 @@ over `JTAG`. Therefore, we add a new `Makefile` target, `make jtagboot`, which
uses the `chainboot` approach to load a tiny helper binary onto the RPi that uses the `chainboot` approach to load a tiny helper binary onto the RPi that
just parks the executing core into a waiting state. just parks the executing core into a waiting state.
The helper binary is maintained separately in this repository's [X1_JTAG_boot](../X1_JTAG_boot) The helper binary is maintained separately in this repository's [X1_JTAG_boot] folder, and is a
folder, and is a modified version of the kernel we used in our tutorials so far. modified version of the kernel we used in our tutorials so far.
[X1_JTAG_boot]: ../X1_JTAG_boot
```console ```console
» make jtagboot $ make jtagboot
Minipush 1.0 Minipush 1.0
[MP] ⏳ Waiting for /dev/ttyUSB0 [MP] ⏳ Waiting for /dev/ttyUSB0
@ -175,18 +177,21 @@ running. When we load the actual kernel later, `UART` output will appear here.
## OpenOCD ## OpenOCD
Next, we need to launch the [Open On-Chip Debugger](http://openocd.org/), aka `OpenOCD` to actually Next, we need to launch the [Open On-Chip Debugger], aka `OpenOCD` to actually connect the `JTAG`.
connect the `JTAG`.
[Open On-Chip Debugger]: http://openocd.org
As always, our tutorials try to be as painless as possible regarding dev-tools, which is why we have As always, our tutorials try to be as painless as possible regarding dev-tools, which is why we have
packaged everything into the [dedicated Docker container](../docker/rustembedded-osdev-utils) that packaged everything into the [dedicated Docker container] that is already used for chainbooting and
is already used for chainbooting and `QEMU`. `QEMU`.
[dedicated Docker container]: ../docker/rustembedded-osdev-utils
Connect the Olimex USB JTAG debugger, open a new terminal and in the same folder, type `make Connect the Olimex USB JTAG debugger, open a new terminal and in the same folder, type `make
openocd` (in that order!). You will see some initial output: openocd` (in that order!). You will see some initial output:
```console ```console
make openocd $ make openocd
[...] [...]
Open On-Chip Debugger 0.10.0 Open On-Chip Debugger 0.10.0
[...] [...]
@ -297,71 +302,3 @@ runs, while keeping the debugger connected.
Thanks to [@naotaco](https://github.com/naotaco) for laying the groundwork for this tutorial. Thanks to [@naotaco](https://github.com/naotaco) for laying the groundwork for this tutorial.
## Diff to previous ## Diff to previous
```diff
diff -uNr 08_timestamps/Makefile 09_hw_debug_JTAG/Makefile
--- 08_timestamps/Makefile
+++ 09_hw_debug_JTAG/Makefile
@@ -19,6 +19,8 @@
QEMU_BINARY = qemu-system-aarch64
QEMU_MACHINE_TYPE = raspi3
QEMU_RELEASE_ARGS = -serial stdio -display none
+ OPENOCD_ARG = -f /openocd/tcl/interface/ftdi/olimex-arm-usb-tiny-h.cfg -f /openocd/rpi3.cfg
+ JTAG_BOOT_IMAGE = jtag_boot_rpi3.img
LINKER_FILE = src/bsp/rpi/link.ld
RUSTC_MISC_ARGS = -C target-cpu=cortex-a53
else ifeq ($(BSP),rpi4)
@@ -27,6 +29,8 @@
# QEMU_BINARY = qemu-system-aarch64
# QEMU_MACHINE_TYPE =
# QEMU_RELEASE_ARGS = -serial stdio -display none
+ OPENOCD_ARG = -f /openocd/tcl/interface/ftdi/olimex-arm-usb-tiny-h.cfg -f /openocd/rpi4.cfg
+ JTAG_BOOT_IMAGE = jtag_boot_rpi4.img
LINKER_FILE = src/bsp/rpi/link.ld
RUSTC_MISC_ARGS = -C target-cpu=cortex-a72
endif
@@ -52,11 +56,13 @@
DOCKER_CMD = docker run -it --rm
DOCKER_ARG_DIR_TUT = -v $(shell pwd):/work -w /work
DOCKER_ARG_DIR_UTILS = -v $(shell pwd)/../utils:/utils
+DOCKER_ARG_DIR_JTAG = -v $(shell pwd)/../X1_JTAG_boot:/jtag
DOCKER_ARG_TTY = --privileged -v /dev:/dev
+DOCKER_ARG_NET = --network host
DOCKER_EXEC_QEMU = $(QEMU_BINARY) -M $(QEMU_MACHINE_TYPE)
DOCKER_EXEC_MINIPUSH = ruby /utils/minipush.rb
-.PHONY: all doc qemu chainboot clippy clean readelf objdump nm
+.PHONY: all doc qemu chainboot jtagboot openocd gdb gdb-opt0 clippy clean readelf objdump nm
all: clean $(OUTPUT)
@@ -86,6 +92,28 @@
$(DOCKER_IMAGE) $(DOCKER_EXEC_MINIPUSH) $(DEV_SERIAL) \
$(OUTPUT)
+jtagboot:
+ @$(DOCKER_CMD) $(DOCKER_ARG_DIR_JTAG) $(DOCKER_ARG_DIR_UTILS) $(DOCKER_ARG_TTY) \
+ $(DOCKER_IMAGE) $(DOCKER_EXEC_MINIPUSH) $(DEV_SERIAL) \
+ /jtag/$(JTAG_BOOT_IMAGE)
+
+openocd:
+ @$(DOCKER_CMD) $(DOCKER_ARG_TTY) $(DOCKER_ARG_NET) $(DOCKER_IMAGE) \
+ openocd $(OPENOCD_ARG)
+
+define gen_gdb
+ RUSTFLAGS="$(RUSTFLAGS_PEDANTIC) $1" $(XRUSTC_CMD)
+ cp $(CARGO_OUTPUT) kernel_for_jtag
+ @$(DOCKER_CMD) $(DOCKER_ARG_DIR_TUT) $(DOCKER_ARG_NET) $(DOCKER_IMAGE) \
+ gdb-multiarch -q kernel_for_jtag
+endef
+
+gdb: clean $(SOURCES)
+ $(call gen_gdb,-C debuginfo=2)
+
+gdb-opt0: clean $(SOURCES)
+ $(call gen_gdb,-C debuginfo=2 -C opt-level=0)
+
clippy:
RUSTFLAGS="$(RUSTFLAGS_PEDANTIC)" cargo xclippy --target=$(TARGET) --features bsp_$(BSP)
```

Binary file not shown.

Binary file not shown.

@ -2,14 +2,15 @@
// //
// Copyright (c) 2018-2020 Andre Richter <andre.o.richter@gmail.com> // Copyright (c) 2018-2020 Andre Richter <andre.o.richter@gmail.com>
//! AArch64. //! Architectural processor code.
pub mod sync; use crate::{bsp, cpu};
mod time;
use crate::{bsp, interface};
use cortex_a::{asm, regs::*}; use cortex_a::{asm, regs::*};
//--------------------------------------------------------------------------------------------------
// Boot Code
//--------------------------------------------------------------------------------------------------
/// The entry of the `kernel` binary. /// The entry of the `kernel` binary.
/// ///
/// The function must be named `_start`, because the linker is looking for this exact name. /// The function must be named `_start`, because the linker is looking for this exact name.
@ -17,13 +18,15 @@ use cortex_a::{asm, regs::*};
/// # Safety /// # Safety
/// ///
/// - Linker script must ensure to place this function at `0x80_000`. /// - Linker script must ensure to place this function at `0x80_000`.
#[naked]
#[no_mangle] #[no_mangle]
pub unsafe extern "C" fn _start() -> ! { pub unsafe extern "C" fn _start() -> ! {
const CORE_MASK: u64 = 0x3; use crate::runtime_init;
if bsp::BOOT_CORE_ID == MPIDR_EL1.get() & CORE_MASK { // Expect the boot core to start in EL2.
SP.set(bsp::BOOT_CORE_STACK_START); if bsp::cpu::BOOT_CORE_ID == cpu::smp::core_id() {
crate::runtime_init::runtime_init() SP.set(bsp::cpu::BOOT_CORE_STACK_START);
runtime_init::runtime_init()
} else { } else {
// If not core0, infinitely wait for events. // If not core0, infinitely wait for events.
wait_forever() wait_forever()
@ -31,30 +34,20 @@ pub unsafe extern "C" fn _start() -> ! {
} }
//-------------------------------------------------------------------------------------------------- //--------------------------------------------------------------------------------------------------
// Global instances // Public Code
//--------------------------------------------------------------------------------------------------
static TIMER: time::Timer = time::Timer;
//--------------------------------------------------------------------------------------------------
// Implementation of the kernel's architecture abstraction code
//-------------------------------------------------------------------------------------------------- //--------------------------------------------------------------------------------------------------
pub use asm::nop; pub use asm::nop;
/// Spin for `n` cycles. /// Spin for `n` cycles.
#[inline(always)]
pub fn spin_for_cycles(n: usize) { pub fn spin_for_cycles(n: usize) {
for _ in 0..n { for _ in 0..n {
asm::nop(); asm::nop();
} }
} }
/// Return a reference to a `interface::time::TimeKeeper` implementation. /// Pause execution on the core.
pub fn timer() -> &'static impl interface::time::Timer {
&TIMER
}
/// Pause execution on the calling CPU core.
#[inline(always)] #[inline(always)]
pub fn wait_forever() -> ! { pub fn wait_forever() -> ! {
loop { loop {

@ -0,0 +1,22 @@
// SPDX-License-Identifier: MIT OR Apache-2.0
//
// Copyright (c) 2018-2020 Andre Richter <andre.o.richter@gmail.com>
//! Architectural symmetric multiprocessing.
use cortex_a::regs::*;
//--------------------------------------------------------------------------------------------------
// Public Code
//--------------------------------------------------------------------------------------------------
/// Return the executing core's id.
#[inline(always)]
pub fn core_id<T>() -> T
where
T: From<u8>,
{
const CORE_MASK: u64 = 0b11;
T::from((MPIDR_EL1.get() & CORE_MASK) as u8)
}

@ -2,25 +2,45 @@
// //
// Copyright (c) 2018-2020 Andre Richter <andre.o.richter@gmail.com> // Copyright (c) 2018-2020 Andre Richter <andre.o.richter@gmail.com>
//! Timer primitives. //! Architectural timer primitives.
use crate::{interface, warn}; use crate::{time, warn};
use core::time::Duration; use core::time::Duration;
use cortex_a::regs::*; use cortex_a::regs::*;
//--------------------------------------------------------------------------------------------------
// Private Definitions
//--------------------------------------------------------------------------------------------------
const NS_PER_S: u64 = 1_000_000_000; const NS_PER_S: u64 = 1_000_000_000;
//-------------------------------------------------------------------------------------------------- //--------------------------------------------------------------------------------------------------
// Arch-public // Public Definitions
//--------------------------------------------------------------------------------------------------
/// ARMv8 Generic Timer.
pub struct GenericTimer;
//--------------------------------------------------------------------------------------------------
// Global instances
//-------------------------------------------------------------------------------------------------- //--------------------------------------------------------------------------------------------------
pub struct Timer; static TIME_MANAGER: GenericTimer = GenericTimer;
//-------------------------------------------------------------------------------------------------- //--------------------------------------------------------------------------------------------------
// OS interface implementations // Public Code
//-------------------------------------------------------------------------------------------------- //--------------------------------------------------------------------------------------------------
impl interface::time::Timer for Timer { /// Return a reference to the time manager.
pub fn time_manager() -> &'static impl time::interface::TimeManager {
&TIME_MANAGER
}
//------------------------------------------------------------------------------
// OS Interface Code
//------------------------------------------------------------------------------
impl time::interface::TimeManager for GenericTimer {
fn resolution(&self) -> Duration { fn resolution(&self) -> Duration {
Duration::from_nanos(NS_PER_S / (CNTFRQ_EL0.get() as u64)) Duration::from_nanos(NS_PER_S / (CNTFRQ_EL0.get() as u64))
} }

@ -1,11 +0,0 @@
// SPDX-License-Identifier: MIT OR Apache-2.0
//
// Copyright (c) 2018-2020 Andre Richter <andre.o.richter@gmail.com>
//! Conditional exporting of processor architecture code.
#[cfg(any(feature = "bsp_rpi3", feature = "bsp_rpi4"))]
mod aarch64;
#[cfg(any(feature = "bsp_rpi3", feature = "bsp_rpi4"))]
pub use aarch64::*;

@ -1,53 +0,0 @@
// SPDX-License-Identifier: MIT OR Apache-2.0
//
// Copyright (c) 2018-2020 Andre Richter <andre.o.richter@gmail.com>
//! Synchronization primitives.
use crate::interface;
use core::cell::UnsafeCell;
//--------------------------------------------------------------------------------------------------
// Arch-public
//--------------------------------------------------------------------------------------------------
/// A pseudo-lock for teaching purposes.
///
/// Used to introduce [interior mutability].
///
/// In contrast to a real Mutex implementation, does not protect against concurrent access to the
/// contained data. This part is preserved for later lessons.
///
/// The lock will only be used as long as it is safe to do so, i.e. as long as the kernel is
/// executing single-threaded, aka only running on a single core with interrupts disabled.
///
/// [interior mutability]: https://doc.rust-lang.org/std/cell/index.html
pub struct NullLock<T: ?Sized> {
data: UnsafeCell<T>,
}
unsafe impl<T: ?Sized + Send> Send for NullLock<T> {}
unsafe impl<T: ?Sized + Send> Sync for NullLock<T> {}
impl<T> NullLock<T> {
/// Wraps `data` into a new `NullLock`.
pub const fn new(data: T) -> NullLock<T> {
NullLock {
data: UnsafeCell::new(data),
}
}
}
//--------------------------------------------------------------------------------------------------
// OS interface implementations
//--------------------------------------------------------------------------------------------------
impl<T> interface::sync::Mutex for &NullLock<T> {
type Data = T;
fn lock<R>(&mut self, f: impl FnOnce(&mut Self::Data) -> R) -> R {
// In a real lock, there would be code encapsulating this line that ensures that this
// mutable reference will ever only be given out once at a time.
f(unsafe { &mut *self.data.get() })
}
}

@ -2,12 +2,12 @@
// //
// Copyright (c) 2018-2020 Andre Richter <andre.o.richter@gmail.com> // Copyright (c) 2018-2020 Andre Richter <andre.o.richter@gmail.com>
//! Conditional exporting of Board Support Packages. //! Conditional re-exporting of Board Support Packages.
mod driver; mod device_driver;
#[cfg(any(feature = "bsp_rpi3", feature = "bsp_rpi4"))] #[cfg(any(feature = "bsp_rpi3", feature = "bsp_rpi4"))]
mod rpi; mod raspberrypi;
#[cfg(any(feature = "bsp_rpi3", feature = "bsp_rpi4"))] #[cfg(any(feature = "bsp_rpi3", feature = "bsp_rpi4"))]
pub use rpi::*; pub use raspberrypi::*;

@ -2,7 +2,7 @@
// //
// Copyright (c) 2018-2020 Andre Richter <andre.o.richter@gmail.com> // Copyright (c) 2018-2020 Andre Richter <andre.o.richter@gmail.com>
//! Drivers. //! Device driver.
#[cfg(any(feature = "bsp_rpi3", feature = "bsp_rpi4"))] #[cfg(any(feature = "bsp_rpi3", feature = "bsp_rpi4"))]
mod bcm; mod bcm;

@ -7,5 +7,5 @@
mod bcm2xxx_gpio; mod bcm2xxx_gpio;
mod bcm2xxx_pl011_uart; mod bcm2xxx_pl011_uart;
pub use bcm2xxx_gpio::GPIO; pub use bcm2xxx_gpio::*;
pub use bcm2xxx_pl011_uart::{PL011Uart, PanicUart}; pub use bcm2xxx_pl011_uart::*;

@ -2,11 +2,15 @@
// //
// Copyright (c) 2018-2020 Andre Richter <andre.o.richter@gmail.com> // Copyright (c) 2018-2020 Andre Richter <andre.o.richter@gmail.com>
//! GPIO driver. //! GPIO Driver.
use crate::{arch, arch::sync::NullLock, interface}; use crate::{cpu, driver, synchronization, synchronization::NullLock};
use core::ops; use core::ops;
use register::{mmio::ReadWrite, register_bitfields, register_structs}; use register::{mmio::*, register_bitfields, register_structs};
//--------------------------------------------------------------------------------------------------
// Private Definitions
//--------------------------------------------------------------------------------------------------
// GPIO registers. // GPIO registers.
// //
@ -66,12 +70,23 @@ register_structs! {
} }
} }
/// The driver's private data.
struct GPIOInner { struct GPIOInner {
base_addr: usize, base_addr: usize,
} }
/// Deref to RegisterBlock. //--------------------------------------------------------------------------------------------------
// Public Definitions
//--------------------------------------------------------------------------------------------------
/// Representation of the GPIO HW.
pub struct GPIO {
inner: NullLock<GPIOInner>,
}
//--------------------------------------------------------------------------------------------------
// Private Code
//--------------------------------------------------------------------------------------------------
impl ops::Deref for GPIOInner { impl ops::Deref for GPIOInner {
type Target = RegisterBlock; type Target = RegisterBlock;
@ -81,29 +96,28 @@ impl ops::Deref for GPIOInner {
} }
impl GPIOInner { impl GPIOInner {
const fn new(base_addr: usize) -> GPIOInner { const fn new(base_addr: usize) -> Self {
GPIOInner { base_addr } Self { base_addr }
} }
/// Return a pointer to the register block. /// Return a pointer to the associated MMIO register block.
fn ptr(&self) -> *const RegisterBlock { fn ptr(&self) -> *const RegisterBlock {
self.base_addr as *const _ self.base_addr as *const _
} }
} }
//-------------------------------------------------------------------------------------------------- //--------------------------------------------------------------------------------------------------
// BSP-public // Public Code
//-------------------------------------------------------------------------------------------------- //--------------------------------------------------------------------------------------------------
use interface::sync::Mutex;
/// The driver's main struct.
pub struct GPIO {
inner: NullLock<GPIOInner>,
}
impl GPIO { impl GPIO {
pub const unsafe fn new(base_addr: usize) -> GPIO { /// Create an instance.
GPIO { ///
/// # Safety
///
/// - The user must ensure to provide the correct `base_addr`.
pub const unsafe fn new(base_addr: usize) -> Self {
Self {
inner: NullLock::new(GPIOInner::new(base_addr)), inner: NullLock::new(GPIOInner::new(base_addr)),
} }
} }
@ -122,24 +136,25 @@ impl GPIO {
// Enable pins 14 and 15. // Enable pins 14 and 15.
inner.GPPUD.set(0); inner.GPPUD.set(0);
arch::spin_for_cycles(150); cpu::spin_for_cycles(150);
inner inner
.GPPUDCLK0 .GPPUDCLK0
.write(GPPUDCLK0::PUDCLK14::AssertClock + GPPUDCLK0::PUDCLK15::AssertClock); .write(GPPUDCLK0::PUDCLK14::AssertClock + GPPUDCLK0::PUDCLK15::AssertClock);
arch::spin_for_cycles(150); cpu::spin_for_cycles(150);
inner.GPPUDCLK0.set(0); inner.GPPUDCLK0.set(0);
}) })
} }
} }
//-------------------------------------------------------------------------------------------------- //------------------------------------------------------------------------------
// OS interface implementations // OS Interface Code
//-------------------------------------------------------------------------------------------------- //------------------------------------------------------------------------------
use synchronization::interface::Mutex;
impl interface::driver::DeviceDriver for GPIO { impl driver::interface::DeviceDriver for GPIO {
fn compatible(&self) -> &str { fn compatible(&self) -> &str {
"GPIO" "BCM GPIO"
} }
} }

@ -4,10 +4,14 @@
//! PL011 UART driver. //! PL011 UART driver.
use crate::{arch, arch::sync::NullLock, interface}; use crate::{console, cpu, driver, synchronization, synchronization::NullLock};
use core::{fmt, ops}; use core::{fmt, ops};
use register::{mmio::*, register_bitfields, register_structs}; use register::{mmio::*, register_bitfields, register_structs};
//--------------------------------------------------------------------------------------------------
// Private Definitions
//--------------------------------------------------------------------------------------------------
// PL011 UART registers. // PL011 UART registers.
// //
// Descriptions taken from // Descriptions taken from
@ -109,6 +113,10 @@ register_bitfields! {
] ]
} }
//--------------------------------------------------------------------------------------------------
// Public Definitions
//--------------------------------------------------------------------------------------------------
register_structs! { register_structs! {
#[allow(non_snake_case)] #[allow(non_snake_case)]
pub RegisterBlock { pub RegisterBlock {
@ -126,13 +134,24 @@ register_structs! {
} }
} }
/// The driver's mutex protected part.
pub struct PL011UartInner { pub struct PL011UartInner {
base_addr: usize, base_addr: usize,
chars_written: usize, chars_written: usize,
chars_read: usize, chars_read: usize,
} }
// Export the inner struct so that BSPs can use it for the panic handler.
pub use PL011UartInner as PanicUart;
/// Representation of the UART.
pub struct PL011Uart {
inner: NullLock<PL011UartInner>,
}
//--------------------------------------------------------------------------------------------------
// Public Code
//--------------------------------------------------------------------------------------------------
/// Deref to RegisterBlock. /// Deref to RegisterBlock.
/// ///
/// Allows writing /// Allows writing
@ -152,8 +171,13 @@ impl ops::Deref for PL011UartInner {
} }
impl PL011UartInner { impl PL011UartInner {
pub const unsafe fn new(base_addr: usize) -> PL011UartInner { /// Create an instance.
PL011UartInner { ///
/// # Safety
///
/// - The user must ensure to provide the correct `base_addr`.
pub const unsafe fn new(base_addr: usize) -> Self {
Self {
base_addr, base_addr,
chars_written: 0, chars_written: 0,
chars_read: 0, chars_read: 0,
@ -164,7 +188,7 @@ impl PL011UartInner {
/// ///
/// Results in 8N1 and 230400 baud (if the clk has been previously set to 48 MHz by the /// Results in 8N1 and 230400 baud (if the clk has been previously set to 48 MHz by the
/// firmware). /// firmware).
pub fn init(&self) { pub fn init(&mut self) {
// Turn it off temporarily. // Turn it off temporarily.
self.CR.set(0); self.CR.set(0);
@ -186,7 +210,7 @@ impl PL011UartInner {
fn write_char(&mut self, c: char) { fn write_char(&mut self, c: char) {
// Spin while TX FIFO full is set, waiting for an empty slot. // Spin while TX FIFO full is set, waiting for an empty slot.
while self.FR.matches_all(FR::TXFF::SET) { while self.FR.matches_all(FR::TXFF::SET) {
arch::nop(); cpu::nop();
} }
// Write the character to the buffer. // Write the character to the buffer.
@ -215,42 +239,28 @@ impl fmt::Write for PL011UartInner {
} }
} }
//--------------------------------------------------------------------------------------------------
// Export the inner struct so that BSPs can use it for the panic handler
//--------------------------------------------------------------------------------------------------
pub use PL011UartInner as PanicUart;
//--------------------------------------------------------------------------------------------------
// BSP-public
//--------------------------------------------------------------------------------------------------
/// The driver's main struct.
pub struct PL011Uart {
inner: NullLock<PL011UartInner>,
}
impl PL011Uart { impl PL011Uart {
/// # Safety /// # Safety
/// ///
/// The user must ensure to provide the correct `base_addr`. /// - The user must ensure to provide the correct `base_addr`.
pub const unsafe fn new(base_addr: usize) -> PL011Uart { pub const unsafe fn new(base_addr: usize) -> Self {
PL011Uart { Self {
inner: NullLock::new(PL011UartInner::new(base_addr)), inner: NullLock::new(PL011UartInner::new(base_addr)),
} }
} }
} }
//-------------------------------------------------------------------------------------------------- //------------------------------------------------------------------------------
// OS interface implementations // OS Interface Code
//-------------------------------------------------------------------------------------------------- //------------------------------------------------------------------------------
use interface::sync::Mutex; use synchronization::interface::Mutex;
impl interface::driver::DeviceDriver for PL011Uart { impl driver::interface::DeviceDriver for PL011Uart {
fn compatible(&self) -> &str { fn compatible(&self) -> &str {
"PL011Uart" "BCM PL011 UART"
} }
fn init(&self) -> interface::driver::Result { fn init(&self) -> Result<(), ()> {
let mut r = &self.inner; let mut r = &self.inner;
r.lock(|inner| inner.init()); r.lock(|inner| inner.init());
@ -258,7 +268,7 @@ impl interface::driver::DeviceDriver for PL011Uart {
} }
} }
impl interface::console::Write for PL011Uart { impl console::interface::Write for PL011Uart {
/// Passthrough of `args` to the `core::fmt::Write` implementation, but guarded by a Mutex to /// Passthrough of `args` to the `core::fmt::Write` implementation, but guarded by a Mutex to
/// serialize access. /// serialize access.
fn write_char(&self, c: char) { fn write_char(&self, c: char) {
@ -274,23 +284,23 @@ impl interface::console::Write for PL011Uart {
} }
fn flush(&self) { fn flush(&self) {
let mut r = &self.inner;
// Spin until TX FIFO empty is set. // Spin until TX FIFO empty is set.
let mut r = &self.inner;
r.lock(|inner| { r.lock(|inner| {
while !inner.FR.matches_all(FR::TXFE::SET) { while !inner.FR.matches_all(FR::TXFE::SET) {
arch::nop(); cpu::nop();
} }
}); });
} }
} }
impl interface::console::Read for PL011Uart { impl console::interface::Read for PL011Uart {
fn read_char(&self) -> char { fn read_char(&self) -> char {
let mut r = &self.inner; let mut r = &self.inner;
r.lock(|inner| { r.lock(|inner| {
// Spin while RX FIFO empty is set. // Spin while RX FIFO empty is set.
while inner.FR.matches_all(FR::RXFE::SET) { while inner.FR.matches_all(FR::RXFE::SET) {
arch::nop(); cpu::nop();
} }
// Read one character. // Read one character.
@ -319,7 +329,7 @@ impl interface::console::Read for PL011Uart {
} }
} }
impl interface::console::Statistics for PL011Uart { impl console::interface::Statistics for PL011Uart {
fn chars_written(&self) -> usize { fn chars_written(&self) -> usize {
let mut r = &self.inner; let mut r = &self.inner;
r.lock(|inner| inner.chars_written) r.lock(|inner| inner.chars_written)

@ -0,0 +1,38 @@
// SPDX-License-Identifier: MIT OR Apache-2.0
//
// Copyright (c) 2018-2020 Andre Richter <andre.o.richter@gmail.com>
//! Top-level BSP file for the Raspberry Pi 3 and 4.
pub mod console;
pub mod cpu;
pub mod driver;
pub mod memory;
//--------------------------------------------------------------------------------------------------
// Global instances
//--------------------------------------------------------------------------------------------------
use super::device_driver;
static GPIO: device_driver::GPIO =
unsafe { device_driver::GPIO::new(memory::map::mmio::GPIO_BASE) };
static PL011_UART: device_driver::PL011Uart =
unsafe { device_driver::PL011Uart::new(memory::map::mmio::PL011_UART_BASE) };
//--------------------------------------------------------------------------------------------------
// Public Code
//--------------------------------------------------------------------------------------------------
/// Board identification.
pub fn board_name() -> &'static str {
#[cfg(feature = "bsp_rpi3")]
{
"Raspberry Pi 3"
}
#[cfg(feature = "bsp_rpi4")]
{
"Raspberry Pi 4"
}
}

@ -0,0 +1,30 @@
// SPDX-License-Identifier: MIT OR Apache-2.0
//
// Copyright (c) 2018-2020 Andre Richter <andre.o.richter@gmail.com>
//! BSP console facilities.
use super::{super::device_driver, memory::map};
use crate::console;
use core::fmt;
//--------------------------------------------------------------------------------------------------
// Public Code
//--------------------------------------------------------------------------------------------------
/// In case of a panic, the panic handler uses this function to take a last shot at printing
/// something before the system is halted.
///
/// # Safety
///
/// - Use only for printing during a panic.
pub unsafe fn panic_console_out() -> impl fmt::Write {
let mut uart = device_driver::PanicUart::new(map::mmio::PL011_UART_BASE);
uart.init();
uart
}
/// Return a reference to the console.
pub fn console() -> &'static impl console::interface::All {
&super::PL011_UART
}

@ -0,0 +1,15 @@
// SPDX-License-Identifier: MIT OR Apache-2.0
//
// Copyright (c) 2018-2020 Andre Richter <andre.o.richter@gmail.com>
//! BSP Processor code.
//--------------------------------------------------------------------------------------------------
// Public Definitions
//--------------------------------------------------------------------------------------------------
/// Used by `arch` code to find the early boot core.
pub const BOOT_CORE_ID: usize = 0;
/// The early boot core's stack address.
pub const BOOT_CORE_STACK_START: u64 = 0x80_000;

@ -0,0 +1,49 @@
// SPDX-License-Identifier: MIT OR Apache-2.0
//
// Copyright (c) 2018-2020 Andre Richter <andre.o.richter@gmail.com>
//! BSP driver support.
use crate::driver;
//--------------------------------------------------------------------------------------------------
// Public Definitions
//--------------------------------------------------------------------------------------------------
/// Device Driver Manager type.
pub struct BSPDriverManager {
device_drivers: [&'static (dyn DeviceDriver + Sync); 2],
}
//--------------------------------------------------------------------------------------------------
// Global instances
//--------------------------------------------------------------------------------------------------
static BSP_DRIVER_MANAGER: BSPDriverManager = BSPDriverManager {
device_drivers: [&super::GPIO, &super::PL011_UART],
};
//--------------------------------------------------------------------------------------------------
// Public Code
//--------------------------------------------------------------------------------------------------
/// Return a reference to the driver manager.
pub fn driver_manager() -> &'static impl driver::interface::DriverManager {
&BSP_DRIVER_MANAGER
}
//------------------------------------------------------------------------------
// OS Interface Code
//------------------------------------------------------------------------------
use driver::interface::DeviceDriver;
impl driver::interface::DriverManager for BSPDriverManager {
fn all_device_drivers(&self) -> &[&'static (dyn DeviceDriver + Sync)] {
&self.device_drivers[..]
}
fn post_device_driver_init(&self) {
// Configure PL011Uart's output pins.
super::GPIO.map_pl011_uart();
}
}

@ -0,0 +1,36 @@
// SPDX-License-Identifier: MIT OR Apache-2.0
//
// Copyright (c) 2018-2020 Andre Richter <andre.o.richter@gmail.com>
//! BSP Memory Management.
//--------------------------------------------------------------------------------------------------
// Public Definitions
//--------------------------------------------------------------------------------------------------
/// The board's memory map.
#[rustfmt::skip]
pub(super) mod map {
pub const GPIO_OFFSET: usize = 0x0020_0000;
pub const UART_OFFSET: usize = 0x0020_1000;
/// Physical devices.
#[cfg(feature = "bsp_rpi3")]
pub mod mmio {
use super::*;
pub const BASE: usize = 0x3F00_0000;
pub const GPIO_BASE: usize = BASE + GPIO_OFFSET;
pub const PL011_UART_BASE: usize = BASE + UART_OFFSET;
}
/// Physical devices.
#[cfg(feature = "bsp_rpi4")]
pub mod mmio {
use super::*;
pub const BASE: usize = 0xFE00_0000;
pub const GPIO_BASE: usize = BASE + GPIO_OFFSET;
pub const PL011_UART_BASE: usize = BASE + UART_OFFSET;
}
}

@ -1,74 +0,0 @@
// SPDX-License-Identifier: MIT OR Apache-2.0
//
// Copyright (c) 2018-2020 Andre Richter <andre.o.richter@gmail.com>
//! Board Support Package for the Raspberry Pi.
mod memory_map;
use super::driver;
use crate::interface;
use core::fmt;
/// Used by `arch` code to find the early boot core.
pub const BOOT_CORE_ID: u64 = 0;
/// The early boot core's stack address.
pub const BOOT_CORE_STACK_START: u64 = 0x80_000;
//--------------------------------------------------------------------------------------------------
// Global BSP driver instances
//--------------------------------------------------------------------------------------------------
static GPIO: driver::GPIO = unsafe { driver::GPIO::new(memory_map::mmio::GPIO_BASE) };
static PL011_UART: driver::PL011Uart =
unsafe { driver::PL011Uart::new(memory_map::mmio::PL011_UART_BASE) };
//--------------------------------------------------------------------------------------------------
// Implementation of the kernel's BSP calls
//--------------------------------------------------------------------------------------------------
/// Board identification.
pub fn board_name() -> &'static str {
#[cfg(feature = "bsp_rpi3")]
{
"Raspberry Pi 3"
}
#[cfg(feature = "bsp_rpi4")]
{
"Raspberry Pi 4"
}
}
/// Return a reference to a `console::All` implementation.
pub fn console() -> &'static impl interface::console::All {
&PL011_UART
}
/// In case of a panic, the panic handler uses this function to take a last shot at printing
/// something before the system is halted.
///
/// # Safety
///
/// - Use only for printing during a panic.
pub unsafe fn panic_console_out() -> impl fmt::Write {
let uart = driver::PanicUart::new(memory_map::mmio::PL011_UART_BASE);
uart.init();
uart
}
/// Return an array of references to all `DeviceDriver` compatible `BSP` drivers.
///
/// # Safety
///
/// The order of devices is the order in which `DeviceDriver::init()` is called.
pub fn device_drivers() -> [&'static dyn interface::driver::DeviceDriver; 2] {
[&GPIO, &PL011_UART]
}
/// BSP initialization code that runs after driver init.
pub fn post_driver_init() {
// Configure PL011Uart's output pins.
GPIO.map_pl011_uart();
}

@ -1,18 +0,0 @@
// SPDX-License-Identifier: MIT OR Apache-2.0
//
// Copyright (c) 2018-2020 Andre Richter <andre.o.richter@gmail.com>
//! The board's memory map.
/// Physical devices.
#[rustfmt::skip]
pub mod mmio {
#[cfg(feature = "bsp_rpi3")]
pub const BASE: usize = 0x3F00_0000;
#[cfg(feature = "bsp_rpi4")]
pub const BASE: usize = 0xFE00_0000;
pub const GPIO_BASE: usize = BASE + 0x0020_0000;
pub const PL011_UART_BASE: usize = BASE + 0x0020_1000;
}

@ -0,0 +1,54 @@
// SPDX-License-Identifier: MIT OR Apache-2.0
//
// Copyright (c) 2018-2020 Andre Richter <andre.o.richter@gmail.com>
//! System console.
//--------------------------------------------------------------------------------------------------
// Public Definitions
//--------------------------------------------------------------------------------------------------
/// Console interfaces.
pub mod interface {
use core::fmt;
/// Console write functions.
pub trait Write {
/// Write a single character.
fn write_char(&self, c: char);
/// Write a Rust format string.
fn write_fmt(&self, args: fmt::Arguments) -> fmt::Result;
/// Block execution until the last character has been physically put on the TX wire
/// (draining TX buffers/FIFOs, if any).
fn flush(&self);
}
/// Console read functions.
pub trait Read {
/// Read a single character.
fn read_char(&self) -> char {
' '
}
/// Clear RX buffers, if any.
fn clear(&self);
}
/// Console statistics.
pub trait Statistics {
/// Return the number of characters written.
fn chars_written(&self) -> usize {
0
}
/// Return the number of characters read.
fn chars_read(&self) -> usize {
0
}
}
/// Trait alias for a full-fledged console.
pub trait All = Write + Read + Statistics;
}

@ -0,0 +1,12 @@
// SPDX-License-Identifier: MIT OR Apache-2.0
//
// Copyright (c) 2020 Andre Richter <andre.o.richter@gmail.com>
//! Processor code.
#[cfg(target_arch = "aarch64")]
#[path = "_arch/aarch64/cpu.rs"]
mod arch_cpu;
pub use arch_cpu::*;
pub mod smp;

@ -0,0 +1,10 @@
// SPDX-License-Identifier: MIT OR Apache-2.0
//
// Copyright (c) 2018-2020 Andre Richter <andre.o.richter@gmail.com>
//! Symmetric multiprocessing.
#[cfg(target_arch = "aarch64")]
#[path = "../_arch/aarch64/cpu/smp.rs"]
mod arch_cpu_smp;
pub use arch_cpu_smp::*;

@ -0,0 +1,41 @@
// SPDX-License-Identifier: MIT OR Apache-2.0
//
// Copyright (c) 2018-2020 Andre Richter <andre.o.richter@gmail.com>
//! Driver support.
//--------------------------------------------------------------------------------------------------
// Public Definitions
//--------------------------------------------------------------------------------------------------
/// Driver interfaces.
pub mod interface {
/// Device Driver functions.
pub trait DeviceDriver {
/// Return a compatibility string for identifying the driver.
fn compatible(&self) -> &str;
/// Called by the kernel to bring up the device.
fn init(&self) -> Result<(), ()> {
Ok(())
}
}
/// Device driver management functions.
///
/// The `BSP` is supposed to supply one global instance.
pub trait DriverManager {
/// Return a slice of references to all `BSP`-instantiated drivers.
///
/// # Safety
///
/// - The order of devices is the order in which `DeviceDriver::init()` is called.
fn all_device_drivers(&self) -> &[&'static (dyn DeviceDriver + Sync)];
/// Initialization code that runs after driver init.
///
/// For example, device driver code that depends on other drivers already being online.
fn post_device_driver_init(&self);
}
}

@ -1,133 +0,0 @@
// SPDX-License-Identifier: MIT OR Apache-2.0
//
// Copyright (c) 2018-2020 Andre Richter <andre.o.richter@gmail.com>
//! Trait definitions for coupling `kernel` and `BSP` code.
//!
//! ```
//! +-------------------+
//! | Interface (Trait) |
//! | |
//! +--+-------------+--+
//! ^ ^
//! | |
//! | |
//! +----------+--+ +--+----------+
//! | Kernel code | | BSP Code |
//! | | | |
//! +-------------+ +-------------+
//! ```
/// System console operations.
pub mod console {
use core::fmt;
/// Console write functions.
pub trait Write {
/// Write a single character.
fn write_char(&self, c: char);
/// Write a Rust format string.
fn write_fmt(&self, args: fmt::Arguments) -> fmt::Result;
/// Block execution until the last character has been physically put on the TX wire
/// (draining TX buffers/FIFOs, if any).
fn flush(&self);
}
/// Console read functions.
pub trait Read {
/// Read a single character.
fn read_char(&self) -> char {
' '
}
/// Clear RX buffers, if any.
fn clear(&self);
}
/// Console statistics.
pub trait Statistics {
/// Return the number of characters written.
fn chars_written(&self) -> usize {
0
}
/// Return the number of characters read.
fn chars_read(&self) -> usize {
0
}
}
/// Trait alias for a full-fledged console.
pub trait All = Write + Read + Statistics;
}
/// Synchronization primitives.
pub mod sync {
/// Any object implementing this trait guarantees exclusive access to the data contained within
/// the mutex for the duration of the lock.
///
/// The trait follows the [Rust embedded WG's
/// proposal](https://github.com/korken89/wg/blob/master/rfcs/0377-mutex-trait.md) and therefore
/// provides some goodness such as [deadlock
/// prevention](https://github.com/korken89/wg/blob/master/rfcs/0377-mutex-trait.md#design-decisions-and-compatibility).
///
/// # Example
///
/// Since the lock function takes an `&mut self` to enable deadlock-prevention, the trait is
/// best implemented **for a reference to a container struct**, and has a usage pattern that
/// might feel strange at first:
///
/// ```
/// static MUT: Mutex<RefCell<i32>> = Mutex::new(RefCell::new(0));
///
/// fn foo() {
/// let mut r = &MUT; // Note that r is mutable
/// r.lock(|data| *data += 1);
/// }
/// ```
pub trait Mutex {
/// Type of data encapsulated by the mutex.
type Data;
/// Creates a critical section and grants temporary mutable access to the encapsulated data.
fn lock<R>(&mut self, f: impl FnOnce(&mut Self::Data) -> R) -> R;
}
}
/// Driver interfaces.
pub mod driver {
/// Driver result type, e.g. for indicating successful driver init.
pub type Result = core::result::Result<(), ()>;
/// Device Driver functions.
pub trait DeviceDriver {
/// Return a compatibility string for identifying the driver.
fn compatible(&self) -> &str;
/// Called by the kernel to bring up the device.
fn init(&self) -> Result {
Ok(())
}
}
}
/// Timekeeping interfaces.
pub mod time {
use core::time::Duration;
/// Timer functions.
pub trait Timer {
/// The timer's resolution.
fn resolution(&self) -> Duration;
/// The uptime since power-on of the device.
///
/// This includes time consumed by firmware and bootloaders.
fn uptime(&self) -> Duration;
/// Spin for a given duration.
fn spin_for(&self, duration: Duration);
}
}

@ -5,56 +5,139 @@
// Rust embedded logo for `make doc`. // Rust embedded logo for `make doc`.
#![doc(html_logo_url = "https://git.io/JeGIp")] #![doc(html_logo_url = "https://git.io/JeGIp")]
//! The `kernel` //! The `kernel` binary.
//! //!
//! The `kernel` is composed by glueing together code from //! # TL;DR - Overview of important Kernel entities
//! //!
//! - [Hardware-specific Board Support Packages] (`BSPs`). //! - [`bsp::console::console()`] - Returns a reference to the kernel's [console interface].
//! - [Architecture-specific code]. //! - [`bsp::driver::driver_manager()`] - Returns a reference to the kernel's [driver interface].
//! - HW- and architecture-agnostic `kernel` code. //! - [`time::time_manager()`] - Returns a reference to the kernel's [timer interface].
//! //!
//! using the [`kernel::interface`] traits. //! [console interface]: ../libkernel/console/interface/index.html
//! [driver interface]: ../libkernel/driver/interface/trait.DriverManager.html
//! [timer interface]: ../libkernel/time/interface/trait.TimeManager.html
//! //!
//! [Hardware-specific Board Support Packages]: bsp/index.html //! # Code organization and architecture
//! [Architecture-specific code]: arch/index.html //!
//! [`kernel::interface`]: interface/index.html //! The code is divided into different *modules*, each representing a typical **subsystem** of the
//! `kernel`. Top-level module files of subsystems reside directly in the `src` folder. For example,
//! `src/memory.rs` contains code that is concerned with all things memory management.
//!
//! ## Visibility of processor architecture code
//!
//! Some of the `kernel`'s subsystems depend on low-level code that is specific to the target
//! processor architecture. For each supported processor architecture, there exists a subfolder in
//! `src/_arch`, for example, `src/_arch/aarch64`.
//!
//! The architecture folders mirror the subsystem modules laid out in `src`. For example,
//! architectural code that belongs to the `kernel`'s memory subsystem (`src/memory.rs`) would go
//! into `src/_arch/aarch64/memory.rs`. The latter file is directly included and re-exported in
//! `src/memory.rs`, so that the architectural code parts are transparent with respect to the code's
//! module organization. That means a public function `foo()` defined in
//! `src/_arch/aarch64/memory.rs` would be reachable as `crate::memory::foo()` only.
//!
//! The `_` in `_arch` denotes that this folder is not part of the standard module hierarchy.
//! Rather, it's contents are conditionally pulled into respective files using the `#[path =
//! "_arch/xxx/yyy.rs"]` attribute.
//!
//! ## BSP code
//!
//! `BSP` stands for Board Support Package. `BSP` code is organized under `src/bsp.rs` and contains
//! target board specific definitions and functions. These are things such as the board's memory map
//! or instances of drivers for devices that are featured on the respective board.
//!
//! Just like processor architecture code, the `BSP` code's module structure tries to mirror the
//! `kernel`'s subsystem modules, but there is no transparent re-exporting this time. That means
//! whatever is provided must be called starting from the `bsp` namespace, e.g.
//! `bsp::driver::driver_manager()`.
//!
//! ## Kernel interfaces
//!
//! Both `arch` and `bsp` contain code that is conditionally compiled depending on the actual target
//! and board for which the kernel is compiled. For example, the `interrupt controller` hardware of
//! the `Raspberry Pi 3` and the `Raspberry Pi 4` is different, but we want the rest of the `kernel`
//! code to play nicely with any of the two without much hassle.
//!
//! In order to provide a clean abstraction between `arch`, `bsp` and `generic kernel code`,
//! `interface` traits are provided *whenever possible* and *where it makes sense*. They are defined
//! in the respective subsystem module and help to enforce the idiom of *program to an interface,
//! not an implementation*. For example, there will be a common IRQ handling interface which the two
//! different interrupt controller `drivers` of both Raspberrys will implement, and only export the
//! interface to the rest of the `kernel`.
//!
//! ```
//! +-------------------+
//! | Interface (Trait) |
//! | |
//! +--+-------------+--+
//! ^ ^
//! | |
//! | |
//! +----------+--+ +--+----------+
//! | kernel code | | bsp code |
//! | | | arch code |
//! +-------------+ +-------------+
//! ```
//!
//! # Summary
//!
//! For a logical `kernel` subsystem, corresponding code can be distributed over several physical
//! locations. Here is an example for the **memory** subsystem:
//!
//! - `src/memory.rs` and `src/memory/**/*`
//! - Common code that is agnostic of target processor architecture and `BSP` characteristics.
//! - Example: A function to zero a chunk of memory.
//! - Interfaces for the memory subsystem that are implemented by `arch` or `BSP` code.
//! - Example: An `MMU` interface that defines `MMU` function prototypes.
//! - `src/bsp/__board_name__/memory.rs` and `src/bsp/__board_name__/memory/**/*`
//! - `BSP` specific code.
//! - Example: The board's memory map (physical addresses of DRAM and MMIO devices).
//! - `src/_arch/__arch_name__/memory.rs` and `src/_arch/__arch_name__/memory/**/*`
//! - Processor architecture specific code.
//! - Example: Implementation of the `MMU` interface for the `__arch_name__` processor
//! architecture.
//!
//! From a namespace perspective, **memory** subsystem code lives in:
//!
//! - `crate::memory::*`
//! - `crate::bsp::memory::*`
#![feature(format_args_nl)] #![feature(format_args_nl)]
#![feature(naked_functions)]
#![feature(panic_info_message)] #![feature(panic_info_message)]
#![feature(trait_alias)] #![feature(trait_alias)]
#![no_main] #![no_main]
#![no_std] #![no_std]
// Conditionally includes the selected `architecture` code, which provides the `_start()` function, // `mod cpu` provides the `_start()` function, the first function to run. `_start()` then calls
// the first function to run. // `runtime_init()`, which jumps to `kernel_init()`.
mod arch;
// `_start()` then calls `runtime_init()`, which on completion, jumps to `kernel_init()`.
mod runtime_init;
// Conditionally includes the selected `BSP` code.
mod bsp; mod bsp;
mod console;
mod interface; mod cpu;
mod driver;
mod memory; mod memory;
mod panic_wait; mod panic_wait;
mod print; mod print;
mod runtime_init;
mod synchronization;
mod time;
/// Early init code. /// Early init code.
/// ///
/// Concerned with with initializing `BSP` and `arch` parts.
///
/// # Safety /// # Safety
/// ///
/// - Only a single core must be active and running this function. /// - Only a single core must be active and running this function.
/// - The init calls in this function must appear in the correct order. /// - The init calls in this function must appear in the correct order.
unsafe fn kernel_init() -> ! { unsafe fn kernel_init() -> ! {
for i in bsp::device_drivers().iter() { use driver::interface::DriverManager;
if let Err(()) = i.init() {
for i in bsp::driver::driver_manager().all_device_drivers().iter() {
if i.init().is_err() {
panic!("Error loading driver: {}", i.compatible()) panic!("Error loading driver: {}", i.compatible())
} }
} }
bsp::post_driver_init(); bsp::driver::driver_manager().post_device_driver_init();
// println! is usable from here on. // println! is usable from here on.
// Transition from unsafe to safe. // Transition from unsafe to safe.
@ -64,24 +147,30 @@ unsafe fn kernel_init() -> ! {
/// The main function running after the early init. /// The main function running after the early init.
fn kernel_main() -> ! { fn kernel_main() -> ! {
use core::time::Duration; use core::time::Duration;
use interface::time::Timer; use driver::interface::DriverManager;
use time::interface::TimeManager;
info!("Booting on: {}", bsp::board_name()); info!("Booting on: {}", bsp::board_name());
info!( info!(
"Architectural timer resolution: {} ns", "Architectural timer resolution: {} ns",
arch::timer().resolution().as_nanos() time::time_manager().resolution().as_nanos()
); );
info!("Drivers loaded:"); info!("Drivers loaded:");
for (i, driver) in bsp::device_drivers().iter().enumerate() { for (i, driver) in bsp::driver::driver_manager()
.all_device_drivers()
.iter()
.enumerate()
{
info!(" {}. {}", i + 1, driver.compatible()); info!(" {}. {}", i + 1, driver.compatible());
} }
// Test a failing timer case. // Test a failing timer case.
arch::timer().spin_for(Duration::from_nanos(1)); time::time_manager().spin_for(Duration::from_nanos(1));
loop { loop {
info!("Spinning for 1 second"); info!("Spinning for 1 second");
arch::timer().spin_for(Duration::from_secs(1)); time::time_manager().spin_for(Duration::from_secs(1));
} }
} }

@ -6,6 +6,10 @@
use core::ops::Range; use core::ops::Range;
//--------------------------------------------------------------------------------------------------
// Public Code
//--------------------------------------------------------------------------------------------------
/// Zero out a memory region. /// Zero out a memory region.
/// ///
/// # Safety /// # Safety

@ -4,13 +4,17 @@
//! A panic handler that infinitely waits. //! A panic handler that infinitely waits.
use crate::{arch, bsp}; use crate::{bsp, cpu};
use core::{fmt, panic::PanicInfo}; use core::{fmt, panic::PanicInfo};
//--------------------------------------------------------------------------------------------------
// Private Code
//--------------------------------------------------------------------------------------------------
fn _panic_print(args: fmt::Arguments) { fn _panic_print(args: fmt::Arguments) {
use fmt::Write; use fmt::Write;
unsafe { bsp::panic_console_out().write_fmt(args).unwrap() }; unsafe { bsp::console::panic_console_out().write_fmt(args).unwrap() };
} }
/// Prints with a newline - only use from the panic handler. /// Prints with a newline - only use from the panic handler.
@ -31,5 +35,5 @@ fn panic(info: &PanicInfo) -> ! {
panic_println!("\nKernel panic!"); panic_println!("\nKernel panic!");
} }
arch::wait_forever() cpu::wait_forever()
} }

@ -4,16 +4,24 @@
//! Printing facilities. //! Printing facilities.
use crate::{bsp, interface}; use crate::{bsp, console};
use core::fmt; use core::fmt;
//--------------------------------------------------------------------------------------------------
// Private Code
//--------------------------------------------------------------------------------------------------
#[doc(hidden)] #[doc(hidden)]
pub fn _print(args: fmt::Arguments) { pub fn _print(args: fmt::Arguments) {
use interface::console::Write; use console::interface::Write;
bsp::console().write_fmt(args).unwrap(); bsp::console::console().write_fmt(args).unwrap();
} }
//--------------------------------------------------------------------------------------------------
// Public Code
//--------------------------------------------------------------------------------------------------
/// Prints without a newline. /// Prints without a newline.
/// ///
/// Carbon copy from https://doc.rust-lang.org/src/std/macros.rs.html /// Carbon copy from https://doc.rust-lang.org/src/std/macros.rs.html
@ -33,14 +41,14 @@ macro_rules! println {
}) })
} }
/// Prints an info, with newline. /// Prints an info, with a newline.
#[macro_export] #[macro_export]
macro_rules! info { macro_rules! info {
($string:expr) => ({ ($string:expr) => ({
#[allow(unused_imports)] #[allow(unused_imports)]
use crate::interface::time::Timer; use crate::time::interface::TimeManager;
let timestamp = $crate::arch::timer().uptime(); let timestamp = $crate::time::time_manager().uptime();
let timestamp_subsec_us = timestamp.subsec_micros(); let timestamp_subsec_us = timestamp.subsec_micros();
$crate::print::_print(format_args_nl!( $crate::print::_print(format_args_nl!(
@ -52,9 +60,9 @@ macro_rules! info {
}); });
($format_string:expr, $($arg:tt)*) => ({ ($format_string:expr, $($arg:tt)*) => ({
#[allow(unused_imports)] #[allow(unused_imports)]
use crate::interface::time::Timer; use crate::time::interface::TimeManager;
let timestamp = $crate::arch::timer().uptime(); let timestamp = $crate::time::time_manager().uptime();
let timestamp_subsec_us = timestamp.subsec_micros(); let timestamp_subsec_us = timestamp.subsec_micros();
$crate::print::_print(format_args_nl!( $crate::print::_print(format_args_nl!(
@ -67,14 +75,14 @@ macro_rules! info {
}) })
} }
/// Prints a warning, with newline. /// Prints a warning, with a newline.
#[macro_export] #[macro_export]
macro_rules! warn { macro_rules! warn {
($string:expr) => ({ ($string:expr) => ({
#[allow(unused_imports)] #[allow(unused_imports)]
use crate::interface::time::Timer; use crate::time::interface::TimeManager;
let timestamp = $crate::arch::timer().uptime(); let timestamp = $crate::time::time_manager().uptime();
let timestamp_subsec_us = timestamp.subsec_micros(); let timestamp_subsec_us = timestamp.subsec_micros();
$crate::print::_print(format_args_nl!( $crate::print::_print(format_args_nl!(
@ -86,9 +94,9 @@ macro_rules! warn {
}); });
($format_string:expr, $($arg:tt)*) => ({ ($format_string:expr, $($arg:tt)*) => ({
#[allow(unused_imports)] #[allow(unused_imports)]
use crate::interface::time::Timer; use crate::time::interface::TimeManager;
let timestamp = $crate::arch::timer().uptime(); let timestamp = $crate::time::time_manager().uptime();
let timestamp_subsec_us = timestamp.subsec_micros(); let timestamp_subsec_us = timestamp.subsec_micros();
$crate::print::_print(format_args_nl!( $crate::print::_print(format_args_nl!(

@ -7,6 +7,10 @@
use crate::memory; use crate::memory;
use core::ops::Range; use core::ops::Range;
//--------------------------------------------------------------------------------------------------
// Private Code
//--------------------------------------------------------------------------------------------------
/// Return the range spanning the .bss section. /// Return the range spanning the .bss section.
/// ///
/// # Safety /// # Safety
@ -36,6 +40,10 @@ unsafe fn zero_bss() {
memory::zero_volatile(bss_range()); memory::zero_volatile(bss_range());
} }
//--------------------------------------------------------------------------------------------------
// Public Code
//--------------------------------------------------------------------------------------------------
/// Equivalent to `crt0` or `c0` code in C/C++ world. Clears the `bss` section, then jumps to kernel /// Equivalent to `crt0` or `c0` code in C/C++ world. Clears the `bss` section, then jumps to kernel
/// init code. /// init code.
/// ///

@ -0,0 +1,91 @@
// SPDX-License-Identifier: MIT OR Apache-2.0
//
// Copyright (c) 2020 Andre Richter <andre.o.richter@gmail.com>
//! Synchronization primitives.
use core::cell::UnsafeCell;
//--------------------------------------------------------------------------------------------------
// Public Definitions
//--------------------------------------------------------------------------------------------------
/// Synchronization interfaces.
pub mod interface {
/// Any object implementing this trait guarantees exclusive access to the data contained within
/// the Mutex for the duration of the provided closure.
///
/// The trait follows the [Rust embedded WG's
/// proposal](https://github.com/korken89/wg/blob/master/rfcs/0377-mutex-trait.md) and therefore
/// provides some goodness such as [deadlock
/// prevention](https://github.com/korken89/wg/blob/master/rfcs/0377-mutex-trait.md#design-decisions-and-compatibility).
///
/// # Example
///
/// Since the lock function takes an `&mut self` to enable deadlock-prevention, the trait is
/// best implemented **for a reference to a container struct**, and has a usage pattern that
/// might feel strange at first:
///
/// ```
/// static MUT: Mutex<RefCell<i32>> = Mutex::new(RefCell::new(0));
///
/// fn foo() {
/// let mut r = &MUT; // Note that r is mutable
/// r.lock(|data| *data += 1);
/// }
/// ```
pub trait Mutex {
/// The type of encapsulated data.
type Data;
/// Creates a critical section and grants temporary mutable access to the encapsulated data.
fn lock<R>(&mut self, f: impl FnOnce(&mut Self::Data) -> R) -> R;
}
}
/// A pseudo-lock for teaching purposes.
///
/// Used to introduce [interior mutability].
///
/// In contrast to a real Mutex implementation, does not protect against concurrent access from
/// other cores to the contained data. This part is preserved for later lessons.
///
/// The lock will only be used as long as it is safe to do so, i.e. as long as the kernel is
/// executing single-threaded, aka only running on a single core with interrupts disabled.
///
/// [interior mutability]: https://doc.rust-lang.org/std/cell/index.html
pub struct NullLock<T: ?Sized> {
data: UnsafeCell<T>,
}
//--------------------------------------------------------------------------------------------------
// Public Code
//--------------------------------------------------------------------------------------------------
unsafe impl<T: ?Sized> Sync for NullLock<T> {}
impl<T> NullLock<T> {
/// Wraps `data` into a new `NullLock`.
pub const fn new(data: T) -> Self {
Self {
data: UnsafeCell::new(data),
}
}
}
//------------------------------------------------------------------------------
// OS Interface Code
//------------------------------------------------------------------------------
impl<T> interface::Mutex for &NullLock<T> {
type Data = T;
fn lock<R>(&mut self, f: impl FnOnce(&mut Self::Data) -> R) -> R {
// In a real lock, there would be code encapsulating this line that ensures that this
// mutable reference will ever only be given out once at a time.
let data = unsafe { &mut *self.data.get() };
f(data)
}
}

@ -0,0 +1,35 @@
// SPDX-License-Identifier: MIT OR Apache-2.0
//
// Copyright (c) 2020 Andre Richter <andre.o.richter@gmail.com>
//! Timer primitives.
#[cfg(target_arch = "aarch64")]
#[path = "_arch/aarch64/time.rs"]
mod arch_time;
pub use arch_time::*;
//--------------------------------------------------------------------------------------------------
// Public Definitions
//--------------------------------------------------------------------------------------------------
/// Timekeeping interfaces.
pub mod interface {
use core::time::Duration;
/// Time management functions.
///
/// The `BSP` is supposed to supply one global instance.
pub trait TimeManager {
/// The timer's resolution.
fn resolution(&self) -> Duration;
/// The uptime since power-on of the device.
///
/// This includes time consumed by firmware and bootloaders.
fn uptime(&self) -> Duration;
/// Spin for a given duration.
fn spin_for(&self, duration: Duration);
}
}
Loading…
Cancel
Save