diff --git a/kernel/arch/x86/src/context.s b/kernel/arch/x86/src/context.s
deleted file mode 100644
index 00babe47..00000000
--- a/kernel/arch/x86/src/context.s
+++ /dev/null
@@ -1,100 +0,0 @@
-/*
- * Copyright 2024 Luc LenĂ´tre
- *
- * This file is part of Maestro.
- *
- * Maestro is free software: you can redistribute it and/or modify it under the
- * terms of the GNU General Public License as published by the Free Software
- * Foundation, either version 3 of the License, or (at your option) any later
- * version.
- *
- * Maestro is distributed in the hope that it will be useful, but WITHOUT ANY
- * WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR
- * A PARTICULAR PURPOSE. See the GNU General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License along with
- * Maestro. If not, see .
- */
-
-.intel_syntax noprefix
-
-.include "arch/x86/src/regs.s"
-
-// Context switch functions
-
-.global context_switch32
-.global context_switch_kernel
-
-.type context_switch32, @function
-.type context_switch_kernel, @function
-
-context_switch32:
- # Restore the fx state
- mov eax, [esp + 4]
- add eax, 0x30
- push eax
- call restore_fxstate
- add esp, 4
-
- # Set segment registers
- mov ax, (32 | 3)
- mov ds, ax
- mov es, ax
-
- # Set registers, except eax
- mov eax, [esp + 4]
- mov ebp, [eax]
- mov ebx, [eax + 20]
- mov ecx, [eax + 24]
- mov edx, [eax + 28]
- mov esi, [eax + 32]
- mov edi, [eax + 36]
- mov gs, [eax + 40]
- mov fs, [eax + 44]
-
- # Place iret data on the stack
- push (32 | 3) # data segment selector
- push [eax + 4] # esp
- push [eax + 12] # eflags
- push (24 | 3) # code segment selector
- push [esp + 24] # eip
-
- # Set eax
- mov eax, [eax + 16]
-
- iretd
-
-context_switch_kernel:
- # Restore the fx state
- mov eax, [esp + 4]
- add eax, 0x30
- push eax
- call restore_fxstate
- add esp, 4
-
- mov eax, [esp + 4]
-
- # Set eflags without the interrupt flag
- mov ebx, [eax + 12]
- mov ecx, 512
- not ecx
- and ebx, ecx
- push ebx
- popfd
-
- # Set registers
- mov ebp, [eax]
- mov esp, [eax + 4]
- push [eax + 8] # eip
- mov [eax + 20], ebx
- mov [eax + 24], ecx
- mov [eax + 28], edx
- mov [eax + 32], esi
- mov [eax + 36], edi
- mov [eax + 40], gs
- mov [eax + 44], fs
- mov [eax + 16], eax
-
- # Set the interrupt flag and jumping to kernel code execution
- # (Note: These two instructions, if placed in this order are atomic on x86, meaning that an interrupt cannot happen in between)
- sti
diff --git a/kernel/arch/x86_64/src/context.s b/kernel/arch/x86_64/src/context.s
deleted file mode 100644
index 577ab2eb..00000000
--- a/kernel/arch/x86_64/src/context.s
+++ /dev/null
@@ -1,37 +0,0 @@
-/*
- * Copyright 2024 Luc LenĂ´tre
- *
- * This file is part of Maestro.
- *
- * Maestro is free software: you can redistribute it and/or modify it under the
- * terms of the GNU General Public License as published by the Free Software
- * Foundation, either version 3 of the License, or (at your option) any later
- * version.
- *
- * Maestro is distributed in the hope that it will be useful, but WITHOUT ANY
- * WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR
- * A PARTICULAR PURPOSE. See the GNU General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License along with
- * Maestro. If not, see .
- */
-
-.intel_syntax noprefix
-
-.include "arch/x86_64/src/regs.s"
-
-// Context switch functions
-
-.global context_switch32
-.global context_switch64
-
-.type context_switch32, @function
-.type context_switch64, @function
-
-context_switch32:
- # TODO
- ud2
-
-context_switch64:
- # TODO
- ud2
diff --git a/kernel/src/arch/x86/gdt.rs b/kernel/src/arch/x86/gdt.rs
index 238064cd..2ce4178e 100644
--- a/kernel/src/arch/x86/gdt.rs
+++ b/kernel/src/arch/x86/gdt.rs
@@ -37,12 +37,14 @@ pub const KERNEL_CS: usize = 8;
pub const KERNEL_DS: usize = 16;
/// The offset of the user code segment.
pub const USER_CS: usize = 24;
-/// The offset of the user data segment.
+/// The offset of the user data segment (32 bits).
pub const USER_DS: usize = 32;
/// The offset of the Task State Segment (TSS).
pub const TSS_OFFSET: usize = 40;
/// The offset of Thread Local Storage (TLS) entries.
pub const TLS_OFFSET: usize = 56;
+/// The offset of the user data segment (64 bits).
+pub const USER_CS64: usize = 88;
/// A GDT entry.
#[repr(C, align(8))]
diff --git a/kernel/src/arch/x86/idt.rs b/kernel/src/arch/x86/idt.rs
index 548336a6..2ec83612 100644
--- a/kernel/src/arch/x86/idt.rs
+++ b/kernel/src/arch/x86/idt.rs
@@ -20,7 +20,10 @@
//! storing the list of interrupt handlers, allowing to catch and handle
//! interruptions.
-use crate::{arch::x86::pic, syscall::syscall};
+use crate::{
+ arch::x86::{gdt, pic, DEFAULT_FLAGS},
+ syscall::syscall,
+};
use core::{
arch::{asm, global_asm},
ffi::c_void,
@@ -50,34 +53,40 @@ pub const SYSCALL_ENTRY: usize = 0x80;
pub const ENTRIES_COUNT: usize = 0x81;
/// Interruption stack frame, with saved registers state.
+#[cfg(target_arch = "x86")]
#[repr(C)]
#[allow(missing_docs)]
-#[cfg(target_arch = "x86")]
+#[derive(Default)]
pub struct IntFrame {
- pub eip: u32,
- pub cs: u32,
- pub eflags: u32,
- pub esp: u32,
- pub ss: u32,
+ // Using the prefix `r` to avoid duplicate code
+ pub rax: u32,
+ pub rbx: u32,
+ pub rcx: u32,
+ pub rdx: u32,
+ pub rsi: u32,
+ pub rdi: u32,
+ pub rbp: u32,
+
+ pub gs: u32,
+ pub fs: u32,
- /// Error code, if any.
- pub code: u32,
/// Interruption number.
pub int: u32,
+ /// Error code, if any.
+ pub code: u32,
- pub eax: u32,
- pub ebx: u32,
- pub ecx: u32,
- pub edx: u32,
- pub esi: u32,
- pub edi: u32,
- pub ebp: u32,
+ pub rip: u32,
+ pub cs: u32,
+ pub rflags: u32,
+ pub rsp: u32,
+ pub ss: u32,
}
/// Interruption stack frame, with saved registers state.
-#[repr(C)]
-#[allow(missing_docs)]
#[cfg(target_arch = "x86_64")]
+#[allow(missing_docs)]
+#[repr(C)]
+#[derive(Default)]
pub struct IntFrame {
pub rax: u64,
pub rbx: u64,
@@ -96,6 +105,9 @@ pub struct IntFrame {
pub r14: u64,
pub r15: u64,
+ pub gs: u32,
+ pub fs: u32,
+
/// Interruption number.
pub int: u64,
/// Error code, if any.
@@ -109,17 +121,15 @@ pub struct IntFrame {
}
impl IntFrame {
+ /// Tells whether the interrupted context is 32 bit.
+ pub const fn is_32bit(&self) -> bool {
+ self.cs as usize == gdt::USER_CS | 3
+ }
+
/// Returns the ID of the system call being executed.
#[inline]
pub const fn get_syscall_id(&self) -> usize {
- #[cfg(target_arch = "x86")]
- {
- self.eax as usize
- }
- #[cfg(target_arch = "x86_64")]
- {
- self.rax as usize
- }
+ self.rax as usize
}
/// Returns the value of the `n`th argument of the syscall being executed.
@@ -130,12 +140,12 @@ impl IntFrame {
pub const fn get_syscall_arg(&self, n: u8) -> usize {
#[cfg(target_arch = "x86")]
let val = match n {
- 0 => self.ebx,
- 1 => self.ecx,
- 2 => self.edx,
- 3 => self.esi,
- 4 => self.edi,
- 5 => self.ebp,
+ 0 => self.rbx,
+ 1 => self.rcx,
+ 2 => self.rdx,
+ 3 => self.rsi,
+ 4 => self.rdi,
+ 5 => self.rbp,
_ => 0,
};
#[cfg(target_arch = "x86_64")]
@@ -153,39 +163,41 @@ impl IntFrame {
/// Sets the return value of a system call.
pub fn set_syscall_return(&mut self, value: EResult) {
- let val = value.map(|v| v as _).unwrap_or_else(|e| (-e.as_int()) as _);
- #[cfg(target_arch = "x86")]
- {
- self.eax = val;
- }
- #[cfg(target_arch = "x86_64")]
- {
- self.rax = val;
- }
+ self.rax = value.map(|v| v as _).unwrap_or_else(|e| (-e.as_int()) as _);
+ }
+
+ /// Returns the stack address.
+ pub fn get_stack_address(&self) -> usize {
+ self.rsp as usize
}
/// Returns the address of the instruction to be executed when the interrupt handler returns.
pub fn get_program_counter(&self) -> usize {
- #[cfg(target_arch = "x86")]
- {
- self.eax as usize
- }
- #[cfg(target_arch = "x86_64")]
- {
- self.rax as usize
- }
+ self.rip as usize
}
/// Sets the address of the instruction to be executed when the interrupt handler returns.
pub fn set_program_counter(&mut self, val: usize) {
- #[cfg(target_arch = "x86")]
- {
- self.eax = val as _;
- }
- #[cfg(target_arch = "x86_64")]
- {
- self.rax = val as _;
- }
+ self.rip = val as _;
+ }
+
+ /// Sets the values of `frame` so that it can be used to begin the execution of a program.
+ ///
+ /// Arguments:
+ /// - `pc` is the program counter
+ /// - `sp` is the stack pointer
+ /// - `bit32` tells whether the program is 32 bits. If the kernel is compiled for 32 bit, this
+ /// value is ignored.
+ pub fn exec(frame: &mut Self, pc: usize, sp: usize, bit32: bool) {
+ let cs_segment = if bit32 { gdt::USER_CS } else { gdt::USER_CS64 };
+ *frame = IntFrame {
+ rip: pc as _,
+ cs: (cs_segment | 3) as _,
+ rflags: DEFAULT_FLAGS as _,
+ rsp: sp as _,
+ ss: (gdt::USER_DS | 3) as _,
+ ..Default::default()
+ };
}
}
diff --git a/kernel/src/elf/parser.rs b/kernel/src/elf/parser.rs
index c8a5e271..985c6ad7 100644
--- a/kernel/src/elf/parser.rs
+++ b/kernel/src/elf/parser.rs
@@ -23,7 +23,7 @@ use crate::elf::relocation::Relocation;
use utils::bytes;
/// The ELF's class.
-#[derive(Clone, Copy)]
+#[derive(Clone, Copy, Eq, PartialEq)]
pub enum Class {
/// 32 bit
Bit32,
diff --git a/kernel/src/event.rs b/kernel/src/event.rs
index a6af4392..e582fd1e 100644
--- a/kernel/src/event.rs
+++ b/kernel/src/event.rs
@@ -209,5 +209,5 @@ extern "C" fn interrupt_handler(frame: &mut IntFrame) {
pic::end_of_interrupt((id - ERROR_MESSAGES.len() as u32) as _);
}
drop(callbacks);
- process::yield_current(ring);
+ process::yield_current(ring, frame);
}
diff --git a/kernel/src/file/fs/proc/proc_dir/stat.rs b/kernel/src/file/fs/proc/proc_dir/stat.rs
index ba16f03c..b2de6b1d 100644
--- a/kernel/src/file/fs/proc/proc_dir/stat.rs
+++ b/kernel/src/file/fs/proc/proc_dir/stat.rs
@@ -25,6 +25,7 @@ use crate::{
FileLocation, FileType, Stat,
},
format_content,
+ memory::VirtAddr,
process::{pid::Pid, Process},
};
use core::{fmt, fmt::Formatter};
@@ -39,14 +40,12 @@ impl<'p> fmt::Display for StatDisp<'p> {
//let vmem_usage = self.0.get_vmem_usage();
let vmem_usage = 0;
let user_regs = self.0.user_regs();
- let sp = user_regs.esp;
- let pc = user_regs.eip;
// TODO Fill every fields with process's data
write!(
f,
"{pid} ({name}) {state_char} {ppid} {pgid} {sid} TODO TODO 0 \
0 0 0 0 {user_jiffies} {kernel_jiffies} TODO TODO {priority} {nice} {num_threads} 0 {vmem_usage} \
-TODO TODO TODO TODO {sp} {pc} TODO TODO TODO TODO 0 0 0 TODO TODO TODO TODO TODO TODO TODO TODO \
+TODO TODO TODO TODO {sp:?} {pc:?} TODO TODO TODO TODO 0 0 0 TODO TODO TODO TODO TODO TODO TODO TODO \
TODO TODO TODO TODO TODO TODO TODO TODO TODO",
pid = self.0.get_pid(),
name = DisplayableStr(name),
@@ -59,6 +58,8 @@ TODO TODO TODO TODO TODO TODO TODO TODO TODO",
priority = self.0.priority,
nice = self.0.nice,
num_threads = 1, // TODO
+ sp = VirtAddr(user_regs.get_stack_address() as _),
+ pc = VirtAddr(user_regs.get_program_counter() as _),
)
}
}
diff --git a/kernel/src/kernel.rs b/kernel/src/kernel.rs
index 2a2b1795..0b9fd931 100644
--- a/kernel/src/kernel.rs
+++ b/kernel/src/kernel.rs
@@ -77,11 +77,16 @@ pub mod time;
pub mod tty;
use crate::{
- arch::x86::{enable_sse, has_sse, idt},
+ arch::x86::{enable_sse, has_sse, idt, idt::IntFrame},
file::{fs::initramfs, vfs, vfs::ResolutionSettings},
logger::LOGGER,
memory::vmem,
- process::{exec, exec::ExecInfo, Process},
+ process::{
+ exec,
+ exec::{exec, ExecInfo},
+ scheduler::switch,
+ Process,
+ },
tty::TTY,
};
use core::{arch::asm, ffi::c_void};
@@ -127,28 +132,31 @@ pub fn enter_loop() -> ! {
/// Launches the init process.
///
/// `init_path` is the path to the init program.
+///
+/// On success, the function does not return.
fn init(init_path: String) -> EResult<()> {
- // The initial environment
- let env: Vec = vec![
- b"PATH=/bin:/sbin:/usr/bin:/usr/sbin:/usr/local/bin:/usr/local/sbin".try_into()?,
- b"TERM=maestro".try_into()?,
- ]?;
-
- let rs = ResolutionSettings::kernel_follow();
-
- let path = Path::new(&init_path)?;
- let file = vfs::get_file_from_path(path, &rs)?;
-
- let exec_info = ExecInfo {
- path_resolution: &rs,
- argv: vec![init_path]?,
- envp: env,
- };
- let program_image = exec::build_image(&file, exec_info)?;
-
- let proc_mutex = Process::new()?;
- let mut proc = proc_mutex.lock();
- exec::exec(&mut proc, program_image)
+ let mut frame = IntFrame::default();
+ {
+ let path = Path::new(&init_path)?;
+ let rs = ResolutionSettings::kernel_follow();
+ let file = vfs::get_file_from_path(path, &rs)?;
+ let program_image = exec::build_image(
+ &file,
+ ExecInfo {
+ path_resolution: &rs,
+ argv: vec![init_path]?,
+ envp: vec![
+ b"PATH=/bin:/sbin:/usr/bin:/usr/sbin:/usr/local/bin:/usr/local/sbin"
+ .try_into()?,
+ b"TERM=maestro".try_into()?,
+ ]?,
+ },
+ )?;
+ let proc_mutex = Process::init()?;
+ let mut proc = proc_mutex.lock();
+ exec(&mut proc, &mut frame, program_image)?;
+ }
+ switch::init(&frame);
}
/// An inner function is required to ensure everything in scope is dropped before calling
diff --git a/kernel/src/process/exec/elf.rs b/kernel/src/process/exec/elf.rs
index 35b8d04d..0c73da21 100644
--- a/kernel/src/process/exec/elf.rs
+++ b/kernel/src/process/exec/elf.rs
@@ -23,7 +23,7 @@ use crate::{
arch::x86,
elf,
elf::{
- parser::{ELFParser, ProgramHeader, Rel, Rela},
+ parser::{Class, ELFParser, ProgramHeader, Rel, Rela},
relocation,
relocation::GOT_SYM,
},
@@ -715,6 +715,7 @@ impl<'s> Executor for ELFExecutor<'s> {
envp,
mem_space,
+ bit32: parser.class() == Class::Bit32,
entry_point: load_info.entry_point,
user_stack: VirtAddr::from(user_stack) - init_stack_size,
diff --git a/kernel/src/process/exec/mod.rs b/kernel/src/process/exec/mod.rs
index 2224e812..73b4d871 100644
--- a/kernel/src/process/exec/mod.rs
+++ b/kernel/src/process/exec/mod.rs
@@ -28,6 +28,7 @@ pub mod elf;
pub mod vdso;
use crate::{
+ arch::x86::idt::IntFrame,
file::{vfs, vfs::ResolutionSettings},
memory::VirtAddr,
process::{mem_space::MemSpace, signal::SignalHandler, Process},
@@ -58,6 +59,8 @@ pub struct ProgramImage {
/// The image's memory space.
mem_space: MemSpace,
+ /// Tells whether the program is 32 bit.
+ bit32: bool,
/// A pointer to the entry point of the program.
entry_point: VirtAddr,
@@ -88,7 +91,10 @@ pub fn build_image(file: &vfs::Entry, info: ExecInfo) -> EResult {
}
/// Executes the program image `image` on the process `proc`.
-pub fn exec(proc: &mut Process, image: ProgramImage) -> EResult<()> {
+///
+/// `frame` is the interrupt frame of the current content. The function sets the appropriate values
+/// for each register so that the execution beings when the interrupt handler returns.
+pub fn exec(proc: &mut Process, frame: &mut IntFrame, image: ProgramImage) -> EResult<()> {
proc.argv = Arc::new(image.argv)?;
proc.envp = Arc::new(image.envp)?;
// TODO Set exec path
@@ -110,10 +116,6 @@ pub fn exec(proc: &mut Process, image: ProgramImage) -> EResult<()> {
proc.tls_entries = Default::default();
proc.update_tss();
// Set the process's registers
- proc.regs = Regs32 {
- esp: image.user_stack.0 as _,
- eip: image.entry_point.0 as _,
- ..Default::default()
- };
+ IntFrame::exec(frame, image.entry_point.0, image.user_stack.0, image.bit32);
Ok(())
}
diff --git a/kernel/src/process/mod.rs b/kernel/src/process/mod.rs
index cb6d790f..c5eb701a 100644
--- a/kernel/src/process/mod.rs
+++ b/kernel/src/process/mod.rs
@@ -59,7 +59,7 @@ use crate::{
time::timer::TimerManager,
};
use core::{
- ffi::c_int,
+ ffi::{c_int, c_void},
fmt,
fmt::Formatter,
intrinsics::unlikely,
@@ -178,6 +178,9 @@ pub struct ForkOptions {
/// This is useful in order to avoid an unnecessary clone of the memory space in case the
/// child process executes a program or exits quickly.
pub vfork: bool,
+
+ /// The stack address the child process begins with.
+ pub stack: Option>,
}
/// The vfork operation is similar to the fork operation except the parent
@@ -397,7 +400,7 @@ impl Process {
/// Creates the init process and places it into the scheduler's queue.
///
/// The process is set to state [`State::Running`] by default and has user root.
- pub fn new() -> EResult>> {
+ pub fn init() -> EResult>> {
let rs = ResolutionSettings::kernel_follow();
// Create the default file descriptors table
let file_descriptors = {
@@ -788,6 +791,8 @@ impl Process {
// TODO if creating a thread: timer_manager: proc.timer_manager.clone(),
timer_manager: Arc::new(Mutex::new(TimerManager::new(pid_int)?))?,
+ kernel_sp,
+
mem_space: Some(mem_space),
kernel_stack: buddy::alloc_kernel(KERNEL_STACK_ORDER)?,
@@ -1011,24 +1016,14 @@ impl Drop for Process {
///
/// Arguments:
/// - `ring` is the ring the current context is returning to.
-/// - `regs` is the set of registers from the previously interrupted context.
+/// - `frame` is the interrupt frame.
///
/// The execution flow can be altered by:
/// - The process is no longer in [`State::Running`] state
/// - A signal handler has to be executed
///
-/// The current function may save `regs` and replaces it with the required state for the new
-/// context.
-///
-/// The function locks the mutex of the current process. Thus, the caller must
-/// ensure the mutex isn't already locked to prevent a deadlock.
-///
-/// # Safety
-///
-/// This function may not return in some cases (example: the process has been turned into a
-/// Zombie). It is the caller's responsibility to drop all objects on the stack that need it, in
-/// order to avoid unintended side effects.
-pub fn yield_current(ring: u8) {
+/// This function never returns in case the process state turns to [`State::Zombie`].
+pub fn yield_current(ring: u8, frame: &mut IntFrame) {
// If returning to kernelspace, do nothing
if ring < 3 {
return;
@@ -1046,18 +1041,11 @@ pub fn yield_current(ring: u8) {
// Prepare signal for execution
let handlers = proc.signal_handlers.clone();
let handlers = handlers.lock();
- let handler = &handlers[sig.get_id() as usize];
- // Update registers with the ones passed to the system call so that `sigreturn` returns to
- // the correct location
- handler.exec(sig, &mut proc);
+ handlers[sig.get_id() as usize].exec(sig, &mut proc, frame);
// Alter the execution flow of the current context according to the new state of the
// process
match proc.state {
- // The process must execute a signal handler: Jump to it
- State::Running => {
- todo!()
- }
- // Stop execution: Waiting until wakeup (or terminate if Zombie)
+ State::Running => {}
State::Sleeping | State::Stopped | State::Zombie => Scheduler::tick(),
}
}
diff --git a/kernel/src/process/scheduler/mod.rs b/kernel/src/process/scheduler/mod.rs
index 6c67abe5..4eac7687 100644
--- a/kernel/src/process/scheduler/mod.rs
+++ b/kernel/src/process/scheduler/mod.rs
@@ -21,9 +21,8 @@
//!
//! TODO
-mod switch;
+pub mod switch;
-use core::mem;
use crate::{
arch::x86::{idt::IntFrame, pic},
event,
@@ -32,6 +31,7 @@ use crate::{
process::{pid::Pid, scheduler::switch::switch, Process, State},
time,
};
+use core::mem;
use utils::{
collections::{
btreemap::{BTreeMap, MapIterator},
diff --git a/kernel/src/process/scheduler/switch.rs b/kernel/src/process/scheduler/switch.rs
index 2bffc0dd..75b5892f 100644
--- a/kernel/src/process/scheduler/switch.rs
+++ b/kernel/src/process/scheduler/switch.rs
@@ -18,8 +18,40 @@
//! Context switching utilities.
-use crate::process::{Process, TLS_ENTRIES_COUNT};
-use core::{arch::global_asm, mem::offset_of};
+use crate::{
+ arch::x86::idt::IntFrame,
+ process::{Process, TLS_ENTRIES_COUNT},
+};
+use core::{
+ arch::{asm, global_asm},
+ mem::offset_of,
+};
+
+/// Jumps to a context with the given `frame`.
+pub fn init(frame: &IntFrame) -> ! {
+ #[cfg(target_arch = "x86")]
+ unsafe {
+ asm!(
+ r"mov esp, {}
+ LOAD_REGS
+ add esp, 8
+ iretd",
+ in(reg) frame,
+ options(noreturn)
+ )
+ }
+ #[cfg(target_arch = "x86_64")]
+ unsafe {
+ asm!(
+ r"mov esp, {}
+ LOAD_REGS
+ add esp, 8
+ iretd",
+ in(reg) frame,
+ options(noreturn)
+ )
+ }
+}
/// Switches context from `prev` to `next`.
///
@@ -35,7 +67,21 @@ extern "C" {
fn switch_asm(prev: &mut Process, next: &mut Process);
}
-// TODO 32 bit
+//#[cfg(target_arch = "x86")]
+global_asm!(r"
+switch_asm:
+ push ebp
+ push ebx
+
+ # Swap contexts
+ mov [edi + {off}], esp
+ mov esp, [esi + {off}]
+
+ push ebx
+ push ebp
+
+ jmp switch_finish
+", off = const offset_of!(Process, kernel_sp));
#[cfg(target_arch = "x86_64")]
global_asm!(r"
diff --git a/kernel/src/process/signal/mod.rs b/kernel/src/process/signal/mod.rs
index 307f2b4f..9446b9c2 100644
--- a/kernel/src/process/signal/mod.rs
+++ b/kernel/src/process/signal/mod.rs
@@ -18,17 +18,20 @@
//! POSIX signals implementation.
-mod signal_trampoline;
+mod trampoline;
pub mod ucontext;
use super::{oom, Process, State, REDZONE_SIZE};
-use crate::{file::perm::Uid, memory::VirtAddr, process::pid::Pid, time::unit::ClockIdT};
+use crate::{
+ arch::x86::idt::IntFrame, file::perm::Uid, memory::VirtAddr, process::pid::Pid,
+ time::unit::ClockIdT,
+};
use core::{
ffi::{c_int, c_void},
fmt,
mem::{size_of, transmute},
ptr,
- ptr::{null_mut, NonNull},
+ ptr::NonNull,
slice,
};
use utils::{errno, errno::Errno};
@@ -320,69 +323,87 @@ impl SignalHandler {
}
/// Executes the action for `signal` on `process`.
- pub fn exec(&self, signal: Signal, process: &mut Process) {
+ pub fn exec(&self, signal: Signal, process: &mut Process, frame: &mut IntFrame) {
let process_state = process.get_state();
if matches!(process_state, State::Zombie) {
return;
}
- match self {
- Self::Ignore => {}
- // TODO handle SA_SIGINFO
- Self::Handler(action) if signal.can_catch() => {
- // Prepare the signal handler stack
- // TODO Handle the case where an alternate stack is specified (sigaltstack + flag
- // SA_ONSTACK)
- let stack_addr = VirtAddr(process.regs.esp as _) - REDZONE_SIZE;
- let signal_data_size = size_of::() + size_of::() * 4;
- let signal_esp = stack_addr - signal_data_size;
- {
- let mem_space = process.get_mem_space().unwrap();
- let mut mem_space = mem_space.lock();
- mem_space.bind();
- // FIXME: a stack overflow would cause an infinite loop
- oom::wrap(|| mem_space.alloc(signal_esp, signal_data_size));
- }
- // Write data on stack
- let ctx = UContext {
- uc_flags: 0, // TODO
- uc_link: null_mut(),
- uc_sigmask: process.sigmask,
- uc_stack: stack_addr.as_ptr(),
- uc_mcontext: process.regs.clone(),
- };
- unsafe {
- // Write `ctx`
- let ctx_addr = stack_addr - size_of::();
- ptr::write_volatile(ctx_addr.as_ptr(), ctx);
- let args = slice::from_raw_parts_mut(signal_esp.as_ptr::(), 4);
- // Pointer to `ctx`
- args[3] = ctx_addr.0;
- // Signal number
- args[2] = signal.get_id() as usize;
- // Pointer to the handler
- args[1] = action.sa_handler.sa_handler.unwrap() as usize;
- // Padding (return pointer)
- args[0] = 0;
- }
- // Block signals from `sa_mask`
- process.sigmask.0 |= action.sa_mask.0;
- if action.sa_flags & SA_NODEFER == 0 {
- process.sigmask.set(signal.get_id() as _);
- }
- // Prepare registers for the trampoline
- let signal_trampoline = signal_trampoline as *const c_void;
- process.regs.ebp = 0;
- process.regs.esp = signal_esp.0 as _;
- process.regs.eip = signal_trampoline as _;
- }
+ let action = match self {
+ Self::Handler(action) if signal.can_catch() => action,
+ Self::Ignore => return,
// Execute default action
_ => {
// Signals on the init process can be executed only if the process has set a
// signal handler
- if signal.can_catch() && process.is_init() {
- return;
+ if !process.is_init() || !signal.can_catch() {
+ signal.get_default_action().exec(signal, process);
}
- signal.get_default_action().exec(signal, process)
+ return;
+ }
+ };
+ // TODO handle SA_SIGINFO
+ // TODO Handle the case where an alternate stack is specified (sigaltstack + flag
+ // SA_ONSTACK)
+ // Prepare the signal handler stack
+ let stack_addr = VirtAddr(frame.get_stack_address()) - REDZONE_SIZE;
+ // Size of the `ucontext_t` struct and arguments *on the stack*
+ let (ctx_size, arg_len) = if frame.is_32bit() {
+ (size_of::(), size_of::() * 4)
+ } else {
+ #[cfg(target_arch = "x86")]
+ unreachable!();
+ #[cfg(target_arch = "x86_64")]
+ (size_of::(), 0)
+ };
+ let ctx_addr = stack_addr - ctx_size;
+ let signal_sp = stack_addr - (ctx_size + arg_len);
+ {
+ let mem_space = process.get_mem_space().unwrap();
+ let mut mem_space = mem_space.lock();
+ mem_space.bind();
+ // FIXME: a stack overflow would cause an infinite loop
+ oom::wrap(|| mem_space.alloc(signal_sp, arg_len));
+ }
+ let handler_pointer = unsafe { action.sa_handler.sa_handler.unwrap() };
+ // Write data on stack
+ if frame.is_32bit() {
+ let args = unsafe {
+ ptr::write_volatile(ctx_addr.as_ptr(), ucontext::UContext32::new(process, frame));
+ // Arguments slice
+ slice::from_raw_parts_mut(signal_sp.as_ptr::(), 4)
+ };
+ // Pointer to `ctx`
+ args[3] = ctx_addr.0 as _;
+ // Signal number
+ args[2] = signal.get_id() as _;
+ // Pointer to the handler
+ args[1] = handler_pointer as _;
+ // Padding (return pointer)
+ args[0] = 0;
+ } else {
+ #[cfg(target_arch = "x86_64")]
+ unsafe {
+ ptr::write_volatile(ctx_addr.as_ptr(), ucontext::UContext64::new(process, frame));
+ }
+ }
+ // Block signals from `sa_mask`
+ process.sigmask.0 |= action.sa_mask.0;
+ if action.sa_flags & SA_NODEFER == 0 {
+ process.sigmask.set(signal.get_id() as _);
+ }
+ // Prepare registers for the trampoline
+ frame.rbp = 0;
+ frame.rsp = signal_sp.0 as _;
+ if frame.is_32bit() {
+ frame.rip = trampoline::trampoline32 as *const c_void as _;
+ } else {
+ #[cfg(target_arch = "x86_64")]
+ {
+ frame.rip = trampoline::trampoline64 as *const c_void as _;
+ // Arguments
+ frame.rdi = ctx_addr.0 as _;
+ frame.rsi = signal.get_id() as _;
+ frame.rdx = handler_pointer as _;
}
}
}
diff --git a/kernel/src/process/signal/signal_trampoline.rs b/kernel/src/process/signal/trampoline.rs
similarity index 89%
rename from kernel/src/process/signal/signal_trampoline.rs
rename to kernel/src/process/signal/trampoline.rs
index 0403f474..23f0f30e 100644
--- a/kernel/src/process/signal/signal_trampoline.rs
+++ b/kernel/src/process/signal/trampoline.rs
@@ -28,28 +28,25 @@
//!
//! Restoring the original context is done by calling [`crate::syscall::sigreturn::sigreturn`].
-use crate::{
- process::signal::ucontext::{UContext32, UContext64},
- syscall::SIGRETURN_ID,
-};
+use crate::{process::signal::ucontext, syscall::SIGRETURN_ID};
use core::arch::asm;
#[link_section = ".user"]
pub unsafe extern "C" fn trampoline32(
handler: unsafe extern "C" fn(i32),
sig: usize,
- ctx: &mut UContext32,
+ ctx: &mut ucontext::UContext32,
) -> ! {
handler(sig as _);
// Call `sigreturn`
asm!(
- "mov esp, {}",
+ "mov esp, {:e}",
"int 0x80",
"ud2",
- in(reg) ctx.uc_stack,
+ in(reg) ctx.uc_stack.ss_sp,
in("eax") SIGRETURN_ID,
options(noreturn)
- );
+ )
}
#[cfg(target_arch = "x86_64")]
@@ -57,7 +54,7 @@ pub unsafe extern "C" fn trampoline32(
pub unsafe extern "C" fn trampoline64(
handler: unsafe extern "C" fn(i32),
sig: usize,
- ctx: &mut UContext64,
+ ctx: &mut ucontext::UContext64,
) -> ! {
handler(sig as _);
// Call `sigreturn`
@@ -65,8 +62,8 @@ pub unsafe extern "C" fn trampoline64(
"mov rsp, {}",
"sysenter",
"ud2",
- in(reg) ctx.uc_stack,
+ in(reg) ctx.uc_stack.ss_sp,
in("rax") SIGRETURN_ID,
options(noreturn)
- );
+ )
}
diff --git a/kernel/src/process/signal/ucontext.rs b/kernel/src/process/signal/ucontext.rs
index d05901f1..f8f60913 100644
--- a/kernel/src/process/signal/ucontext.rs
+++ b/kernel/src/process/signal/ucontext.rs
@@ -18,14 +18,42 @@
//! Userspace signal context structures.
-use crate::process::signal::SigSet;
-use core::ffi::c_void;
+use crate::{
+ arch::x86::{gdt, idt::IntFrame},
+ process::{signal::SigSet, Process},
+};
+// TODO restore everything
// ------------------------------
// 32 bit structures
+/// General purpose registers (32 bit).
+#[repr(usize)]
+pub enum GReg32 {
+ Gs = 0,
+ Fs,
+ Es,
+ Ds,
+ Edi,
+ Esi,
+ Ebp,
+ Esp,
+ Ebx,
+ Edx,
+ Ecx,
+ Eax,
+ Trapno,
+ Err,
+ Eip,
+ Cs,
+ Efl,
+ Uesp,
+ Ss,
+}
+
/// 32-bit userspace signal context.
#[repr(C)]
+#[derive(Debug)]
pub struct UContext32 {
pub uc_flags: u32,
pub uc_link: u32, // 32 bit pointer
@@ -36,8 +64,82 @@ pub struct UContext32 {
pub __ssp: [u64; 4],
}
+impl UContext32 {
+ /// Creates a context structure from the current.
+ pub fn new(process: &Process, frame: &IntFrame) -> Self {
+ Self {
+ uc_flags: 0, // TODO
+ uc_link: 0,
+ // TODO
+ uc_stack: Stack32 {
+ ss_sp: 0,
+ ss_flags: 0,
+ ss_size: 0,
+ },
+ uc_mcontext: MContext32 {
+ gregs: [
+ frame.gs as _,
+ frame.fs as _,
+ (gdt::USER_DS | 3) as _,
+ (gdt::USER_DS | 3) as _,
+ frame.rdi as _,
+ frame.rsi as _,
+ frame.rbp as _,
+ frame.rsp as _,
+ frame.rbx as _,
+ frame.rdx as _,
+ frame.rcx as _,
+ frame.rax as _,
+ 0, // TODO trapno
+ 0, // TODO err
+ frame.rip as _,
+ frame.cs as _,
+ frame.rflags as _,
+ 0, // TODO uesp
+ frame.ss as _,
+ ],
+ fpregs: 0, // TODO
+ oldmask: 0, // TODO
+ cr2: 0,
+ },
+ uc_sigmask: process.sigmask,
+ // TODO
+ __fpregs_mem: FpState32 {
+ cw: 0,
+ sw: 0,
+ tag: 0,
+ ipoff: 0,
+ cssel: 0,
+ dataoff: 0,
+ datasel: 0,
+ _st: [FpReg32 {
+ significand: [0; 4],
+ exponent: 0,
+ }; 8],
+ status: 0,
+ },
+ __ssp: [0; 4],
+ }
+ }
+
+ /// Restores the context.
+ pub fn restore_regs(&self, proc: &mut Process, frame: &mut IntFrame) {
+ // Restore general registers
+ frame.rax = self.uc_mcontext.gregs[GReg32::Eax as usize] as _;
+ frame.rbx = self.uc_mcontext.gregs[GReg32::Ebx as usize] as _;
+ frame.rcx = self.uc_mcontext.gregs[GReg32::Ecx as usize] as _;
+ frame.rdx = self.uc_mcontext.gregs[GReg32::Edx as usize] as _;
+ frame.rsi = self.uc_mcontext.gregs[GReg32::Esi as usize] as _;
+ frame.rdi = self.uc_mcontext.gregs[GReg32::Edi as usize] as _;
+ frame.rbp = self.uc_mcontext.gregs[GReg32::Ebp as usize] as _;
+ // TODO restore fpstate
+ proc.sigmask = self.uc_sigmask;
+ }
+}
+
/// 32-bit description of a signal stack.
#[repr(C)]
+#[derive(Debug)]
pub struct Stack32 {
pub ss_sp: u32, // 32 bit pointer
pub ss_flags: i32,
@@ -46,6 +148,7 @@ pub struct Stack32 {
/// 32-bit registers state.
#[repr(C)]
+#[derive(Debug)]
pub struct MContext32 {
pub gregs: [u32; 19],
pub fpregs: u32, // 32 bit pointer
@@ -55,6 +158,7 @@ pub struct MContext32 {
/// 32-bit floating point registers state.
#[repr(C)]
+#[derive(Debug)]
pub struct FpState32 {
pub cw: u32,
pub sw: u32,
@@ -69,6 +173,7 @@ pub struct FpState32 {
/// TODO doc
#[repr(C)]
+#[derive(Clone, Copy, Debug)]
pub struct FpReg32 {
pub significand: [u16; 4],
pub exponent: u16,
@@ -77,12 +182,42 @@ pub struct FpReg32 {
// ------------------------------
// 64 bit structures
+/// General purpose registers (64 bit).
+#[cfg(target_arch = "x86_64")]
+#[repr(usize)]
+pub enum GReg64 {
+ R8 = 0,
+ R9,
+ R10,
+ R11,
+ R12,
+ R13,
+ R14,
+ R15,
+ Rdi,
+ Rsi,
+ Rbp,
+ Rbx,
+ Rdx,
+ Rax,
+ Rcx,
+ Rsp,
+ Rip,
+ Efl,
+ Csgsfs,
+ Err,
+ Trapno,
+ Oldmask,
+ Cr2,
+}
+
/// 64-bit userspace signal context.
#[cfg(target_arch = "x86_64")]
#[repr(C)]
+#[derive(Debug)]
pub struct UContext64 {
pub uc_flags: u64,
- pub uc_link: *mut Self,
+ pub uc_link: u64, // 64 bit pointer
pub uc_stack: Stack64,
pub uc_mcontext: MContext64,
pub uc_sigmask: SigSet,
@@ -90,11 +225,102 @@ pub struct UContext64 {
pub __ssp: [u64; 4],
}
+#[cfg(target_arch = "x86_64")]
+impl UContext64 {
+ /// Creates a context structure from the current.
+ pub fn new(process: &Process, frame: &IntFrame) -> Self {
+ Self {
+ uc_flags: 0, // TODO
+ uc_link: 0,
+ // TODO
+ uc_stack: Stack64 {
+ ss_sp: 0,
+ ss_flags: 0,
+ ss_size: 0,
+ },
+ uc_mcontext: MContext64 {
+ gregs: [
+ frame.r8,
+ frame.r9,
+ frame.r10,
+ frame.r11,
+ frame.r12,
+ frame.r13,
+ frame.r14,
+ frame.r15,
+ frame.rdi,
+ frame.rsi,
+ frame.rbp,
+ frame.rbx,
+ frame.rdx,
+ frame.rax,
+ frame.rcx,
+ frame.rsp,
+ frame.rip,
+ frame.rflags,
+ 0, // TODO csgsfs
+ 0, // TODO err
+ 0, // TODO trapno
+ 0, // TODO oldmask
+ 0, // cr2
+ ],
+ fpregs: 0, // TODO
+ __reserved1: [0; 8],
+ },
+ uc_sigmask: process.sigmask,
+ // TODO
+ __fpregs_mem: FpState64 {
+ cwd: 0,
+ swd: 0,
+ ftw: 0,
+ fop: 0,
+ rip: 0,
+ rdp: 0,
+ mxcsr: 0,
+ mxcr_mask: 0,
+ _st: [FpReg64 {
+ significand: [0; 4],
+ exponent: 0,
+ __glibc_reserved1: [0; 3],
+ }; 8],
+ _xmm: [XmmReg64 {
+ element: [0; 4],
+ }; 16],
+ __glibc_reserved1: [0; 24],
+ },
+ __ssp: [0; 4],
+ }
+ }
+
+ /// Restores the context.
+ pub fn restore_regs(&self, proc: &mut Process, frame: &mut IntFrame) {
+ // Restore general registers
+ frame.rax = self.uc_mcontext.gregs[GReg64::Rax as usize] as _;
+ frame.rbx = self.uc_mcontext.gregs[GReg64::Rbx as usize] as _;
+ frame.rcx = self.uc_mcontext.gregs[GReg64::Rcx as usize] as _;
+ frame.rdx = self.uc_mcontext.gregs[GReg64::Rdx as usize] as _;
+ frame.rsi = self.uc_mcontext.gregs[GReg64::Rsi as usize] as _;
+ frame.rdi = self.uc_mcontext.gregs[GReg64::Rdi as usize] as _;
+ frame.rbp = self.uc_mcontext.gregs[GReg64::Rbp as usize] as _;
+ frame.r8 = self.uc_mcontext.gregs[GReg64::R8 as usize] as _;
+ frame.r9 = self.uc_mcontext.gregs[GReg64::R9 as usize] as _;
+ frame.r10 = self.uc_mcontext.gregs[GReg64::R10 as usize] as _;
+ frame.r11 = self.uc_mcontext.gregs[GReg64::R11 as usize] as _;
+ frame.r12 = self.uc_mcontext.gregs[GReg64::R12 as usize] as _;
+ frame.r13 = self.uc_mcontext.gregs[GReg64::R13 as usize] as _;
+ frame.r14 = self.uc_mcontext.gregs[GReg64::R14 as usize] as _;
+ frame.r15 = self.uc_mcontext.gregs[GReg64::R15 as usize] as _;
+ // TODO restore fpstate
+ proc.sigmask = self.uc_sigmask;
+ }
+}
+
/// 64-bit description of a signal stack.
#[cfg(target_arch = "x86_64")]
#[repr(C)]
+#[derive(Debug)]
pub struct Stack64 {
- pub ss_sp: *mut c_void,
+ pub ss_sp: u64, // 64 bit pointer
pub ss_flags: i32,
pub ss_size: usize,
}
@@ -102,15 +328,17 @@ pub struct Stack64 {
/// 64-bit registers state.
#[cfg(target_arch = "x86_64")]
#[repr(C)]
+#[derive(Debug)]
pub struct MContext64 {
pub gregs: [u64; 23],
- pub fpregs: *mut FpState64,
+ pub fpregs: u64, // 64 bit pointer
pub __reserved1: [u64; 8],
}
/// 64-bit floating point registers state.
#[cfg(target_arch = "x86_64")]
#[repr(C)]
+#[derive(Debug)]
pub struct FpState64 {
pub cwd: u16,
pub swd: u16,
@@ -128,6 +356,7 @@ pub struct FpState64 {
/// TODO doc
#[cfg(target_arch = "x86_64")]
#[repr(C)]
+#[derive(Clone, Copy, Debug)]
pub struct FpReg64 {
pub significand: [u16; 4],
pub exponent: u16,
@@ -137,6 +366,7 @@ pub struct FpReg64 {
/// TODO doc
#[cfg(target_arch = "x86_64")]
#[repr(C)]
+#[derive(Clone, Copy, Debug)]
pub struct XmmReg64 {
pub element: [u32; 4],
}
diff --git a/kernel/src/syscall/clone.rs b/kernel/src/syscall/clone.rs
index 1b5803b8..b7546034 100644
--- a/kernel/src/syscall/clone.rs
+++ b/kernel/src/syscall/clone.rs
@@ -20,10 +20,16 @@
use crate::{
arch::x86::idt::IntFrame,
- process::{mem_space::copy::SyscallPtr, scheduler, user_desc::UserDesc, ForkOptions, Process},
+ process::{
+ mem_space::copy::SyscallPtr, scheduler, scheduler::Scheduler, user_desc::UserDesc,
+ ForkOptions, Process,
+ },
syscall::{Args, FromSyscallArg},
};
-use core::ffi::{c_int, c_ulong, c_void};
+use core::{
+ ffi::{c_int, c_ulong, c_void},
+ ptr::NonNull,
+};
use utils::{errno::EResult, lock::IntMutex, ptr::arc::Arc};
/// TODO doc
@@ -79,20 +85,18 @@ const CLONE_NEWNET: c_ulong = 0x40000000;
#[allow(clippy::type_complexity)]
pub fn clone(
- Args((flags, stack, _parent_tid, tls, _child_tid)): Args<(
+ Args((flags, stack, _parent_tid, _tls, _child_tid)): Args<(
c_ulong,
*mut c_void,
SyscallPtr,
c_ulong,
SyscallPtr,
)>,
- frame: &IntFrame,
proc_mutex: Arc>,
) -> EResult {
let new_tid = {
if flags & CLONE_PARENT_SETTID != 0 {
- // TODO
- todo!();
+ todo!()
}
let new_mutex = Process::fork(
proc_mutex,
@@ -102,40 +106,26 @@ pub fn clone(
share_sighand: flags & CLONE_SIGHAND != 0,
vfork: flags & CLONE_VFORK != 0,
+
+ stack: NonNull::new(stack),
},
)?;
- let mut new_proc = new_mutex.lock();
- // Set the process's registers
- let mut new_regs = frame.clone();
- // Set return value to `0`
- new_regs.eax = 0;
- // Set stack
- new_regs.esp = if stack.is_null() {
- frame.esp
- } else {
- stack as _
- };
- // Set TLS
+ let new_proc = new_mutex.lock();
if flags & CLONE_SETTLS != 0 {
- let _tls = SyscallPtr::::from_syscall_arg(tls as usize);
- // TODO
- todo!();
+ todo!()
}
- new_proc.regs = new_regs;
if flags & CLONE_CHILD_CLEARTID != 0 {
- // TODO new_proc.set_clear_child_tid(child_tid);
- todo!();
+ todo!()
}
if flags & CLONE_CHILD_SETTID != 0 {
- // TODO
- todo!();
+ todo!()
}
new_proc.tid
};
if flags & CLONE_VFORK != 0 {
// Let another process run instead of the current. Because the current
// process must now wait for the child process to terminate or execute a program
- scheduler::end_tick();
+ Scheduler::tick();
}
Ok(new_tid as _)
}
diff --git a/kernel/src/syscall/execve.rs b/kernel/src/syscall/execve.rs
index 131721f7..e0655a7a 100644
--- a/kernel/src/syscall/execve.rs
+++ b/kernel/src/syscall/execve.rs
@@ -20,11 +20,12 @@
use super::Args;
use crate::{
+ arch::x86::idt::IntFrame,
file::{vfs, vfs::ResolutionSettings, File},
memory::stack,
process::{
exec,
- exec::{ExecInfo, ProgramImage},
+ exec::{exec, ExecInfo, ProgramImage},
mem_space::copy::{SyscallArray, SyscallString},
scheduler::SCHEDULER,
Process,
@@ -141,45 +142,10 @@ fn get_file>>(
Ok((file, final_argv))
}
-/// Performs the execution on the current process.
-fn do_exec(
- file: &vfs::Entry,
- rs: &ResolutionSettings,
- argv: Vec,
- envp: Vec,
-) -> EResult {
- let program_image = build_image(file, rs, argv, envp)?;
- let proc_mutex = Process::current();
- let mut proc = proc_mutex.lock();
- // Execute the program
- exec::exec(&mut proc, program_image)?;
- Ok(proc.regs.clone())
-}
-
-/// Builds a program image.
-///
-/// Arguments:
-/// - `file` is the executable file
-/// - `path_resolution` is settings for path resolution
-/// - `argv` is the arguments list
-/// - `envp` is the environment variables list
-fn build_image(
- file: &vfs::Entry,
- path_resolution: &ResolutionSettings,
- argv: Vec,
- envp: Vec,
-) -> EResult {
- let exec_info = ExecInfo {
- path_resolution,
- argv,
- envp,
- };
- exec::build_image(file, exec_info)
-}
-
pub fn execve(
Args((pathname, argv, envp)): Args<(SyscallString, SyscallArray, SyscallArray)>,
rs: ResolutionSettings,
+ frame: &mut IntFrame,
) -> EResult {
let (file, argv, envp) = {
let path = pathname.copy_from_user()?.ok_or_else(|| errno!(EFAULT))?;
@@ -189,15 +155,16 @@ pub fn execve(
let envp = envp.iter().collect::>>>()?.0?;
(file, argv, envp)
};
- // Disable interrupt to prevent stack switching while using a temporary stack,
- // preventing this temporary stack from being used as a signal handling stack
- cli();
- let tmp_stack = SCHEDULER.get().lock().get_tmp_stack();
- let exec = move || {
- let regs = do_exec(&file, &rs, argv, envp)?;
- unsafe {
- regs.switch(true);
- }
- };
- unsafe { stack::switch(tmp_stack as _, exec) }
+ let program_image = exec::build_image(
+ &file,
+ ExecInfo {
+ path_resolution: &rs,
+ argv,
+ envp,
+ },
+ )?;
+ let proc_mutex = Process::current();
+ let mut proc = proc_mutex.lock();
+ exec(&mut proc, frame, program_image)?;
+ Ok(0)
}
diff --git a/kernel/src/syscall/fork.rs b/kernel/src/syscall/fork.rs
index dab68ae6..b15ce0e3 100644
--- a/kernel/src/syscall/fork.rs
+++ b/kernel/src/syscall/fork.rs
@@ -30,13 +30,8 @@ use utils::{
ptr::arc::Arc,
};
-pub fn fork(proc: Arc>, frame: &IntFrame) -> EResult {
+pub fn fork(proc: Arc>) -> EResult {
let new_mutex = Process::fork(proc, ForkOptions::default())?;
- let mut new_proc = new_mutex.lock();
- // Set child's return value to `0`
- let mut frame = frame.clone();
- frame.set_syscall_return(Ok(0));
- new_proc.regs = frame;
- // Set parent's return value to the child's PID
+ let new_proc = new_mutex.lock();
Ok(new_proc.get_pid() as _)
}
diff --git a/kernel/src/syscall/mod.rs b/kernel/src/syscall/mod.rs
index e3a15fad..4fdc5223 100644
--- a/kernel/src/syscall/mod.rs
+++ b/kernel/src/syscall/mod.rs
@@ -309,7 +309,7 @@ use writev::writev;
pub const SIGRETURN_ID: usize = 0x077;
/// A system call handler.
-pub trait SyscallHandler<'p, Args> {
+pub trait SyscallHandler {
/// Calls the system call.
///
/// Arguments:
@@ -317,18 +317,19 @@ pub trait SyscallHandler<'p, Args> {
/// - `frame` is the interrupt handler's stack frame.
///
/// The function returns the result of the system call.
- fn call(self, name: &str, frame: &'p IntFrame) -> EResult;
+ fn call(self, name: &str, frame: &mut IntFrame) -> EResult;
}
/// Implementation of [`SyscallHandler`] for functions with arguments.
macro_rules! impl_syscall_handler {
($($ty:ident),*) => {
- impl<'p, F, $($ty,)*> SyscallHandler<'p, ($($ty,)*)> for F
+ // Implementation **without** trailing reference to frame
+ impl SyscallHandler<($($ty,)*)> for F
where F: FnOnce($($ty,)*) -> EResult,
- $($ty: FromSyscall<'p>,)*
+ $($ty: FromSyscall,)*
{
#[allow(non_snake_case, unused_variables)]
- fn call(self, name: &str, frame: &'p IntFrame) -> EResult {
+ fn call(self, name: &str, frame: &mut IntFrame) -> EResult {
#[cfg(feature = "strace")]
let pid = {
let pid = Process::current().lock().get_pid();
@@ -343,6 +344,30 @@ macro_rules! impl_syscall_handler {
println!("[strace {pid}] -> {res:?}");
res
}
+ }
+
+ // Implementation **with** trailing reference to frame
+ #[allow(unused_parens)]
+ impl SyscallHandler<($($ty,)* &mut IntFrame)> for F
+ where F: FnOnce($($ty,)* &mut IntFrame) -> EResult,
+ $($ty: FromSyscall,)*
+ {
+ #[allow(non_snake_case, unused_variables)]
+ fn call(self, name: &str, frame: &mut IntFrame) -> EResult {
+ #[cfg(feature = "strace")]
+ let pid = {
+ let pid = Process::current().lock().get_pid();
+ print!("[strace {pid}] {name}");
+ pid
+ };
+ $(
+ let $ty = $ty::from_syscall(frame);
+ )*
+ let res = self($($ty,)* frame);
+ #[cfg(feature = "strace")]
+ println!("[strace {pid}] -> {res:?}");
+ res
+ }
}
};
}
@@ -358,39 +383,39 @@ impl_syscall_handler!(T1, T2, T3, T4, T5, T6, T7);
impl_syscall_handler!(T1, T2, T3, T4, T5, T6, T7, T8);
/// Extracts a value from the process that made a system call.
-pub trait FromSyscall<'p> {
+pub trait FromSyscall {
/// Constructs the value from the given process or syscall argument value.
- fn from_syscall(frame: &'p IntFrame) -> Self;
+ fn from_syscall(frame: &IntFrame) -> Self;
}
-impl<'p> FromSyscall<'p> for Arc> {
+impl FromSyscall for Arc> {
#[inline]
- fn from_syscall(_frame: &'p IntFrame) -> Self {
+ fn from_syscall(_frame: &IntFrame) -> Self {
Process::current()
}
}
-impl FromSyscall<'_> for Arc> {
+impl FromSyscall for Arc> {
#[inline]
fn from_syscall(_frame: &IntFrame) -> Self {
Process::current().lock().get_mem_space().unwrap().clone()
}
}
-impl FromSyscall<'_> for Arc> {
+impl FromSyscall for Arc> {
#[inline]
fn from_syscall(_frame: &IntFrame) -> Self {
Process::current().lock().file_descriptors.clone().unwrap()
}
}
-impl FromSyscall<'_> for AccessProfile {
+impl FromSyscall for AccessProfile {
fn from_syscall(_frame: &IntFrame) -> Self {
Process::current().lock().access_profile
}
}
-impl FromSyscall<'_> for ResolutionSettings {
+impl FromSyscall for ResolutionSettings {
fn from_syscall(_frame: &IntFrame) -> Self {
ResolutionSettings::for_process(&Process::current().lock(), true)
}
@@ -399,24 +424,17 @@ impl FromSyscall<'_> for ResolutionSettings {
/// The umask of the process performing the system call.
pub struct Umask(file::Mode);
-impl FromSyscall<'_> for Umask {
+impl FromSyscall for Umask {
fn from_syscall(_frame: &IntFrame) -> Self {
Self(Process::current().lock().umask)
}
}
-impl<'p> FromSyscall<'p> for &'p IntFrame {
- #[inline]
- fn from_syscall(frame: &'p IntFrame) -> Self {
- frame
- }
-}
-
/// System call arguments.
#[derive(Debug)]
pub struct Args(pub T);
-impl FromSyscall<'_> for Args {
+impl FromSyscall for Args {
fn from_syscall(frame: &IntFrame) -> Self {
let arg = T::from_syscall_arg(frame.get_syscall_arg(0));
#[cfg(feature = "strace")]
@@ -427,7 +445,7 @@ impl FromSyscall<'_> for Args {
macro_rules! impl_from_syscall_args {
($($ty:ident),*) => {
- impl<$($ty: FromSyscallArg,)*> FromSyscall<'_> for Args<($($ty,)*)> {
+ impl<$($ty: FromSyscallArg,)*> FromSyscall for Args<($($ty,)*)> {
#[inline]
#[allow(non_snake_case, unused_variables, unused_mut, unused_assignments)]
fn from_syscall(
@@ -497,17 +515,16 @@ impl FromSyscallArg for *mut T {
/// Syscall declaration.
macro_rules! syscall {
- ($name:ident, $frame:expr) => {{
- const NAME: &str = stringify!($name);
- SyscallHandler::call($name, NAME, $frame)
- }};
+ ($name:ident, $frame:expr) => {
+ SyscallHandler::call($name, stringify!($name), $frame)
+ };
}
/// Executes the system call associated with the given `id` and returns its result.
///
/// If the syscall doesn't exist, the function returns `None`.
#[inline]
-fn do_syscall(id: usize, frame: &IntFrame) -> Option> {
+fn do_syscall(id: usize, frame: &mut IntFrame) -> Option> {
match id {
0x001 => Some(syscall!(_exit, frame)),
0x002 => Some(syscall!(fork, frame)),
@@ -971,7 +988,7 @@ pub extern "C" fn syscall_handler(frame: &mut IntFrame) {
}
}
// If the process has been killed, handle it
- process::yield_current(3);
+ process::yield_current(3, frame);
}
extern "C" {
diff --git a/kernel/src/syscall/sigreturn.rs b/kernel/src/syscall/sigreturn.rs
index 1fb64485..5cf574a3 100644
--- a/kernel/src/syscall/sigreturn.rs
+++ b/kernel/src/syscall/sigreturn.rs
@@ -24,7 +24,11 @@
use crate::{
arch::x86::idt::IntFrame,
- process::{mem_space::copy::SyscallPtr, signal::Signal, Process},
+ process::{
+ mem_space::copy::SyscallPtr,
+ signal::{ucontext, Signal},
+ Process,
+ },
syscall::FromSyscallArg,
};
use core::{mem::size_of, ptr};
@@ -35,22 +39,23 @@ use utils::{
lock::{IntMutex, IntMutexGuard},
};
-pub fn sigreturn(frame: &IntFrame) -> EResult {
- // Avoid re-enabling interrupts before context switching
- cli();
- // Retrieve the previous state
- let ctx_ptr = frame.esp as usize - size_of::();
- let ctx_ptr = SyscallPtr::::from_syscall_arg(ctx_ptr);
- let ctx = ctx_ptr.copy_from_user()?.ok_or_else(|| errno!(EFAULT))?;
- {
- let proc_mutex = Process::current();
- let mut proc = proc_mutex.lock();
- // Restores the state of the process before the signal handler
- proc.sigmask = ctx.uc_sigmask;
- }
- // Do not handle the next pending signal here, to prevent signal spamming from completely
- // blocking the process
- unsafe {
- ctx.uc_mcontext.switch(true);
+pub fn sigreturn(frame: &mut IntFrame) -> EResult {
+ let proc_mutex = Process::current();
+ let mut proc = proc_mutex.lock();
+ // Retrieve and restore previous state
+ let ctx_ptr = frame.get_stack_address();
+ if frame.is_32bit() {
+ let ctx = SyscallPtr::::from_syscall_arg(ctx_ptr);
+ let ctx = ctx.copy_from_user()?.ok_or_else(|| errno!(EFAULT))?;
+ ctx.restore_regs(&mut proc, frame);
+ } else {
+ #[cfg(target_arch = "x86_64")]
+ {
+ let ctx = SyscallPtr::::from_syscall_arg(ctx_ptr);
+ let ctx = ctx.copy_from_user()?.ok_or_else(|| errno!(EFAULT))?;
+ ctx.restore_regs(&mut proc, frame);
+ }
}
+ // Do not touch register
+ Ok(frame.get_syscall_id())
}
diff --git a/kernel/src/syscall/vfork.rs b/kernel/src/syscall/vfork.rs
index dbe1706a..d2511a8c 100644
--- a/kernel/src/syscall/vfork.rs
+++ b/kernel/src/syscall/vfork.rs
@@ -31,18 +31,16 @@ use utils::{
ptr::arc::Arc,
};
-pub fn vfork(proc: Arc>, frame: &IntFrame) -> EResult {
+pub fn vfork(proc: Arc>) -> EResult {
let new_pid = {
- let fork_options = ForkOptions {
- vfork: true,
- ..ForkOptions::default()
- };
- let new_mutex = Process::fork(proc, fork_options)?;
- let mut new_proc = new_mutex.lock();
- // Set child's return value to `0`
- let mut frame = frame.clone();
- frame.set_syscall_return(Ok(0));
- new_proc.regs = frame;
+ let new_mutex = Process::fork(
+ proc,
+ ForkOptions {
+ vfork: true,
+ ..ForkOptions::default()
+ },
+ )?;
+ let new_proc = new_mutex.lock();
new_proc.get_pid()
};
// Let another process run instead of the current. Because the current