diff --git a/Cargo.toml b/Cargo.toml index b67152c5..805002a3 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -20,7 +20,6 @@ cfg-if = "1.0.0" bitmap-font = { version = "0.3.0" } embedded-graphics = "0.8.0" git-version = "0.3.5" -acpi = "4.1.1" [dependencies.elf] version = "0.7.2" @@ -35,3 +34,4 @@ aarch64-cpu = "9.3.1" [target.'cfg(target_arch = "x86_64")'.dependencies] yboot-proto = { git = "https://git.alnyan.me/yggdrasil/yboot-proto.git" } aml = "0.16.4" +acpi = "4.1.1" diff --git a/src/arch/aarch64/context.rs b/src/arch/aarch64/context.rs index 1bcc0e55..ab0e2370 100644 --- a/src/arch/aarch64/context.rs +++ b/src/arch/aarch64/context.rs @@ -1,12 +1,15 @@ //! AArch64-specific task context implementation use core::{arch::global_asm, cell::UnsafeCell}; -use abi::error::Error; +use abi::{error::Error, process::ExitCode}; use alloc::boxed::Box; -use crate::mem::{ - phys::{self, PageUsage}, - ConvertAddress, +use crate::{ + mem::{ + phys::{self, PageUsage}, + ConvertAddress, + }, + task::process::Process, }; struct StackBuilder { @@ -82,6 +85,11 @@ impl StackBuilder { } impl TaskContext { + /// Extra number of bytes to offset the user stack pointer + pub const USER_STACK_EXTRA_ALIGN: usize = 0; + /// Extra number of bytes to offset the signal stack pointer + pub const SIGNAL_STACK_EXTRA_ALIGN: usize = 0; + /// Constructs a kernel thread context. For a more convenient way of constructing kernel /// processes, see [TaskContext::kernel_closure()]. pub fn kernel(entry: extern "C" fn(usize) -> !, arg: usize) -> Result { @@ -114,7 +122,8 @@ impl TaskContext { extern "C" fn closure_wrapper(closure_addr: usize) -> ! { let closure = unsafe { Box::from_raw(closure_addr as *mut F) }; closure(); - todo!("Process termination"); + Process::current().exit(ExitCode::SUCCESS); + unreachable!(); } let closure = Box::new(f); diff --git a/src/arch/aarch64/exception.rs b/src/arch/aarch64/exception.rs index 546e4145..5ebf8e0b 100644 --- a/src/arch/aarch64/exception.rs +++ b/src/arch/aarch64/exception.rs @@ -3,7 +3,8 @@ use core::{arch::global_asm, fmt}; use aarch64_cpu::registers::{ELR_EL1, ESR_EL1, FAR_EL1, TTBR0_EL1, TTBR1_EL1, VBAR_EL1}; use abi::{ - process::{SavedFrame, Signal, SignalEntryData}, + arch::SavedFrame, + process::{Signal, SignalEntryData}, syscall::SyscallFunction, }; use tock_registers::interfaces::{Readable, Writeable}; @@ -11,10 +12,10 @@ use tock_registers::interfaces::{Readable, Writeable}; use crate::{ arch::{aarch64::cpu::Cpu, CpuMessage, PLATFORM}, debug::LogLevel, - device::{interrupt::IrqContext, platform::Platform}, + device::interrupt::IrqContext, panic::panic_secondary, syscall::raw_syscall_handler, - task::process::Process, + task::process::{Process, TaskFrame}, }; /// Struct for register values saved when taking an exception @@ -32,9 +33,8 @@ pub struct ExceptionFrame { // ... } -impl ExceptionFrame { - /// Saves an userspace execution context into a frame "snapshot" - pub fn to_saved_frame(&self) -> SavedFrame { +impl TaskFrame for ExceptionFrame { + fn store(&self) -> SavedFrame { SavedFrame { gp_regs: self.r, spsr_el1: self.spsr_el1, @@ -43,12 +43,39 @@ impl ExceptionFrame { } } - /// Restores an userspace execution context from its frame "snapshot" - pub fn restore_from_signal(&mut self, frame: &SavedFrame) { - self.r = frame.gp_regs; - self.spsr_el1 = frame.spsr_el1; - self.elr_el1 = frame.elr_el1; - self.sp_el0 = frame.sp_el0; + fn restore(&mut self, saved: &SavedFrame) { + self.r = saved.gp_regs; + self.spsr_el1 = saved.spsr_el1; + self.elr_el1 = saved.elr_el1; + self.sp_el0 = saved.sp_el0; + } + + fn argument(&self) -> u64 { + self.r[0] + } + + fn user_ip(&self) -> usize { + self.elr_el1 as _ + } + + fn user_sp(&self) -> usize { + self.sp_el0 as _ + } + + fn set_argument(&mut self, value: u64) { + self.r[0] = value; + } + + fn set_return_value(&mut self, value: u64) { + self.r[0] = value; + } + + fn set_user_ip(&mut self, value: usize) { + self.elr_el1 = value as _; + } + + fn set_user_sp(&mut self, value: usize) { + self.sp_el0 = value as _; } } @@ -217,7 +244,7 @@ fn el0_sync_inner(frame: &mut ExceptionFrame) { 0b111100 => { let proc = Process::current(); warnln!("Process #{} hit a breakpoint", proc.id()); - proc.try_set_signal(Signal::Aborted).ok(); + proc.raise_signal(Signal::Aborted); } _ => { let iss = esr_el1 & 0x1FFFFFF; @@ -231,7 +258,7 @@ fn el0_sync_inner(frame: &mut ExceptionFrame) { FAR_EL1.get() ); - proc.try_set_signal(Signal::MemoryAccessViolation).ok(); + proc.raise_signal(Signal::MemoryAccessViolation); return; } @@ -245,7 +272,7 @@ fn el0_sync_inner(frame: &mut ExceptionFrame) { fn irq_common() { unsafe { let ic = IrqContext::new(); - PLATFORM.interrupt_controller().handle_pending_irqs(&ic); + PLATFORM.gic.handle_pending_irqs(&ic); } } @@ -258,7 +285,7 @@ unsafe fn handle_signal_exit(frame: &mut ExceptionFrame) { saved_data.frame.sp_el0 ); - frame.restore_from_signal(&saved_data.frame); + frame.restore(&saved_data.frame); } pub(super) fn ipi_handler(msg: Option) { diff --git a/src/arch/aarch64/gic/gicd.rs b/src/arch/aarch64/gic/gicd.rs index e428f7ae..5ed010cd 100644 --- a/src/arch/aarch64/gic/gicd.rs +++ b/src/arch/aarch64/gic/gicd.rs @@ -96,6 +96,7 @@ impl Gicd { } } + #[allow(dead_code)] pub unsafe fn set_sgir(&self, target: IpiDeliveryTarget, interrupt_id: u64) { assert_eq!(interrupt_id & !0xF, 0); let value = match target { diff --git a/src/arch/aarch64/gic/mod.rs b/src/arch/aarch64/gic/mod.rs index d6461f96..23aa6d36 100644 --- a/src/arch/aarch64/gic/mod.rs +++ b/src/arch/aarch64/gic/mod.rs @@ -1,14 +1,11 @@ //! ARM Generic Interrupt Controller v2 driver -use core::sync::atomic::Ordering; -use aarch64_cpu::asm::barrier; use abi::error::Error; use spinning_top::Spinlock; use crate::{ - arch::CpuMessage, device::{ - interrupt::{InterruptController, InterruptSource, IpiDeliveryTarget}, + interrupt::{ExternalInterruptController, InterruptSource, IrqContext}, Device, }, mem::device::{DeviceMemory, DeviceMemoryIo}, @@ -17,7 +14,7 @@ use crate::{ use self::{gicc::Gicc, gicd::Gicd}; -use super::{cpu::Cpu, exception::ipi_handler, smp::CPU_COUNT}; +use super::{cpu::Cpu, exception::ipi_handler}; const MAX_IRQ: usize = 300; const IPI_VECTOR: u64 = 1; @@ -82,7 +79,7 @@ impl Device for Gic { } } -impl InterruptController for Gic { +impl ExternalInterruptController for Gic { type IrqNumber = IrqNumber; fn enable_irq(&self, irq: Self::IrqNumber) -> Result<(), Error> { @@ -90,34 +87,6 @@ impl InterruptController for Gic { Ok(()) } - fn handle_pending_irqs<'irq>(&'irq self, ic: &crate::device::interrupt::IrqContext<'irq>) { - let gicc = self.gicc.get(); - let irq_number = gicc.pending_irq_number(ic); - if irq_number >= MAX_IRQ { - return; - } - - gicc.clear_irq(irq_number, ic); - - if irq_number as u64 == IPI_VECTOR { - // IPI received - let msg = Cpu::local().get_ipi(); - ipi_handler(msg); - return; - } - - { - let table = self.irq_table.lock(); - match table[irq_number] { - None => panic!("No IRQ handler registered for irq{}", irq_number), - Some(handler) => { - drop(table); - handler.handle_irq().expect("IRQ handler failed"); - } - } - } - } - fn register_handler( &self, irq: Self::IrqNumber, @@ -135,28 +104,28 @@ impl InterruptController for Gic { Ok(()) } - unsafe fn send_ipi(&self, target: IpiDeliveryTarget, msg: CpuMessage) -> Result<(), Error> { - // TODO message queue insertion should be moved - match target { - IpiDeliveryTarget::AllExceptLocal => { - let local = Cpu::local_id(); - for i in 0..CPU_COUNT.load(Ordering::Acquire) { - if i != local as usize { - Cpu::push_ipi_queue(i as u32, msg); - } - } - } - IpiDeliveryTarget::Specified(_) => todo!(), - } + // unsafe fn send_ipi(&self, target: IpiDeliveryTarget, msg: CpuMessage) -> Result<(), Error> { + // // TODO message queue insertion should be moved + // match target { + // IpiDeliveryTarget::AllExceptLocal => { + // let local = Cpu::local_id(); + // for i in 0..CPU_COUNT.load(Ordering::Acquire) { + // if i != local as usize { + // Cpu::push_ipi_queue(i as u32, msg); + // } + // } + // } + // IpiDeliveryTarget::Specified(_) => todo!(), + // } - // Issue a memory barrier - barrier::dsb(barrier::ISH); - barrier::isb(barrier::SY); + // // Issue a memory barrier + // barrier::dsb(barrier::ISH); + // barrier::isb(barrier::SY); - self.gicd.get().set_sgir(target, IPI_VECTOR); + // self.gicd.get().set_sgir(target, IPI_VECTOR); - Ok(()) - } + // Ok(()) + // } } impl Gic { @@ -184,4 +153,33 @@ impl Gic { self.gicc.get().init(); Ok(()) } + + /// Handles a single pending IRQ (if there're many, the CPU will just get here again) + pub fn handle_pending_irqs<'irq>(&'irq self, ic: &IrqContext<'irq>) { + let gicc = self.gicc.get(); + let irq_number = gicc.pending_irq_number(ic); + if irq_number >= MAX_IRQ { + return; + } + + gicc.clear_irq(irq_number, ic); + + if irq_number as u64 == IPI_VECTOR { + // IPI received + let msg = Cpu::local().get_ipi(); + ipi_handler(msg); + return; + } + + { + let table = self.irq_table.lock(); + match table[irq_number] { + None => panic!("No IRQ handler registered for irq{}", irq_number), + Some(handler) => { + drop(table); + handler.handle_irq().expect("IRQ handler failed"); + } + } + } + } } diff --git a/src/arch/aarch64/intrinsics.rs b/src/arch/aarch64/intrinsics.rs deleted file mode 100644 index 66d1b8cd..00000000 --- a/src/arch/aarch64/intrinsics.rs +++ /dev/null @@ -1,13 +0,0 @@ -//! Intrinsic helper functions for AArch64 platforms - -/// Returns an absolute address to the given symbol -#[macro_export] -macro_rules! absolute_address { - ($sym:expr) => {{ - let mut _x: usize; - unsafe { - core::arch::asm!("ldr {0}, ={1}", out(reg) _x, sym $sym); - } - _x - }}; -} diff --git a/src/arch/aarch64/mod.rs b/src/arch/aarch64/mod.rs index a8ca6e3c..0ddc263e 100644 --- a/src/arch/aarch64/mod.rs +++ b/src/arch/aarch64/mod.rs @@ -30,8 +30,6 @@ use self::{ table::{init_fixed_tables, KERNEL_TABLES}, }; -pub mod intrinsics; - pub mod plat_qemu; pub mod boot; @@ -205,7 +203,7 @@ pub fn kernel_main(dtb_phys: usize) -> ! { AArch64::set_interrupt_mask(true); ARCHITECTURE.init_device_tree(dtb_phys); - PLATFORM.init_primary_serial(); + PLATFORM.init_primary_debug_sink(); } // Setup debugging functions debug::init(); diff --git a/src/arch/aarch64/plat_qemu/mod.rs b/src/arch/aarch64/plat_qemu/mod.rs index a6420b97..0750633c 100644 --- a/src/arch/aarch64/plat_qemu/mod.rs +++ b/src/arch/aarch64/plat_qemu/mod.rs @@ -4,11 +4,11 @@ use abi::error::Error; use tock_registers::interfaces::Writeable; use crate::{ + debug::DebugSink, device::{ - interrupt::{InterruptController, InterruptSource}, + interrupt::{ExternalInterruptController, InterruptSource}, platform::Platform, - serial::{pl011::Pl011, SerialDevice}, - timer::TimestampSource, + serial::pl011::Pl011, Device, }, fs::devfs::{self, CharDeviceType}, @@ -21,7 +21,8 @@ use super::{ /// AArch64 "virt" platform implementation pub struct QemuPlatform { - gic: Gic, + /// ... + pub gic: Gic, pl011: Pl011, local_timer: ArmTimer, } @@ -52,25 +53,39 @@ impl Platform for QemuPlatform { Ok(()) } - unsafe fn init_primary_serial(&self) { + unsafe fn init_primary_debug_sink(&self) { self.pl011.init().ok(); } + fn primary_debug_sink(&self) -> Option<&dyn DebugSink> { + Some(&self.pl011) + } + + fn interrupt_controller( + &self, + ) -> &dyn ExternalInterruptController { + &self.gic + } + + // unsafe fn init_primary_serial(&self) { + // self.pl011.init().ok(); + // } + fn name(&self) -> &'static str { "qemu" } - fn primary_serial(&self) -> Option<&dyn SerialDevice> { - Some(&self.pl011) - } + // fn primary_serial(&self) -> Option<&dyn SerialDevice> { + // Some(&self.pl011) + // } - fn interrupt_controller(&self) -> &dyn InterruptController { - &self.gic - } + // fn interrupt_controller(&self) -> &dyn InterruptController { + // &self.gic + // } - fn timestamp_source(&self) -> &dyn TimestampSource { - &self.local_timer - } + // fn timestamp_source(&self) -> &dyn TimestampSource { + // &self.local_timer + // } } /// AArch64 "virt" platform diff --git a/src/arch/aarch64/table.rs b/src/arch/aarch64/table.rs index 57dcc78a..01e6156a 100644 --- a/src/arch/aarch64/table.rs +++ b/src/arch/aarch64/table.rs @@ -12,7 +12,9 @@ use tock_registers::interfaces::Readable; use crate::mem::{ phys::{self, PageUsage}, - table::{EntryLevel, NextPageTable, VirtualMemoryManager}, + table::{ + EntryLevel, MapAttributes, NextPageTable, NonTerminalEntryLevel, VirtualMemoryManager, + }, ConvertAddress, KERNEL_VIRT_OFFSET, }; @@ -306,12 +308,27 @@ impl FixedTables { } } +impl From for PageAttributes { + fn from(value: MapAttributes) -> Self { + let mut res = Self::empty(); + if value.contains(MapAttributes::USER_WRITE) { + res |= PageAttributes::AP_BOTH_READWRITE; + } else { + res |= PageAttributes::AP_BOTH_READONLY; + } + if value.contains(MapAttributes::NON_GLOBAL) { + res |= PageAttributes::NON_GLOBAL; + } + res + } +} + impl VirtualMemoryManager for AddressSpace { fn allocate( &self, hint: Option, len: usize, - attrs: PageAttributes, + attrs: MapAttributes, ) -> Result { assert_eq!(DAIF.read(DAIF::I), 1); @@ -356,6 +373,10 @@ impl VirtualMemoryManager for AddressSpace { Ok(()) } + + fn map_page(&self, virt: usize, phys: usize, attrs: MapAttributes) -> Result<(), Error> { + self.write_entry(virt, PageEntry::page(phys, attrs.into()), true) + } } impl AddressSpace { @@ -412,11 +433,6 @@ impl AddressSpace { Ok(()) } - /// Inserts a single 4KiB virt -> phys mapping into the address apce - pub fn map_page(&self, virt: usize, phys: usize, attrs: PageAttributes) -> Result<(), Error> { - self.write_entry(virt, PageEntry::page(phys, attrs), true) - } - /// Returns the physical address of the address space (to be used in a TTBRn_ELx) pub fn physical_address(&self) -> usize { unsafe { (self.l1 as usize).physicalize() | ((self.asid as usize) << 48) } diff --git a/src/arch/aarch64/timer.rs b/src/arch/aarch64/timer.rs index 2d8622fd..2f010428 100644 --- a/src/arch/aarch64/timer.rs +++ b/src/arch/aarch64/timer.rs @@ -44,7 +44,7 @@ impl TimestampSource for ArmTimer { } impl InterruptSource for ArmTimer { - fn handle_irq(&self) -> Result<(), Error> { + fn handle_irq(&self) -> Result { CNTP_TVAL_EL0.set(TICK_INTERVAL); let t = self.timestamp()?; @@ -55,7 +55,7 @@ impl InterruptSource for ArmTimer { Cpu::local().queue().yield_cpu(); } - Ok(()) + Ok(true) } unsafe fn init_irq(&'static self) -> Result<(), Error> { diff --git a/src/arch/mod.rs b/src/arch/mod.rs index 122a746d..cdf04700 100644 --- a/src/arch/mod.rs +++ b/src/arch/mod.rs @@ -3,18 +3,32 @@ use abi::error::Error; use cfg_if::cfg_if; +/// Returns an absolute address to the given symbol +#[macro_export] +macro_rules! absolute_address { + ($sym:expr) => {{ + let mut _x: usize; + #[cfg(target_arch = "aarch64")] + unsafe { + core::arch::asm!("ldr {0}, ={1}", out(reg) _x, sym $sym); + } + #[cfg(target_arch = "x86_64")] + unsafe { + core::arch::asm!("movabsq ${1}, {0}", out(reg) _x, sym $sym, options(att_syntax)); + } + _x + }}; +} + cfg_if! { if #[cfg(target_arch = "aarch64")] { pub mod aarch64; - pub use aarch64::intrinsics::absolute_address; pub use aarch64::plat_qemu::{QemuPlatform as PlatformImpl, PLATFORM}; pub use aarch64::{AArch64 as ArchitectureImpl, ARCHITECTURE}; - use abi::error::Error; - use cfg_if::cfg_if; + } else if #[cfg(target_arch = "x86_64")] { - #[macro_use] pub mod x86_64; pub use x86_64::{ diff --git a/src/arch/x86_64/apic/mod.rs b/src/arch/x86_64/apic/mod.rs index 5608cded..4ac72820 100644 --- a/src/arch/x86_64/apic/mod.rs +++ b/src/arch/x86_64/apic/mod.rs @@ -8,7 +8,7 @@ use crate::{ task::process::Process, }; -use super::exception::{self, ExceptionFrame, IrqFrame}; +use super::exception::{self, IrqFrame}; pub mod ioapic; pub mod local; @@ -82,15 +82,17 @@ fn apic_irq_inner(vector: u32) { } } -/// Main handler for APIC interrupts -pub extern "C" fn __x86_64_apic_irq_handler(vector: u32, frame: *mut IrqFrame) { - let frame = unsafe { &mut *frame }; +/// Main handler for APIC interrupts. +/// +/// # Safety +/// +/// Only meant to be called from the assembly irq vector. +pub unsafe extern "C" fn __x86_64_apic_irq_handler(vector: u32, frame: *mut IrqFrame) { + let frame = &mut *frame; apic_irq_inner(vector); if let Some(process) = Process::get_current() { - unsafe { - process.handle_signal(frame); - } + process.handle_signal(frame); } } diff --git a/src/arch/x86_64/context.rs b/src/arch/x86_64/context.rs index f25f17ad..3af8be5c 100644 --- a/src/arch/x86_64/context.rs +++ b/src/arch/x86_64/context.rs @@ -1,7 +1,7 @@ //! x86-64 task context setup and switching use core::{arch::global_asm, cell::UnsafeCell}; -use abi::error::Error; +use abi::{error::Error, process::ExitCode}; use alloc::boxed::Box; use crate::{ @@ -10,6 +10,7 @@ use crate::{ phys::{self, PageUsage}, ConvertAddress, }, + task::process::Process, }; struct StackBuilder { @@ -84,7 +85,9 @@ impl StackBuilder { } impl TaskContext { + /// Number of bytes to offset the signal stack pointer by pub const SIGNAL_STACK_EXTRA_ALIGN: usize = 8; + /// Number of bytes to offset the user stack pointer by pub const USER_STACK_EXTRA_ALIGN: usize = 8; /// Constructs a kernel-space task context @@ -147,7 +150,8 @@ impl TaskContext { extern "C" fn closure_wrapper(closure_addr: usize) -> ! { let closure = unsafe { Box::from_raw(closure_addr as *mut F) }; closure(); - todo!("Process termination"); + Process::current().exit(ExitCode::SUCCESS); + unreachable!(); } let closure = Box::new(f); diff --git a/src/arch/x86_64/exception.rs b/src/arch/x86_64/exception.rs index 39c529ce..97e3cf31 100644 --- a/src/arch/x86_64/exception.rs +++ b/src/arch/x86_64/exception.rs @@ -1,32 +1,15 @@ //! x86-64 exception and interrupt handling use core::{arch::global_asm, mem::size_of_val}; -use abi::{ - arch::SavedFrame, - primitive_enum, - process::{Signal, SignalEntryData}, - syscall::SyscallFunction, -}; -use tock_registers::interfaces::{ReadWriteable, Writeable}; +use abi::{arch::SavedFrame, primitive_enum, process::Signal}; use crate::{ - arch::{ - x86_64::{ - apic::{self, __x86_64_apic_irq_handler}, - registers::{MSR_IA32_EFER, MSR_IA32_LSTAR, MSR_IA32_SFMASK, MSR_IA32_STAR}, - }, - Architecture, ArchitectureImpl, - }, - mem::table::AddressSpace, - syscall::raw_syscall_handler, - task::{ - process::{Process, TaskFrame}, - Cpu, - }, + arch::x86_64::apic::{self, __x86_64_apic_irq_handler}, + task::process::{Process, TaskFrame}, }; primitive_enum! { - pub enum ExceptionKind: u64 { + enum ExceptionKind: u64 { DivisionError = 0, Debug = 1, NonMaskableInterrupt = 2, @@ -53,119 +36,25 @@ primitive_enum! { } impl ExceptionKind { - pub fn ring3_possible(&self) -> bool { - match self { + fn ring3_possible(&self) -> bool { + matches!( + self, Self::DivisionError - | Self::Debug - | Self::Breakpoint - | Self::Overflow - | Self::BoundRangeExceeded - | Self::InvalidOpcode - | Self::GeneralProtectionFault - | Self::PageFault - | Self::FpuException - | Self::AlignmentCheck - | Self::SimdFpuException => true, - _ => false, - } - } -} - -impl TaskFrame for IrqFrame { - fn store(&self) -> SavedFrame { - todo!() - } - - fn restore(&mut self, saved: &SavedFrame) { - todo!() - } - - fn argument(&self) -> u64 { - todo!(); - } - - fn user_ip(&self) -> usize { - todo!() - } - - fn user_sp(&self) -> usize { - todo!() - } - - fn set_argument(&mut self, value: u64) { - self.rdi = value; - } - - fn set_return_value(&mut self, value: u64) { - todo!() - } - - fn set_user_ip(&mut self, value: usize) { - todo!() - } - - fn set_user_sp(&mut self, value: usize) { - todo!() - } -} - -impl TaskFrame for ExceptionFrame { - fn store(&self) -> SavedFrame { - SavedFrame { - rax: self.rax, - rcx: self.rcx, - rdx: self.rdx, - rbx: self.rbx, - rsi: self.rsi, - rdi: self.rdi, - rbp: self.rbp, - r8: self.r8, - r9: self.r9, - r10: self.r10, - r11: self.r11, - r12: self.r12, - r13: self.r13, - r14: self.r14, - r15: self.r15, - user_ip: self.rip, - user_sp: self.rsp, - rflags: self.rflags, - } - } - - fn restore(&mut self, saved: &SavedFrame) { - todo!() - } - - fn argument(&self) -> u64 { - 0 - } - - fn user_sp(&self) -> usize { - self.rsp as _ - } - - fn user_ip(&self) -> usize { - self.rip as _ - } - - fn set_user_sp(&mut self, value: usize) { - self.rsp = value as _; - } - - fn set_user_ip(&mut self, value: usize) { - self.rip = value as _; - } - - fn set_return_value(&mut self, _value: u64) { - // Not in syscall, do not overwrite - } - - fn set_argument(&mut self, value: u64) { - self.rdi = value; + | Self::Debug + | Self::Breakpoint + | Self::Overflow + | Self::BoundRangeExceeded + | Self::InvalidOpcode + | Self::GeneralProtectionFault + | Self::PageFault + | Self::FpuException + | Self::AlignmentCheck + | Self::SimdFpuException + ) } } +/// Frame saved onto the stack when taking an IRQ #[derive(Debug)] #[repr(C)] pub struct IrqFrame { @@ -243,6 +132,101 @@ struct Pointer { offset: usize, } +impl TaskFrame for IrqFrame { + fn store(&self) -> SavedFrame { + todo!() + } + + fn restore(&mut self, _saved: &SavedFrame) { + todo!() + } + + fn argument(&self) -> u64 { + todo!(); + } + + fn user_ip(&self) -> usize { + todo!() + } + + fn user_sp(&self) -> usize { + todo!() + } + + fn set_argument(&mut self, value: u64) { + self.rdi = value; + } + + fn set_return_value(&mut self, _value: u64) { + todo!() + } + + fn set_user_ip(&mut self, _value: usize) { + todo!() + } + + fn set_user_sp(&mut self, _value: usize) { + todo!() + } +} + +impl TaskFrame for ExceptionFrame { + fn store(&self) -> SavedFrame { + SavedFrame { + rax: self.rax, + rcx: self.rcx, + rdx: self.rdx, + rbx: self.rbx, + rsi: self.rsi, + rdi: self.rdi, + rbp: self.rbp, + r8: self.r8, + r9: self.r9, + r10: self.r10, + r11: self.r11, + r12: self.r12, + r13: self.r13, + r14: self.r14, + r15: self.r15, + user_ip: self.rip, + user_sp: self.rsp, + rflags: self.rflags, + } + } + + fn restore(&mut self, _saved: &SavedFrame) { + todo!() + } + + fn argument(&self) -> u64 { + 0 + } + + fn user_sp(&self) -> usize { + self.rsp as _ + } + + fn user_ip(&self) -> usize { + self.rip as _ + } + + fn set_user_sp(&mut self, value: usize) { + self.rsp = value as _; + } + + fn set_user_ip(&mut self, value: usize) { + self.rip = value as _; + } + + fn set_return_value(&mut self, _value: u64) { + // Not in syscall, do not overwrite + } + + fn set_argument(&mut self, value: u64) { + self.rdi = value; + } +} + const SIZE: usize = 256; impl Entry { @@ -278,7 +262,7 @@ impl Entry { static mut IDT: [Entry; SIZE] = [Entry::NULL; SIZE]; -fn user_exception_inner(kind: ExceptionKind, frame: &mut ExceptionFrame) { +fn user_exception_inner(kind: ExceptionKind, frame: &ExceptionFrame) { let process = Process::current(); warnln!("{:?} in #{} {:?}", kind, process.id(), process.name()); @@ -295,42 +279,15 @@ fn user_exception_inner(kind: ExceptionKind, frame: &mut ExceptionFrame) { warnln!("CR2 = {:#x}", cr2); process.raise_signal(Signal::MemoryAccessViolation); - return; } ExceptionKind::InvalidOpcode => { process.raise_signal(Signal::Aborted); - return; } _ => todo!("No handler for exception: {:?}", kind), } - - // errorln!("Exception {}", frame.exc_number); - // errorln!("CS:RIP = {:#x}:{:#x}", frame.cs, frame.rip); - // errorln!("SS:RSP = {:#x}:{:#x}", frame.ss, frame.rsp); - - // if let Some(cpu) = Cpu::get_local() { - // let current = cpu.queue().current_process(); - // if let Some(current) = current { - // errorln!("In process #{} {:?}", current.id(), current.name()); - // } - // } - - // debugln!("Registers:\n{:#x?}", &frame); - - // if frame.exc_number == 6 { - // // Invalid opcode - // warnln!("Invalid opcode"); - // } - - // if frame.exc_number == 14 { - // } - - // loop { - // ArchitectureImpl::wait_for_interrupt(); - // } } -fn kernel_exception_inner(kind: ExceptionKind, frame: &ExceptionFrame) -> ! { +fn kernel_exception_inner(_kind: ExceptionKind, _frame: &ExceptionFrame) -> ! { todo!() } @@ -349,18 +306,6 @@ extern "C" fn __x86_64_exception_handler(frame: *mut ExceptionFrame) { } } -pub unsafe fn handle_signal_exit(frame: &mut F) { - // TODO validate the argument - let saved_data = &*(frame.argument() as *const SignalEntryData); - infoln!( - "Handling signal exit to ip={:#x}, sp={:#x}", - saved_data.frame.user_ip, - saved_data.frame.user_sp - ); - - frame.restore(&saved_data.frame); -} - /// Initializes the interrupt descriptor table for the given CPU. /// /// # Safety diff --git a/src/arch/x86_64/intrinsics.rs b/src/arch/x86_64/intrinsics.rs index 71375ac7..c359d00e 100644 --- a/src/arch/x86_64/intrinsics.rs +++ b/src/arch/x86_64/intrinsics.rs @@ -2,18 +2,6 @@ use core::marker::PhantomData; -/// Returns an absolute address to the given symbol -#[macro_export] -macro_rules! absolute_address { - ($sym:expr) => {{ - let mut _x: usize; - unsafe { - core::arch::asm!("movabsq ${1}, {0}", out(reg) _x, sym $sym, options(att_syntax)); - } - _x - }}; -} - /// Wrapper struct providing access to an x86 I/O port #[derive(Clone, Debug)] #[repr(transparent)] diff --git a/src/arch/x86_64/peripherals/ps2/mod.rs b/src/arch/x86_64/peripherals/ps2/mod.rs index f194ed25..297f7177 100644 --- a/src/arch/x86_64/peripherals/ps2/mod.rs +++ b/src/arch/x86_64/peripherals/ps2/mod.rs @@ -76,10 +76,10 @@ impl InterruptSource for PS2Controller { return Ok(false); } - let mut key = self.data.read(); + let key = self.data.read(); if key == 0xE0 { - key = self.data.read(); + self.data.read(); infoln!("TODO: handle 0xE0"); return Ok(true); } diff --git a/src/arch/x86_64/syscall.rs b/src/arch/x86_64/syscall.rs index 20405d20..792e0e53 100644 --- a/src/arch/x86_64/syscall.rs +++ b/src/arch/x86_64/syscall.rs @@ -1,6 +1,8 @@ +//! x86-64 implementation of system call interface + use core::arch::global_asm; -use abi::{arch::SavedFrame, syscall::SyscallFunction}; +use abi::{arch::SavedFrame, process::SignalEntryData, syscall::SyscallFunction}; use tock_registers::interfaces::{ReadWriteable, Writeable}; use crate::{ @@ -9,12 +11,10 @@ use crate::{ task::process::{Process, TaskFrame}, }; -use super::exception::handle_signal_exit; - /// Set of registers saved when taking a syscall instruction #[derive(Debug)] #[repr(C)] -pub struct SyscallFrame { +struct SyscallFrame { rax: u64, args: [u64; 6], @@ -132,6 +132,23 @@ extern "C" fn __x86_64_syscall_handler(frame: *mut SyscallFrame) { } } +unsafe fn handle_signal_exit(frame: &mut F) { + // TODO validate the argument + let saved_data = &*(frame.argument() as *const SignalEntryData); + infoln!( + "Handling signal exit to ip={:#x}, sp={:#x}", + saved_data.frame.user_ip, + saved_data.frame.user_sp + ); + + frame.restore(&saved_data.frame); +} + +/// Initializes system call instruction support for the current CPU. +/// +/// # Safety +/// +/// Only meant to be called once per each CPU during their init. pub unsafe fn init_syscall() { extern "C" { fn __x86_64_syscall_vector(); diff --git a/src/arch/x86_64/table/mod.rs b/src/arch/x86_64/table/mod.rs index e5eb864d..1c9327f4 100644 --- a/src/arch/x86_64/table/mod.rs +++ b/src/arch/x86_64/table/mod.rs @@ -182,6 +182,7 @@ impl PageEntry { /// An entry that is not mapped pub const INVALID: Self = Self(0, PhantomData); + /// Returns `true` if the entry contains a valid mapping to either a table or to a page/block pub fn is_present(&self) -> bool { self.0 & PageAttributes::PRESENT.bits() != 0 } @@ -252,12 +253,6 @@ impl IndexMut for PageTable { } } -impl From for MapAttributes { - fn from(value: PageAttributes) -> Self { - todo!(); - } -} - impl From for PageAttributes { fn from(value: MapAttributes) -> Self { let mut res = PageAttributes::WRITABLE; @@ -337,12 +332,6 @@ impl AddressSpace { Ok(Self { l0 }) } - pub unsafe fn from_cr3(cr3: usize) -> Self { - let cr3_virt = cr3.virtualize(); - let l0 = unsafe { cr3_virt as *mut PageTable }; - Self { l0 } - } - unsafe fn as_mut(&self) -> &'static mut PageTable { self.l0.as_mut().unwrap() } diff --git a/src/debug.rs b/src/debug.rs index 9ee927b7..155d4e81 100644 --- a/src/debug.rs +++ b/src/debug.rs @@ -3,7 +3,12 @@ use core::fmt::{self, Arguments}; use abi::error::Error; -use crate::{arch::PLATFORM, device::platform::Platform, sync::IrqSafeSpinlock, util::OneTimeInit}; +use crate::{ + arch::PLATFORM, + device::{platform::Platform, serial::SerialDevice}, + sync::IrqSafeSpinlock, + util::OneTimeInit, +}; // use crate::{ // arch::PLATFORM, @@ -46,6 +51,12 @@ pub trait DebugSink { } } +impl DebugSink for T { + fn putc(&self, c: u8) -> Result<(), Error> { + self.send(c) + } +} + struct DebugPrinter { sink: &'static dyn DebugSink, } diff --git a/src/device/input.rs b/src/device/input.rs index b2f543c8..7e462dc2 100644 --- a/src/device/input.rs +++ b/src/device/input.rs @@ -1,5 +1,10 @@ +//! Input device interfaces + use super::{tty::TtyDevice, Device}; +/// Generic keyboard-like input device interface pub trait KeyboardDevice: Device { + /// Indicates to the keyboard driver that it was attached to a terminal so it knows where to + /// send its input data to fn attach(&self, terminal: &'static dyn TtyDevice<16>); } diff --git a/src/device/serial/pl011.rs b/src/device/serial/pl011.rs index 051ae0e9..7d567e1d 100644 --- a/src/device/serial/pl011.rs +++ b/src/device/serial/pl011.rs @@ -151,7 +151,7 @@ impl InterruptSource for Pl011 { Ok(()) } - fn handle_irq(&self) -> Result<(), Error> { + fn handle_irq(&self) -> Result { let inner = self.inner.get().lock(); inner.regs.ICR.write(ICR::ALL::CLEAR); @@ -160,7 +160,7 @@ impl InterruptSource for Pl011 { self.recv_byte(byte as u8); - Ok(()) + Ok(true) } } diff --git a/src/device/tty.rs b/src/device/tty.rs index 8a7af3da..6677cd93 100644 --- a/src/device/tty.rs +++ b/src/device/tty.rs @@ -19,14 +19,18 @@ use crate::{ use super::{input::KeyboardDevice, serial::SerialDevice, Device}; +// TODO rewrite this +/// Helper device to combine a display and a keyboard input into a single terminal pub struct CombinedTerminal { + #[allow(dead_code)] input: &'static dyn KeyboardDevice, output: &'static FramebufferConsole, - // TODO output + input_ring: CharRing<16>, } impl CombinedTerminal { + /// Create a combined terminal device from a keyboard and console output devices pub fn new(input: &'static dyn KeyboardDevice, output: &'static FramebufferConsole) -> Self { Self { input, @@ -43,7 +47,7 @@ impl TtyDevice<16> for CombinedTerminal { } impl SerialDevice for CombinedTerminal { - fn receive(&self, blocking: bool) -> Result { + fn receive(&self, _blocking: bool) -> Result { todo!() } diff --git a/src/main.rs b/src/main.rs index 4f9d7053..3eb7c487 100644 --- a/src/main.rs +++ b/src/main.rs @@ -19,25 +19,13 @@ use abi::{ error::Error, io::{FileMode, OpenOptions, RawFd}, - process::ExitCode, }; use fs::{devfs, FileBlockAllocator, INITRD_DATA}; use memfs::MemoryFilesystem; -use task::process::Process; use vfs::{Filesystem, IoContext, VnodeRef}; extern crate yggdrasil_abi as abi; -// -// use abi::{ -// error::Error, -// io::{FileMode, OpenOptions, RawFd}, -// process::ExitCode, -// }; -// use fs::{devfs, FileBlockAllocator, INITRD_DATA}; -// use memfs::MemoryFilesystem; -// use task::process::Process; -// use vfs::{Filesystem, IoContext, VnodeRef}; -// + extern crate alloc; #[macro_use] @@ -94,7 +82,12 @@ pub fn kernel_main() { let file = node.open(OpenOptions::READ, FileMode::empty()).unwrap(); let devfs = devfs::root(); + #[cfg(target_arch = "x86_64")] let console = ioctx.find(Some(devfs.clone()), "tty0", true, true).unwrap(); + #[cfg(target_arch = "aarch64")] + let console = ioctx + .find(Some(devfs.clone()), "ttyS0", true, true) + .unwrap(); let stdin = console.open(OpenOptions::READ, FileMode::empty()).unwrap(); let stdout = console.open(OpenOptions::WRITE, FileMode::empty()).unwrap(); let stderr = stdout.clone(); @@ -112,8 +105,4 @@ pub fn kernel_main() { user_init.enqueue_somewhere(); } - - loop {} - // XXX - // Process::current().exit(ExitCode::SUCCESS); } diff --git a/src/mem/table.rs b/src/mem/table.rs index 97c205cf..fd40e306 100644 --- a/src/mem/table.rs +++ b/src/mem/table.rs @@ -12,10 +12,14 @@ cfg_if! { } bitflags! { + /// Describes how a page translation mapping should behave #[derive(Clone, Copy)] pub struct MapAttributes: u64 { + /// The data mapped can be read by the user process const USER_READ = 1 << 0; + /// The data mapped can be written to by the user process const USER_WRITE = 1 << 1; + /// The mapping is not global across the address spaces const NON_GLOBAL = 1 << 2; } } @@ -31,6 +35,7 @@ pub trait VirtualMemoryManager { attrs: MapAttributes, ) -> Result; + /// Insert a single 4KiB-page translation mapping into the table fn map_page(&self, virt: usize, phys: usize, attrs: MapAttributes) -> Result<(), Error>; /// Releases the virtual memory region from the address space and the pages it refers to diff --git a/src/proc/exec.rs b/src/proc/exec.rs index 78f9e577..52cb3140 100644 --- a/src/proc/exec.rs +++ b/src/proc/exec.rs @@ -106,6 +106,8 @@ fn setup_binary>( // Fill with some sentinel value to detect stack underflows let ptr = user_sp as *mut u64; + + #[allow(clippy::reversed_empty_ranges)] for i in 0..TaskContext::USER_STACK_EXTRA_ALIGN / 8 { unsafe { ptr.add(i).write_foreign_volatile(&space, 0xDEADC0DE); diff --git a/src/proc/wait.rs b/src/proc/wait.rs index 0b95f3dd..ad1cbc5f 100644 --- a/src/proc/wait.rs +++ b/src/proc/wait.rs @@ -5,8 +5,6 @@ use abi::error::Error; use alloc::{collections::LinkedList, rc::Rc}; use crate::{ - arch::PLATFORM, - device::platform::Platform, sync::IrqSafeSpinlock, task::process::{Process, ProcessState}, }; @@ -32,6 +30,7 @@ pub struct Wait { struct Timeout { process: Rc, + #[allow(dead_code)] deadline: Duration, } @@ -122,7 +121,7 @@ impl Wait { queue_lock = self.queue.lock(); - if let Some(deadline) = deadline { + if let Some(_deadline) = deadline { // let now = PLATFORM.timestamp_source().timestamp()?; // if now > deadline { @@ -147,7 +146,7 @@ impl Wait { static TICK_LIST: IrqSafeSpinlock> = IrqSafeSpinlock::new(LinkedList::new()); /// Suspends current task until given deadline -pub fn sleep(timeout: Duration, remaining: &mut Duration) -> Result<(), Error> { +pub fn sleep(_timeout: Duration, _remaining: &mut Duration) -> Result<(), Error> { todo!(); // static SLEEP_NOTIFY: Wait = Wait::new("sleep"); // let now = PLATFORM.timestamp_source().timestamp()?; @@ -166,8 +165,7 @@ pub fn sleep(timeout: Duration, remaining: &mut Duration) -> Result<(), Error> { } /// Updates all pending timeouts and wakes up the tasks that have reached theirs -pub fn tick(now: Duration) { - todo!(); +pub fn tick(_now: Duration) { // let mut list = TICK_LIST.lock(); // let mut cursor = list.cursor_front_mut(); diff --git a/src/syscall/mod.rs b/src/syscall/mod.rs index 5d2219af..11cf35d6 100644 --- a/src/syscall/mod.rs +++ b/src/syscall/mod.rs @@ -20,7 +20,7 @@ use crate::{ proc::{ self, io::ProcessIo, - wait::PROCESS_EXIT_WAIT, + wait::{self, PROCESS_EXIT_WAIT}, // wait::{self, PROCESS_EXIT_WAIT}, }, sync::IrqSafeSpinlockGuard, @@ -63,15 +63,14 @@ fn syscall_handler(func: SyscallFunction, args: &[u64]) -> Result Ok(0) } SyscallFunction::Nanosleep => { - todo!(); - // let seconds = args[0]; - // let nanos = args[1] as u32; - // let duration = Duration::new(seconds, nanos); - // let mut remaining = Duration::ZERO; + let seconds = args[0]; + let nanos = args[1] as u32; + let duration = Duration::new(seconds, nanos); + let mut remaining = Duration::ZERO; - // wait::sleep(duration, &mut remaining).unwrap(); + wait::sleep(duration, &mut remaining).unwrap(); - // Ok(0) + Ok(0) } SyscallFunction::Exit => { let code = ExitCode::from(args[0] as i32); @@ -142,11 +141,11 @@ fn syscall_handler(func: SyscallFunction, args: &[u64]) -> Result debugln!("run_with_io_at {:?}", at); let file = io.ioctx().open(at, path, opts, mode)?; - // if proc.session_terminal().is_none() && - // let Ok(node) = file.borrow().node() && node.kind() == VnodeKind::Char { - // debugln!("Session terminal set for #{}: {}", proc.id(), path); - // proc.set_session_terminal(node); - // } + if proc.session_terminal().is_none() && + let Ok(node) = file.borrow().node() && node.kind() == VnodeKind::Char { + debugln!("Session terminal set for #{}: {}", proc.id(), path); + proc.set_session_terminal(node); + } let fd = io.place_file(file)?; Ok(fd.0 as usize) @@ -179,17 +178,16 @@ fn syscall_handler(func: SyscallFunction, args: &[u64]) -> Result }) } SyscallFunction::Unmount => { - todo!(); - // let options = arg_user_ref::(args[0] as usize)?; + let options = arg_user_ref::(args[0] as usize)?; - // run_with_io(|mut io| { - // let mountpoint = io.ioctx().find(None, options.mountpoint, true, false)?; - // mountpoint.unmount_target()?; + run_with_io(|mut io| { + let mountpoint = io.ioctx().find(None, options.mountpoint, true, false)?; + mountpoint.unmount_target()?; - // debugln!("{:?}", vfs::VnodeDump::new(io.ioctx().root().clone())); + debugln!("{:?}", vfs::VnodeDump::new(io.ioctx().root().clone())); - // Ok(0) - // }) + Ok(0) + }) } SyscallFunction::OpenDirectory => { let at = arg_option_fd(args[0] as u32); @@ -218,70 +216,66 @@ fn syscall_handler(func: SyscallFunction, args: &[u64]) -> Result }) } SyscallFunction::CreateDirectory => { - todo!(); - // let at = arg_option_fd(args[0] as u32); - // let path = arg_user_str(args[1] as usize, args[2] as usize)?; - // let _mode = FileMode::from(args[3] as u32); + let at = arg_option_fd(args[0] as u32); + let path = arg_user_str(args[1] as usize, args[2] as usize)?; + let _mode = FileMode::from(args[3] as u32); - // run_with_io_at(at, |at, mut io| { - // let (parent, name) = abi::path::split_right(path); - // let parent_node = io.ioctx().find(at, parent, true, true)?; - // parent_node.create(name, VnodeKind::Directory)?; + run_with_io_at(at, |at, mut io| { + let (parent, name) = abi::path::split_right(path); + let parent_node = io.ioctx().find(at, parent, true, true)?; + parent_node.create(name, VnodeKind::Directory)?; - // Ok(0) - // }) + Ok(0) + }) } SyscallFunction::Remove => { - todo!(); - // let at = arg_option_fd(args[0] as u32); - // let path = arg_user_str(args[1] as usize, args[2] as usize)?; - // let recurse = args[3] != 0; + let at = arg_option_fd(args[0] as u32); + let path = arg_user_str(args[1] as usize, args[2] as usize)?; + let recurse = args[3] != 0; - // run_with_io_at(at, |at, mut io| { - // let node = io.ioctx().find(at, path, false, false)?; + run_with_io_at(at, |at, mut io| { + let node = io.ioctx().find(at, path, false, false)?; - // if node.is_root() || Rc::ptr_eq(io.ioctx().root(), &node) { - // todo!(); - // } + if node.is_root() || Rc::ptr_eq(io.ioctx().root(), &node) { + todo!(); + } - // let parent = node.parent(); + let parent = node.parent(); - // parent.remove(node, recurse)?; + parent.remove(node, recurse)?; - // Ok(0) - // }) + Ok(0) + }) } SyscallFunction::GetMetadata => { - todo!(); - // let at = arg_option_fd(args[0] as u32); - // let path = arg_user_str(args[1] as usize, args[2] as usize)?; - // let buffer = arg_user_mut::>(args[3] as usize)?; - // let follow = args[4] != 0; + let at = arg_option_fd(args[0] as u32); + let path = arg_user_str(args[1] as usize, args[2] as usize)?; + let buffer = arg_user_mut::>(args[3] as usize)?; + let follow = args[4] != 0; - // run_with_io_at(at, |at, mut io| { - // let node = if path.is_empty() { - // at.ok_or(Error::InvalidArgument)? - // } else { - // io.ioctx().find(None, path, follow, true)? - // }; + run_with_io_at(at, |at, mut io| { + let node = if path.is_empty() { + at.ok_or(Error::InvalidArgument)? + } else { + io.ioctx().find(None, path, follow, true)? + }; - // let metadata = node.metadata()?; - // buffer.write(metadata); + let metadata = node.metadata()?; + buffer.write(metadata); - // Ok(0) - // }) + Ok(0) + }) } SyscallFunction::Seek => { - todo!(); - // let fd = RawFd(args[0] as u32); - // let pos = SeekFrom::from(args[1]); + let fd = RawFd(args[0] as u32); + let pos = SeekFrom::from(args[1]); - // run_with_io(|io| { - // let file = io.file(fd)?; - // let mut file_borrow = file.borrow_mut(); + run_with_io(|io| { + let file = io.file(fd)?; + let mut file_borrow = file.borrow_mut(); - // file_borrow.seek(pos).map(|v| v as usize) - // }) + file_borrow.seek(pos).map(|v| v as usize) + }) } SyscallFunction::Spawn => { let options = arg_user_ref::(args[0] as usize)?; @@ -342,14 +336,13 @@ fn syscall_handler(func: SyscallFunction, args: &[u64]) -> Result } } SyscallFunction::SendSignal => { - todo!(); - // let pid = args[0] as u32; - // let signal = Signal::try_from(args[1] as u32).map_err(|_| Error::InvalidArgument)?; + let pid = args[0] as u32; + let signal = Signal::try_from(args[1] as u32).map_err(|_| Error::InvalidArgument)?; - // let target = Process::get(pid as _).ok_or(Error::DoesNotExist)?; - // target.try_set_signal(signal)?; + let target = Process::get(pid as _).ok_or(Error::DoesNotExist)?; + target.raise_signal(signal); - // Ok(0) + Ok(0) } SyscallFunction::SetSignalEntry => { let entry = args[0] as usize; diff --git a/src/task/mod.rs b/src/task/mod.rs index 3cd1122e..0da9ebb8 100644 --- a/src/task/mod.rs +++ b/src/task/mod.rs @@ -16,13 +16,6 @@ cfg_if! { use crate::{ kernel_main, - mem::{ - phys::{self, PageUsage}, - table::AddressSpace, - ConvertAddress, - }, - //arch::aarch64::{context::TaskContext, cpu::Cpu, smp::CPU_COUNT}, - // kernel_main, sync::{IrqSafeSpinlock, SpinFence}, task::sched::CpuQueue, }; diff --git a/src/task/process.rs b/src/task/process.rs index 2a07d1fa..6bedad48 100644 --- a/src/task/process.rs +++ b/src/task/process.rs @@ -26,17 +26,33 @@ use crate::{ use super::{sched::CpuQueue, Cpu, ProcessId, TaskContext, PROCESSES}; +/// Interface for task state save/restore mechanisms pub trait TaskFrame { + /// Creates a "snapshot" of a exception/syscall frame fn store(&self) -> SavedFrame; + + /// Restores the exception/syscall frame from its saved state fn restore(&mut self, saved: &SavedFrame); + /// Replaces the return value in the frame (or does nothing, if the frame is not a part of a + /// syscall signal handler) fn set_return_value(&mut self, value: u64); + + /// Replaces the userspace stack pointer in the frame fn set_user_sp(&mut self, value: usize); + + /// Replaces the userspace instruction pointer in the frame fn set_user_ip(&mut self, value: usize); + + /// Replaces the argument in the frame fn set_argument(&mut self, value: u64); + /// Returns the argument (if any) of the frame being processed fn argument(&self) -> u64; + + /// Returns the userspace stack pointer fn user_sp(&self) -> usize; + /// Returns the userspace instruction pointer fn user_ip(&self) -> usize; } @@ -149,6 +165,7 @@ impl Process { *self.id.get() } + /// Returns the binary name of the process pub fn name(&self) -> &str { self.name.as_str() } @@ -187,7 +204,6 @@ impl Process { self.space.as_ref() } - // XXX /// Replaces the task's session terminal device with another one pub fn set_session_terminal(&self, terminal: VnodeRef) { self.inner.lock().session_terminal.replace(terminal); @@ -324,7 +340,7 @@ impl Process { Self::get_current().unwrap() } - // /// Handles the cleanup of an exited process + /// Handles the cleanup of an exited process pub fn handle_exit(&self) { // Queue lock is still held assert_eq!(self.state(), ProcessState::Terminated); diff --git a/src/task/sched.rs b/src/task/sched.rs index 4c326bcd..5797adc1 100644 --- a/src/task/sched.rs +++ b/src/task/sched.rs @@ -139,7 +139,9 @@ impl CpuQueue { /// The function is only meant to be called from kernel threads (e.g. if they want to yield /// CPU execution to wait for something) or interrupt handlers. pub unsafe fn yield_cpu(&self) { - assert!(ArchitectureImpl::interrupt_mask()); + // Make sure the scheduling process doesn't get interrupted + ArchitectureImpl::set_interrupt_mask(true); + let mut inner = self.inner.lock(); // let t = CNTPCT_EL0.get();