Merge remote-tracking branch 'equation314/arch-aarch64' into merging

# Conflicts:
#	kernel/Makefile
#	kernel/src/arch/aarch64/board/raspi3/irq.rs
#	kernel/src/arch/aarch64/memory.rs
#	kernel/src/arch/riscv32/paging.rs
#	kernel/src/arch/x86_64/paging.rs
master
WangRunji 6 years ago
commit 61dfcb5558

@ -5,6 +5,7 @@ extern crate volatile;
pub mod gpio; pub mod gpio;
pub mod timer; pub mod timer;
pub mod mailbox;
pub mod mini_uart; pub mod mini_uart;
pub mod interrupt; pub mod interrupt;

@ -0,0 +1,80 @@
use crate::IO_BASE;
use volatile::{ReadOnly, Volatile, WriteOnly};
/// The base address for the `MU` registers.
const MAILBOX_BASE: usize = IO_BASE + 0xB000 + 0x880;
/// Available mailbox channels
///
/// (ref: https://github.com/raspberrypi/firmware/wiki/Mailboxes)
#[repr(u8)]
#[derive(Copy, Clone, Debug)]
pub enum MailboxChannel {
Framebuffer = 1,
Property = 8,
}
/// Read from mailbox status register (MAILx_STA).
#[repr(u32)]
enum MailboxStatus {
MailboxEmpty = 1 << 30,
MailboxFull = 1 << 31,
}
/// Mailbox registers. We basically only support mailbox 0 & 1. We
/// deliver to the VC in mailbox 1, it delivers to us in mailbox 0. See
/// BCM2835-ARM-Peripherals.pdf section 1.3 for an explanation about
/// the placement of memory barriers.
///
/// (ref: https://github.com/raspberrypi/firmware/wiki/Mailboxes)
#[repr(C)]
#[allow(non_snake_case)]
struct Registers {
MAIL0_RD: ReadOnly<u32>, // 0x00
__reserved0: [u32; 3],
MAIL0_POL: ReadOnly<u32>, // 0x10
MAIL0_SND: ReadOnly<u32>, // 0x14
MAIL0_STA: ReadOnly<u32>, // 0x18
MAIL0_CNF: Volatile<u32>, // 0x1c
MAIL1_WRT: WriteOnly<u32>, // 0x20
__reserved1: [u32; 3],
_MAIL1_POL: ReadOnly<u32>, // 0x30
_MAIL1_SND: ReadOnly<u32>, // 0x34
MAIL1_STA: ReadOnly<u32>, // 0x38
_MAIL1_CNF: Volatile<u32>, // 0x3c
}
/// The Raspberry Pi's mailbox.
///
/// (ref: https://github.com/raspberrypi/firmware/wiki/Accessing-mailboxes)
pub struct Mailbox {
registers: &'static mut Registers,
}
impl Mailbox {
/// Returns a new instance of `Mailbox`.
#[inline]
pub fn new() -> Mailbox {
Mailbox {
registers: unsafe { &mut *(MAILBOX_BASE as *mut Registers) },
}
}
/// Read from the requested channel of mailbox 0.
pub fn read(&self, channel: MailboxChannel) -> u32 {
loop {
while self.registers.MAIL0_STA.read() & (MailboxStatus::MailboxEmpty as u32) != 0 {}
let data = self.registers.MAIL0_RD.read();
if data & 0xF == channel as u32 {
return data & !0xF;
}
}
}
/// Write to the requested channel of mailbox 1.
pub fn write(&mut self, channel: MailboxChannel, data: u32) {
while self.registers.MAIL1_STA.read() & (MailboxStatus::MailboxFull as u32) != 0 {}
self.registers.MAIL1_WRT.write((data & !0xF) | (channel as u32));
}
}

@ -2,12 +2,12 @@ use crate::IO_BASE;
use crate::gpio::{Function, Gpio}; use crate::gpio::{Function, Gpio};
use volatile::{ReadOnly, Volatile}; use volatile::{ReadOnly, Volatile};
/// The base address for the `MU` registers.
const MU_REG_BASE: usize = IO_BASE + 0x215040;
/// The `AUXENB` register from page 9 of the BCM2837 documentation. /// The `AUXENB` register from page 9 of the BCM2837 documentation.
const AUX_ENABLES: *mut Volatile<u8> = (IO_BASE + 0x215004) as *mut Volatile<u8>; const AUX_ENABLES: *mut Volatile<u8> = (IO_BASE + 0x215004) as *mut Volatile<u8>;
/// The base address for the `MU` registers.
const MU_REG_BASE: usize = IO_BASE + 0x215040;
/// Enum representing bit fields of the `AUX_MU_IIR_REG` register. /// Enum representing bit fields of the `AUX_MU_IIR_REG` register.
#[repr(u8)] #[repr(u8)]
pub enum MiniUartInterruptId { pub enum MiniUartInterruptId {
@ -55,19 +55,10 @@ pub struct MiniUart {
} }
impl MiniUart { impl MiniUart {
/// Initializes the mini UART by enabling it as an auxiliary peripheral, /// Returns a new instance of `MiniUart`.
/// setting the data size to 8 bits, setting the BAUD rate to ~115200 (baud #[inline]
/// divider of 270), setting GPIO pins 14 and 15 to alternative function 5
/// (TXD1/RDXD1), and finally enabling the UART transmitter and receiver.
///
/// By default, reads will never time out. To set a read timeout, use
/// `set_read_timeout()`.
pub fn new() -> MiniUart { pub fn new() -> MiniUart {
let registers = unsafe { let registers = unsafe { &mut *(MU_REG_BASE as *mut Registers) };
// Enable the mini UART as an auxiliary device.
(*AUX_ENABLES).write(1);
&mut *(MU_REG_BASE as *mut Registers)
};
MiniUart { MiniUart {
registers: registers, registers: registers,
@ -75,7 +66,17 @@ impl MiniUart {
} }
} }
/// Initializes the mini UART by enabling it as an auxiliary peripheral,
/// setting the data size to 8 bits, setting the BAUD rate to ~115200 (baud
/// divider of 270), setting GPIO pins 14 and 15 to alternative function 5
/// (TXD1/RDXD1), and finally enabling the UART transmitter and receiver.
///
/// By default, reads will never time out. To set a read timeout, use
/// `set_read_timeout()`.
pub fn init(&mut self) { pub fn init(&mut self) {
// Enable the mini UART as an auxiliary device.
unsafe { (*AUX_ENABLES).write(1) }
Gpio::new(14).into_alt(Function::Alt5).set_gpio_pd(0); Gpio::new(14).into_alt(Function::Alt5).set_gpio_pd(0);
Gpio::new(15).into_alt(Function::Alt5).set_gpio_pd(0); Gpio::new(15).into_alt(Function::Alt5).set_gpio_pd(0);

@ -1,5 +1,6 @@
extern crate aarch64; extern crate aarch64;
use super::BasicTimer;
use aarch64::regs::*; use aarch64::regs::*;
use volatile::*; use volatile::*;
@ -43,41 +44,33 @@ struct Registers {
} }
/// The ARM generic timer. /// The ARM generic timer.
pub struct Timer { pub struct GenericTimer {
registers: &'static mut Registers, registers: &'static mut Registers,
} }
impl Timer { impl BasicTimer for GenericTimer {
/// Returns a new instance of `Timer`. fn new() -> Self {
pub fn new() -> Timer { GenericTimer {
Timer {
registers: unsafe { &mut *(GEN_TIMER_REG_BASE as *mut Registers) }, registers: unsafe { &mut *(GEN_TIMER_REG_BASE as *mut Registers) },
} }
} }
/// Reads the generic timer's counter and returns the 64-bit counter value. fn init(&mut self) {
/// The returned value is the number of elapsed microseconds. self.registers.CORE_TIMER_IRQCNTL[0].write(1 << (CoreInterrupt::CNTPNSIRQ as u8));
pub fn read(&self) -> u64 { CNTP_CTL_EL0.write(CNTP_CTL_EL0::ENABLE::SET);
}
fn read(&self) -> u64 {
let cntfrq = CNTFRQ_EL0.get(); // 62500000 let cntfrq = CNTFRQ_EL0.get(); // 62500000
(CNTPCT_EL0.get() * 1000000 / (cntfrq as u64)) as u64 (CNTPCT_EL0.get() * 1000000 / (cntfrq as u64)) as u64
} }
/// Sets up a match in timer 1 to occur `us` microseconds from now. If fn tick_in(&mut self, us: u32) {
/// interrupts for timer 1 are enabled and IRQs are unmasked, then a timer
/// interrupt will be issued in `us` microseconds.
pub fn tick_in(&mut self, us: u32) {
let cntfrq = CNTFRQ_EL0.get(); // 62500000 let cntfrq = CNTFRQ_EL0.get(); // 62500000
CNTP_TVAL_EL0.set(((cntfrq as f64) * (us as f64) / 1000000.0) as u32); CNTP_TVAL_EL0.set(((cntfrq as f64) * (us as f64) / 1000000.0) as u32);
} }
/// Initialization timer fn is_pending(&self) -> bool {
pub fn init(&mut self) {
self.registers.CORE_TIMER_IRQCNTL[0].write(1 << (CoreInterrupt::CNTPNSIRQ as u8));
CNTP_CTL_EL0.write(CNTP_CTL_EL0::ENABLE::SET);
}
/// Returns `true` if timer interruption is pending. Otherwise, returns `false`.
pub fn is_pending(&self) -> bool {
self.registers.CORE_IRQ_SRC[0].read() & (1 << (CoreInterrupt::CNTPNSIRQ as u8)) != 0 self.registers.CORE_IRQ_SRC[0].read() & (1 << (CoreInterrupt::CNTPNSIRQ as u8)) != 0
} }
} }

@ -1,28 +1,32 @@
#[cfg(feature = "use_generic_timer")] #[cfg(feature = "use_generic_timer")]
mod generic_timer; mod generic_timer;
#[cfg(feature = "use_generic_timer")] #[cfg(feature = "use_generic_timer")]
pub use self::generic_timer::Timer; pub use self::generic_timer::GenericTimer as Timer;
#[cfg(not(feature = "use_generic_timer"))] #[cfg(not(feature = "use_generic_timer"))]
mod system_timer; mod system_timer;
#[cfg(not(feature = "use_generic_timer"))] #[cfg(not(feature = "use_generic_timer"))]
pub use self::system_timer::Timer; pub use self::system_timer::SystemTimer as Timer;
/// Initialization timer /// The Raspberry Pi timer.
pub fn init() { pub trait BasicTimer {
Timer::new().init(); /// Returns a new instance.
} fn new() -> Self;
/// Returns the current time in microseconds. /// Initialization timer.
pub fn current_time() -> u64 { fn init(&mut self);
Timer::new().read()
} /// Reads the timer's counter and returns the 64-bit counter value.
/// The returned value is the number of elapsed microseconds.
fn read(&self) -> u64;
/// Sets up a match in timer 1 to occur `us` microseconds from now. If
/// interrupts for timer 1 are enabled and IRQs are unmasked, then a timer
/// interrupt will be issued in `us` microseconds.
fn tick_in(&mut self, us: u32);
/// Sets up a match in timer 1 to occur `us` microseconds from now. If /// Returns `true` if timer interruption is pending. Otherwise, returns `false`.
/// interrupts for timer 1 are enabled and IRQs are unmasked, then a timer fn is_pending(&self) -> bool;
/// interrupt will be issued in `us` microseconds.
pub fn tick_in(us: u32) {
Timer::new().tick_in(us);
} }
/// wait for `cycle` CPU cycles /// wait for `cycle` CPU cycles

@ -1,5 +1,6 @@
use crate::IO_BASE; use super::BasicTimer;
use crate::interrupt::{Controller, Interrupt}; use crate::interrupt::{Controller, Interrupt};
use crate::IO_BASE;
use volatile::{ReadOnly, Volatile}; use volatile::{ReadOnly, Volatile};
/// The base address for the ARM system timer registers. /// The base address for the ARM system timer registers.
@ -18,7 +19,7 @@ struct Registers {
#[repr(u8)] #[repr(u8)]
#[allow(dead_code)] #[allow(dead_code)]
#[derive(Copy, Clone, PartialEq, Debug)] #[derive(Copy, Clone, PartialEq, Debug)]
enum SystemTimer { enum SystemTimerId {
Timer0 = 0, Timer0 = 0,
Timer1 = 1, Timer1 = 1,
Timer2 = 2, Timer2 = 2,
@ -26,43 +27,35 @@ enum SystemTimer {
} }
/// The Raspberry Pi ARM system timer. /// The Raspberry Pi ARM system timer.
pub struct Timer { pub struct SystemTimer {
registers: &'static mut Registers, registers: &'static mut Registers,
} }
impl Timer { impl BasicTimer for SystemTimer {
/// Returns a new instance of `Timer`. fn new() -> Self {
pub fn new() -> Timer { SystemTimer {
Timer {
registers: unsafe { &mut *(TIMER_REG_BASE as *mut Registers) }, registers: unsafe { &mut *(TIMER_REG_BASE as *mut Registers) },
} }
} }
/// Reads the system timer's counter and returns the 64-bit counter value. fn init(&mut self) {
/// The returned value is the number of elapsed microseconds. Controller::new().enable(Interrupt::Timer1);
pub fn read(&self) -> u64 { }
fn read(&self) -> u64 {
let low = self.registers.CLO.read(); let low = self.registers.CLO.read();
let high = self.registers.CHI.read(); let high = self.registers.CHI.read();
((high as u64) << 32) | (low as u64) ((high as u64) << 32) | (low as u64)
} }
/// Sets up a match in timer 1 to occur `us` microseconds from now. If fn tick_in(&mut self, us: u32) {
/// interrupts for timer 1 are enabled and IRQs are unmasked, then a timer
/// interrupt will be issued in `us` microseconds.
pub fn tick_in(&mut self, us: u32) {
let current_low = self.registers.CLO.read(); let current_low = self.registers.CLO.read();
let compare = current_low.wrapping_add(us); let compare = current_low.wrapping_add(us);
self.registers.COMPARE[SystemTimer::Timer1 as usize].write(compare); self.registers.COMPARE[SystemTimerId::Timer1 as usize].write(compare);
self.registers.CS.write(1 << (SystemTimer::Timer1 as usize)); // unmask self.registers.CS.write(1 << (SystemTimerId::Timer1 as usize)); // unmask
}
/// Initialization timer
pub fn init(&mut self) {
Controller::new().enable(Interrupt::Timer1);
} }
/// Returns `true` if timer interruption is pending. Otherwise, returns `false`. fn is_pending(&self) -> bool {
pub fn is_pending(&self) -> bool {
let controller = Controller::new(); let controller = Controller::new();
controller.is_pending(Interrupt::Timer1) controller.is_pending(Interrupt::Timer1)
} }

@ -82,7 +82,7 @@ pub struct MemoryAttr {
user: bool, user: bool,
readonly: bool, readonly: bool,
execute: bool, execute: bool,
mmio: bool, mmio: u8,
} }
impl MemoryAttr { impl MemoryAttr {
@ -110,8 +110,12 @@ impl MemoryAttr {
self.execute = true; self.execute = true;
self self
} }
pub fn mmio(mut self) -> Self { /*
self.mmio = true; ** @brief set the MMIO type
** @retval MemoryAttr the memory attribute itself
*/
pub fn mmio(mut self, value: u8) -> Self {
self.mmio = value;
self self
} }
/* /*

@ -85,8 +85,8 @@ pub trait Entry {
fn set_user(&mut self, value: bool); fn set_user(&mut self, value: bool);
fn execute(&self) -> bool; fn execute(&self) -> bool;
fn set_execute(&mut self, value: bool); fn set_execute(&mut self, value: bool);
fn mmio(&self) -> bool; fn mmio(&self) -> u8;
fn set_mmio(&mut self, value: bool); fn set_mmio(&mut self, value: u8);
} }
/// An inactive page table /// An inactive page table

@ -0,0 +1,17 @@
# Rust OS 在 Raspberry Pi 3 上的移植
计54 贾越凯 2015011335
计54 寇明阳 2015011318
计55 孔彦 2015011349
## 目录
* [概述](overview.md)
* [环境配置](environment.md)
* [启动与初始化](boot.md)
* [中断与异常](interrupt.md)
* [内存管理](memory.md)
* [上下文切换](context.md)
* [设备驱动](drivers.md)

@ -0,0 +1,218 @@
# 启动与初始化
## 树莓派启动流程
树莓派的启动流程如下:
1. 第一阶段:第一级 bootloader 位于片上 ROM 中,它挂载 SD 卡中的 FAT32 启动分区,并载入第二级 bootloader。
2. 第二阶段:第二级 bootloader 位于`bootcode.bin` 中,它将载入 GPU 固件代码,并启动 GPU进入第三级 bootloader。
3. GPU 固件:该阶段将运行 GPU 固件 `start.elf`,它会读取 `config.txt` 中的启动参数,并将内核镜像 `kernel8.img` 复制到 `0x80000` 上。
4. CPU 代码CPU 从 `0x80000` 处开始执行内核代码。
> 参考https://github.com/DieterReuter/workshop-raspberrypi-64bit-os/blob/master/part1-bootloader.md
## linker.ld
链接脚本位于 [kernel/src/arch/aarch64/boot/linker.ld](../../../kernel/src/arch/aarch64/boot/linker.ld),主要内容如下:
```
SECTIONS {
. = 0x80000; /* Raspbery Pi 3 AArch64 (kernel8.img) load address */
.boot : {
KEEP(*(.text.boot)) /* from boot.S */
}
. = 0x100000; /* Load the kernel at this address. It's also kernel stack top address */
bootstacktop = .;
.text : {
stext = .;
*(.text.entry)
*(.text .text.* .gnu.linkonce.t*)
. = ALIGN(4K);
etext = .;
}
/* ... */
}
```
几个要点:
* CPU 最先从 `.text.boot (0x80000)` 处开始执行。
* 在 [boot.S](../../../kernel/src/arch/aarch64/boot/boot.S) 中做好了必要的初始化后,将跳转到 `_start (0x100000)`,再从这里跳转到 Rust 代码 `rust_main()`
* [boot.S](../../../kernel/src/arch/aarch64/boot/boot.S) 的偏移为 `0x80000`Rust 代码的偏移为 `0x100000`
* 跳转到 `rust_main()` 后,`0x0~0x100000` 这段内存将被作为内核栈,大小为 1MB栈顶即 `bootstacktop (0x100000)`
* [boot.S](../../../kernel/src/arch/aarch64/boot/boot.S) 结束后还未启用 MMU可直接访问物理地址。
## boot.S
在 RustOS 中,内核将运行在 EL1 上,用户程序将运行在 EL0 上。
CPU 启动代码位于 [kernel/src/arch/aarch64/boot/boot.S](../../../kernel/src/arch/aarch64/boot/boot.S),负责初始化一些系统寄存器,并将当前异常级别切换到 EL1。
[boot.S](../../../kernel/src/arch/aarch64/boot/boot.S) 的主要流程如下:
1. 获取核的编号,目前只使用 0 号核,其余核将被闲置:
```armasm
.section .text.boot
boot:
# read cpu affinity, start core 0, halt rest
mrs x1, mpidr_el1
and x1, x1, #3
cbz x1, setup
halt:
# core affinity != 0, halt it
wfe
b halt
```
2. 读取当前异常级别:
```armasm
# read the current exception level into x0 (ref: C5.2.1)
mrs x0, CurrentEL
and x0, x0, #0b1100
lsr x0, x0, #2
```
3. 如果当前位于 EL3初始化一些 EL3 下的系统寄存器,并使用 `eret` 指令切换到 EL2
```armasm
switch_to_el2:
# switch to EL2 if we are in EL3. otherwise switch to EL1
cmp x0, #2
beq switch_to_el1
# set-up SCR_EL3 (bits 0, 4, 5, 7, 8, 10) (A53: 4.3.42)
mov x0, #0x5b1
msr scr_el3, x0
# set-up SPSR_EL3 (bits 0, 3, 6, 7, 8, 9) (ref: C5.2.20)
mov x0, #0x3c9
msr spsr_el3, x0
# switch
adr x0, switch_to_el1
msr elr_el3, x0
eret
```
4. 当前位于 EL2初值化 EL2 下的系统寄存器,并使用 `eret` 指令切换到 EL1
```armasm
switch_to_el1:
# switch to EL1 if we are not already in EL1. otherwise continue with start
cmp x0, #1
beq set_stack
# set the stack-pointer for EL1
msr sp_el1, x1
# set-up HCR_EL2, enable AArch64 in EL1 (bits 1, 31) (ref: D10.2.45)
mov x0, #0x0002
movk x0, #0x8000, lsl #16
msr hcr_el2, x0
# do not trap accessing SVE registers (ref: D10.2.30)
msr cptr_el2, xzr
# enable floating point and SVE (SIMD) (bits 20, 21) (ref: D10.2.29)
mrs x0, cpacr_el1
orr x0, x0, #(0x3 << 20)
msr cpacr_el1, x0
# Set SCTLR to known state (RES1: 11, 20, 22, 23, 28, 29) (ref: D10.2.100)
mov x0, #0x0800
movk x0, #0x30d0, lsl #16
msr sctlr_el1, x0
# set-up SPSR_EL2 (bits 0, 2, 6, 7, 8, 9) (ref: C5.2.19)
mov x0, #0x3c5
msr spsr_el2, x0
# enable CNTP for EL1/EL0 (ref: D7.5.2, D7.5.13)
# NOTE: This does not actually enable the counter stream.
mrs x0, cnthctl_el2
orr x0, x0, #3
msr cnthctl_el2, x0
msr cntvoff_el2, xzr
# switch
adr x0, set_stack
msr elr_el2, x0
eret
```
5. 当前位于 EL1设置栈顶地址为 `_start (0x100000)`,清空 BSS 段的数据:
```armasm
set_stack:
# set the current stack pointer
mov sp, x1
zero_bss:
# load the start address and number of bytes in BSS section
ldr x1, =sbss
ldr x2, =__bss_length
zero_bss_loop:
# zero out the BSS section, 64-bits at a time
cbz x2, zero_bss_loop_end
str xzr, [x1], #8
sub x2, x2, #8
cbnz x2, zero_bss_loop
zero_bss_loop_end:
b _start
```
6. 最后跳转到 Rust 代码 `rust_main()`
```armasm
.section .text.entry
.globl _start
_start:
# jump to rust_main, which should not return. halt if it does
bl rust_main
b halt
```
## rust_main
在 [boot.S](../../../kernel/src/arch/aarch64/boot/boot.S) 初始化完毕后,会进入 [kernel/src/arch/aarch64/mod.rs](../../../kernel/src/arch/aarch64/mod.rs#L19) 的 Rust 函数 `rust_main()`
```rust
/// The entry point of kernel
#[no_mangle] // don't mangle the name of this function
pub extern "C" fn rust_main() -> ! {
memory::init_mmu_early(); // Enable mmu and paging
board::init_serial_early();
crate::logging::init();
interrupt::init();
memory::init();
driver::init();
println!("{}", LOGO);
crate::process::init();
crate::kmain();
}
```
流程如下:
1. 建立临时页表,启动 MMU。
2. 初始化串口输入输出,可以使用 `println!()` 等宏了。
3. 初始化 logging 模块,可以使用 `info!()`、`error!()` 等宏了。
4. 初始化中断,其实就是设置了异常向量基址。
5. 初始化内存管理,包括物理页帧分配器与内核堆分配器,最后会建立一个新的页表重新映射内核。
6. 初始化其他设备驱动,包括 Frambuffer、Console、Timer。
7. 初始化进程管理,包括线程调度器、进程管理器,并为每个核建立一个 idle 线程,最后会加载 SFS 文件系统加入用户态 shell 进程。
8. 最后调用 `crate::kmain()`,按调度器轮流执行创建的线程。

@ -0,0 +1,226 @@
# 上下文切换
平台无关的代码位于 [kernel/src/process/context.rs](../../../kernel/src/process/context.rs) 中,而平台相关(aarch64)的代码位于 [kernel/src/arch/aarch64/interrupt/context.rs](../../../kernel/src/arch/aarch64/interrupt/context.rs) 中。
## 相关数据结构
在 [kernel/src/arch/aarch64/interrupt/context.rs](../../../kernel/src/arch/aarch64/interrupt/context.rs) 中定义了下列数据结构:
1. `TrapFrame`:
```rust
pub struct TrapFrame {
pub elr: usize,
pub spsr: usize,
pub sp: usize,
pub tpidr: usize, // currently unused
// pub q0to31: [u128; 32], // disable SIMD/FP registers
pub x1to29: [usize; 29],
pub __reserved: usize,
pub x30: usize, // lr
pub x0: usize,
}
```
在陷入异常时向栈中压入的内容,由 [trap.S](../../../kernel/src/arch/aarch64/interrupt/trap.S#L92) 的 `__alltraps` 构建。详见“中断与异常”相关章节。
2. `ContextData`:
```rust
struct ContextData {
x19to29: [usize; 11],
lr: usize,
}
```
执行上下文切换时向栈中压入的内容,由 `__switch()` 函数构建。仅需保存 callee-saved 寄存器(被调用者保存,即 `x19~x30`)。详见下节“切换流程”。
3. `InitStack`:
```rust
pub struct InitStack {
context: ContextData,
tf: TrapFrame,
}
```
对于新创建的线程,不仅要向栈中压入 `ContextData` 结构,还需手动构造 `TrapFrame` 结构。为了方便管理就定义了 `InitStack` 包含这两个结构体。
4. `Context`:
```rust
pub struct Context {
stack_top: usize,
ttbr: PhysFrame,
asid: Asid,
}
```
每个进程控制块 `Process` ([kernel/src/process/context.rs](../../../kernel/src/process/context.rs#L13)) 都会维护一个平台相关的 `Context` 对象,在 AArch64 中包含下列信息:
1. `stack_top`:内核栈顶地址
2. `ttbr`:页表基址
3. `asid`Address Space ID详见下文“页表切换与 ASID 机制”
## 切换流程
在 [kernel/src/process/context.rs](../../../kernel/src/process/context.rs#L22) 里,`switch_to()` 是平台无关的切换函数,最终会调用 [kernel/src/arch/aarch64/interrupt/context.rs](../../../kernel/src/arch/aarch64/interrupt/context.rs#L129) 里平台相关的切换函数 `Context::switch()`
```rust
pub unsafe fn switch(&mut self, target: &mut Self) {
target.asid = ASID_ALLOCATOR.lock().alloc(target.asid);
// with ASID we needn't flush TLB frequently
ttbr_el1_write_asid(1, target.asid.value, target.ttbr);
barrier::dsb(barrier::ISH);
Self::__switch(&mut self.stack_top, &mut target.stack_top);
}
```
### 页表切换与 ASID 机制
首先进行的是页表的切换,即向 `TTBR1_EL1` 寄存器写入目标线程页表基址 `target.ttbr`。一般来说,切换页表后需要刷新 TLB不过 ARMv8 引入了 ASID (Address Space ID) 机制来避免频繁刷新 TLB。
#### ASID 机制
在页表项描述符中,有一个 nG 位,如果该位为 0表示这页内存是全局可访问的(用于内核空间);如果该位为 1表示这页内存不是全局可访问的只有特定线程可访问。具体地如果页表项中该位为 1当访问相应虚拟地址更新 TLB 时,会有额外的信息被写入 TLB该信息即 ASID由操作系统分配下次在 TLB 中查找该虚拟地址时就会检查 TLB 表项中的 ASID 是否与当前 ASID 匹配。相当于为不同的 ASID 各自创建了一个页表。
ASID 的大小可以为 8 位或 16 位,由 `TCR_EL1` 的 AS 字段指定,当前的 ASID 保存在 TTBR 的高位中,也可以由 `TCR_EL1``A1` 字段指定是 `TTBR0_EL1` 还是 `TTBR1_EL1`。在 RustOS 中ASID 大小为 16 位,当前 ASID 保存在 `TTBR1_EL1` 的高 16 位。
`switch()` 函数里,首先会为目标线程分配一个 ASID然后同时将该 ASID 与 `target.ttbr` 写入 `TTBR1_EL1` 即可,无需进行 TLB 刷新。
#### ASID 的分配
ASID 的分配需要保证同一时刻不同线程的 ASID 是不同的。这一部分参考了 Linux主要思想是每次上下文切换时检查该线程原来的 ASID 是否有效,如果无效需要重新分配并刷新 TLB。
使用的数据结构如下:
```rust
struct Asid {
value: u16,
generation: u16,
}
struct AsidAllocator(Asid);
```
一个 ASID 结构由 16 位的 `value``generation` 组成,`value` 即 ASID 的具体值,`generation` 相当于时间戳。初始的 ASID 两个值都是 0一定是无效的。该结构也被用于实现 ASID 分配器 `AsidAllocator`,此时该结构表示上一个被分配出去的 ASID。
```rust
const ASID_MASK: u16 = 0xffff;
impl AsidAllocator {
fn new() -> Self {
AsidAllocator(Asid { value: 0, generation: 1 })
}
fn alloc(&mut self, old_asid: Asid) -> Asid {
if self.0.generation == old_asid.generation {
return old_asid;
}
if self.0.value == ASID_MASK {
self.0.value = 0;
self.0.generation = self.0.generation.wrapping_add(1);
if self.0.generation == 0 {
self.0.generation += 1;
}
tlb_invalidate_all();
}
self.0.value += 1;
return self.0;
}
}
```
分配的流程如下:
1. 判断 `old_asid` 是否等于 `self.0.generation`,如果相等说明这一代的 ASID 还是有效的,直接返回 `old_asid`
2. 否则,`old_asid` 已失效,如果当前代的 65535 个 ASID 没有分配完,就直接分配下一个。
3. 如果当前代的 65535 个 ASID 都分配完了,就开始新的一代,同时刷新 TLB。
### 寄存器与栈的切换
这一部分即 `Context``__switch()` 函数,传入的两个参数 `_self_stack``_target_stack` 是两个引用,分别用于保存**当前线程内核栈顶**与**目标线程内核栈顶**。
该函数用汇编实现(两个参数分别保存在 `x0``x1` 寄存器中)
```armasm
mov x10, #-(12 * 8)
add x8, sp, x10
str x8, [x0]
stp x19, x20, [x8], #16 // store callee-saved registers
stp x21, x22, [x8], #16
stp x23, x24, [x8], #16
stp x25, x26, [x8], #16
stp x27, x28, [x8], #16
stp x29, lr, [x8], #16
ldr x8, [x1]
ldp x19, x20, [x8], #16 // restore callee-saved registers
ldp x21, x22, [x8], #16
ldp x23, x24, [x8], #16
ldp x25, x26, [x8], #16
ldp x27, x28, [x8], #16
ldp x29, lr, [x8], #16
mov sp, x8
str xzr, [x1]
ret
```
流程如下:
1. 保存**当前栈顶** `sp``_self_stack` (`x0`),保存 **callee-saved 寄存器**到当前栈上。
2. 从 `_target_stack` (`x1`) 获取目标线程的**内核栈顶**,从目标线程内核栈顶恢复 **callee-saved 寄存器**
3. 将 `sp` 设为目标线程内核栈顶,将 `_target_stack` (`x1`) 里的内容清空。
4. 使用 `ret` 指令返回,这会跳转到目标线程 `lr` 寄存器中存放的地址。
为什么只保存了 `sp` 与 callee-saved 寄存器,而不是所有寄存器?因为执行上下文切换就是在调用一个函数,在调用前后编译器会自动保存并恢复 caller-saved 寄存器(调用者保存,即 `x0~x18`)。
### 异常级别切换
异常发生前的异常级别保存在 `TrapFrame``spsr` 的相应位,在异常返回后会恢复给 PSTATE实现异常级别切换。通过构造特定的 `spsr` 可让新线程运行在指定的异常级别。
## 创建新线程
线程可通过下列三种方式创建:
1. 创建新的**内核线程**:直接给出一个内核函数。
2. 创建新的**用户线程**:解析 ELF 文件。
3. 从一个线程 **fork** 出一个新线程:通过 `fork` 系统调用。
三种线程的平台无关创建流程实现在 [kernel/src/process/context.rs](../../../kernel/src/process/context.rs#L40) 里,最终会分别调用 [kernel/src/arch/aarch64/interrupt/context.rs](../../../kernel/src/arch/aarch64/interrupt/context.rs#L146) 里的 `new_kernel_thread()`、`new_user_thread()` 和 `new_fork()` 这三个函数创建平台相关的 `Context` 结构。
在这三个函数里,会构造 `ContextData``TrapFrame` 结构,构成一个 `InitStack`,并向新线程的内核栈压入 `InitStack` 结构,最后将新内核栈顶地址、页表基址等信息构成 `Context` 结构返回。这两个结构的构造方式如下:
* `ContextData`:
三种线程的初始 `ContextData` 结构都一样:清空 `x19~x29` 寄存器,将 `lr` 寄存器设为 `__trapret`,表示在 `__switch()` 结束后立即返回 `__trapret`,避免破坏构建好的栈帧结构。
* `TrapFrame`:
三种线程的 `TrapFrame` 各不相同:
1. 内核线程:
| `TrapFrame` 中的字段| 值 |
|---------------------|----------------------------------------|
| `x0` | 内核线程参数 `arg` |
| `sp` | 内核栈顶地址 `kstack_top` |
| `elr` | 内核线程入口函数 `entry` 的地址 |
| `spsr` | `0b1101_00_0101`,切换到 EL1启用 IRQ |
| 其他 | 清零 |
2. 用户线程:
| `TrapFrame` 中的字段| 值 |
|---------------------|----------------------------------------|
| `sp` | 用户栈顶地址 `ustack_top` |
| `elr` | 用户线程入口地址 `entry_addr` |
| `spsr` | `0b1101_00_0000`,切换到 EL0启用 IRQ |
| 其他 | 清零 |
注意用户线程是根据 ELF 文件创建的,参数即命令行参数,通过栈而不是寄存器传递。
3. fork 线程:直接复制父线程的 `TrapFrame`,并将 fork 的返回值 `x0` 设为 0。

@ -0,0 +1,604 @@
# 设备驱动
树莓派上有着丰富的外围设备(peripherals),物理地址空间 `0x3F000000~0x3FFFFFFF` 专门用于访问外围设备。
一个设备一般提供多个可供访问的 IO 地址,一般 4 字节对齐。将它们按给定的偏移构造结构体,并使用 crate [volatile](https://crates.io/crates/volatile) 抽象为一些寄存器,可方便地对这些 IO 地址进行读写,例如:
```rust
const INT_BASE: usize = IO_BASE + 0xB000 + 0x200;
#[repr(C)]
#[allow(non_snake_case)]
struct Registers {
IRQBasicPending: ReadOnly<u32>,
IRQPending: [ReadOnly<u32>; 2],
FIQControl: Volatile<u32>,
EnableIRQ: [Volatile<u32>; 2],
EnableBasicIRQ: Volatile<u32>,
DisableIRQ: [Volatile<u32>; 2],
DisableBasicIRQ: Volatile<u32>,
}
pub fn new() -> Controller {
Controller {
registers: unsafe { &mut *(INT_BASE as *mut Registers) },
}
}
```
这些外围设备的最底层驱动实现在 crate [bcm2837](../../../crate/bcm2837/) 中,包括:
* GPIO
* Interrupt
* Mini UART
* Mailbox
* Timer
一些稍微高级的与具体硬件板子相关的驱动实现在 [kernel/src/arch/aarch64/board/raspi3](../../../kernel/src/arch/aarch64/board/raspi3/) 中,包括:
* Framebuffer
* Mailbox property interface
* Serial
更高级的硬件无关的驱动实现在 [kernel/src/arch/aarch64/driver](../../../kernel/src/arch/aarch64/driver/) 中,包括:
* Console
## GPIO
> 参考BCM2837 ARM Peripherals: chapter 6, General Purpose I/O (GPIO).
目前 RustOS 中的 GPIO 驱动只是为了初始化 mini UART 而使用,实现在 crate [bcm2837](../../../crate/bcm2837/) 的 [gpio.rs](../../../crate/bcm2837/src/gpio.rs) 中。主要提供两个功能:
* 设置引脚模式
* 设置引脚上拉/下拉状态
### 设置引脚模式
引脚模式有 8 种:输入、输出与 alternative function 0~5。根据引脚编号向相应的 GPFSELx 寄存器的相应位写入模式代码即可。
```rust
pub fn into_alt(self, function: Function) -> Gpio<Alt> {
let select = (self.pin / 10) as usize;
let offset = 3 * (self.pin % 10) as usize;
self.registers.FSEL[select].update(|value| {
*value &= !(0b111 << offset);
*value |= (function as u32) << offset;
});
self.transition()
}
pub fn into_output(self) -> Gpio<Output> {
self.into_alt(Function::Output).transition()
}
pub fn into_input(self) -> Gpio<Input> {
self.into_alt(Function::Input).transition()
}
```
### 设置引脚上拉/下拉状态
引脚的上拉/下拉状态有 3 种:上拉(`10`)、下拉(`01`)与不拉(`00`)。设置该状态的流程如下:
1. 向 GPPUD 寄存器写入状态代码。
2. 等待 150 个时钟周期。
3. 根据引脚编号向相应的 GPPUDCLK0/1 寄存器的相应位写入 1。
4. 等待 150 个时钟周期。
5. 向 GPPUD 寄存器写入 0。
6. 根据引脚编号向相应的 GPPUDCLK0/1 寄存器的相应位写入 0。
```rust
pub fn set_gpio_pd(&mut self, pud_value: u8) {
let index = if self.pin >= 32 { 1 } else { 0 };
self.registers.PUD.write(pud_value as u32);
delay(150);
self.registers.PUDCLK[index as usize].write((1 << self.pin) as u32);
delay(150);
self.registers.PUD.write(0);
self.registers.PUDCLK[index as usize].write(0);
}
```
## Interrupt
> 参考BCM2837 ARM Peripherals: chapter 7, Interrupts.
该设备为其他外围设备提供异步异常(中断)支持,实现在 crate [bcm2837](../../../crate/bcm2837/) 的 [interrupt.rs](../../../crate/bcm2837/src/interrupt.rs) 中。目前只有对 IRQ 的支持,没有对 FIQ 的支持。
当中断发生时IRQ basic pending 寄存器中的某些位会被设置,表示哪个 basic IRQ 待处理(详见 BCM2837 ARM Peripherals 第 114 页的表)。如果其第 8 或 9 位被设置,则需要进一步到 IRQ pending 1/2 寄存器中去查找。此时共有 64 个中断,部分如下(详见第 113 页的表)
| 编号 | 中断 |
|--------|------------------|
| 1 | system timer 1 |
| 3 | system timer 3 |
| 9 | USB controller |
| 29 | Aux int |
| 49 | gpio[0] |
| 50 | gpio[1] |
| 51 | gpio[2] |
| 52 | gpio[3] |
| 57 | uart_int |
| ... | ... |
目前 RustOS 只支持上表中的 IRQ不支持其他 basic IRQ。在 RustOS 中用到了 System Timer 与 mini UART 的 IRQ分别为 system timer 1 (1) 与 Aux int (29)。
在 [kernel/src/arch/aarch64/board/raspi3/irq.rs](../../../kernel/src/arch/aarch64/board/raspi3/irq.rs#L23) 中实现了 IRQ 的注册,只需调用 `register_irq()` 函数绑定 IRQ 编号与处理函数,在 `handle_irq()` 里就会自动处理已注册的中断。
### 启用与禁用中断
只需分别向 Enable IRQs 1/2 和 Disable IRQs 1/2 寄存器的相应位写 1 即可:
```rust
pub fn enable(&mut self, int: Interrupt) {
self.registers.EnableIRQ[int as usize / 32].write(1 << (int as usize) % 32);
}
pub fn disable(&mut self, int: Interrupt) {
self.registers.DisableIRQ[int as usize / 32].write(1 << (int as usize) % 32);
}
```
### 获取待处理的中断
只需读取 IRQ pending 1/2 寄存器中的相应位,就能知道某一 IRQ 是否待处理:
```rust
pub fn is_pending(&self, int: Interrupt) -> bool {
self.registers.IRQPending[int as usize / 32].read() & (1 << (int as usize) % 32) != 0
}
```
此外也可将当前所有待处理的 IRQ 构成一个迭代器方便遍历:
```rust
pub struct PendingInterrupts(u64);
impl Iterator for PendingInterrupts {
type Item = usize;
#[inline]
fn next(&mut self) -> Option<Self::Item> {
let int = self.0.trailing_zeros();
if int < 64 {
self.0 &= !(1 << int);
Some(int as usize)
} else {
None
}
}
}
pub fn pending_interrupts(&self) -> PendingInterrupts {
let irq1 = self.registers.IRQPending[0].read() as u64;
let irq2 = self.registers.IRQPending[1].read() as u64;
PendingInterrupts((irq2 << 32) | irq1)
}
```
## Mini UART
> 参考BCM2837 ARM Peripherals: chapter 2, Auxiliaries: UART1 & SPI1, SPI2; chapter 6, General Purpose I/O (GPIO), page 101~102.
Mini UART 可用于树莓派与上位机直接的通信,一般被称为“串口”。该驱动实现简单,在没有显示器、键盘等驱动时是一种非常好的输入输出设备。
RustOS 中 mini UART 的驱动主要实现在 crate [bcm2837](../../../crate/bcm2837/) 的 [mini_uart.rs](../../../crate/bcm2837/src/mini_uart.rs) 中。在 [kernel/src/arch/aarch64/board/raspi3/serial.rs](../../../kernel/src/arch/aarch64/board/raspi3/serial.rs) 中将其封装为了一个 `SerialPort`,以便通过统一的接口调用。
### 初始化
初始化 mini UART 的流程如下:
1. 向 AUX_ENABLES 寄存器写 1启用 mini UART。
2. 将 GPIO 的 14/15 引脚都设为 alternative function ALT5 (TXD1/RXD1) 模式,并都设为不拉状态。
3. 配置 mini UART 参数:
1. 暂时禁用接收器与发送器。
2. 启用接收中断,禁用发送中断。
3. 设置数据大小为 8 bit。
4. 设置 RTS line 为 high。
5. 设置波特率为 115200。
6. 重新启用接收器与发送器。
```rust
pub fn init(&mut self) {
// Enable the mini UART as an auxiliary device.
unsafe { (*AUX_ENABLES).write(1) }
Gpio::new(14).into_alt(Function::Alt5).set_gpio_pd(0);
Gpio::new(15).into_alt(Function::Alt5).set_gpio_pd(0);
self.registers.AUX_MU_CNTL_REG.write(0); // Disable auto flow control and disable receiver and transmitter (for now)
self.registers.AUX_MU_IER_REG.write(1); // Enable receive interrupts and disable transmit interrupts
self.registers.AUX_MU_LCR_REG.write(3); // Enable 8 bit mode
self.registers.AUX_MU_MCR_REG.write(0); // Set RTS line to be always high
self.registers.AUX_MU_BAUD_REG.write(270); // Set baud rate to 115200
self.registers.AUX_MU_CNTL_REG.write(3); // Finally, enable transmitter and receiver
}
```
### 读
```rust
pub fn has_byte(&self) -> bool {
self.registers.AUX_MU_LSR_REG.read() & (LsrStatus::DataReady as u8) != 0
}
pub fn read_byte(&self) -> u8 {
while !self.has_byte() {}
self.registers.AUX_MU_IO_REG.read()
}
```
### 写
```rust
pub fn write_byte(&mut self, byte: u8) {
while self.registers.AUX_MU_LSR_REG.read() & (LsrStatus::TxAvailable as u8) == 0 {}
self.registers.AUX_MU_IO_REG.write(byte);
}
```
## Timer
BCM283x 系列可用下列三种不同的时钟:
* System TimerBCM2837 ARM Peripherals 第 12 章IO 基地址为 `0x3F003000`,最常用的时钟,但是在 QEMU 中不可用。
* ARM TimerBCM2837 ARM Peripherals 第 14 章IO 基地址为 `0x3F00B400`,在 QEMU 中也不可用RustOS 并未实现。
* Generic TimerARMv8 Reference Manual 第 D10 章,通过 AArch64 系统寄存器访问 CPU 的时钟,外围设备只提供了中断控制(IO 基地址为 `0x40000000`),可同时在 QEMU 与真机上使用。
时钟主要实现在 crate [bcm2837](../../../crate/bcm2837/) 的 [timer](../../../crate/bcm2837/src/timer) 模块中。可以指定 crate bcm2837 的 feature `use_generic_timer` 来选择是否使用 Generic Timer。在 [mod.rs](../../../crate/bcm2837/src/timer/mod.rs#L12) 中提供了以下 `trait`,具体的时钟驱动需要实现这些函数:
```rust
/// The Raspberry Pi timer.
pub trait BasicTimer {
/// Returns a new instance.
fn new() -> Self;
/// Initialization timer.
fn init(&mut self);
/// Reads the timer's counter and returns the 64-bit counter value.
/// The returned value is the number of elapsed microseconds.
fn read(&self) -> u64;
/// Sets up a match in timer 1 to occur `us` microseconds from now. If
/// interrupts for timer 1 are enabled and IRQs are unmasked, then a timer
/// interrupt will be issued in `us` microseconds.
fn tick_in(&mut self, us: u32);
/// Returns `true` if timer interruption is pending. Otherwise, returns `false`.
fn is_pending(&self) -> bool;
}
```
在 [kernel/src/arch/aarch64/board/raspi3/timer.rs](../../../kernel/src/arch/aarch64/board/raspi3/timer.rs) 中对这些函数进行了简单封装。在 [kernel/src/arch/aarch64/board/raspi3/irq.rs](../../../kernel/src/arch/aarch64/board/raspi3/irq.rs#L9) 的 `handler_irq()` 函数中处理了时钟中断:
```rust
let controller = bcm2837::timer::Timer::new();
if controller.is_pending() {
super::timer::set_next();
crate::trap::timer();
}
```
### System Timer
> 参考BCM2837 ARM Peripherals: chapter 12, System Timer.
System Timer 通过 CS、CLO、CHI 等 IO 地址访问时钟,通过上文 Interrupt 节描述的 IRQ 控制器提供中断(IRQ 编号为 system timer 1)。实现方式如下:
* 初始化:使用 [interrupt](../../../crate/bcm2837/src/interrupt.rs#L68) 模块的 `enable()` 函数启用 system timer 1 IRQ。
* 当前时刻:分别读取时钟计数器的高、低 32 位(CLO、CHI),再拼接起来得到 64 位计数器值(单位微秒)。
* 设置下一次中断的时刻:向 System Timer Compare 1 (C1) 寄存器写入当前计数器值加上时间间隔,同时向 System Timer Control/Status (CS) 寄存器的第 1 位写入 1 表示当前的中断已被处理好。
* 判断是否有时钟中断:使用 [interrupt](../../../crate/bcm2837/src/interrupt.rs#L78) 模块的 `is_pending()` 函数。
```rust
fn init(&mut self) {
Controller::new().enable(Interrupt::Timer1);
}
fn read(&self) -> u64 {
let low = self.registers.CLO.read();
let high = self.registers.CHI.read();
((high as u64) << 32) | (low as u64)
}
fn tick_in(&mut self, us: u32) {
let current_low = self.registers.CLO.read();
let compare = current_low.wrapping_add(us);
self.registers.COMPARE[SystemTimerId::Timer1 as usize].write(compare);
self.registers.CS.write(1 << (SystemTimerId::Timer1 as usize)); // unmask
}
fn is_pending(&self) -> bool {
let controller = Controller::new();
controller.is_pending(Interrupt::Timer1)
}
```
### Generic Timer
> 参考:
> 1. ARMv8 Reference Manual: chapter D10, The Generic Timer in AArch64 state.
> 2. BCM2836 ARM-local peripherals (Quad-A7 control): section 4.6, Core timers interrupts; section 4.10, Core interrupt sources.
RustOS 实现的 Generic Timer 是 CPU 在 EL1 下的 Physical Timer可通过下列 AArch64 系统寄存器访问:
| Generic Timer 系统寄存器 | 名称 | 描述 |
|----------------------------|----------------------------------------------------|------------------------------------------------|
| `CNTFRQ_EL0` | Counter-timer Frequency register | 获取时钟的频率,单位 Hz典型的值为 62.5 MHz |
| `CNTP_CTL_EL0` | Counter-timer Physical Timer Control register | 控制 Physical Timer 是否启用,中断是否屏蔽等 |
| `CNTP_TVAL_EL0` | Counter-timer Physical Timer TimerValue register | 下一次时钟中断要再经过多少时钟周期。每当时钟计数器增加 1该值就会减少 1如果该值为 0 了就会触发时钟中断 |
| `CNTPCT_EL0` | Counter-timer Physical Count register | 获取时钟计数器的值 |
而 Generic Timer 的中断控制器需要通过 `0x40000000` 开始的那些 IO 地址访问。Generic Timer 实现方式如下:
* 初始化:将 `CNTP_CTL_EL0` 寄存器的 ENABLE 位置为 1启用 CPU Physical Timer将 Core0 timers Interrupt control 的 CNTPNSIRQ 位置为 1开启中断。
* 当前时刻:读取 `CNTPCT_EL0` 寄存器获得当前时钟计数器的值,再与时钟频率 `CNTFRQ_EL0` 经过简单的换算即能得到以微秒为单位的当前时刻。
* 设置下一次中断的时刻:向 `CNTP_TVAL_EL0` 寄存器写入时间间隔对应的时钟周期数。
* 判断是否有时钟中断:判断 Core0 IRQ Source 的 CNTPNSIRQ 位是否为 1。
```rust
fn init(&mut self) {
self.registers.CORE_TIMER_IRQCNTL[0].write(1 << (CoreInterrupt::CNTPNSIRQ as u8));
CNTP_CTL_EL0.write(CNTP_CTL_EL0::ENABLE::SET);
}
fn read(&self) -> u64 {
let cntfrq = CNTFRQ_EL0.get(); // 62500000
(CNTPCT_EL0.get() * 1000000 / (cntfrq as u64)) as u64
}
fn tick_in(&mut self, us: u32) {
let cntfrq = CNTFRQ_EL0.get(); // 62500000
CNTP_TVAL_EL0.set(((cntfrq as f64) * (us as f64) / 1000000.0) as u32);
}
fn is_pending(&self) -> bool {
self.registers.CORE_IRQ_SRC[0].read() & (1 << (CoreInterrupt::CNTPNSIRQ as u8)) != 0
}
```
## Mailbox
> 参考https://github.com/raspberrypi/firmware/wiki/Mailboxes
Mailbox 是树莓派上 ARM CPU 与 VideoCore IV GPU 之间通信的渠道。Mailbox 能够识别一段按特定格式存储的请求指令包含请求代码、请求长度、请求参数等信息GPU 会根据请求的指令完成相应的操作,并将结果写在原处。
BCM283x 系列有两个 mailbox一般 MB0 总是用于 GPU 向 CPU 发送消息 MB1 总是用于 CPU 向 GPU 发送消息,对 CPU 来说即一个只读一个只写。
Mailbox 有若干通道(channels),不同通道提供不同种类的功能。一般使用 property tags 通道(编号为 8),即 mailbox property interface。
### 基本读写
> 参考https://github.com/raspberrypi/firmware/wiki/Accessing-mailboxes
对 mailbox 的基本读写实现在 crate [bcm2837](../../../crate/bcm2837/) 的 [mailbox.rs](../../../crate/bcm2837/src/mailbox.rs) 中。一般一次操作是向 mailbox 写入请求的地址,然后读 mailbox 来轮询等待操作完成。注意读写 mailbox 时只有数据的高 28 位有效,低 4 位被用于存放通道,所以如果写入的是一个地址则该地址必须 16 字节对齐。
读的流程如下:
1. 读状态寄存器 MAIL0_STA直到 empty 位没有被设置。
2. 从 MAIL0_RD 寄存器读取数据。
3. 如果数据的最低 4 位不与要读的通道匹配,则回到 1。
4. 否则返回数据的高 28 位。
```rust
pub fn read(&self, channel: MailboxChannel) -> u32 {
loop {
while self.registers.MAIL0_STA.read() & (MailboxStatus::MailboxEmpty as u32) != 0 {}
let data = self.registers.MAIL0_RD.read();
if data & 0xF == channel as u32 {
return data & !0xF;
}
}
}
```
写的流程如下:
1. 读状态寄存器 MAIL1_STA直到 full 位没有被设置。
2. 将数据(高 28 位)与通道(低 4 位)拼接,写入 MAIL1_WRT 寄存器。
```rust
pub fn write(&mut self, channel: MailboxChannel, data: u32) {
while self.registers.MAIL1_STA.read() & (MailboxStatus::MailboxFull as u32) != 0 {}
self.registers.MAIL1_WRT.write((data & !0xF) | (channel as u32));
}
```
### Mailbox property interface
> 参考https://github.com/raspberrypi/firmware/wiki/Mailbox-property-interface
Mailbox property interface 提供了丰富的访问底层硬件的接口包括电源、温度、DMA、GPU、内存、Framebuffer 等模块。RustOS 中封装了一系列 mailbox property interface 函数,实现在 [kernel/src/arch/aarch64/board/raspi3/mailbox.rs](../../../kernel/src/arch/aarch64/board/raspi3/mailbox.rs) 中。
向 mailbox property interface 发送的请求需要符合一定的格式。在 RustOS 中,对 mailbox property interface 的一个功能调用被称为一个 `PropertyMailboxTag`,格式如下:
```rust
#[repr(C, packed)]
struct PropertyMailboxTag<T: Sized> {
id: PropertyMailboxTagId,
buf_size: u32,
req_resp_size: u32,
buf: T,
}
```
这里的 `buf` 一般是一个 32 位无符号整数的数组。一个或多个 `PropertyMailboxTag` 可构成一个 `PropertyMailboxRequest`,这是最终需要向 mailbox 发送的请求,格式如下:
```rust
#[repr(C, packed)]
struct PropertyMailboxRequest<T: Sized> {
buf_size: u32,
req_resp_code: PropertyMailboxStatus,
buf: T,
end_tag: PropertyMailboxTagId,
}
```
这里的 `buf` 可以是多个大小不一的 `PropertyMailboxTag` 构成的数组,不过内存布局必须连续而没有空隙。
为了方便构造这两个结构体,定义了宏 `send_one_tag!()``send_request!()`
* `send_request!($tags: ident)`:发送一个或多个 `PropertyMailboxTag`。这会构建一个 16 字节对齐的 `PropertyMailboxRequest` 结构体,将其地址写入 mailbox。等待 GPU 操作完毕后,返回被修改过的 `PropertyMailboxTag` 列表。
* `send_one_tag!($id: expr, [$($arg: expr),*])`:这会根据 `id` 与 32 位无符号整数的数组构造一个 `PropertyMailboxTag` 结构体,然后通过宏 `send_request!()` 发送给 mailbox返回被修改过的数组。
有了这两个宏,就可以非常方便地实现所需的 mailbox property interface 功能了。例如获取 framebuffer 物理分辨率:
```rust
pub fn framebuffer_get_physical_size() -> PropertyMailboxResult<(u32, u32)> {
let ret = send_one_tag!(RPI_FIRMWARE_FRAMEBUFFER_GET_PHYSICAL_WIDTH_HEIGHT, [0, 0])?;
Ok((ret[0], ret[1]))
}
```
`framebuffer_alloc()` 函数是一次性发送多个大小不一的 `PropertyMailboxTag` 的例子。
需要注意的是,当启用 MMU 与 cache 后,在访问 mailbox 的前后都需要刷新整个 `PropertyMailboxRequest` 结构的数据缓存,因为这里涉及到 GPU 与 CPU 的数据共享,必须时刻保证主存与 cache 中数据的一致性。
## Framebuffer
Framebuffer 是一块内存缓存区,树莓派的 GPU 会将其中的数据转换为 HDMI 信号输出给显示器。Framebuffer 的底层访问接口通过 mailbox property interface 实现。在 RustOS 中,树莓派的 framebuffer 实现在 [kernel/src/arch/aarch64/board/raspi3/fb.rs](../../../kernel/src/arch/aarch64/board/raspi3/fb.rs) 中。
### 相关数据结构
[fb.rs](../../../kernel/src/arch/aarch64/board/raspi3/fb.rs) 中定义了下列结构体:
* `FramebufferInfo`framebuffer 的信息,包括:
+ 实际可见的分辨率 `xres`、`yres`
+ 虚拟的分辨率 `xres_virtual`、`yres_virtual`
+ 位置偏移 `xoffset`、`yoffset`
+ 颜色深度 `depth`
+ 一行的字节数 `pitch`
+ GPU 总线地址 `bus_addr`
+ 大小 `screen_size`
* `ColorDepth`:表示颜色深度的枚举值,目前支持 16 位和 32 位颜色深度。
* `ColorBuffer`:一个 union 类型,可将同一个 framebuffer 基址解析为下列三种类型:
+ 一个 32 位无符号整数,表示 framebuffer 基址的虚拟地址。
+ 一个类型为 16 位整数,大小为 framebuffer 分辨率的数组,表示 16 位颜色深度下的每个像素点。
+ 一个类型为 32 位整数,大小为 framebuffer 分辨率的数组,表示 32 位颜色深度下的每个像素点。
```rust
union ColorBuffer {
base_addr: usize,
buf16: &'static mut [u16],
buf32: &'static mut [u32],
}
```
该 union 还提供了 `read16()`、`write16()`、`read32()`、`write32()` 等函数用于直接读写不同颜色深度下的 framebuffer。
* `Framebuffer`:具体的 framebuffer 结构体:
```rust
pub struct Framebuffer {
pub fb_info: FramebufferInfo,
pub color_depth: ColorDepth,
buf: ColorBuffer,
}
```
### 初始化
Framebuffer 在函数 `Framebuffer::new()` 中初始化。流程如下:
1. 通过 mailbox property interface获取 framebuffer 物理分辨率、颜色深度等信息。也可以不获取,而是手动设置。
2. 设置好相关参数,调用 `mailbox::framebuffer_alloc()` 由 GPU 分配 framebuffer构造出 `FramebufferInfo` 结构体。
3. 将 framebuffer GPU 总线地址转换为物理内存地址,然后调用 `memory::ioremap()` 将这段内存做对等映射,内存属性为 NormalNonCacheable。
4. 构造出 `Framebuffer` 结构体并返回。
### 读写
可通过 `Framebuffer::read()``Framebuffer::write()` 函数读取 framebuffer 中的一个像素,或写入一个像素。
为了提升连续区域读写的速度,还实现了 `Framebuffer::copy()``Framebuffer::fill()` 函数,分别用于拷贝一块区域、将一块区域都置为同一颜色。具体做法是将连续几个像素拼成一个 64 位整数,以减少访存次数。
`Framebuffer::clear()` 函数用于将屏幕清空(黑屏)。
## Console
有了 framebuffer就可以将显示器作为输出设备显示字符了。为此
Console (控制台) 是一个平台无关的抽象输出设备,表示屏幕上要显示的字符矩阵。该设备负责将字符转成像素点写入 framebuffer 中,以实现显示器中字符的显示,并支持颜色、字体等多种效果。
Console 驱动实现在模块 [kernel/src/arch/aarch64/driver/console](../../../kernel/src/arch/aarch64/driver/console/) 中,依赖 framebuffer包含下面几部分
1. 控制台主体([mod.rs](../../../kernel/src/arch/aarch64/driver/console/mod.rs))
2. 颜色([color.rs](../../../kernel/src/arch/aarch64/driver/console/color.rs))
3. 字体([fonts](../../../kernel/src/arch/aarch64/driver/console/fonts))
4. ANSI 转移序列解析器([escape_parser.rs](../../../kernel/src/arch/aarch64/driver/console/escape_parser.rs))
### 控制台主体
包含下列结构体:
* `ConsoleChar`:控制台中的字符,由 ASCII 码 `ascii_char` 与字符属性 `attr` (详见下节“ANSI 转移序列解析器”)构成。
* `ConsoleBuffer`:控制台字符缓冲区,是一个 `num_row``num_col` 列,元素类型是 `ConsoleChar` 的二维数组。主要包含以下函数:
+ `write()`:向 `(row, col)` 处写入一个字符 `ch`。这会根据给定的字体与字符属性,将字符转成像素点呈现在 framebuffer 上。
+ `new_line()`:向字符缓冲区的底部插入一个新行,并将原来的内容都向上平移一行。在真机上测试时,发现 framebuffer 读的速度非常慢,所以没有用 `Framebuffer::copy()` 函数直接拷贝 framebuffer 内容,而是根据新的字符缓冲区重新绘制。
+ `clear()`:清空屏幕与字符缓冲区内容。
* `Console`:具体的控制台结构体,通过传入的字体泛型 `<F: Font>` 构造,包含当前光标位置 `(row, col)`、 ANSI 转移序列解析器 `parser` 以及控制台字符缓冲区 `buffer`,主要包含以下函数:
+ `new()`:根据 `FramebufferInfo` 新建一个 `Console` 对象。当前字体下字符的高、宽与 framebuffer 分辨率将决定字符缓冲区的大小。
+ `write_byte()`:向当前光标位置处写入一个字符。这会根据具体是什么字符进行相应的操作,包括:直接显示该字符、换行、删除前一个字符、传给转移序列解析器。
+ `new_line()`:换行。如果当前光标位于字符缓冲区最底部则会调用 `ConsoleBuffer::new_line()` 移动屏幕内容。
+ `clear()`:清空并初始化。
此外,`Console` 实现了 trait `fmt::Write``write_str()` 函数,这样就可以用 `write_fmt()` 格式化输出了。
### 颜色
该模块定义了 16 种颜色(8 种标准颜色与 8 种高亮的标准颜色),并提供了将 RGB 值转换为 framebuffer 可识别的 16/32 位像素值的方法。
### 字体
该模块定义了统一的字体接口:
```rust
pub trait Font {
const HEIGHT: usize;
const WIDTH: usize;
/// the `y` coordinate of underline.
const UNDERLINE: usize;
/// the `y` coordinate of strikethrough.
const STRIKETHROUGH: usize;
/// Whether the character `byte` is visible at `(x, y)`.
fn get(byte: u8, x: usize, y: usize) -> bool;
}
```
添加一种字体只需实现该 trait 即可,支持下划线与删除线。目前内置了一种 8x16 的字体(直接从 linux 中拷贝而来,[CP437 编码](https://en.wikipedia.org/wiki/Code_page_437))。
### ANSI 转移序列解析器
> 参考https://en.wikipedia.org/wiki/ANSI_escape_code
为了在控制台上支持文字颜色等选项RustOS 实现了一个简易的 ANSI 转移序列(ANSI escape sequences)解析器可识别标准的ANSI 转移序列并呈现在屏幕上,支持下列 SGR (Select Graphic Rendition) 字符属性:
| SGR 代码 | 效果 |
|------------|------------------------|
| 0 | 重置为默认 |
| 4 | 下划线 |
| 7 | 反转前景与背景色 |
| 9 | 删除线 |
| 24 | 取消下划线 |
| 27 | 取消反转前景与背景色 |
| 29 | 取消删除线 |
| 30~37 | 设置前景色 |
| 40~47 | 设置背景色 |
| 90~97 | 设置高亮前景色 |
| 100~107 | 设置高亮背景色 |
具体实现时,结构体 `EscapeParser` 维护了一个状态机,通过 `parse()` 函数传入一个字符,转移状态,解析出 SGR 参数并更新当前字符属性;通过 `char_attribute()` 函数获取当前的字符属性。
目前显示效果与在终端下使用 `screen` 获取串口输出的效果一致,如在 QEMU 中运行 `fantastic_text` 测例的效果如下:
![](img/fantastic-text.png)

@ -0,0 +1,100 @@
# 环境配置
## 软件需求
* [Rust](https://www.rust-lang.org/) nightly 编译器
```
curl https://sh.rustup.rs -sSf | sh
rustup component add rust-src
```
* Cargo tools: [cargo-xbuild](https://github.com/rust-osdev/cargo-xbuild)
```
cargo install cargo-xbuild
```
* [QEMU](https://www.qemu.org/) >= 3.0.0
* [AArch64 GNU toolchain](https://web.stanford.edu/class/cs140e/assignments/0-blinky/)
+ macOS: 从 [homebrew](https://brew.sh/) 安装:
```
brew tap SergioBenitez/osxct
brew install aarch64-none-elf
```
+ Linux: 下载 [aarch64-none-elf-linux-x64.tar.gz](https://web.stanford.edu/class/cs140e/files/aarch64-none-elf-linux-x64.tar.gz) 并解压到任意目录。
## 硬件需求
* 1 块 Raspberry Pi 3 Model A+/B/B+
* 1 块 4GB 及以上的 microSD 卡与读卡器
* 1 个 CP2102 USB 转 TTL 模块
* 若干杜邦线
## 在模拟器中运行
* 构建并运行
```
git clone https://github.com/wangrunji0408/RustOS.git --recursive
cd RustOS/kernel
rustup override set nightly
make run arch=aarch64 [board=raspi3]
```
* 使用 GDB 调试
```
make debug arch=aarch64
```
* 反汇编
```
make asm arch=aarch64
```
* 更多 Makefile 选项
* `mode=debug|release`:指定 `debug` 还是 `release` 模式。默认 `debug`
* `graphic=on|off`:是否启用图形输出。默认 `on`
* `smp=1|2|3|4|...`:指定 SMP 的核数。目前 AArch64 的 SMP 未实现,该选项无效。
* `raspi3_timer=system|generic`:使用 Raspberry Pi 的 System Timer 还是 Generic Timer。默认 `generic`,且在 QEMU 中只能使用 Generic Timer。
* `prefix=<prefix>`:指定 AArch64 工具链前缀。默认 `aarch64-none-elf-`,某些 Linux 中的工具链前缀为 `aarch64-linux-gnu-`
* `LOG=off|error|warn|info|debug|trace`:指定输出日志的级别。默认 `warn`
* `SFSIMG=<sfsimg>`:用户程序 SFS 镜像路径。默认 `../user/img/ucore-aarch64.img`,即用 C 语言编写的直接从原 uCore 中移植过来的用户程序。如欲使用 Rust 编写的用户程序可将其设为 `../user/build/user-aarch64.img`
## 在真机上运行
1. 往 SD 卡中写入 [Raspbian](https://www.raspberrypi.org/downloads/raspbian/) 原版系统镜像:直接看 <https://www.raspberrypi.org/documentation/installation/installing-images>。然后需要将原版的 `config.txt` 替换为 [tools/raspi-firmware/config.txt](../../../tools/raspi-firmware/config.txt)。
2. 写入 RustOS 内核镜像:
```
make install arch=aarch64
```
3. 连接 Raspberry Pi、CP2102 模块与 PC
![](img/usb-ttl-pi3.png)
注意最好使用 Raspberry Pi 自带的电源适配器供电,而不要用 CP2102 模块的 +5V 供电(即不用连上图中的红线)。
4. 使用 [screen](https://www.gnu.org/software/screen/manual/screen.html#Overview) 与串口进行通信:
```
screen /dev/<your-path> 115200
```
在 macOS 中 CP2102 模块的设备路径一般为 `/dev/tty.SLAB_USBtoUART`,在 Linux 中一般为 `/dev/ttyUSB0`
5. 插入 SD 卡,上电,看终端的输出结果。如果连接了 Raspberry Pi 的 HDMI 接口与显示器,还能看到显示器中有输出。
## 实用技巧
1. 从 QEMU 中退出:按 `<ctrl-a> c`,再输入 `q`
2. 从 screen 中退出:按 `<ctrl-a> k`,再输入 `y`

Binary file not shown.

After

Width:  |  Height:  |  Size: 125 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 120 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 342 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 163 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 182 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 54 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 60 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 30 KiB

@ -0,0 +1,229 @@
# 中断与异常
## AArch64 异常模型
> 参考ARMv8 Reference Manual: chapter D1.1, D1.7, D1.10, D1.11, D1.13, D1.14, D1.16.
在 AArch64 中,各种中断被统称为**异常**(exception),包括:
* Reset.
* Interrupts.
* Memory system aborts.
* Undefined instructions.
* Supervisor calls (SVCs), Secure Monitor calls (SMCs), and hypervisor calls (HVCs).
* Debug exceptions.
这些异常可分为**同步异常**(synchronous exception)与**异步异常**(asynchronous exception)两大类:
* 同步异常:发生在执行一条特定的指令时,包括执行系统调用指令(`svc`、`hvc`)、断点指令(debug exceptions)、Instruction Aborts、Data Aborts 等。
* 异步异常:发生的时机不确定,又被称为**中断**(interrupt),是发送给处理机的信号,包括 SError、IRQ、FIQ 等。
### 异常处理
当发生异常时CPU 会根据异常的类型,跳转到特定的地址执行,该地址被称为**异常向量**(exception vector)。
不同类型异常的异常向量通过统一的**向量基地址寄存器**(Vector Base Address Register, VBAR)加上不同的偏移得到。在 EL1、EL2、EL3 下各有一个 VBAR 寄存器 `VBAR_ELx`。此时异常被分为 4 大类,每一类根据异常来源的不同又可分为 4 类,于是共有 16 个异常向量。
4 种类型的异常分别为:
1. Synchronous exception
2. IRQ (Interrupt Request)
3. FIQ (Fast Interrupt Request)
4. SError (System Error)
4 种异常来源分为:
1. Current Exception level with `SP_EL0`. 即发生异常时的异常级别与当前(指跳转到异常向量后)一样,且 `SP = SP_EL0` (`SPsel = 0`)。
2. Current Exception level with `SP_ELx`, `x>0`. 即发生异常时的异常级别与当前一样,且 `SP = SP_ELx` (`SPsel = 1`)。
3. Lower Exception level, where the implemented level immediately lower than the target level is using AArch64. 即发生异常时的异常级别低于当前级别,且运行于 AArch64 模式。
4. Lower Exception level, where the implemented level immediately lower than the target level is using AArch32. 即发生异常时的异常级别低于当前级别,且运行于 AArch32 模式。
16 种异常对应的异常向量相对于 VBAR 的偏移如下表所示:
| Exception taken from | Synchronous | IRQ | FIQ | SError |
|----------------------|-------------|---------|---------|---------|
| CurrentSpEl0 | `0x000` | `0x080` | `0x100` | `0x180` |
| CurrentSpElx | `0x200` | `0x280` | `0x300` | `0x380` |
| LowerAArch64 | `0x400` | `0x480` | `0x500` | `0x580` |
| LowerAArch32 | `0x600` | `0x680` | `0x700` | `0x780` |
如果该异常是 Synchronous 或 SError**异常症状寄存器**(Exception Syndrome Register, ESR)将被设置,用于记录具体的异常类别 EC (exception class) 与 ISS (Instruction Specific Syndrome)。在 EL1、EL2、EL3 下各有一个 ESR 寄存器 `ESR_ELx`。具体的 EC、ISS 编码见官方文档 ARMv8 Reference Manual D1.10.4 节。
### 异常屏蔽
某些异常可以被**屏蔽**(mask),即发生时不跳转到相应的异常向量。可被屏蔽的异常包括所有异步异常与调试时的同步异常(debug exceptions),共 4 种,分别由 PSTATE 中 `DAIF` 字段的 4 个位控制:
1. `D`: Debug exception
2. `A`: SError interrupt
3. `I`: IRQ interrupt
4. `F`: FIQ interrupt
### 异常返回
当发生异常时,异常返回地址会被设置,保存在**异常链接寄存器**(Exception Link Register, ELR) `ELR_ELx` 中;当前的**进程状态 PSTATE** 会保存在**保存的进程状态寄存器**(Saved Process Status Register, SPSR) `SPSR_ELx` 中。
异常返回使用 **`eret`** 指令完成。当异常返回时,`pc` 会根据当前特权级被恢复为 `ELR_ELx` 中的PSTATE 也会被恢复为 `SPSR_ELx` 中的。通过修改 `SPSR_ELx` 中相应的位并进行异常返回,就能使 PSTATE 被修改,从而实现异常级别切换、异常开启/屏蔽等功能。
### 系统调用
一般使用 **`svc`** 指令(supervisor call)完成,将触发一个同步异常。
## RustOS 中的实现
中断与异常部分的代码主要位于模块 [kernel/src/arch/aarch64/interrupt](../../../kernel/src/arch/aarch64/interrupt/) 中。
### 异常启用与屏蔽
在 [interrupt/mod.rs](../../../kernel/src/arch/aarch64/interrupt/mod.rs#L24) 中,通过写入 `DAIFClr``DAIFSet` 特殊寄存器修改 PSTATE分别实现了异常的启用与屏蔽(仅针对 IRQ),代码如下:
```rust
/// Enable the interrupt (only IRQ).
#[inline(always)]
pub unsafe fn enable() {
asm!("msr daifclr, #2");
}
/// Disable the interrupt (only IRQ).
#[inline(always)]
pub unsafe fn disable() {
asm!("msr daifset, #2");
}
```
此外,也可在异常返回前修改保存的 `SPSR_EL1` 寄存器,使得异常返回时 PSTATE 改变,从而实现启用或屏蔽异常,详见 [interrupt/context.rs](../../../kernel/src/arch/aarch64/interrupt/context.rs#L26) 中的 `TrapFrame::new_kernel_thread()``TrapFrame::new_user_thread()` 函数。
### 异常向量
全局符号 `__vectors` 定义了异常向量基址,并在 [interrupt/mod.rs](../../../kernel/src/arch/aarch64/interrupt/mod.rs#L13) 的 `init()` 函数中通过 `msr vbar_el1, x0` 指令,将 `VBAR_EL1` 设为了 `__vectors`
16 个异常向量分别通过宏 `HANDLER source kind` 定义在 [interrupt/vector.S](../../../kernel/src/arch/aarch64/interrupt/vector.S) 中,代码如下:
```armasm
.macro HANDLER source kind
.align 7
stp lr, x0, [sp, #-16]!
mov x0, #\source
movk x0, #\kind, lsl #16
b __alltraps
.endm
```
不同的异常向量对应的异常处理例程结构相同,仅有 `source``kind` 不同。`source` 与 `kind` 将会被合并成一个整数并存到寄存器 `x0` 中,以便作为参数传给 Rust 编写的异常处理函数。
由于不同异常向量的间距较少(仅为 `0x80` 字节),所以不在 `HANDLER` 中做细致的处理,而是统一跳转到 [trap.S](../../../kernel/src/arch/aarch64/interrupt/trap.S#L92) 的 `__alltraps` 中进行处理。
### 异常处理
统一异常处理例程 `__alltraps` 的代码如下:
```armasm
.global __alltraps
__alltraps:
SAVE_ALL
# x0 is set in HANDLER
mrs x1, esr_el1
mov x2, sp
bl rust_trap
.global __trapret
__trapret:
RESTORE_ALL
eret
```
流程如下:
1. 首先通过宏 `SAVE_ALL` 保存各寄存器,构成 `TrapFrame`
2. 然后构造函数参数 `x0`、`x1`、`x2`,分别表示异常类型、异常症状 ESR、`TrapFrame`,并调用 Rust 异常处理函数 `rust_trap()`
3. 当该函数返回时,通过宏 `RESTORE_ALL``TrapFrame` 中恢复各寄存器。
4. 最后通过 `eret` 指令进行异常返回。
`TrapFrame` 定义在 [interrupt/context.rs](../../../kernel/src/arch/aarch64/interrupt/context.rs#L12)中,结构如下:
```rust
pub struct TrapFrame {
pub elr: usize,
pub spsr: usize,
pub sp: usize,
pub tpidr: usize, // currently unused
// pub q0to31: [u128; 32], // disable SIMD/FP registers
pub x1to29: [usize; 29],
pub __reserved: usize,
pub x30: usize, // lr
pub x0: usize,
}
```
目前保存的寄存器包括:通用寄存器 `x0~x30`、异常返回地址 `elr_el1`、用户栈指针 `sp_el0`、进程状态 `spsr_el1`。由于在 `aarch64-blog_os.json` 中禁用了 NEON 指令,不需要保存 `q0~q31` 这些 SIMD/FP 寄存器。
`rust_trap()` 函数定义在 [interrupt/handler.rs](../../../kernel/src/arch/aarch64/interrupt/handler.rs#L43) 中。首先判断传入的 `kind`
* 如果是 `Synchronous`:在 [interrupt/syndrome.rs](../../../kernel/src/arch/aarch64/interrupt/syndrome.rs) 中解析 ESR根据具体的异常类别分别处理断点指令、系统调用、缺页异常等。
* 如果是 IRQ调用 `handle_irq()` 函数处理 IRQ。
* 其他类型的异常(SError interrupt、Debug exception)暂不做处理,直接调用 `crate::trap::error()`
#### 系统调用
如果 ESR 的异常类别是 SVC则说明该异常由系统调用指令 `svc` 触发,紧接着会调用 `handle_syscall()` 函数。
RustOS 的系统调用方式如下(实现在 [user/ucore-ulib/src/syscall.rs](../../../user/ucore-ulib/src/syscall.rs#L47) 中)
1. 将系统调用号保存在寄存器 `x8`,将 6 参数分别保存在寄存器 `x0~x5` 中。
2. 执行系统调用指令 `svc 0`
3. 系统调用返回值保存在寄存器 `x0` 中。
`handle_syscall()` 函数中,会从 `TrapFrame` 保存的寄存器中恢复系统调用参数,并调用 `crate::syscall::syscall()` 进行具体的系统调用。
#### 缺页异常
缺页异常只会在 MMU 启用后,虚拟地址翻译失败时产生,这时候根据是取指还是访存,分别触发 Instruction Abort 与 Data Abort。此时 ISS 中还记录了具体的状态码,例如:
* Address size fault, level 0~3.
* Translation fault, level 0~3.
* Access flag fault, level 0~3.
* Permission fault, level 0~3.
* Alignment fault.
* TLB conflict abort.
* ...
其中 level 表示在第几级翻译表产生异常。当状态码是 translation fault、access flag fault、permission fault 时,将被判断为是缺页异常,并调用 `handle_page_fault()` 处理缺页异常。
发生 Instruction Abort 与 Data Abort 的虚拟地址将会被保存到 `FAR_ELx` 系统寄存器中。此时再调用 `crate::memory::page_fault_handler(addr)` 来做具体的缺页处理。
#### IRQ
如果该异常是 IRQ则会调用 [kernel/src/arch/aarch64/board/raspi3/irq.rs](../../../kernel/src/arch/aarch64/board/raspi3/irq.rs#L8) 中的 `handle_irq()` 函数。该函数与具体的硬件板子相关,即使都是在 AArch64 下,不同 board 的 IRQ 处理方式也不一样,所以放到了模块 [kernel/src/arch/aarch64/board/raspi3](../../../kernel/src/arch/aarch64/board/raspi3/) 中,表示是 RPi3 特有的 IRQ 处理方式。
该函数首先会判断是否有时钟中断,如果有就先处理时钟中断:
```rust
let controller = bcm2837::timer::Timer::new();
if controller.is_pending() {
super::timer::set_next();
crate::trap::timer();
}
```
其中使用了 crate bcm2837位于 [crate/bcm2837](../../../crate/bcm2837/) 中,是一个封装良好的访问 RPi3 底层外围设备的库。
然后会遍历所有其他未处理的 IRQ如果该 IRQ 已注册,就调用它的处理函数:
```rust
for int in Controller::new().pending_interrupts() {
if let Some(handler) = IRQ_HANDLERS[int] {
handler();
}
}
```
IRQ 的注册可通过调用 `register_irq()` 函数进行,实现如下:
```rust
pub fn register_irq(int: Interrupt, handler: fn()) {
unsafe {
*(&IRQ_HANDLERS[int as usize] as *const _ as *mut Option<fn()>) = Some(handler);
}
Controller::new().enable(int);
}
```

@ -0,0 +1,347 @@
# 内存管理
## AArch64 虚拟内存系统
> 参考ARMv8 Reference Manual: chapter D5, The AArch64 Virtual Memory System Architecture.
(注:完整的 AArch64 文档中描述了许多可选的配置,如页大小、翻译表级数等,以下描述都是指在 RustOS 中的实现,不代表只有这一种实现方式)
### 地址空间 (D5.1.3)
AArch64 拥有 64 位地址,支持两段虚拟内存地址空间,分别为:
* 低地址空间:高 16 位是 0`0x0000_0000_0000_0000``0x0000_FFFF_FFFF_FFFF`
* 高地址空间:高 16 位是 1`0xFFFF_0000_0000_0000``0xFFFF_FFFF_FFFF_FFFF`
在 RustOS 中,低地址空间被用于内核地址空间,高地址空间被用于用户程序地址空间。
### 地址翻译系统 (D5.2)
地址翻译系统(address translation system),会随着 MMU 的启用而启用,负责将虚拟地址(或输入地址IA)映射为物理地址(或输出地址OA)。完整的翻译过程包含两个阶段 stage 1 与 stage 2一般只使用 stage 1 的输出作为最终的物理地址。
翻译的基本流程是:给定**翻译表**(translation table也可称为页表)的基址,截取虚拟地址中的一段 bit将其作为索引去翻译表中查找查得的物理地址作为下一级翻译表的基址。最后一级翻译表返回的是物理页帧(page)的基址,加上虚拟地址页内偏移即可得到原虚拟地址对应的物理地址。
第 0 级翻译表的基址保存在**翻译表基址寄存器**(Translation Table Base Register, TTBR)中,有两个,分别为 `TTBR0_EL1``TTBR1_EL1`MMU 会根据虚拟地址是位于低地址空间还是高地址空间,自动选择对应的 TTBR。相当于低地址空间与高地址空间各用一套不同的地址翻译系统。
翻译表共有 4 级(0~3),每级有 512 个表项,因此每级翻译表的索引为 9 位,一个翻译表的大小为 512 x 8 = 4KB。而最后得到的物理页帧的大小一般为 4KB页内偏移有 12 字节。
一般来说,最后一级得到的物理页帧大小为 4KB不过也可不用翻译到最后一级而在中间的某一级就停止翻译直接返回一个物理页帧的地址此时该页帧的大小会大于 4KB一般称其为**块**(block)。如在第 1 级就返回,会得到一个 1GB 的物理内存块;如在第 2 级返回,会得到一个 2MB 的物理内存块。翻译表项中有专门的位来区别该表项中的地址是下一级翻译表的基址还是一个块的基址。
![](img/address-translation.png)
使用**翻译控制寄存器**(Translation Control Register, TCR) `TCR_EL1` 可配置翻译系统的参数,常用的字段如下:
1. ASASID 的大小8 位或 16位。RustOS 中为 16 位。
2. IPS中间级物理地址大小。由于 RustOS 不使用 stage2 翻译系统,所以该地址就是物理地址。一般设为与 `ID_AA64MMFR0_EL1` 中的 `PARange` 字段一致。
3. TG0/1低/高地址空间翻译系统的物理页帧粒度4KB、16KB 或 64KB。RustOS 中都为 4KB。
4. SH0/1低/高地址空间翻译系统的内存共享属性不共享、内部共享或外部共享。RustOS 中都为内部共享。
5. ORGN0/1低/高地址空间翻译系统的外部缓存属性。
6. IRGN0/1低/高地址空间翻译系统的内部缓存属性。
7. EPD0/1是否使用 `TTBR0/1_EL1` 翻译系统。RustOS 中为都使用。
8. T0/1SZ在低/高地址空间翻译系统中,第 0 级翻译表从高往低数第几位开始索引。RustOS 中都为 16即从第 48 位开始索引。
9. A1ASID 定义在 `TTBR0_EL1` 还是 `TTBR1_EL1` 中。RustOS 中为 `TTBR1_EL1`
### 翻译表描述符 (D5.3)
翻译表描述符即翻译表项,由一段地址空间的基址与这段地址空间的属性构成。根据这段地址空间的用处不同,将描述符分为 3 类:
1. **页描述符**(page descriptor):该描述符中的地址指向一个 4KB 大小的页。
2. **块描述符**(block descriptor):该描述符中的地址指向一个 1GB 或 2MB 大小的块。
3. **表描述符**(table descriptor):该描述符中的地址指向另一个翻译表。
#### 第 0, 1, 2 级翻译表描述符
第 0 级翻译表只能包含表描述符,第 1、2 级翻译表同时支持表描述符与块描述符。一个描述符的各字段如下图所示:
![](img/level012-descriptor.png)
#### 第 3 级翻译表描述符
第 3 级翻译表只能包含页描述符。一个描述符的各字段如下图所示:
![](img/level3-descriptor.png)
#### 表描述符属性
![](img/table-descriptor_attributes.png)
#### 块/页描述符属性
![](img/block-page-descriptor_attributes.png)
各字段的具体说明详见官方文档 ARMv8 Reference Manual D5.3.3 节。
### 内存属性 (D5.5)
可为一段内存设置的特定属性,如可缓存性、可共享性、内存类型等。
#### 内存类型与可缓存性
可为内存设置多达 8 个不同的类型,每个类型的内存的可缓存性不同,如普通可缓存内存、普通不可缓存内存、设备内存等。
在块/页描述符的 AttrIndex 字段可设置内存的类型。关于内存类型、Device 与 Normal 内存的区别的详细资料参见 Programmers Guide for ARMv8-A 13.1 节。
8 种内存类型的配置通过 `MAIR_EL1` 实现,每 8 位代表一种类型的内存配置。具体参见 ARMv8 Reference Manual D12.2.82 节。
#### 可共享性
可共享性分为 3 种:
1. 不可共享,即每个核都不与其他核共享这段内存。
2. 内部共享,即多核之间可以共享这段内存。
3. 外部共享即除了多核之间外CPU 与 GPU 之间也可共享这段内存。
在块/页描述符的 SH 字段可设置内存的可共享性。
### TLB、Cache 操作
#### TLB 操作 (C5.5)
**TLB** (Translation Lookaside Buffers) 是翻译表的缓存,如果一个虚拟地址在 TLB 中命中,将不再通过地址翻译系统翻译,而是直接从缓存中得到物理地址。
当翻译表被修改后,需要刷新 TLB以防由于缓存而使新的虚拟——物理地址映射不起作用。有以下两种刷新方式
* 根据虚拟地址刷新:只会使 TLB 中的该虚拟地址无效,代码如下:
```armasm
dsb ishst
tlbi vaae1is, <vaddr>
dsb ish
isb
```
* 全部刷新:会使 TLB 中的所有表项无效,代码如下:
```armasm
dsb ishst
tlbi vmalle1is
dsb ish
isb
```
#### Cache 操作 (C5.3)
**Cache** 是主存的缓存,如果一个物理地址在 cache 中命中,将不会访问主存,而是直接从 cache 中得到数据。Cache 又分为指令 cache 与 数据 cache分别作用在取指与普通访存时。
当通过普通访存的形式修改了代码段的数据,并跳转到了这里运行,此时需要刷新指令 cache以防取指时从指令 cache 中取到旧的数据。指令 cache 可使用下列代码一次性全部清空:
```armasm
ic ialluis
dsb ish
isb
```
当 CPU 与 GPU 通信,共享一段内存时,由于 GPU 不使用 cache需要保证 CPU 写入数据时一定被写入主存了而不是在 cache 中,以便 GPU 能读出正确的数据;同时,也要保证这段内存不在 cache 中,以便 GPU 对其进行修改后 CPU 能立即看到修改的结果。这时候就需要清空数据 cache 了。可使用下列代码清空一个 cache line 的数据:
```armasm
dc civac, <vaddr>
dsb sy
isb
```
Cache line 的大小可通过 `CTR_EL0` 寄存器读取,一般为 16 个 WORD即 64 字节。
### ASID 机制 (D5.9.1)
在上下文切换时,需要修改 TTBR1_EL1 寄存器,如果不刷新 TLB 也不使用 ASIDTLB 中将会保留旧进程的虚拟——物理地址映射关系,导致进程访问错误的物理地址。不过如果每次上下文切换都刷新 TLB开销又较大。
**ASID** (Address Space ID) 的引入就是为了避免在上下文切换过程中刷新 TLB。详见“上下文切换”相关章节。
## RustOS 中的实现
在 RustOS 中AArch64 平台相关的内存管理主要实现在 [kernel/src/arch/aarch64/memory.rs](../../../kernel/src/arch/aarch64/memory.rs) 与 [kernel/src/arch/aarch64/paging.rs](../../../kernel/src/arch/aarch64/paging.rs) 中。此外crate [aarch64](https://github.com/equation314/aarch64) 类似其他平台下的 x86_64、riscv 库,封装了对 AArch64 底层系统寄存器、翻译表的访问。
(注:为了保持与其他平台的一致性,下文使用“页表”指代“翻译表”,并且下文中页表的级数 1, 2, 3, 4 分别指官方文档中翻译表的级数 3, 2, 1, 0)
### 物理内存探测
### aarch64 库中的页表
与其他平台一样,页表实现在内核代码 [paging.rs](../../../kernel/src/arch/aarch64/paging.rs) 中,其实只是套了层壳,诸如 map 等复杂操作的实现位于 aarch64 库中。
#### 页表描述符
在 [aarch64/src/paging/page_table.rs](https://github.com/equation314/aarch64/blob/master/src/paging/page_table.rs) 中实现了页表(`PageTable`)与页表项(`PageTableEntry`)。页表有 512 个项,每个页表项是一个 64 位描述符。一个页表项描述符由下面 3 部分字段构成:
1. **地址**(address):位于描述符的第 12 到 47 位。根据描述符的 `TABLE_OR_PAGE` 位,分别指向下列 3 种地址:
1. 页描述符(page descriptor):该地址指向一个 4KB 大小的页,该地址 4KB 对齐。
2. 块描述符(block descriptor):该地址指向一个 1GB 或 2MB 大小的块,该地址 1GB 或 2MB 对齐。
3. 表描述符(table descriptor):该地址指向另一个页表,该地址 4KB 对齐。
2. **标志位**(flags):仅由一个位来表示的内存属性。对于表/块描述符包含下列位:
| 位 | 名称 | 描述 |
|------|-----------------|---------------------------------------------------------------------|
| 0 | VALID | 该描述符是否有效 |
| 1 | TABLE_OR_PAGE | 为 0 表示是块描述符,为 1 表示是表或页描述符 |
| 6 | AP_EL0 | 这段内存是否可在 EL0 (用户态) 下访问 |
| 7 | AP_RO | 这段内存是否是只读的 |
| 10 | AF | Access flag必须为 1 |
| 11 | nG | 是否不是全局内存。用户态内存必须设置这一位才能使用 ASID |
| 51 | DBM | Dirty Bit Modifier。不过 dirty 位只在 ARMv8.2 中由硬件自动设置,该位用于软件模拟 dirty 位 |
| 52 | PXN | 这段内存是否在特权级下不可执行 |
| 53 | UXN | 这段内存是否在非特权级下不可执行 |
以及下列保留给软件实现特定功能的位:
| 位 | 名称 | 描述 |
|------|-----------------|---------------------------------------------------------------------|
| 51 | WRITE | 软件模拟的 DMB 位 |
| 55 | DIRTY | 软件模拟的 dirty 位 |
| 56 | SWAPPED | 软件实现的页换出标志位 |
| 57 | WRITABLE_SHARED | 软件实现的可写共享位,用于 COW 机制 |
| 57 | READONLY_SHARED | 软件实现的只读共享位,用于 COW 机制 |
对于表描述符只包含下列位:
| 位 | 名称 | 描述 |
|------|-----------------|---------------------------------------------------------------------|
| 59 | PXNTable | 该页表所映射的所有内存都是特权级下不可执行的 |
| 60 | XNTable | 该页表所映射的所有内存都是非特权级下不可执行的 |
3. **属性**(attribute):属性字段指明了这段内存的内存属性,包括内存类型(位 2、3、4)与可共享性(位 8、9)。在 [aarch64/src/paging/memory_attribute.rs](https://github.com/equation314/aarch64/blob/master/src/paging/memory_attribute.rs) 中预定义了 3 中内存属性,分别为:
1. Normal普通可缓存内存cache 属性为 Write-Back Non-transient Read-Allocate Write-Allocate内部共享。
2. DeviceDevice-nGnRE 类型的内存,不可缓存,外部共享。
3. NormalNonCacheable普通不可缓存内存外部共享。
#### 自映射机制
为了方便对页表的修改与其他平台一样aarch64 下的 RustOS 也使用了**自映射**的页表。
具体地,设**递归索引**为 `R` (RustOS 中为 `0o777 = 512`,即页表的最后一项),只需将第 4 级页表的第 `R` 项映射为第 4 级页表自身即可建立自映射页表。这样一来,一个虚拟地址 `IA` 的四级页表分别被以下虚拟地址所映射(`||` 表示比特串的连接)
* 4 级页表:`R || R || R || R`
* 3 级页表:`R || R || R || IA[47..39]`
* 2 级页表:`R || R || IA[47..39] || IA[38..30]`
* 1 级页表:`R || IA[47..39] || IA[38..30] || IA[29..21]`
在 [aarch64/src/paging/recursive.rs](https://github.com/equation314/aarch64/blob/master/src/paging/recursive.rs) 中,为结构体 `RecursivePageTable` 实现了一系列函数,主要的几个如下:
* `new(table: PageTable)`:将虚拟地址表示的 `table` 作为 4 级页表,新建 `RecursivePageTable` 对象。
* `map_to(self, page: Page<Size4KiB>, frame: PhysFrame<Size4KiB>, flags: PageTableFlags, attr: PageTableAttribute, allocator: FrameAllocator<Size4KiB>)`:将虚拟地址表示的**页** `page`,映射为物理地址表示的**帧** `frame`,并设置标志位 `flags` 和属性 `attr`,如果需要新分配页表就用 `allocator` 分配。页与帧的大小都是 4KB。
* `unmap(self, page: Page<Size4KiB>)`:取消虚拟地址表示的页 `page` 的映射。
### 实现内存管理
下面是 [memory.rs](../../../kernel/src/arch/aarch64/memory.rs) 与 [paging.rs](../../../kernel/src/arch/aarch64/paging.rs) 中对内存管理的实现。
#### 启用 MMU
由于在真机上使用原子指令需要 MMU 的支持,应该尽量早地启用 MMU而 [boot.S](../../../kernel/src/arch/aarch64/boot/boot.S) 中并没有建立页表与启用 MMU所以启动完毕一进入 `rust_main()` 函数,就会调用 [memory.rs](../../../kernel/src/arch/aarch64/memory.rs#L20) 里的 `init_mmu_early()` 函数来启用 MMU。
该函数主要做了下面三件事:
1. 建立一个临时的地址翻译系统。
这部分的代码主要位于 [paging.rs](../../../kernel/src/arch/aarch64/paging.rs#L14) 里的 `setup_temp_page_table()` 函数。这个地址翻译系统只是临时的,未进行细致的权限控制,更细致的地址翻译系统将在下节“重新映射内核地址空间”中建立。
该过程共需要三个 4KB 大小的页面,分别用于第 2~4 级页表。然后按下图方式映射:
```
+------------+
| TTBR0_EL1 |---+
+------------+ |
|
|
+------+-------------------+
| |
p4_table v |
+-----------+ 0x0000_0000_0000 |
0 | D_Table |--------------------+ |
+-----------+ 0x0080_0000_0000 | |
| ... | | |
+-----------+ | |
| ... | | |
+-----------+ 0xFF80_0000_0000 | |
511 | D_Table |------------------------+
+-----------+ |
+----------------------+
|
p3_table v
+-----------+ 0x0000_0000_0000
0 | D_Table |--------------------+
+-----------+ 0x0000_4000_0000 |
1 | D_Block | |
+-----------+ 0x0000_8000_0000 |
| ... | |
+-----------+ |
| ... | |
+-----------+ |
+----------------------+
|
p2_table v
+-----------+ 0x0000_0000_0000
0 | D_Block |
+-----------+ 0x0000_0020_0000
1 | D_Block |
+-----------+ 0x0000_0040_0000
| ... |
+-----------+ 0x0000_3FE0_0000
511 | D_Block |
+-----------+
```
注意 `4000_0000 ~ 0x8000_0000` 以及 `0x3F00_0000 ~ 0x4000_0000` 这些内存区域是 IO 地址空间,内存属性为 Device其他内存区域属性都是 Normal。
2. 初始化 `MAIR_EL1`、`TCR_EL1` 等系统寄存器。
`MAIR_EL1` 系统寄存器定义了三种内存属性Normal、Device 和 NormalNonCacheable。
`TCR_EL1` 系统寄存器用于设置翻译系统的参数(详见上文描述)。
3. 修改 `SCTLR_EL1` 寄存器以启用 MMU。
一切准备就绪后,用下列代码启用 MMU 和 cache
```rust
unsafe { barrier::isb(barrier::SY) }
SCTLR_EL1.modify(SCTLR_EL1::M::Enable + SCTLR_EL1::C::Cacheable + SCTLR_EL1::I::Cacheable);
unsafe { barrier::isb(barrier::SY) }
```
注意修改 `SCTLR_EL1` 系统寄存器的前后都要需要有内存屏障指令 `isb sy`
#### 初始化内存管理
这部分实现在 [memory.rs](../../../kernel/src/arch/aarch64/memory.rs#L12) 里的 `init()` 函数中。包含下列三部分:
1. 探测物理内存,初始化物理页帧分配器:由函数 `init_frame_allocator()`,先用 atags 库探测出可用物理内存的区间 `[start, end]`,然后以 4KB 大小的页为单位插入 `FRAME_ALLOCATOR` 中。由于 Raspberry Pi 3 拥有 1GB 内存,物理页帧数多达 256K所以需要使用 `bit_allocator::BitAlloc1M`
2. 初始化堆分配器:直接调用 `crate::memory::init_heap()`,堆大小为 8MB。
3. 重新映射内核地址空间:由函数 `remap_the_kernel()` 完成,见下节。
#### 重新映射内核地址空间
有了物理页帧分配器后,就可以使用 `RecursivePageTable` 等结构体提高的函数映射页面,而不用像 `setup_temp_page_table()` 那样手动映射了。
在函数 `remap_the_kernel()` 中,使用了类 `MemorySet` 来管理内核使用的内存空间。新建一个 `MemorySet` 将新建一个 `InactivePageTable`,即一个非活跃页表或一套地址翻译系统。为了以后方便实现 ioremap使用全局变量 `KERNEL_MEMORY_SET` 记录内核的 `MemorySet` 结构。
然后该函数分别将内核的栈、代码段、数据段、只读数据段、BSS 段加入 `MemorySet`,设置好访问权限,建立 `Linear` 对等映射,这会导致调用 `ActivePageTable``map()` 函数,进而调用 `RecursivePageTable``map_to()` 函数建立映射。需要注意的是,对于 IO 地址空间 `0x3F00_0000 ~ 0x4000_1000`,额外设置了 `MemoryAttr``mmio` 属性,这将使得这段内存的内存属性为 Device。最后调用 `InactivePageTable``activate_as_kernel()` 函数向 `TTBR0_EL1` 写入新的页表基址。
如果以后想访问其他的 IO 地址空间(如 Framebuffer),可调用 `ioremap()` 函数建立对等映射。该函数会将要映射的内存区域插入全局的 `KERNEL_MEMORY_SET` 结构,并将内存属性设为 NormalNonCacheable。
#### InactivePageTable
`InactivePageTable` 定义了一个**非活跃页表**,准确地说是由第 4 级页表基址指定的一套地址翻译系统,一般随着 `MemorySet` 的建立而建立。除了在 `remap_the_kernel()` 中建立的是内核新页表,其他时候都是用户页表。
在不同的平台下需要各自实现以下函数([paging.rs](../../../kernel/src/arch/aarch64/paging.rs#L183) 中)
* `new_bare()`:新建一套地址翻译系统。首先调用 `alloc_frame()` 分配一个物理页帧用于存放唯一的 4 级页表,然后修改该物理页帧,使得其最后一项映射到自身,即建立自映射页表。通过调用 `active_table().with_temporary_map()` 让当前活跃的页表新建一个临时的映射,可在页表被激活后也能修改任意物理页帧。
* `token()`:获取该翻译系统的页表基址,即第 4 级页表的物理地址。
* `set_token(token)`:将页表基址 `token` 写入页表基址寄存器用于激活该地址翻译系统。RustOS 中是写入 `TTBR1_EL1`
* `active_token()`获取当前活跃页表的页表基址寄存器内容。RustOS 中是读取 `TTBR1_EL1`
* `flush_tlb()`:刷新 TLB 以立即生效对地址翻译系统的修改。
* `edit()`:让该翻译系统变得可编辑。本质上是将当前活跃页表(`TTBR0_EL1` 指向的页表)的递归索引指向该翻译系统的第 4 级页表,使得所有对该翻译系统第 1~4 级页表的访问,都可直接通过自映射机制构造相应的虚拟地址来实现。同时由于不修改当前活跃页表的其他表项,对内核地址空间可正常访问。
* `new()`:建立用户页表时调用,会同时调用 `new_bare()``map_kernel()`。不过在 AArch64 下不需要 `map_kernel()`
* `map_kernel()`:为了让用户程序陷入中断后能访问内核地址空间,需要在用户页表中映射内核的地址空间,通过 `edit()` 函数修改自身来实现。使用 `new()` 建立用户页表时会额外调用该函数。不过在 AArch64 下可使用 `TTBR0_EL1``TTBR1_EL1` 区分内核页表与用户页表,所以 AArch64 下该函数无效。
#### 分离内核页表与用户页表
AArch64 提供了两个翻译表基址寄存器 `TTBR0_EL1``TTBR1_EL1`MMU 会根据虚拟地址是低地址空间还是高地址空间自动选择相应的 TTBR 作为翻译表基址。
在 RustOS 中,低地址空间(高 16 位是 0)用于内核地址空间,高地址空间(高 16 位是 1)用于用户程序地址空间。这样在内核态可不加偏移直接访问 IO 地址空间,只需建立对等映射;而用户程序的地址都需加上偏移 `0xFFFF_0000_0000_0000`
实现该机制,只需记住一点:内核页表基址 `TTBR0_EL1` 在设好后就无需修改了(其实 RustOS 修改了一次,即重新映射内核地址时),之后所有的对页表基址的修改一定都是 `TTBR1_EL1`。于是像 `set_token()`、`active_token()` 等函数,以及上下文切换中的页表基址都是 `TTBR1_EL1`
需要注意的是,当映射用户程序地址空间时,要调用 `InactivePageTable``edit()` 函数来编辑用户页表,这时用于访问翻译系统各级页表的地址的高 16 位都是 1会自动使用 `TTBR1_EL1` 作为页表基址寄存器。于是 `edit()` 中除了设置当前活跃页表的递归索引外,`TTBR1_EL1` 也需设为该翻译系统的第 4 级页表。

@ -0,0 +1,134 @@
# 概述
## Raspberry Pi 简介
本实验的目标是将 RustOS 移植到 Raspberry Pi 3 Model B+ 上。其主要硬件参数如下:
| Raspberry Pi 3B+ | |
|-------|---------|
| 指令集 | ARMv8-A 32/64 bit |
| 片上系统(SoC) | Broadcom BCM2837B0 |
| 处理器(CPU) | 4 x Cortex-A53 1.4Ghz |
| 图形处理器(GPU) | Broadcom VideoCore IV |
| 内存 | 1GB (与 GPU 共享) |
## ARMv8 架构简介
### 运行状态
根据寄存器位数的不同ARMv8 架构定义了两种**运行状态**(Execution States),分别为 **AArch64****AArch32**。两种运行状态使用的指令集也不相同。RustOS 实现的是 AArch64。
### 异常级别
在 AArch64 下,可在 4 个**异常级别**(Exception level)中运行,分别为:
* EL0: Normal user applications.
* EL1: Operating system kernel typically described as *privileged*.
* EL2: Hypervisor.
* EL3: Secure monitor.
级别越高,特权(privilege)越高。一般称 EL0 为非特权级(unprivileged),其他的为特权级(privileged)。
### 寄存器
#### 通用寄存器
AArch64 有 31 个 64 位**通用寄存器**(General-purpose registers) `X0~X30`,每个 64 位寄存器都有一个 32 位的版本 `W0~W30`。寄存器的使用规范一般如下:
* 参数寄存器 (Argument registers, `X0~X7`):作为函数调用时的参数,返回值保存在 `X0`
* 调用者保存寄存器(Caller-saved temporary registers, `X9~X15`):在函数调用前,如果调用者需要保护这些寄存器中的值直到函数调用之后,则调用者需要将它们保存到当前栈帧上,而被调用者可直接使用而不必保存与恢复。
* 被调用者保存寄存器(Callee-saved registers, `X19~X29`):在函数调用中,如果该函数需要修改这些寄存器,则需要在函数开始执行前将它们保存到当前栈帧上,并在返回时恢复它们。
* 帧指针寄存器(Frame point register, `FP``X29`):用于保存当前函数的栈帧指针。
* 链接寄存器(Link register, `LR``X30`):用于保存函数返回的地址,执行 `ret` 指令会跳转到 `LR`
![](img/general-register.png)
#### 特殊寄存器
AArch64 有下列**特殊寄存器**(Special-purpose registers)
* 零寄存器(Zero register, ZR):被映射为立即数 0可分别用 `WZR/XZR` 访问 32/64 位版本。
* 程序计数器(Program counter, `PC`)当前指令的地址64 位。
* 栈指针(Stack pointer, `SP`)当前栈顶地址64 位。在每个异常级别下都有一个栈指针,分别为 `SP_EL0`、`SP_EL1`、`SP_EL2`、`SP_EL3`,直接访问 `SP` 时会根据当前异常级别自动选择对应的(如果 `SPSel = 0`,则在任何异常级别下都使用 `SP_EL0`)。
* 异常链接寄存器(Exception Link Register, ELR):用于保存异常返回的地址,在异常级别 1~3 下分别为 `ELR_ELx`,执行 `eret` 指令进行异常返回时会根据当前异常级别跳转到相应的 ELR。
* 保存的进程状态寄存器(Saved Process Status Register, SPSR):用于保存异常发生时的进程状态(PSTATE),在异常级别 1~3 下分别为 `SPSR_ELx`。执行 `eret` 指令进行异常返回时会根据当前异常级别,从相应的 SPSR 恢复进程状态。
#### 进程状态
**进程状态**(Process state, PSTATE)是当前进程状态信息的抽象。AArch64 提供了一系列特殊寄存器来独立访问 PSTATE 中的每个字段,常用的几个如下(完整的字段描述参见 ARMv8 Reference Manual D1.7 节)
* 条件标志位(Condition flags, `NZCV`)
+ `N`: Negative Condition flag
+ `Z`: Zero Condition flag
+ `C`: Carry Condition flag
+ `V`: oVerflow Condition flag
* 异常屏蔽位(exception masking bits, `DAIF`)
+ `D`: Debug exception mask bit
+ `A`: SError interrupt mask bit
+ `I`: IRQ interrupt mask bit
+ `F`: FIQ interrupt mask bit
* 当前异常级别(Current Exception level, `CurrentEL`):获取当前的异常级别。
* 栈指针选择(Stack Pointer Select, `SPSel`):如果为 1则在不同异常级别下分别使用相应的 `SP_ELx` 作为 `SP`,否则任何时候都使用 `SP_EL0` 作为 `SP`
当异常发生时,当前的 PSTATE 会根据进入哪个异常级别保存到相应的 `SPSR_ELx` 中。
#### 系统寄存器
可以通过**系统寄存器**(System registers)来进行 AArch64 的系统配置。一般每种系统寄存器在不同异常级别下都有相应的版本,用后缀 `_ELx` 表示。下表列出了常用的几个系统寄存器(全部系统寄存器参见 ARMv8 Reference Manual D12.1 节)
| 系统寄存器_ELx | 名称 | 描述 |
|------------------|-----------------------------------------|------------------------------|
| CTR | Cache Type Register | 获取 cache 信息 |
| ESR | Exception Syndrome Register | 发生异常的原因 |
| FAR | Fault Address Register | 发生访存错误的虚拟地址 |
| HCR | Hypervisor Configuration Register | 配置 EL2 下的虚拟化 |
| MAIR | Memory Attribute Indirection Register | 配置内存属性 |
| MPIDR | Multiprocessor Affinity Register | 多核系统中核的编号 |
| SCTLR | System Control Register | 提供对内存系统等系统配置 |
| TCR | Translation Control Register | 配置地址翻译系统的参数 |
| TTBR0/TTBR1 | Translation Table Base Register | 设置翻译表(页表)基址 |
| VBAR | Vector Based Address Register | 设置异常向量基址 |
对系统寄存器(包括部分特殊寄存器)的访问需要使用 `mrs``msr` 指令:
* 读:
```armasm
mrs x0, TTBR0_EL1
```
* 写:
```armasm
msr TTBR0_EL1, x0
```
crate [aarch64](https://github.com/equation314/aarch64) 的 [regs](https://github.com/equation314/aarch64/tree/master/src/regs) 模块封装了对部分系统寄存器的访问。
#### SIMD/FP 寄存器
共有 32 个最高为 128 位的 **SIMD/floating-point 寄存器**,可分别通过 `Q0~Q31`、`D0~D31`、`S0~S31`、`H0~H31`、`B0~B31` 访问其 128、64、32、16、8 位版本。
使用这些寄存器需要 NEON 技术的支持。为了方便,在 RustOS 中禁用了 NEON (Cargo features `+a53,+strict-align,-neon`),这样在处理异常时无需保存这些寄存器。
## 官方文档
* [ARM Architecture Reference Manual, for ARMv8-A architecture profile](https://static.docs.arm.com/ddi0487/da/DDI0487D_a_armv8_arm.pdf)AArch64 的完整文档,有 7000 多页,最为详细。
* [ARM Cortex-A Series Programmers Guide for ARMv8-A](http://infocenter.arm.com/help/topic/com.arm.doc.den0024a/DEN0024A_v8_architecture_PG.pdf):可认为是上一文档的精简版,仅有不到 300 页。
* [BCM2837 ARM Peripherals](https://web.stanford.edu/class/cs140e/docs/BCM2837-ARM-Peripherals.pdf)Raspberry Pi SoC BCM283x 系列的外围设备文档,包含对 GPIO、中断控制器、mini UART、System Timer 等外围设备的访问。
* [BCM2836 ARM-local peripherals (Quad-A7 control)](https://www.raspberrypi.org/documentation/hardware/raspberrypi/bcm2836/QA7_rev3.4.pdf):仅用于如何使用 AArch64 Generic Timer 的中断。
* [Raspberry Pi firmware](https://github.com/raspberrypi/firmware)Raspberry Pi 二进制固件,部分开源,其中最有价值的是 [mailbox](https://github.com/raspberrypi/firmware/wiki) 的文档。
## 其他参考
* [Stanford CS140e](http://cs140e.stanford.edu/)Stanford CS140e 课程,一个用 Rust 语言编写的 Raspberry Pi 3 操作系统,包含串口输入输出、文件系统、进程管理等功能,但没有虚拟内存管理。
* [Learning operating system development using Linux kernel and Raspberry Pi](https://github.com/s-matyukevich/raspberry-pi-os):一个用 C 语言编写的 Raspberry Pi 3 操作系统,仿照 Linux特点是文档非常详细。其中 Kernel Initialization、Interrupt handling、Virtual memory management 部分很有参考价值。
* [Bare Metal Rust Programming on Raspberry Pi 3](https://github.com/bztsrc/raspi3-tutorial):另一个用 C 语言编写的 Raspberry Pi 3 操作系统。
* [Bare Metal Rust Programming on Raspberry Pi 3 (Rust)](https://github.com/rust-embedded/rust-raspi3-tutorial):上一个项目的 Rust 版本,主要参考的是虚拟内存部分。

2
kernel/Cargo.lock generated

@ -1,7 +1,7 @@
[[package]] [[package]]
name = "aarch64" name = "aarch64"
version = "2.2.2" version = "2.2.2"
source = "git+https://github.com/equation314/aarch64#e3b60adb233ad34d05443e0b5ec34cac29253296" source = "git+https://github.com/equation314/aarch64#b6a0f4a3be6f74927c88305a6af5ad2be079bccd"
dependencies = [ dependencies = [
"bit_field 0.9.0 (registry+https://github.com/rust-lang/crates.io-index)", "bit_field 0.9.0 (registry+https://github.com/rust-lang/crates.io-index)",
"bitflags 1.0.4 (registry+https://github.com/rust-lang/crates.io-index)", "bitflags 1.0.4 (registry+https://github.com/rust-lang/crates.io-index)",

@ -20,6 +20,7 @@ no_mmu = []
# Kernel in M-mode (for riscv) # Kernel in M-mode (for riscv)
m_mode = ["no_mmu"] m_mode = ["no_mmu"]
# (for aarch64 RaspberryPi3) # (for aarch64 RaspberryPi3)
nographic = []
board_raspi3 = ["bcm2837"] board_raspi3 = ["bcm2837"]
# (for riscv64) # (for riscv64)
board_k210 = ["m_mode"] board_k210 = ["m_mode"]

@ -8,13 +8,14 @@
# make clean Clean # make clean Clean
# #
# Options: # Options:
# arch = x86_64 | riscv32 | riscv64 | aarch64 # arch = x86_64 | riscv32 | riscv64 | aarch64
# d = int | in_asm | ... QEMU debug info # d = int | in_asm | ... QEMU debug info
# mode = debug | release # mode = debug | release
# LOG = off | error | warn | info | debug | trace # LOG = off | error | warn | info | debug | trace
# SFSIMG = SFS image path of user programs # SFSIMG = <sfsimg> SFS image path of user programs
# smp = 1 | 2 | ... SMP core number # smp = 1 | 2 | ... SMP core number
# board = none Running on QEMU # graphic = on | off enable/disable qemu graphical output
# board = none Running on QEMU
# | k210 Only available on riscv64, build without bbl, run on K210 # | k210 Only available on riscv64, build without bbl, run on K210
# | raspi3 Only available on aarch64, run on Raspberry Pi 3 Model B/B+ # | raspi3 Only available on aarch64, run on Raspberry Pi 3 Model B/B+
# m_mode Only available on riscv32, build for M-Mode, without MMU # m_mode Only available on riscv32, build for M-Mode, without MMU
@ -51,10 +52,15 @@ endif
# crate 'process' use this to set interrupt (MIE or SIE) # crate 'process' use this to set interrupt (MIE or SIE)
export M_MODE = $(m_mode) export M_MODE = $(m_mode)
ifeq ($(arch), aarch64)
graphic ?= on
else
graphic ?= off
endif
### qemu options ### ### qemu options ###
qemu_opts := \ qemu_opts := \
-smp cores=$(smp) \ -smp cores=$(smp)
-nographic
ifeq ($(arch), x86_64) ifeq ($(arch), x86_64)
qemu_opts += \ qemu_opts += \
@ -86,11 +92,19 @@ qemu_opts += \
-kernel $(bin) -kernel $(bin)
endif endif
ifneq ($(graphic), on)
qemu_opts += -nographic
endif
ifdef d ifdef d
qemu_opts += -d $(d) qemu_opts += -d $(d)
endif endif
### build args ### ### build args ###
ifneq ($(graphic), on)
features += nographic
endif
ifeq ($(board), raspi3) ifeq ($(board), raspi3)
# qemu only has generic timer # qemu only has generic timer
# TODO: configure system/generic timer automatically # TODO: configure system/generic timer automatically

@ -0,0 +1,238 @@
//! Framebuffer
use super::mailbox;
use alloc::string::String;
use core::fmt;
use lazy_static::lazy_static;
use log::*;
use once::*;
use spin::Mutex;
/// Framebuffer information
#[repr(C)]
#[derive(Debug, Clone, Copy)]
pub struct FramebufferInfo {
/// visible width
pub xres: u32,
/// visible height
pub yres: u32,
/// virtual width
pub xres_virtual: u32,
/// virtual height
pub yres_virtual: u32,
/// virtual offset x
pub xoffset: u32,
/// virtual offset y
pub yoffset: u32,
/// bits per pixel
pub depth: u32,
/// bytes per line
pub pitch: u32,
/// bus address, starts from 0xC0000000/0x40000000
/// (see https://github.com/raspberrypi/firmware/wiki/Accessing-mailboxes)
pub bus_addr: u32,
/// screen buffer size
pub screen_size: u32,
}
#[repr(u32)]
#[derive(Debug, Clone, Copy)]
pub enum ColorDepth {
ColorDepth16 = 16,
ColorDepth32 = 32,
}
use self::ColorDepth::*;
#[repr(C)]
union ColorBuffer {
base_addr: usize,
buf16: &'static mut [u16],
buf32: &'static mut [u32],
}
impl ColorBuffer {
fn new(color_depth: ColorDepth, bus_addr: u32, size: u32) -> ColorBuffer {
unsafe {
match color_depth {
ColorDepth16 => ColorBuffer {
buf16: core::slice::from_raw_parts_mut(
bus_addr as *mut u16,
(size / 2) as usize,
),
},
ColorDepth32 => ColorBuffer {
buf32: core::slice::from_raw_parts_mut(
bus_addr as *mut u32,
(size / 4) as usize,
),
},
}
}
}
#[inline]
fn read16(&self, index: u32) -> u16 {
unsafe { self.buf16[index as usize] }
}
#[inline]
fn read32(&self, index: u32) -> u32 {
unsafe { self.buf32[index as usize] }
}
#[inline]
fn write16(&mut self, index: u32, pixel: u16) {
unsafe { self.buf16[index as usize] = pixel }
}
#[inline]
fn write32(&mut self, index: u32, pixel: u32) {
unsafe { self.buf32[index as usize] = pixel }
}
}
/// Frambuffer structure
pub struct Framebuffer {
pub fb_info: FramebufferInfo,
pub color_depth: ColorDepth,
buf: ColorBuffer,
}
impl fmt::Debug for Framebuffer {
fn fmt(&self, f: &mut fmt::Formatter) -> fmt::Result {
let mut f = f.debug_struct("Framebuffer");
f.field("fb_info", &self.fb_info);
f.field("color_depth", &self.color_depth);
f.field("base_addr", unsafe { &self.buf.base_addr });
f.finish()
}
}
impl Framebuffer {
fn new(width: u32, height: u32, depth: u32) -> Result<Framebuffer, String> {
assert_has_not_been_called!("Framebuffer::new must be called only once");
let (width, height) = if width == 0 || height == 0 {
mailbox::framebuffer_get_physical_size()?
} else {
(width, height)
};
let depth = if depth == 0 {
mailbox::framebuffer_get_depth()?
} else {
depth
};
let info = mailbox::framebuffer_alloc(width, height, depth)?;
let color_depth = match info.depth {
16 => ColorDepth16,
32 => ColorDepth32,
_ => Err(format!("unsupported color depth {}", info.depth))?,
};
if info.bus_addr == 0 || info.screen_size == 0 {
Err(format!("mailbox call returned an invalid address/size"))?;
}
if info.pitch == 0 || info.pitch != info.xres * info.depth / 8 {
Err(format!(
"mailbox call returned an invalid pitch value {}",
info.pitch
))?;
}
use crate::arch::memory;
let paddr = info.bus_addr & !0xC0000000;
let vaddr = memory::ioremap(paddr as usize, info.screen_size as usize, "fb") as u32;
if vaddr == 0 {
Err(format!(
"cannot remap memory range [{:#x?}..{:#x?}]",
paddr,
paddr + info.screen_size
))?;
}
Ok(Framebuffer {
buf: ColorBuffer::new(color_depth, vaddr, info.screen_size),
color_depth,
fb_info: info,
})
}
#[inline]
pub fn base_addr(&self) -> usize {
unsafe { self.buf.base_addr }
}
/// Read pixel at `(x, y)`.
#[inline]
pub fn read(&self, x: u32, y: u32) -> u32 {
match self.color_depth {
ColorDepth16 => self.buf.read16(y * self.fb_info.xres + x) as u32,
ColorDepth32 => self.buf.read32(y * self.fb_info.xres + x),
}
}
/// Write pixel at `(x, y)`.
#[inline]
pub fn write(&mut self, x: u32, y: u32, pixel: u32) {
match self.color_depth {
ColorDepth16 => self.buf.write16(y * self.fb_info.xres + x, pixel as u16),
ColorDepth32 => self.buf.write32(y * self.fb_info.xres + x, pixel),
}
}
/// Copy buffer `[src_off .. src_off + size]` to `[dst_off .. dst_off + size]`.
/// `dst_off`, `src_off` and `size` must be aligned with `usize`.
pub fn copy(&mut self, dst_off: usize, src_off: usize, size: usize) {
const USIZE: usize = core::mem::size_of::<usize>();
let mut dst = self.base_addr() + dst_off;
let mut src = self.base_addr() + src_off;
let src_end = src + size;
while src < src_end {
unsafe { *(dst as *mut usize) = *(src as *mut usize) }
dst += USIZE;
src += USIZE;
}
}
/// Fill buffer `[offset .. offset + size]` with `pixel`.
/// `offset` and `size` must be aligned with `usize`.
pub fn fill(&mut self, offset: usize, size: usize, pixel: u32) {
const USIZE: usize = core::mem::size_of::<usize>();
let mut value: usize = 0;
let repeat = USIZE * 8 / self.fb_info.depth as usize;
let mask = ((1u64 << self.fb_info.depth) - 1) as usize;
for _i in 0..repeat {
value <<= self.fb_info.depth;
value += pixel as usize & mask;
}
let mut start = self.base_addr() + offset;
let end = start + size;
while start < end {
unsafe { *(start as *mut usize) = value }
start += USIZE;
}
}
/// Fill the entire buffer with `0`.
pub fn clear(&mut self) {
self.fill(0, self.fb_info.screen_size as usize, 0);
}
}
lazy_static! {
pub static ref FRAME_BUFFER: Mutex<Option<Framebuffer>> = Mutex::new(None);
}
/// Initialize framebuffer
pub fn init() {
match Framebuffer::new(0, 0, 0) {
Ok(fb) => {
info!("framebuffer: init end\n{:#x?}", fb);
*FRAME_BUFFER.lock() = Some(fb);
}
Err(err) => warn!("framebuffer init failed: {}", err),
}
}

@ -1,5 +1,6 @@
use crate::arch::interrupt::TrapFrame; use crate::arch::interrupt::TrapFrame;
use bcm2837::interrupt::Controller; use bcm2837::interrupt::Controller;
use bcm2837::timer::BasicTimer;
pub use bcm2837::interrupt::Interrupt; pub use bcm2837::interrupt::Interrupt;

@ -0,0 +1,353 @@
//! Mailbox property interface
//!
//! (ref: https://github.com/raspberrypi/firmware/wiki/Mailbox-property-interface)
use super::fb::FramebufferInfo;
use bcm2837::mailbox::{Mailbox, MailboxChannel};
use lazy_static::lazy_static;
use alloc::string::String;
use core::mem;
use spin::Mutex;
use aarch64::asm;
lazy_static! {
static ref MAILBOX: Mutex<Mailbox> = Mutex::new(Mailbox::new());
}
#[derive(Debug)]
pub struct PropertyMailboxError(u32);
pub type PropertyMailboxResult<T> = Result<T, PropertyMailboxError>;
impl From<PropertyMailboxError> for String {
fn from(error: PropertyMailboxError) -> Self {
format!("{:x?}", error)
}
}
/// Buffer request/response code.
/// Copied from `linux/include/soc/bcm2835/raspberrypi-firmware.h`
#[repr(u32)]
#[allow(dead_code)]
#[derive(Copy, Clone, Debug)]
#[allow(non_camel_case_types)]
enum PropertyMailboxStatus {
RPI_FIRMWARE_STATUS_REQUEST = 0,
RPI_FIRMWARE_STATUS_SUCCESS = 0x80000000,
RPI_FIRMWARE_STATUS_ERROR = 0x80000001,
}
use self::PropertyMailboxStatus::*;
/// Tag identifier.
/// Copied from `linux/include/soc/bcm2835/raspberrypi-firmware.h`
#[repr(u32)]
#[allow(dead_code)]
#[derive(Copy, Clone, Debug)]
#[allow(non_camel_case_types)]
enum PropertyMailboxTagId {
RPI_FIRMWARE_PROPERTY_END = 0,
RPI_FIRMWARE_GET_FIRMWARE_REVISION = 0x00000001,
RPI_FIRMWARE_SET_CURSOR_INFO = 0x00008010,
RPI_FIRMWARE_SET_CURSOR_STATE = 0x00008011,
RPI_FIRMWARE_GET_BOARD_MODEL = 0x00010001,
RPI_FIRMWARE_GET_BOARD_REVISION = 0x00010002,
RPI_FIRMWARE_GET_BOARD_MAC_ADDRESS = 0x00010003,
RPI_FIRMWARE_GET_BOARD_SERIAL = 0x00010004,
RPI_FIRMWARE_GET_ARM_MEMORY = 0x00010005,
RPI_FIRMWARE_GET_VC_MEMORY = 0x00010006,
RPI_FIRMWARE_GET_CLOCKS = 0x00010007,
RPI_FIRMWARE_GET_POWER_STATE = 0x00020001,
RPI_FIRMWARE_GET_TIMING = 0x00020002,
RPI_FIRMWARE_SET_POWER_STATE = 0x00028001,
RPI_FIRMWARE_GET_CLOCK_STATE = 0x00030001,
RPI_FIRMWARE_GET_CLOCK_RATE = 0x00030002,
RPI_FIRMWARE_GET_VOLTAGE = 0x00030003,
RPI_FIRMWARE_GET_MAX_CLOCK_RATE = 0x00030004,
RPI_FIRMWARE_GET_MAX_VOLTAGE = 0x00030005,
RPI_FIRMWARE_GET_TEMPERATURE = 0x00030006,
RPI_FIRMWARE_GET_MIN_CLOCK_RATE = 0x00030007,
RPI_FIRMWARE_GET_MIN_VOLTAGE = 0x00030008,
RPI_FIRMWARE_GET_TURBO = 0x00030009,
RPI_FIRMWARE_GET_MAX_TEMPERATURE = 0x0003000a,
RPI_FIRMWARE_GET_STC = 0x0003000b,
RPI_FIRMWARE_ALLOCATE_MEMORY = 0x0003000c,
RPI_FIRMWARE_LOCK_MEMORY = 0x0003000d,
RPI_FIRMWARE_UNLOCK_MEMORY = 0x0003000e,
RPI_FIRMWARE_RELEASE_MEMORY = 0x0003000f,
RPI_FIRMWARE_EXECUTE_CODE = 0x00030010,
RPI_FIRMWARE_EXECUTE_QPU = 0x00030011,
RPI_FIRMWARE_SET_ENABLE_QPU = 0x00030012,
RPI_FIRMWARE_GET_DISPMANX_RESOURCE_MEM_HANDLE = 0x00030014,
RPI_FIRMWARE_GET_EDID_BLOCK = 0x00030020,
RPI_FIRMWARE_GET_CUSTOMER_OTP = 0x00030021,
RPI_FIRMWARE_GET_DOMAIN_STATE = 0x00030030,
RPI_FIRMWARE_GET_THROTTLED = 0x00030046,
RPI_FIRMWARE_GET_CLOCK_MEASURED = 0x00030047,
RPI_FIRMWARE_NOTIFY_REBOOT = 0x00030048,
RPI_FIRMWARE_SET_CLOCK_STATE = 0x00038001,
RPI_FIRMWARE_SET_CLOCK_RATE = 0x00038002,
RPI_FIRMWARE_SET_VOLTAGE = 0x00038003,
RPI_FIRMWARE_SET_TURBO = 0x00038009,
RPI_FIRMWARE_SET_CUSTOMER_OTP = 0x00038021,
RPI_FIRMWARE_SET_DOMAIN_STATE = 0x00038030,
RPI_FIRMWARE_GET_GPIO_STATE = 0x00030041,
RPI_FIRMWARE_SET_GPIO_STATE = 0x00038041,
RPI_FIRMWARE_SET_SDHOST_CLOCK = 0x00038042,
RPI_FIRMWARE_GET_GPIO_CONFIG = 0x00030043,
RPI_FIRMWARE_SET_GPIO_CONFIG = 0x00038043,
RPI_FIRMWARE_GET_PERIPH_REG = 0x00030045,
RPI_FIRMWARE_SET_PERIPH_REG = 0x00038045,
RPI_FIRMWARE_GET_POE_HAT_VAL = 0x00030049,
RPI_FIRMWARE_SET_POE_HAT_VAL = 0x00030050,
/* Dispmanx TAGS */
RPI_FIRMWARE_FRAMEBUFFER_ALLOCATE = 0x00040001,
RPI_FIRMWARE_FRAMEBUFFER_BLANK = 0x00040002,
RPI_FIRMWARE_FRAMEBUFFER_GET_PHYSICAL_WIDTH_HEIGHT = 0x00040003,
RPI_FIRMWARE_FRAMEBUFFER_GET_VIRTUAL_WIDTH_HEIGHT = 0x00040004,
RPI_FIRMWARE_FRAMEBUFFER_GET_DEPTH = 0x00040005,
RPI_FIRMWARE_FRAMEBUFFER_GET_PIXEL_ORDER = 0x00040006,
RPI_FIRMWARE_FRAMEBUFFER_GET_ALPHA_MODE = 0x00040007,
RPI_FIRMWARE_FRAMEBUFFER_GET_PITCH = 0x00040008,
RPI_FIRMWARE_FRAMEBUFFER_GET_VIRTUAL_OFFSET = 0x00040009,
RPI_FIRMWARE_FRAMEBUFFER_GET_OVERSCAN = 0x0004000a,
RPI_FIRMWARE_FRAMEBUFFER_GET_PALETTE = 0x0004000b,
RPI_FIRMWARE_FRAMEBUFFER_GET_TOUCHBUF = 0x0004000f,
RPI_FIRMWARE_FRAMEBUFFER_GET_GPIOVIRTBUF = 0x00040010,
RPI_FIRMWARE_FRAMEBUFFER_RELEASE = 0x00048001,
RPI_FIRMWARE_FRAMEBUFFER_TEST_PHYSICAL_WIDTH_HEIGHT = 0x00044003,
RPI_FIRMWARE_FRAMEBUFFER_TEST_VIRTUAL_WIDTH_HEIGHT = 0x00044004,
RPI_FIRMWARE_FRAMEBUFFER_TEST_DEPTH = 0x00044005,
RPI_FIRMWARE_FRAMEBUFFER_TEST_PIXEL_ORDER = 0x00044006,
RPI_FIRMWARE_FRAMEBUFFER_TEST_ALPHA_MODE = 0x00044007,
RPI_FIRMWARE_FRAMEBUFFER_TEST_VIRTUAL_OFFSET = 0x00044009,
RPI_FIRMWARE_FRAMEBUFFER_TEST_OVERSCAN = 0x0004400a,
RPI_FIRMWARE_FRAMEBUFFER_TEST_PALETTE = 0x0004400b,
RPI_FIRMWARE_FRAMEBUFFER_TEST_VSYNC = 0x0004400e,
RPI_FIRMWARE_FRAMEBUFFER_SET_PHYSICAL_WIDTH_HEIGHT = 0x00048003,
RPI_FIRMWARE_FRAMEBUFFER_SET_VIRTUAL_WIDTH_HEIGHT = 0x00048004,
RPI_FIRMWARE_FRAMEBUFFER_SET_DEPTH = 0x00048005,
RPI_FIRMWARE_FRAMEBUFFER_SET_PIXEL_ORDER = 0x00048006,
RPI_FIRMWARE_FRAMEBUFFER_SET_ALPHA_MODE = 0x00048007,
RPI_FIRMWARE_FRAMEBUFFER_SET_VIRTUAL_OFFSET = 0x00048009,
RPI_FIRMWARE_FRAMEBUFFER_SET_OVERSCAN = 0x0004800a,
RPI_FIRMWARE_FRAMEBUFFER_SET_PALETTE = 0x0004800b,
RPI_FIRMWARE_FRAMEBUFFER_SET_TOUCHBUF = 0x0004801f,
RPI_FIRMWARE_FRAMEBUFFER_SET_GPIOVIRTBUF = 0x00048020,
RPI_FIRMWARE_FRAMEBUFFER_SET_VSYNC = 0x0004800e,
RPI_FIRMWARE_FRAMEBUFFER_SET_BACKLIGHT = 0x0004800f,
RPI_FIRMWARE_VCHIQ_INIT = 0x00048010,
RPI_FIRMWARE_GET_COMMAND_LINE = 0x00050001,
RPI_FIRMWARE_GET_DMA_CHANNELS = 0x00060001,
}
use self::PropertyMailboxTagId::*;
/// A property mailbox tag.
#[repr(C, packed)]
#[derive(Debug)]
#[allow(safe_packed_borrows)]
struct PropertyMailboxTag<T: Sized> {
id: PropertyMailboxTagId,
buf_size: u32,
req_resp_size: u32,
buf: T,
}
/// A request that contained a sequence of concatenated tags. The response
/// overwrites the request.
#[repr(C, packed)]
#[derive(Debug)]
#[allow(safe_packed_borrows)]
struct PropertyMailboxRequest<T: Sized> {
buf_size: u32,
req_resp_code: PropertyMailboxStatus,
buf: T,
end_tag: PropertyMailboxTagId,
}
/// Request buffer address must be 16-byte aligned.
#[repr(C, align(16))]
#[derive(Debug)]
struct Align16<T: Sized>(PropertyMailboxRequest<T>);
/// Pack a sequence of concatenated tags into a request, and send the address
/// to the mailbox.
/// Returns `PropertyMailboxResult<typeof($tags)>`.
macro_rules! send_request {
($tags: ident) => {{
let req = Align16(PropertyMailboxRequest {
buf_size: mem::size_of_val(&$tags) as u32 + 12,
req_resp_code: RPI_FIRMWARE_STATUS_REQUEST,
buf: $tags,
end_tag: RPI_FIRMWARE_PROPERTY_END,
});
let start = &req as *const _ as u32;
let end = start + req.0.buf_size;
{
// flush data cache around mailbox accesses
let mut mbox = MAILBOX.lock();
asm::flush_dcache_range(start as usize, end as usize);
mbox.write(MailboxChannel::Property, start);
mbox.read(MailboxChannel::Property);
asm::flush_dcache_range(start as usize, end as usize);
}
match req.0.req_resp_code {
RPI_FIRMWARE_STATUS_SUCCESS => Ok(req.0.buf),
other => Err(PropertyMailboxError(other as u32)),
}
}};
}
/// Send a tag to mailbox. Will call `send_request!`.
/// Returns `PropertyMailboxResult<typeof(buf)>`.
macro_rules! send_one_tag {
($id: expr, [$($arg: expr),*]) => {{
let buf = [$($arg),*];
let tag = PropertyMailboxTag {
id: $id,
buf_size: mem::size_of_val(&buf) as u32,
req_resp_size: 0,
buf,
};
Ok(send_request!(tag)?.buf)
}};
}
/// Allocates contiguous memory on the GPU. `size` and `align` are in bytes.
/// Returns memory `handle`.
pub fn mem_alloc(size: u32, align: u32, flags: u32) -> PropertyMailboxResult<u32> {
let ret = send_one_tag!(RPI_FIRMWARE_LOCK_MEMORY, [size, align, flags])?;
Ok(ret[0])
}
/// Free the memory buffer of `handle`. status=0 is success.
pub fn mem_free(handle: u32) -> PropertyMailboxResult<()> {
let status = send_one_tag!(RPI_FIRMWARE_RELEASE_MEMORY, [handle])?;
match status[0] {
0 => Ok(()),
other => Err(PropertyMailboxError(other)),
}
}
/// Lock buffer in place, and return a `bus_address`. Must be done before memory
/// can be accessed.
pub fn mem_lock(handle: u32) -> PropertyMailboxResult<u32> {
let ret = send_one_tag!(RPI_FIRMWARE_LOCK_MEMORY, [handle])?;
Ok(ret[0])
}
/// Unlock buffer. It retains contents, but may move. Needs to be locked before
/// next use. status=0 is success.
pub fn mem_unlock(handle: u32) -> PropertyMailboxResult<()> {
let status = send_one_tag!(RPI_FIRMWARE_UNLOCK_MEMORY, [handle])?;
match status[0] {
0 => Ok(()),
other => Err(PropertyMailboxError(other)),
}
}
/// Get physical (display) width/height. Returns `(width, height)` in pixels.
/// Note that the "physical (display)" size is the size of the allocated buffer
/// in memory, not the resolution of the video signal sent to the display device.
pub fn framebuffer_get_physical_size() -> PropertyMailboxResult<(u32, u32)> {
let ret = send_one_tag!(RPI_FIRMWARE_FRAMEBUFFER_GET_PHYSICAL_WIDTH_HEIGHT, [0, 0])?;
Ok((ret[0], ret[1]))
}
/// Get depth. Returns bits per pixel.
pub fn framebuffer_get_depth() -> PropertyMailboxResult<u32> {
let ret = send_one_tag!(RPI_FIRMWARE_FRAMEBUFFER_GET_DEPTH, [0])?;
Ok(ret[0])
}
/// Set virtual offset. Returns `(X, Y)` in pixel.
/// The response may not be the same as the request so it must be checked.
/// May be the previous offset or 0 for unsupported.
pub fn framebuffer_set_virtual_offset(xoffset: u32, yoffset: u32) -> PropertyMailboxResult<(u32, u32)> {
let ret = send_one_tag!(
RPI_FIRMWARE_FRAMEBUFFER_SET_VIRTUAL_OFFSET,
[xoffset, yoffset]
)?;
Ok((ret[0], ret[1]))
}
/// Allocate framebuffer on GPU and try to set width/height/depth.
/// Returns `FramebufferInfo`.
pub fn framebuffer_alloc(width: u32, height: u32, depth: u32) -> PropertyMailboxResult<FramebufferInfo> {
#[repr(C, packed)]
#[derive(Debug)]
struct FramebufferAllocTag {
set_physical_size: PropertyMailboxTag<[u32; 2]>,
set_virtual_size: PropertyMailboxTag<[u32; 2]>,
set_depth: PropertyMailboxTag<[u32; 1]>,
set_virtual_offset: PropertyMailboxTag<[u32; 2]>,
allocate: PropertyMailboxTag<[u32; 2]>,
get_pitch: PropertyMailboxTag<[u32; 1]>,
}
let tags = FramebufferAllocTag {
// Set physical (buffer) width/height. Returns `(width, height)` in pixel.
set_physical_size: PropertyMailboxTag {
id: RPI_FIRMWARE_FRAMEBUFFER_SET_PHYSICAL_WIDTH_HEIGHT,
buf_size: 8,
req_resp_size: 0,
buf: [width, height],
},
// Set virtual (buffer) width/height. Returns `(width, height)` in pixel.
set_virtual_size: PropertyMailboxTag {
id: RPI_FIRMWARE_FRAMEBUFFER_SET_VIRTUAL_WIDTH_HEIGHT,
buf_size: 8,
req_resp_size: 0,
buf: [width, height],
},
// Set depth; Returns bits per pixel.
set_depth: PropertyMailboxTag {
id: RPI_FIRMWARE_FRAMEBUFFER_SET_DEPTH,
buf_size: 4,
req_resp_size: 0,
buf: [depth],
},
// Set virtual offset. Returns `(X, Y)` in pixel.
set_virtual_offset: PropertyMailboxTag {
id: RPI_FIRMWARE_FRAMEBUFFER_SET_VIRTUAL_OFFSET,
buf_size: 8,
req_resp_size: 0,
buf: [0, 0],
},
// Allocate buffer. Returns `(base_address, size)` in bytes.
allocate: PropertyMailboxTag {
id: RPI_FIRMWARE_FRAMEBUFFER_ALLOCATE,
buf_size: 8,
req_resp_size: 0,
buf: [0x1000, 0],
},
// Get pitch. Return bytes per line.
get_pitch: PropertyMailboxTag {
id: RPI_FIRMWARE_FRAMEBUFFER_GET_PITCH,
buf_size: 4,
req_resp_size: 0,
buf: [0],
},
};
let ret = send_request!(tags)?;
Ok(FramebufferInfo {
xres: ret.set_physical_size.buf[0],
yres: ret.set_physical_size.buf[1],
xres_virtual: ret.set_virtual_size.buf[0],
yres_virtual: ret.set_virtual_size.buf[1],
xoffset: ret.set_virtual_offset.buf[0],
yoffset: ret.set_virtual_offset.buf[1],
depth: ret.set_depth.buf[0],
pitch: ret.get_pitch.buf[0],
bus_addr: ret.allocate.buf[0],
screen_size: ret.allocate.buf[1],
})
}

@ -2,23 +2,27 @@
use once::*; use once::*;
pub mod fb;
pub mod irq; pub mod irq;
pub mod timer; pub mod timer;
pub mod serial; pub mod serial;
pub mod mailbox;
pub const IO_REMAP_BASE: usize = bcm2837::IO_BASE; pub const IO_REMAP_BASE: usize = bcm2837::IO_BASE;
pub const IO_REMAP_END: usize = 0x40001000; pub const IO_REMAP_END: usize = 0x40001000;
/// Some initializations must be done before other initializations. /// Initialize serial port before other initializations.
pub fn init_early() { pub fn init_serial_early() {
assert_has_not_been_called!("board::init must be called only once"); assert_has_not_been_called!("board::init must be called only once");
serial::SERIAL_PORT.lock().init(); serial::init();
println!("Hello Raspberry Pi!"); println!("Hello Raspberry Pi!");
} }
/// Initialize raspi3 drivers /// Initialize raspi3 drivers
pub fn init_driver() { pub fn init_driver() {
#[cfg(not(feature = "nographic"))]
fb::init();
timer::init(); timer::init();
} }

@ -2,6 +2,7 @@ use bcm2837::mini_uart::{MiniUart, MiniUartInterruptId};
use lazy_static::lazy_static; use lazy_static::lazy_static;
use core::fmt; use core::fmt;
use spin::Mutex; use spin::Mutex;
use once::*;
/// Struct to get a global SerialPort interface /// Struct to get a global SerialPort interface
pub struct SerialPort { pub struct SerialPort {
@ -21,7 +22,9 @@ impl SerialPort {
} }
/// Init a newly created SerialPort, can only be called once. /// Init a newly created SerialPort, can only be called once.
pub fn init(&mut self) { fn init(&mut self) {
assert_has_not_been_called!("SerialPort::init must be called only once");
self.mu.init(); self.mu.init();
super::irq::register_irq(super::irq::Interrupt::Aux, handle_serial_irq); super::irq::register_irq(super::irq::Interrupt::Aux, handle_serial_irq);
} }
@ -78,6 +81,10 @@ fn handle_serial_irq() {
} }
} }
lazy_static!{ lazy_static! {
pub static ref SERIAL_PORT: Mutex<SerialPort> = Mutex::new(SerialPort::new()); pub static ref SERIAL_PORT: Mutex<SerialPort> = Mutex::new(SerialPort::new());
} }
pub fn init() {
SERIAL_PORT.lock().init();
}

@ -1,17 +1,19 @@
use bcm2837::timer; use bcm2837::timer::{BasicTimer, Timer};
use log::*; use log::*;
/// Initialization timer.
pub fn init() { pub fn init() {
timer::init(); Timer::new().init();
set_next(); set_next();
info!("timer: init end"); info!("timer: init end");
} }
/// Returns the current time in microseconds.
pub fn get_cycle() -> u64 { pub fn get_cycle() -> u64 {
timer::current_time() Timer::new().read()
} }
/// Set next timer interrupt to 10 ms from now.
pub fn set_next() { pub fn set_next() {
// 10 ms Timer::new().tick_in(10 * 1000);
timer::tick_in(10 * 1000);
} }

@ -1,7 +1,7 @@
ENTRY(_start) ENTRY(_start)
SECTIONS { SECTIONS {
. = 0x80000; /* Raspbery Pi 3 Aarch64 (kernel8.img) load address */ . = 0x80000; /* Raspbery Pi 3 AArch64 (kernel8.img) load address */
.boot : { .boot : {
KEEP(*(.text.boot)) /* from boot.S */ KEEP(*(.text.boot)) /* from boot.S */

@ -0,0 +1,90 @@
//! Frambuffer color
pub trait FramebufferColor {
/// pack as 32-bit integer
fn pack16(&self) -> u16;
/// pack as 32-bit integer
fn pack32(&self) -> u32;
}
#[repr(C)]
#[derive(Debug, Clone, Copy, PartialEq)]
pub struct RgbColor(u8, u8, u8);
#[repr(u8)]
#[allow(dead_code)]
#[derive(Debug, Clone, Copy, PartialEq)]
pub enum ConsoleColor {
Black = 0,
Red = 1,
Green = 2,
Yellow = 3,
Blue = 4,
Magenta = 5,
Cyan = 6,
White = 7,
BrightBlack = 60,
BrightRed = 61,
BrightGreen = 62,
BrightYellow = 63,
BrightBlue = 64,
BrightMagenta = 65,
BrightCyan = 66,
BrightWhite = 67,
}
use self::ConsoleColor::*;
impl From<ConsoleColor> for RgbColor {
/// Convert `ConsoleColor` to `RgbColor`.
/// use `CMD` color scheme.
/// (ref: https://en.wikipedia.org/wiki/ANSI_escape_code)
fn from(color: ConsoleColor) -> Self {
match color {
Black => RgbColor(0, 0, 0),
Red => RgbColor(128, 0, 0),
Green => RgbColor(0, 128, 8),
Yellow => RgbColor(128, 128, 0),
Blue => RgbColor(0, 0, 128),
Magenta => RgbColor(128, 0, 128),
Cyan => RgbColor(0, 128, 128),
White => RgbColor(192, 192, 192),
BrightBlack => RgbColor(128, 128, 128),
BrightRed => RgbColor(255, 0, 0),
BrightGreen => RgbColor(0, 255, 0),
BrightYellow => RgbColor(255, 255, 0),
BrightBlue => RgbColor(0, 0, 255),
BrightMagenta => RgbColor(255, 0, 255),
BrightCyan => RgbColor(0, 255, 255),
BrightWhite => RgbColor(255, 255, 255),
}
}
}
impl FramebufferColor for RgbColor {
#[inline]
fn pack16(&self) -> u16 {
// BGR565
((self.0 as u16 & 0xF8) << 8) | ((self.1 as u16 & 0xFC) << 3) | (self.2 as u16 >> 3)
}
#[inline]
fn pack32(&self) -> u32 {
// BGRA8888
// FIXME: qemu and low version RPi use RGBA order for 24/32-bit color depth,
// but RPi3 B+ uses BGRA order for 24/32-bit color depth.
((self.0 as u32) << 16) | ((self.1 as u32) << 8) | (self.2 as u32)
}
}
impl FramebufferColor for ConsoleColor {
#[inline]
fn pack16(&self) -> u16 {
RgbColor::from(*self).pack16()
}
#[inline]
fn pack32(&self) -> u32 {
RgbColor::from(*self).pack32()
}
}

@ -0,0 +1,152 @@
//! ANSI escape sequences parser
//! (ref: https://en.wikipedia.org/wiki/ANSI_escape_code)
use super::color::{ConsoleColor, ConsoleColor::*, FramebufferColor};
use alloc::vec::Vec;
#[repr(C)]
#[derive(Debug, Clone, Copy, PartialEq)]
pub struct CharacterAttribute<C: FramebufferColor = ConsoleColor> {
/// foreground color
pub foreground: C,
/// background color
pub background: C,
/// show underline
pub underline: bool,
/// swap foreground and background colors
pub reverse: bool,
/// text marked cfor deletion
pub strikethrough: bool,
}
impl Default for CharacterAttribute {
fn default() -> Self {
CharacterAttribute {
foreground: White,
background: Black,
underline: false,
reverse: false,
strikethrough: false,
}
}
}
#[derive(Debug, PartialEq)]
enum ParseStatus {
/// The last character is `ESC`, start parsing the escape sequence.
BeginEscapeSequence,
/// The character followed by `ESC` is `[`, start parsing the CSI (Control
/// Sequence Introducer) sequence. The CSI sequence format is like
/// `ESC [ n1 ; n2 ; ... m`.
ParsingCSI,
/// Display text Normally.
Text,
}
#[derive(Debug)]
pub struct EscapeParser {
status: ParseStatus,
char_attr: CharacterAttribute,
current_param: Option<u8>,
params: Vec<u8>,
}
impl EscapeParser {
pub fn new() -> EscapeParser {
EscapeParser {
status: ParseStatus::Text,
char_attr: CharacterAttribute::default(),
params: Vec::new(),
current_param: None,
}
}
pub fn is_parsing(&self) -> bool {
self.status != ParseStatus::Text
}
/// See an `ECS` character, start parsing escape sequence.
pub fn start_parse(&mut self) {
assert!(self.status == ParseStatus::Text);
self.status = ParseStatus::BeginEscapeSequence;
self.current_param = None;
}
//// Parse SGR (Select Graphic Rendition) parameters.
fn parse_sgr_params(&mut self) {
use core::mem::transmute;
for param in &self.params {
match param {
0 => self.char_attr = CharacterAttribute::default(),
4 => self.char_attr.underline = true,
7 => self.char_attr.reverse = true,
9 => self.char_attr.strikethrough = true,
24 => self.char_attr.underline = false,
27 => self.char_attr.reverse = false,
29 => self.char_attr.strikethrough = false,
30...37 | 90...97 => self.char_attr.foreground = unsafe { transmute(param - 30) },
40...47 | 100...107 => self.char_attr.background = unsafe { transmute(param - 40) },
_ => { /* unimplemented!() */ }
}
}
}
/// See a character during parsing.
pub fn parse(&mut self, byte: u8) -> bool {
assert!(self.status != ParseStatus::Text);
match self.status {
ParseStatus::BeginEscapeSequence => match byte {
b'[' => {
self.status = ParseStatus::ParsingCSI;
self.current_param = Some(0);
self.params.clear();
return true;
}
_ => { /* unimplemented!() */ }
},
ParseStatus::ParsingCSI => match byte {
b'0'...b'9' => {
let digit = (byte - b'0') as u32;
if let Some(param) = self.current_param {
let res: u32 = param as u32 * 10 + digit;
self.current_param = if res <= 0xFF { Some(res as u8) } else { None };
}
return true;
}
b';' => {
if let Some(param) = self.current_param {
self.params.push(param);
}
self.current_param = Some(0);
return true;
}
// @AZ[\]^_`az{|}~
0x40...0x7E => {
if let Some(param) = self.current_param {
self.params.push(param);
}
match byte {
b'm' => self.parse_sgr_params(),
_ => { /* unimplemented!() */ }
}
self.status = ParseStatus::Text;
self.current_param = None;
self.params.clear();
return true;
}
_ => {}
},
ParseStatus::Text => {}
}
self.status = ParseStatus::Text;
self.current_param = None;
self.params.clear();
false
}
pub fn char_attribute(&self) -> CharacterAttribute {
self.char_attr
}
}

File diff suppressed because it is too large Load Diff

@ -0,0 +1,18 @@
//! Console font
mod font8x16;
pub use self::font8x16::Font8x16;
pub trait Font {
const HEIGHT: usize;
const WIDTH: usize;
/// The `y` coordinate of underline.
const UNDERLINE: usize;
/// The `y` coordinate of strikethrough.
const STRIKETHROUGH: usize;
/// Whether the character `byte` is visible at `(x, y)`.
fn get(byte: u8, x: usize, y: usize) -> bool;
}

@ -0,0 +1,237 @@
//! Framebuffer console display driver for ARM64
mod color;
mod escape_parser;
mod fonts;
use self::color::FramebufferColor;
use self::escape_parser::{CharacterAttribute, EscapeParser};
use self::fonts::{Font, Font8x16};
use super::fb::{ColorDepth::*, FramebufferInfo, FRAME_BUFFER};
use alloc::vec::Vec;
use core::fmt;
use core::marker::PhantomData;
use lazy_static::lazy_static;
use log::*;
use spin::Mutex;
#[repr(C)]
#[derive(Debug, Clone, Copy, PartialEq)]
pub struct ConsoleChar {
ascii_char: u8,
attr: CharacterAttribute,
}
impl Default for ConsoleChar {
fn default() -> Self {
ConsoleChar {
ascii_char: 0,
attr: CharacterAttribute::default(),
}
}
}
/// Character buffer
struct ConsoleBuffer<F: Font> {
num_row: usize,
num_col: usize,
buf: Vec<Vec<ConsoleChar>>,
font: PhantomData<F>,
}
impl<F: Font> ConsoleBuffer<F> {
fn new(num_row: usize, num_col: usize) -> ConsoleBuffer<F> {
ConsoleBuffer {
num_row,
num_col,
buf: vec![vec![ConsoleChar::default(); num_col]; num_row],
font: PhantomData,
}
}
/// Write one character at `(row, col)`.
fn write(&mut self, row: usize, col: usize, ch: ConsoleChar) {
if self.buf[row][col] == ch {
return;
}
self.buf[row][col] = ch;
let off_x = col * F::WIDTH;
let off_y = row * F::HEIGHT;
if let Some(fb) = FRAME_BUFFER.lock().as_mut() {
let (mut foreground, mut background) = match fb.color_depth {
ColorDepth16 => (
ch.attr.foreground.pack16() as u32,
ch.attr.background.pack16() as u32,
),
ColorDepth32 => (
ch.attr.foreground.pack32(),
ch.attr.background.pack32(),
),
};
if ch.attr.reverse {
core::mem::swap(&mut foreground, &mut background);
}
let underline_y = if ch.attr.underline {
F::UNDERLINE
} else {
F::HEIGHT
};
let strikethrough_y = if ch.attr.strikethrough {
F::STRIKETHROUGH
} else {
F::HEIGHT
};
for y in 0..F::HEIGHT {
for x in 0..F::WIDTH {
let pixel = if y == underline_y || y == strikethrough_y || F::get(ch.ascii_char, x, y) {
foreground
} else {
background
};
fb.write((off_x + x) as u32, (off_y + y) as u32, pixel);
}
}
}
}
/// Delete one character at `(row, col)`.
fn delete(&mut self, row: usize, col: usize) {
self.write(row, col, ConsoleChar::default());
}
/// Insert one blank line at the bottom, and scroll up one line.
/// XXX: read framebuffer is toooo slow, do not use `fb.copy()`.
fn new_line(&mut self) {
for i in 1..self.num_row {
for j in 0..self.num_col {
self.write(i - 1, j, self.buf[i][j]);
}
}
for j in 0..self.num_col {
self.write(self.num_row - 1, j, ConsoleChar::default());
}
}
/// Clear the entire buffer and screen.
fn clear(&mut self) {
for i in 0..self.num_row {
for j in 0..self.num_col {
self.buf[i][j] = ConsoleChar::default()
}
}
if let Some(fb) = FRAME_BUFFER.lock().as_mut() {
fb.clear();
}
}
}
/// Console structure
pub struct Console<F: Font> {
/// cursor row
row: usize,
/// cursor column
col: usize,
/// escape sequence parser
parser: EscapeParser,
/// character buffer
buf: ConsoleBuffer<F>,
}
impl<F: Font> Console<F> {
fn new(fb: &FramebufferInfo) -> Console<F> {
let num_row = fb.yres as usize / F::HEIGHT;
let num_col = fb.xres as usize / F::WIDTH;
Console {
row: 0,
col: 0,
parser: EscapeParser::new(),
buf: ConsoleBuffer::new(num_row, num_col),
}
}
fn new_line(&mut self) {
let attr_blank = ConsoleChar {
ascii_char: 0,
attr: self.parser.char_attribute(),
};
for j in self.col..self.buf.num_col {
self.buf.write(self.row, j, attr_blank);
}
self.col = 0;
if self.row < self.buf.num_row - 1 {
self.row += 1;
} else {
self.buf.new_line();
}
}
fn write_byte(&mut self, byte: u8) {
if self.parser.is_parsing() {
if self.parser.parse(byte) {
return;
}
}
match byte {
b'\x7f' => {
if self.col > 0 {
self.col -= 1;
self.buf.delete(self.row, self.col);
} else if self.row > 0 {
self.row -= 1;
self.col = self.buf.num_col - 1;
self.buf.delete(self.row, self.col);
}
}
b'\n' => self.new_line(),
b'\r' => self.col = 0,
b'\x1b' => self.parser.start_parse(),
byte => {
if self.col >= self.buf.num_col {
self.new_line();
}
let ch = ConsoleChar {
ascii_char: byte,
attr: self.parser.char_attribute(),
};
self.buf.write(self.row, self.col, ch);
self.col += 1;
}
}
}
pub fn clear(&mut self) {
self.row = 0;
self.col = 0;
self.parser = EscapeParser::new();
self.buf.clear();
}
}
impl<F: Font> fmt::Write for Console<F> {
fn write_str(&mut self, s: &str) -> fmt::Result {
for byte in s.bytes() {
self.write_byte(byte)
}
Ok(())
}
}
lazy_static! {
pub static ref CONSOLE: Mutex<Option<Console<Font8x16>>> = Mutex::new(None);
}
/// Initialize console driver
pub fn init() {
if let Some(fb) = FRAME_BUFFER.lock().as_ref() {
*CONSOLE.lock() = Some(Console::new(&fb.fb_info));
}
if !CONSOLE.lock().is_none() {
info!("console: init end");
} else {
warn!("console: init failed");
}
}

@ -1,12 +1,16 @@
/// ARM64 drivers //! ARM64 drivers
use super::board;
use once::*; use once::*;
use super::board; pub use self::board::fb;
pub use self::board::serial;
pub mod console;
/// Initialize ARM64 common drivers /// Initialize ARM64 common drivers
pub fn init() { pub fn init() {
assert_has_not_been_called!(); assert_has_not_been_called!("driver::init must be called only once");
board::init_driver(); board::init_driver();
console::init();
} }

@ -1,14 +1,20 @@
//! Serial driver for aarch64. //! Input/output for aarch64.
use super::driver::serial::*;
use super::driver::console::CONSOLE;
use core::fmt::{Arguments, Write}; use core::fmt::{Arguments, Write};
use super::board::serial::*;
pub fn getchar() -> char { pub fn getchar() -> char {
unsafe { SERIAL_PORT.force_unlock(); } unsafe { SERIAL_PORT.force_unlock() }
SERIAL_PORT.lock().receive() as char SERIAL_PORT.lock().receive() as char
} }
pub fn putfmt(fmt: Arguments) { pub fn putfmt(fmt: Arguments) {
unsafe { SERIAL_PORT.force_unlock(); } unsafe { SERIAL_PORT.force_unlock() }
SERIAL_PORT.lock().write_fmt(fmt).unwrap() SERIAL_PORT.lock().write_fmt(fmt).unwrap();
unsafe { CONSOLE.force_unlock() }
if let Some(console) = CONSOLE.lock().as_mut() {
console.write_fmt(fmt).unwrap();
}
} }

@ -1,11 +1,12 @@
//! Memory initialization for aarch64. //! Memory initialization for aarch64.
use crate::memory::{init_heap, Linear, MemoryAttr, MemorySet, FRAME_ALLOCATOR};
use super::paging::MMIOType;
use aarch64::paging::{memory_attribute::*, PhysFrame as Frame};
use aarch64::{addr::*, barrier, regs::*};
use atags::atags::Atags;
use log::*; use log::*;
use ucore_memory::PAGE_SIZE; use ucore_memory::PAGE_SIZE;
use atags::atags::Atags;
use aarch64::{barrier, regs::*, addr::*};
use aarch64::paging::{PhysFrame as Frame, memory_attribute::*};
use crate::memory::{FRAME_ALLOCATOR, init_heap, MemoryAttr, MemorySet, Linear};
/// Memory initialization. /// Memory initialization.
pub fn init() { pub fn init() {
@ -30,8 +31,8 @@ pub fn init_mmu_early() {
// device. // device.
MAIR_EL1.write( MAIR_EL1.write(
MAIR_EL1::Attr0.val(MairDevice::config_value()) + MAIR_EL1::Attr0.val(MairNormal::config_value()) +
MAIR_EL1::Attr1.val(MairNormal::config_value()) + MAIR_EL1::Attr1.val(MairDevice::config_value()) +
MAIR_EL1::Attr2.val(MairNormalNonCacheable::config_value()), MAIR_EL1::Attr2.val(MairNormalNonCacheable::config_value()),
); );
@ -62,19 +63,19 @@ pub fn init_mmu_early() {
// Switch the MMU on. // Switch the MMU on.
// //
// First, force all previous changes to be seen before the MMU is enabled. // First, force all previous changes to be seen before the MMU is enabled.
unsafe { barrier::isb(barrier::SY); } unsafe { barrier::isb(barrier::SY) }
// Enable the MMU and turn on data and instruction caching. // Enable the MMU and turn on data and instruction caching.
SCTLR_EL1.modify(SCTLR_EL1::M::Enable + SCTLR_EL1::C::Cacheable + SCTLR_EL1::I::Cacheable); SCTLR_EL1.modify(SCTLR_EL1::M::Enable + SCTLR_EL1::C::Cacheable + SCTLR_EL1::I::Cacheable);
// Force MMU init to complete before next instruction // Force MMU init to complete before next instruction
unsafe { barrier::isb(barrier::SY); } unsafe { barrier::isb(barrier::SY) }
} }
fn init_frame_allocator() { fn init_frame_allocator() {
use crate::consts::MEMORY_OFFSET;
use bit_allocator::BitAlloc; use bit_allocator::BitAlloc;
use core::ops::Range; use core::ops::Range;
use crate::consts::MEMORY_OFFSET;
let (start, end) = memory_map().expect("failed to find memory map"); let (start, end) = memory_map().expect("failed to find memory map");
let mut ba = FRAME_ALLOCATOR.lock(); let mut ba = FRAME_ALLOCATOR.lock();
@ -82,14 +83,14 @@ fn init_frame_allocator() {
info!("FrameAllocator init end"); info!("FrameAllocator init end");
/* /*
* @param: * @param:
* start: start address * start: start address
* end: end address * end: end address
* @brief: * @brief:
* transform the memory address to the page number * transform the memory address to the page number
* @retval: * @retval:
* the page number range from start address to end address * the page number range from start address to end address
*/ */
fn to_range(start: usize, end: usize) -> Range<usize> { fn to_range(start: usize, end: usize) -> Range<usize> {
let page_start = (start - MEMORY_OFFSET) / PAGE_SIZE; let page_start = (start - MEMORY_OFFSET) / PAGE_SIZE;
let page_end = (end - MEMORY_OFFSET - 1) / PAGE_SIZE + 1; let page_end = (end - MEMORY_OFFSET - 1) / PAGE_SIZE + 1;
@ -97,6 +98,8 @@ fn init_frame_allocator() {
} }
} }
static mut KERNEL_MEMORY_SET: Option<MemorySet> = None;
/// remap kernel page table after all initialization. /// remap kernel page table after all initialization.
fn remap_the_kernel() { fn remap_the_kernel() {
let mut ms = MemorySet::new_bare(); let mut ms = MemorySet::new_bare();
@ -107,13 +110,21 @@ fn remap_the_kernel() {
ms.push(sbss as usize, ebss as usize, Linear::new(0, MemoryAttr::default()), "bss"); ms.push(sbss as usize, ebss as usize, Linear::new(0, MemoryAttr::default()), "bss");
use super::board::{IO_REMAP_BASE, IO_REMAP_END}; use super::board::{IO_REMAP_BASE, IO_REMAP_END};
ms.push(IO_REMAP_BASE, IO_REMAP_END, Linear::new(0, MemoryAttr::default().mmio()), "io_remap"); ms.push(IO_REMAP_BASE, IO_REMAP_END, Linear::new(0, MemoryAttr::default().mmio(MMIOType::Device as u8)), "io_remap");
unsafe { ms.get_page_table_mut().activate_as_kernel(); } unsafe { ms.get_page_table_mut().activate_as_kernel() }
::core::mem::forget(ms); unsafe { KERNEL_MEMORY_SET = Some(ms) }
info!("kernel remap end"); info!("kernel remap end");
} }
pub fn ioremap(start: usize, len: usize, name: &'static str) -> usize {
if let Some(ms) = unsafe { KERNEL_MEMORY_SET.as_mut() } {
ms.push(start, start + len, Linear::new(0, MemoryAttr::default().mmio(MMIOType::NormalNonCacheable as u8)), name);
return start;
}
0
}
/// Returns the (start address, end address) of the available memory on this /// Returns the (start address, end address) of the available memory on this
/// system if it can be determined. If it cannot, `None` is returned. /// system if it can be determined. If it cannot, `None` is returned.
/// ///
@ -131,7 +142,7 @@ fn memory_map() -> Option<(usize, usize)> {
None None
} }
extern { extern "C" {
fn bootstacktop(); fn bootstacktop();
fn stext(); fn stext();
fn etext(); fn etext();

@ -18,13 +18,13 @@ global_asm!(include_str!("boot/boot.S"));
#[no_mangle] // don't mangle the name of this function #[no_mangle] // don't mangle the name of this function
pub extern "C" fn rust_main() -> ! { pub extern "C" fn rust_main() -> ! {
memory::init_mmu_early(); // Enable mmu and paging memory::init_mmu_early(); // Enable mmu and paging
board::init_early(); board::init_serial_early();
println!("{}", LOGO);
crate::logging::init(); crate::logging::init();
interrupt::init(); interrupt::init();
memory::init(); memory::init();
driver::init(); driver::init();
println!("{}", LOGO);
crate::process::init(); crate::process::init();

@ -20,7 +20,7 @@ pub fn setup_temp_page_table(frame_lvl4: Frame, frame_lvl3: Frame, frame_lvl2: F
p2.zero(); p2.zero();
let (start_addr, end_addr) = (0, 0x40000000); let (start_addr, end_addr) = (0, 0x40000000);
let block_flags = EF::VALID | EF::AF | EF::WRITE | EF::XN; let block_flags = EF::VALID | EF::AF | EF::WRITE | EF::UXN;
for page in Page::<Size2MiB>::range_of(start_addr, end_addr) { for page in Page::<Size2MiB>::range_of(start_addr, end_addr) {
let paddr = PhysAddr::new(page.start_address().as_u64()); let paddr = PhysAddr::new(page.start_address().as_u64());
@ -79,6 +79,14 @@ impl ActivePageTable {
} }
} }
#[repr(u8)]
pub enum MMIOType {
Normal = 0,
Device = 1,
NormalNonCacheable = 2,
Unsupported = 3,
}
impl Entry for PageEntry { impl Entry for PageEntry {
fn update(&mut self) { fn update(&mut self) {
let addr = VirtAddr::new_unchecked((self as *const _ as u64) << 9); let addr = VirtAddr::new_unchecked((self as *const _ as u64) << 9);
@ -123,28 +131,39 @@ impl Entry for PageEntry {
} }
fn execute(&self) -> bool { fn execute(&self) -> bool {
if self.user() { if self.user() {
!self.0.flags().contains(EF::XN) !self.0.flags().contains(EF::UXN)
} else { } else {
!self.0.flags().contains(EF::PXN) !self.0.flags().contains(EF::PXN)
} }
} }
fn set_execute(&mut self, value: bool) { fn set_execute(&mut self, value: bool) {
if self.user() { if self.user() {
self.as_flags().set(EF::XN, !value) self.as_flags().set(EF::UXN, !value)
} else { } else {
self.as_flags().set(EF::PXN, !value) self.as_flags().set(EF::PXN, !value)
} }
} }
fn mmio(&self) -> bool { fn mmio(&self) -> u8 {
self.0.attr().value == MairDevice::attr_value().value let value = self.0.attr().value;
} if value == MairNormal::attr_value().value {
fn set_mmio(&mut self, value: bool) { 0
if value { } else if value == MairDevice::attr_value().value {
self.0.modify_attr(MairDevice::attr_value()) 1
} else if value == MairNormalNonCacheable::attr_value().value {
2
} else { } else {
self.0.modify_attr(MairNormal::attr_value()) 3
} }
} }
fn set_mmio(&mut self, value: u8) {
let attr = match value {
0 => MairNormal::attr_value(),
1 => MairDevice::attr_value(),
2 => MairNormalNonCacheable::attr_value(),
_ => return,
};
self.0.modify_attr(attr);
}
} }
impl PageEntry { impl PageEntry {

@ -214,8 +214,8 @@ impl Entry for PageEntry {
fn set_user(&mut self, value: bool) { self.0.flags_mut().set(EF::USER, value); } fn set_user(&mut self, value: bool) { self.0.flags_mut().set(EF::USER, value); }
fn execute(&self) -> bool { self.0.flags().contains(EF::EXECUTABLE) } fn execute(&self) -> bool { self.0.flags().contains(EF::EXECUTABLE) }
fn set_execute(&mut self, value: bool) { self.0.flags_mut().set(EF::EXECUTABLE, value); } fn set_execute(&mut self, value: bool) { self.0.flags_mut().set(EF::EXECUTABLE, value); }
fn mmio(&self) -> bool { false } fn mmio(&self) -> u8 { 0 }
fn set_mmio(&mut self, _value: bool) { } fn set_mmio(&mut self, _value: u8) { }
} }
#[derive(Debug)] #[derive(Debug)]

@ -111,8 +111,8 @@ impl Entry for PageEntry {
} }
fn execute(&self) -> bool { !self.0.flags().contains(EF::NO_EXECUTE) } fn execute(&self) -> bool { !self.0.flags().contains(EF::NO_EXECUTE) }
fn set_execute(&mut self, value: bool) { self.as_flags().set(EF::NO_EXECUTE, !value); } fn set_execute(&mut self, value: bool) { self.as_flags().set(EF::NO_EXECUTE, !value); }
fn mmio(&self) -> bool { false } fn mmio(&self) -> u8 { 0 }
fn set_mmio(&mut self, _value: bool) { } fn set_mmio(&mut self, _value: u8) { }
} }
fn get_entry_ptr(addr: usize, level: u8) -> *mut PageEntry { fn get_entry_ptr(addr: usize, level: u8) -> *mut PageEntry {

@ -1,6 +1,7 @@
#![feature(lang_items)] #![feature(lang_items)]
#![feature(alloc)] #![feature(alloc)]
#![feature(naked_functions)] #![feature(naked_functions)]
#![feature(untagged_unions)]
#![feature(asm)] #![feature(asm)]
#![feature(optin_builtin_traits)] #![feature(optin_builtin_traits)]
#![feature(panic_info_message)] #![feature(panic_info_message)]
@ -8,6 +9,7 @@
#![no_std] #![no_std]
// just keep it ... // just keep it ...
#[macro_use]
extern crate alloc; extern crate alloc;
pub use crate::process::{processor, new_kernel_context}; pub use crate::process::{processor, new_kernel_context};

@ -25,8 +25,8 @@
#hdmi_force_hotplug=1 #hdmi_force_hotplug=1
# uncomment to force a specific HDMI mode (this will force VGA) # uncomment to force a specific HDMI mode (this will force VGA)
#hdmi_group=1 hdmi_group=2 # DMT
#hdmi_mode=1 hdmi_mode=85 # 1280x720
# uncomment to force a HDMI mode rather than DVI. This can make audio work in # uncomment to force a HDMI mode rather than DVI. This can make audio work in
# DMT (computer monitor) modes # DMT (computer monitor) modes

@ -0,0 +1,43 @@
#![no_std]
#![no_main]
#[macro_use]
extern crate ucore_ulib;
macro_rules! color_text {
($text:expr, $color:expr) => {{
format_args!("\x1b[{}m{}\x1b[0m", $color, $text)
}};
}
// IMPORTANT: Must define main() like this
#[no_mangle]
pub fn main() {
println!(
"{}{}{}{}{} {}{}{}{} {}{}{}{}{}{}",
color_text!("H", 31),
color_text!("e", 32),
color_text!("l", 33),
color_text!("l", 34),
color_text!("o", 35),
color_text!("R", 36),
color_text!("u", 37),
color_text!("s", 90),
color_text!("t", 91),
color_text!("u", 92),
color_text!("C", 93),
color_text!("o", 94),
color_text!("r", 95),
color_text!("e", 96),
color_text!("!", 97),
);
let text = "reguler \x1b[4munderline\x1b[24m \x1b[7mreverse\x1b[27m \x1b[9mstrikethrough\x1b[29m";
println!("\x1b[47m{}\x1b[0m", color_text!(text, 30));
for i in 31..38 {
println!("{}", color_text!(text, i));
}
for i in 90..98 {
println!("{}", color_text!(text, i));
}
}
Loading…
Cancel
Save