Compare commits

...

4 Commits

Author SHA1 Message Date
Bananymous 8141b9977d Kernel: Per processor information is now stored in class Processor
This allows us to allocate processor stacks, and other per processor
structures dynamically in runtime. Giving processor stack to
ap_trampoline feels super hacky, but it works for now.
2024-03-03 22:30:06 +02:00
Bananymous c035d3c82c Kernel: Start all processors on kernel boot
Processors don't do anything, except print hello message and halt.
2024-03-03 02:19:43 +02:00
Bananymous 1de9daa40f Kernel: Move interrupt status stuff to Processor.h
SpinLocks are now locked with processor id instead of thread id. This
allows having multiple processors running while scheduler is not yet
activated.
2024-03-03 01:47:22 +02:00
Bananymous efd8203232 BAN: Atomic memory order can be set per function call 2024-03-03 01:41:46 +02:00
21 changed files with 399 additions and 118 deletions

View File

@ -3,7 +3,17 @@
namespace BAN
{
template<typename T, int MEM_ORDER = __ATOMIC_SEQ_CST>
enum MemoryOrder
{
memory_order_relaxed = __ATOMIC_RELAXED,
memory_order_consume = __ATOMIC_CONSUME,
memory_order_acquire = __ATOMIC_ACQUIRE,
memory_order_release = __ATOMIC_RELEASE,
memory_order_acq_rel = __ATOMIC_ACQ_REL,
memory_order_seq_cst = __ATOMIC_SEQ_CST,
};
template<typename T, MemoryOrder MEM_ORDER = MemoryOrder::memory_order_seq_cst>
requires requires { __atomic_always_lock_free(sizeof(T), 0); }
class Atomic
{
@ -16,8 +26,8 @@ namespace BAN
constexpr Atomic() : m_value(0) {}
constexpr Atomic(T val) : m_value(val) {}
inline T load() const volatile { return __atomic_load_n(&m_value, MEM_ORDER); }
inline void store(T val) volatile { __atomic_store_n(&m_value, val, MEM_ORDER); }
inline T load(MemoryOrder mem_order = MEM_ORDER) const volatile { return __atomic_load_n(&m_value, mem_order); }
inline void store(T val, MemoryOrder mem_order = MEM_ORDER) volatile { __atomic_store_n(&m_value, val, mem_order); }
inline T operator=(T val) volatile { store(val); return val; }
@ -35,7 +45,7 @@ namespace BAN
inline T operator--(int) volatile { return __atomic_fetch_sub(&m_value, 1, MEM_ORDER); }
inline T operator++(int) volatile { return __atomic_fetch_add(&m_value, 1, MEM_ORDER); }
inline bool compare_exchange(T expected, T desired) volatile { return __atomic_compare_exchange_n(&m_value, &expected, desired, false, MEM_ORDER, MEM_ORDER); }
inline bool compare_exchange(T expected, T desired, MemoryOrder mem_order = MEM_ORDER) volatile { return __atomic_compare_exchange_n(&m_value, &expected, desired, false, mem_order, mem_order); }
private:
T m_value;

View File

@ -66,6 +66,7 @@ set(KERNEL_SOURCES
kernel/PCI.cpp
kernel/PIC.cpp
kernel/Process.cpp
kernel/Processor.cpp
kernel/Random.cpp
kernel/Scheduler.cpp
kernel/Semaphore.cpp

View File

@ -3,8 +3,6 @@
#include <string.h>
extern "C" uintptr_t g_boot_stack_top[0];
namespace Kernel::GDT
{

View File

@ -306,6 +306,7 @@ namespace Kernel
void PageTable::load()
{
SpinLockGuard _(m_lock);
asm volatile("movq %0, %%cr3" :: "r"(m_highest_paging_struct));
s_current = this;
}

View File

@ -53,12 +53,9 @@ bananboot_start:
bananboot_end:
.section .bss, "aw", @nobits
# Create stack
.global g_boot_stack_bottom
g_boot_stack_bottom:
.skip 16384
.global g_boot_stack_top
g_boot_stack_top:
boot_stack_bottom:
.skip 4096 * 4
boot_stack_top:
.global g_kernel_cmdline
g_kernel_cmdline:
@ -105,6 +102,16 @@ boot_gdtr:
.short . - boot_gdt - 1
.quad V2P(boot_gdt)
.global g_ap_startup_done
g_ap_startup_done:
.byte 0
.global g_ap_running_count
g_ap_running_count:
.byte 0
.global g_ap_stack_loaded
g_ap_stack_loaded:
.byte 0
.section .text
has_cpuid:
@ -151,6 +158,13 @@ enable_sse:
movl %eax, %cr4
ret
initialize_lapic_id:
movl $1, %eax
cpuid
shrl $24, %ebx
movw %bx, %gs
ret
initialize_paging:
# enable PAE
movl %cr4, %ecx
@ -177,11 +191,15 @@ initialize_paging:
.global _start
.type _start, @function
_start:
cli; cld
# Initialize stack and multiboot info
movl $V2P(g_boot_stack_top), %esp
movl %eax, V2P(bootloader_magic)
movl %ebx, V2P(bootloader_info)
movl $V2P(boot_stack_top), %esp
call initialize_lapic_id
call check_requirements
call enable_sse
@ -194,17 +212,15 @@ _start:
.code64
long_mode:
movw $0x10, %ax
movw %ax, %ss
# clear segment registers (unused in x86_64?)
movw $0x00, %ax
movw %ax, %ds
movw %ax, %ss
movw %ax, %es
movw %ax, %fs
movw %ax, %gs
# move stack pointer to higher half
movl %esp, %esp
addq $KERNEL_OFFSET, %rsp
# jump to higher half
movq $g_boot_stack_top, %rsp
movabsq $higher_half, %rcx
jmp *%rcx
@ -227,3 +243,78 @@ system_halt:
cli
1: hlt
jmp 1b
.section .ap_init, "ax"
.code16
.global ap_trampoline
ap_trampoline:
jmp 1f
.align 8
ap_stack_ptr:
.skip 4
1:
cli; cld
ljmpl $0x00, $ap_cs_clear
ap_cs_clear:
xorw %ax, %ax
movw %ax, %ds
# load ap gdt and enter protected mode
lgdt ap_gdtr
movl %cr0, %eax
orb $1, %al
movl %eax, %cr0
ljmpl $0x08, $ap_protected_mode
.code32
ap_protected_mode:
movw $0x10, %ax
movw %ax, %ds
movw %ax, %ss
movw %ax, %es
movl ap_stack_ptr, %esp
movb $1, V2P(g_ap_stack_loaded)
call V2P(initialize_lapic_id)
call V2P(enable_sse)
call V2P(initialize_paging)
# load boot gdt and enter long mode
lgdt V2P(boot_gdtr)
ljmpl $0x08, $ap_long_mode
.code64
ap_long_mode:
# move stack pointer to higher half
movl %esp, %esp
addq $KERNEL_OFFSET, %rsp
# jump to higher half
movabsq $ap_higher_half, %rcx
jmp *%rcx
ap_higher_half:
# clear rbp for stacktrace
xorq %rbp, %rbp
1: pause
cmpb $0, g_ap_startup_done
jz 1b
lock incb g_ap_running_count
call ap_main
jmp system_halt
ap_gdt:
.quad 0x0000000000000000 # null descriptor
.quad 0x00CF9A000000FFFF # 32 bit code
.quad 0x00CF92000000FFFF # 32 bit data
ap_gdtr:
.short . - ap_gdt - 1
.quad ap_gdt

View File

@ -4,6 +4,13 @@ KERNEL_OFFSET = 0xFFFFFFFF80000000;
SECTIONS
{
. = 0xF000;
.ap_init ALIGN(4K) : AT(ADDR(.ap_init))
{
g_ap_init_addr = .;
*(.ap_init)
}
. = 0x00100000 + KERNEL_OFFSET;
g_kernel_start = .;

View File

@ -18,6 +18,8 @@ namespace Kernel
virtual BAN::ErrorOr<void> reserve_irq(uint8_t irq) override;
virtual BAN::Optional<uint8_t> get_free_irq() override;
virtual void initialize_multiprocessor() override;
private:
uint32_t read_from_local_apic(ptrdiff_t);
void write_to_local_apic(ptrdiff_t, uint32_t);

View File

@ -37,6 +37,8 @@ namespace Kernel
static void initialize(bool force_pic);
static InterruptController& get();
virtual void initialize_multiprocessor() = 0;
virtual BAN::ErrorOr<void> reserve_irq(uint8_t irq) = 0;
virtual BAN::Optional<uint8_t> get_free_irq() = 0;

View File

@ -1,37 +0,0 @@
#pragma once
#include <kernel/Arch.h>
namespace Kernel
{
enum class InterruptState
{
Disabled,
Enabled,
};
#if ARCH(x86_64) || ARCH(i386)
inline void set_interrupt_state(InterruptState state)
{
if (state == InterruptState::Enabled)
asm volatile("sti");
else
asm volatile("cli");
}
inline InterruptState get_interrupt_state()
{
uintptr_t flags;
asm volatile("pushf; pop %0" : "=rm"(flags));
if (flags & (1 << 9))
return InterruptState::Enabled;
return InterruptState::Disabled;
}
#else
#error "Unknown architecure"
#endif
}

View File

@ -2,7 +2,7 @@
#include <BAN/Atomic.h>
#include <BAN/NoCopyMove.h>
#include <kernel/Interrupts.h>
#include <kernel/Processor.h>
#include <sys/types.h>
@ -21,7 +21,7 @@ namespace Kernel
void unlock(InterruptState state);
private:
BAN::Atomic<pid_t> m_locker { -1 };
BAN::Atomic<ProcessorID> m_locker { PROCESSOR_NONE };
};
class RecursiveSpinLock
@ -36,8 +36,8 @@ namespace Kernel
void unlock(InterruptState state);
private:
BAN::Atomic<pid_t> m_locker { -1 };
uint32_t m_lock_depth { 0 };
BAN::Atomic<ProcessorID> m_locker { PROCESSOR_NONE };
uint32_t m_lock_depth { 0 };
};
class SpinLockUnsafe
@ -50,10 +50,12 @@ namespace Kernel
InterruptState lock()
{
auto state = get_interrupt_state();
set_interrupt_state(InterruptState::Disabled);
auto id = Processor::current_id();
while (!m_locked.compare_exchange(false, true))
auto state = Processor::get_interrupt_state();
Processor::set_interrupt_state(InterruptState::Disabled);
while (!m_locker.compare_exchange(PROCESSOR_NONE, id, BAN::MemoryOrder::memory_order_acquire))
__builtin_ia32_pause();
return state;
@ -61,14 +63,14 @@ namespace Kernel
void unlock(InterruptState state)
{
m_locked.store(false);
set_interrupt_state(state);
m_locker.store(PROCESSOR_NONE, BAN::MemoryOrder::memory_order_release);
Processor::set_interrupt_state(state);
}
bool is_locked() const { return m_locked; }
bool is_locked() const { return m_locker != PROCESSOR_NONE; }
private:
BAN::Atomic<bool> m_locked;
BAN::Atomic<ProcessorID> m_locker { PROCESSOR_NONE };
};
template<typename Lock>

View File

@ -16,6 +16,8 @@ namespace Kernel
virtual BAN::ErrorOr<void> reserve_irq(uint8_t irq) override;
virtual BAN::Optional<uint8_t> get_free_irq() override;
virtual void initialize_multiprocessor() override;
static void remap();
static void mask_all();

View File

@ -0,0 +1,76 @@
#pragma once
#include <BAN/ForwardList.h>
#include <kernel/Arch.h>
namespace Kernel
{
enum class InterruptState
{
Disabled,
Enabled,
};
using ProcessorID = uint8_t;
constexpr ProcessorID PROCESSOR_NONE = 0xFF;
#if ARCH(x86_64)
class Processor
{
BAN_NON_COPYABLE(Processor);
public:
static Processor& create(ProcessorID id);
static ProcessorID current_id()
{
uint16_t id;
asm volatile("movw %%gs, %0" : "=rm"(id));
return id;
}
static Processor& get(ProcessorID);
static Processor& current() { return get(current_id()); }
static void set_interrupt_state(InterruptState state)
{
if (state == InterruptState::Enabled)
asm volatile("sti");
else
asm volatile("cli");
}
static InterruptState get_interrupt_state()
{
uintptr_t flags;
asm volatile("pushf; pop %0" : "=rm"(flags));
if (flags & (1 << 9))
return InterruptState::Enabled;
return InterruptState::Disabled;
};
uintptr_t stack_bottom() const { return reinterpret_cast<uintptr_t>(m_stack); }
uintptr_t stack_top() const { return stack_bottom() + m_stack_size; }
private:
Processor() = default;
Processor(Processor&& other)
{
m_stack = other.m_stack;
other.m_stack = nullptr;
}
~Processor();
private:
void* m_stack { nullptr };
static constexpr size_t m_stack_size { 4096 };
friend class BAN::Vector<Processor>;
};
#else
#error
#endif
}

View File

@ -6,20 +6,28 @@
#include <kernel/IDT.h>
#include <kernel/Memory/PageTable.h>
#include <kernel/MMIO.h>
#include <kernel/Timer/Timer.h>
#include <string.h>
#define LAPIC_EIO_REG 0xB0
#define LAPIC_SIV_REG 0xF0
#define LAPIC_IS_REG 0x100
#define LAPIC_ERROR_REG 0x280
#define LAPIC_ICR_LO_REG 0x300
#define LAPIC_ICR_HI_REG 0x310
#define IOAPIC_MAX_REDIRS 0x01
#define IOAPIC_REDIRS 0x10
#define DEBUG_PRINT_PROCESSORS 0
// https://uefi.org/specs/ACPI/6.5/05_ACPI_Software_Programming_Model.html#multiple-apic-description-table-madt-format
extern uint8_t g_ap_init_addr[];
extern volatile uint8_t g_ap_startup_done[];
extern volatile uint8_t g_ap_running_count[];
extern volatile uint8_t g_ap_stack_loaded[];
namespace Kernel
{
@ -182,18 +190,76 @@ namespace Kernel
uint32_t sivr = apic->read_from_local_apic(LAPIC_SIV_REG);
apic->write_to_local_apic(LAPIC_SIV_REG, sivr | 0x1FF);
#if DEBUG_PRINT_PROCESSORS
for (auto& processor : apic->m_processors)
{
dprintln("Processor{}", processor.processor_id);
dprintln(" lapic id: {}", processor.apic_id);
dprintln(" status: {}", (processor.flags & Processor::Flags::Enabled) ? "enabled" : (processor.flags & Processor::Flags::OnlineCapable) ? "can be enabled" : "disabled");
}
#endif
return apic;
}
void APIC::initialize_multiprocessor()
{
constexpr auto udelay =
[](uint64_t us) {
uint64_t wake_time = SystemTimer::get().ns_since_boot() + us * 1000;
while (SystemTimer::get().ns_since_boot() < wake_time)
__builtin_ia32_pause();
};
const auto send_ipi =
[&](uint8_t processor, uint32_t data, uint64_t ud)
{
write_to_local_apic(LAPIC_ICR_HI_REG, (read_from_local_apic(LAPIC_ICR_HI_REG) & 0x00FFFFFF) | (processor << 24));
write_to_local_apic(LAPIC_ICR_LO_REG, data);
udelay(ud);
while (read_from_local_apic(LAPIC_ICR_LO_REG) & (1 << 12))
__builtin_ia32_pause();
};
const size_t ap_init_page = reinterpret_cast<vaddr_t>(g_ap_init_addr) / PAGE_SIZE;
dprintln("System has {} processors", m_processors.size());
uint8_t bsp_id = Kernel::Processor::current_id();
dprintln("BSP lapic id: {}", bsp_id);
for (auto& processor : m_processors)
{
if (processor.apic_id == bsp_id)
continue;
if (!(processor.flags & (Processor::Flags::Enabled | Processor::Flags::OnlineCapable)))
{
dwarnln("Skipping processor (lapic id {}) initialization", processor.apic_id);
continue;
}
dprintln("Trying to enable processor (lapic id {})", processor.apic_id);
Kernel::Processor::create(processor.processor_id);
PageTable::with_fast_page((paddr_t)g_ap_init_addr, [&] {
PageTable::fast_page_as_sized<uint32_t>(2) = V2P(Kernel::Processor::get(processor.processor_id).stack_top());
});
*g_ap_stack_loaded = 0;
write_to_local_apic(LAPIC_ERROR_REG, 0x00);
send_ipi(processor.processor_id, (read_from_local_apic(LAPIC_ICR_LO_REG) & 0xFFF00000) | 0x0000C500, 0);
send_ipi(processor.processor_id, (read_from_local_apic(LAPIC_ICR_LO_REG) & 0xFFF0F800) | 0x00008500, 0);
udelay(10 * 1000);
for (int i = 0; i < 2; i++)
{
write_to_local_apic(LAPIC_ERROR_REG, 0x00);
send_ipi(processor.processor_id, (read_from_local_apic(LAPIC_ICR_LO_REG) & 0xFFF0F800) | 0x00000600 | ap_init_page, 200);
}
// give processor upto 100 * 100 us (10 ms to boot)
for (int i = 0; *g_ap_stack_loaded == 0 && i < 100; i++)
udelay(100);
}
*g_ap_startup_done = 1;
dprintln("{} processors started", *g_ap_running_count);
}
uint32_t APIC::read_from_local_apic(ptrdiff_t offset)
{
return MMIO::read32(m_local_apic_vaddr + offset);

View File

@ -9,38 +9,38 @@ namespace Kernel
InterruptState SpinLock::lock()
{
auto tid = Scheduler::current_tid();
ASSERT_NEQ(m_locker.load(), tid);
auto id = Processor::current_id();
ASSERT_NEQ(m_locker.load(), id);
auto state = get_interrupt_state();
set_interrupt_state(InterruptState::Disabled);
auto state = Processor::get_interrupt_state();
Processor::set_interrupt_state(InterruptState::Disabled);
if (!m_locker.compare_exchange(-1, tid))
ASSERT_NOT_REACHED();
while (!m_locker.compare_exchange(PROCESSOR_NONE, id, BAN::MemoryOrder::memory_order_acquire))
__builtin_ia32_pause();
return state;
}
void SpinLock::unlock(InterruptState state)
{
ASSERT_EQ(m_locker.load(), Scheduler::current_tid());
m_locker.store(-1);
set_interrupt_state(state);
ASSERT_EQ(m_locker.load(), Processor::current_id());
m_locker.store(PROCESSOR_NONE, BAN::MemoryOrder::memory_order_release);
Processor::set_interrupt_state(state);
}
InterruptState RecursiveSpinLock::lock()
{
auto tid = Scheduler::current_tid();
auto id = Processor::current_id();
auto state = get_interrupt_state();
set_interrupt_state(InterruptState::Disabled);
auto state = Processor::get_interrupt_state();
Processor::set_interrupt_state(InterruptState::Disabled);
if (tid == m_locker)
if (id == m_locker)
ASSERT_GT(m_lock_depth, 0);
else
{
if (!m_locker.compare_exchange(-1, tid))
ASSERT_NOT_REACHED();
while (!m_locker.compare_exchange(PROCESSOR_NONE, id, BAN::MemoryOrder::memory_order_acquire))
__builtin_ia32_pause();
ASSERT_EQ(m_lock_depth, 0);
}
@ -51,12 +51,11 @@ namespace Kernel
void RecursiveSpinLock::unlock(InterruptState state)
{
auto tid = Scheduler::current_tid();
ASSERT_EQ(m_locker.load(), tid);
ASSERT_EQ(m_locker.load(), Processor::current_id());
ASSERT_GT(m_lock_depth, 0);
if (--m_lock_depth == 0)
m_locker = -1;
set_interrupt_state(state);
m_locker.store(PROCESSOR_NONE, BAN::MemoryOrder::memory_order_release);
Processor::set_interrupt_state(state);
}
}

View File

@ -75,6 +75,11 @@ struct kmalloc_info
return nullptr;
}
bool contains(uintptr_t addr) const
{
return base <= addr && addr < end;
}
size_t used = 0;
size_t free = size;
};
@ -161,8 +166,17 @@ static bool is_corrupted()
Kernel::SpinLockGuard _(s_kmalloc_lock);
auto& info = s_kmalloc_info;
auto* temp = info.first();
for (; temp->end() <= info.end; temp = temp->after());
return (uintptr_t)temp != info.end;
while (reinterpret_cast<uintptr_t>(temp) != info.end)
{
if (!info.contains(reinterpret_cast<uintptr_t>(temp)))
return true;
if (!info.contains(temp->end() - 1))
return true;
if (temp->after() <= temp)
return true;
temp = temp->after();
}
return false;
}
[[maybe_unused]] static void debug_dump()
@ -235,12 +249,12 @@ static void* kmalloc_impl(size_t size, size_t align)
auto& info = s_kmalloc_info;
for (auto* node = info.first(); node->end() <= info.end; node = node->after())
for (auto* node = info.first(); info.contains(reinterpret_cast<uintptr_t>(node)); node = node->after())
{
if (node->used())
continue;
if (auto* next = node->after(); next->end() <= info.end)
if (auto* next = node->after(); info.contains(reinterpret_cast<uintptr_t>(next)))
if (!next->used())
node->set_end(next->end());

View File

@ -134,4 +134,9 @@ namespace Kernel
return IO::inb(port) & (1 << irq);
}
void PIC::initialize_multiprocessor()
{
dprintln("Only single processor supported with PIC");
}
}

View File

@ -220,7 +220,7 @@ namespace Kernel
void Process::on_thread_exit(Thread& thread)
{
ASSERT(get_interrupt_state() == InterruptState::Disabled);
ASSERT(Processor::get_interrupt_state() == InterruptState::Disabled);
ASSERT(m_threads.size() > 0);

View File

@ -0,0 +1,34 @@
#include <BAN/Vector.h>
#include <kernel/Processor.h>
namespace Kernel
{
static BAN::Vector<Processor> s_processors;
Processor& Processor::create(ProcessorID id)
{
while (s_processors.size() <= id)
MUST(s_processors.emplace_back());
auto& processor = s_processors[id];
if (processor.m_stack == nullptr)
{
processor.m_stack = kmalloc(m_stack_size, 4096, true);
ASSERT(processor.m_stack);
}
return processor;
}
Processor::~Processor()
{
if (m_stack)
kfree(m_stack);
m_stack = nullptr;
}
Processor& Processor::get(ProcessorID id)
{
return s_processors[id];
}
}

View File

@ -16,10 +16,9 @@ namespace Kernel
static Scheduler* s_instance = nullptr;
static uint8_t s_temp_stack[1024];
ALWAYS_INLINE static void load_temp_stack()
{
asm volatile("movq %0, %%rsp" :: "r"(s_temp_stack + sizeof(s_temp_stack)));
asm volatile("movq %0, %%rsp" :: "rm"(Processor::current().stack_top()));
}
BAN::ErrorOr<void> Scheduler::initialize()
@ -40,7 +39,7 @@ namespace Kernel
void Scheduler::start()
{
ASSERT(get_interrupt_state() == InterruptState::Disabled);
ASSERT(Processor::get_interrupt_state() == InterruptState::Disabled);
m_lock.lock();
ASSERT(!m_active_threads.empty());
m_current_thread = m_active_threads.begin();
@ -75,7 +74,7 @@ namespace Kernel
{
auto state = m_lock.lock();
if (save_current_thread())
return set_interrupt_state(state);
return Processor::set_interrupt_state(state);
advance_current_thread();
execute_current_thread_locked();
ASSERT_NOT_REACHED();
@ -210,6 +209,7 @@ namespace Kernel
void Scheduler::execute_current_thread_locked()
{
ASSERT(m_lock.is_locked());
load_temp_stack();
PageTable::kernel().load();
execute_current_thread_stack_loaded();
@ -220,13 +220,10 @@ namespace Kernel
{
ASSERT(m_lock.is_locked());
load_temp_stack();
PageTable::kernel().load();
#if SCHEDULER_VERIFY_STACK
vaddr_t rsp;
read_rsp(rsp);
ASSERT((vaddr_t)s_temp_stack <= rsp && rsp <= (vaddr_t)s_temp_stack + sizeof(s_temp_stack));
ASSERT(Processor::current().stack_bottom() <= rsp && rsp <= Processor::current().stack_top());
ASSERT(&PageTable::current() == &PageTable::kernel());
#endif
@ -287,10 +284,7 @@ namespace Kernel
ASSERT(m_lock.is_locked());
if (save_current_thread())
{
set_interrupt_state(InterruptState::Enabled);
return;
}
auto it = m_sleeping_threads.begin();
for (; it != m_sleeping_threads.end(); it++)

View File

@ -19,12 +19,13 @@
#include <kernel/PCI.h>
#include <kernel/PIC.h>
#include <kernel/Process.h>
#include <kernel/Processor.h>
#include <kernel/Random.h>
#include <kernel/Scheduler.h>
#include <kernel/Syscall.h>
#include <kernel/Terminal/FramebufferTerminal.h>
#include <kernel/Terminal/Serial.h>
#include <kernel/Terminal/VirtualTTY.h>
#include <kernel/Terminal/FramebufferTerminal.h>
#include <kernel/Timer/Timer.h>
struct ParsedCommandLine
@ -82,8 +83,6 @@ extern "C" void kernel_main(uint32_t boot_magic, uint32_t boot_info)
{
using namespace Kernel;
set_interrupt_state(InterruptState::Disabled);
if (!validate_boot_magic(boot_magic))
{
Serial::initialize();
@ -103,6 +102,9 @@ extern "C" void kernel_main(uint32_t boot_magic, uint32_t boot_info)
parse_boot_info(boot_magic, boot_info);
dprintln("boot info parsed");
Processor::create(Processor::current_id());
dprintln("BSP initialized");
GDT::initialize();
dprintln("GDT initialized");
@ -127,6 +129,8 @@ extern "C" void kernel_main(uint32_t boot_magic, uint32_t boot_info)
SystemTimer::initialize(cmdline.force_pic);
dprintln("Timers initialized");
InterruptController::get().initialize_multiprocessor();
DevFileSystem::initialize();
dprintln("devfs initialized");
@ -206,3 +210,13 @@ static void init2(void*)
MUST(Process::create_userspace({ 0, 0, 0, 0 }, "/usr/bin/init"sv));
}
extern "C" void ap_main()
{
using namespace Kernel;
dprintln("hello from processor {}", Processor::current_id());
for (;;)
asm volatile("");
}

View File

@ -21,7 +21,7 @@ fi
qemu-system-$BANAN_ARCH \
-m 1G \
-smp 2 \
-smp 4 \
$BIOS_ARGS \
-drive format=raw,id=disk,file=${BANAN_DISK_IMAGE_PATH},if=none \
-device e1000e,netdev=net \