Magic‐1 Emulator Technical Information (no GUI version) - retrotruestory/M1DEV GitHub Wiki

Magic-1 Emulator Technical Information - Part 1: Core System Organization

File Structure

magic1-emu/
├── src/
│   ├── core/
│   │   ├── cpu.h
│   │   ├── mmu.h
│   │   └── bus.h
│   ├── devices/
│   │   ├── uart.h
│   │   ├── rtc.h
│   │   └── cf_card.h
│   └── memory/
│       ├── rom.h
│       └── ram.h
├── microcode/
│   ├── prom0.hex
│   ├── prom1.hex
│   ├── prom2.hex
│   ├── prom3.hex
│   └── prom4.hex
└── boot/
    └── bootloader.bin

Core CPU Definition

typedef struct {
    // Core Registers
    uint16_t msw;          // Machine Status Word
    uint16_t pc;           // Program Counter
    uint16_t sp;           // Stack Pointer
    uint16_t dp;           // Data Pointer
    uint16_t a;            // Accumulator
    uint16_t b;            // General Purpose
    uint16_t c;            // General Purpose
    uint16_t mdr;          // Memory Data Register
    
    // Internal State
    uint8_t mode;          // Operating Mode
    bool interrupt_enable;
    bool waiting;
    
    // Microcode State
    uint16_t micro_pc;     // Microcode Program Counter
    uint64_t micro_ir;     // Current Microinstruction
    
    // Bus Interface
    uint16_t address_bus;
    uint16_t data_bus;
    uint8_t control_bus;
} magic1_cpu_t;

Memory Management Unit

typedef struct {
    uint16_t page_table_base;
    bool paging_enabled;
    
    // Page Table Entry Format
    struct {
        uint16_t present:1;
        uint16_t writable:1;
        uint16_t user:1;
        uint16_t device:1;
        uint16_t frame:12;
    } pte_t;
    
    // TLB Entry
    struct tlb_entry {
        uint16_t virtual_page;
        uint16_t physical_frame;
        uint8_t flags;
        bool valid;
    } tlb[16];
} magic1_mmu_t;

System Bus Interface

typedef struct {
    // Memory Map
    uint8_t *rom;          // 0x0000-0x3FFF
    uint8_t *device_sram;  // 0x4000-0x7FFF
    uint8_t *main_memory;  // 0x8000-0xF7FF
    uint8_t *device_page;  // 0xF800-0xFFFF
    
    // Bus Control
    uint16_t address;
    uint16_t data;
    bool read_strobe;
    bool write_strobe;
    bool io_request;
    bool memory_request;
    
    // Device Select
    uint8_t device_select;
} magic1_bus_t;

Type 'next' to continue with Part 2: Microcode Loading and Interpretation.

Magic-1 Emulator Technical Information - Part 2: Microcode System

Microcode Loader Module

#pragma once

typedef struct {
    uint64_t instruction[512];  // 56-bit microinstructions stored in 64-bit words
    uint16_t current_address;   // Current microcode address
} microcode_rom_t;

typedef struct {
    uint8_t prom0[512];  // Next address field
    uint8_t prom1[512];  // Control bits 1
    uint8_t prom2[512];  // Control bits 2
    uint8_t prom3[512];  // Control bits 3
    uint8_t prom4[512];  // Control bits 4
} microcode_proms_t;

Microcode Control Implementation

#pragma once

// Microinstruction fields
typedef struct {
    uint8_t  next;         // Next microinstruction address
    uint8_t  latch;        // Register latch control
    uint8_t  mar_control;  // Memory address register control
    uint8_t  mdr_control;  // Memory data register control
    uint8_t  bus_control;  // Bus control signals
    uint8_t  alu_op;      // ALU operation
    uint8_t  misc;        // Miscellaneous control
} decoded_microinst_t;

class MicrocodeController {
private:
    microcode_rom_t rom;
    decoded_microinst_t current_instruction;
    
public:
    // Load microcode from PROM files
    bool load_microcode(const char* prom_files[5]);
    
    // Fetch and decode next microinstruction
    decoded_microinst_t fetch();
    
    // Execute current microinstruction
    void execute(magic1_cpu_t* cpu);
};

Microcode Loading Functions

#include "microcode_loader.h"

bool load_prom_file(const char* filename, uint8_t* buffer, size_t size) {
    FILE* fp = fopen(filename, "rb");
    if (!fp) return false;
    
    // Read Intel HEX format
    char line[256];
    uint16_t address = 0;
    
    while (fgets(line, sizeof(line), fp)) {
        if (line[0] != ':') continue;
        
        // Parse HEX record
        uint8_t length = hex_to_byte(line + 1);
        uint16_t addr = (hex_to_byte(line + 3) << 8) | hex_to_byte(line + 5);
        uint8_t type = hex_to_byte(line + 7);
        
        if (type == 0) {  // Data record
            for (int i = 0; i < length; i++) {
                buffer[addr + i] = hex_to_byte(line + 9 + i*2);
            }
        }
    }
    
    fclose(fp);
    return true;
}

// Main microcode loading function
bool load_microcode(microcode_rom_t* rom, const char* prom_files[5]) {
    microcode_proms_t proms;
    
    // Load all PROM files
    for (int i = 0; i < 5; i++) {
        if (!load_prom_file(prom_files[i], 
            ((uint8_t*)&proms) + i*512, 512)) {
            return false;
        }
    }
    
    // Combine PROM contents into 56-bit microinstructions
    for (int i = 0; i < 512; i++) {
        rom->instruction[i] = combine_prom_bytes(&proms, i);
    }
    
    return true;
}

To test the microcode loading in VS Code's integrated terminal:

cd src/core
g++ -o test_microcode test_microcode.cpp microcode_loader.cpp
./test_microcode ../../microcode/prom*.hex

Magic-1 Emulator Technical Information - Part 3: Memory Management and Address Translation

Memory Manager Implementation

#pragma once

struct PageTableEntry {
    uint16_t frame_number : 12;
    uint16_t device      : 1;
    uint16_t user        : 1;
    uint16_t writable    : 1;
    uint16_t present     : 1;
};

class MemoryManager {
private:
    uint8_t* physical_memory[64];  // 64 x 2KB pages
    PageTableEntry* page_tables;
    bool paging_enabled;

public:
    static constexpr uint32_t PAGE_SIZE = 2048;     // 2KB pages
    static constexpr uint32_t NUM_PAGES = 64;       // 128KB total
    static constexpr uint32_t DEVICE_PAGE = 0xF8;   // Device page number
};

Address Translation Module

#pragma once

class AddressTranslator {
private:
    struct TLBEntry {
        uint16_t virtual_page;
        uint16_t physical_frame;
        uint8_t flags;
        bool valid;
    } tlb[16];

public:
    uint32_t translate_address(uint16_t virtual_addr, bool is_write, bool is_user) {
        uint16_t page = virtual_addr >> 11;     // Top 5 bits
        uint16_t offset = virtual_addr & 0x7FF; // Bottom 11 bits

        // Check TLB first
        for (int i = 0; i < 16; i++) {
            if (tlb[i].valid && tlb[i].virtual_page == page) {
                return (tlb[i].physical_frame << 11) | offset;
            }
        }

        // TLB miss - do full page table walk
        return page_table_walk(page, offset, is_write, is_user);
    }
};

Memory Access Controller

#pragma once

class MemoryController {
private:
    MemoryManager* mem_mgr;
    AddressTranslator* translator;

    // Memory regions
    uint8_t* rom;          // 0x0000-0x3FFF
    uint8_t* device_sram;  // 0x4000-0x7FFF
    uint8_t* main_ram;     // 0x8000-0xF7FF
    uint8_t* device_page;  // 0xF800-0xFFFF

public:
    uint16_t read_word(uint16_t addr, bool is_user) {
        uint32_t phys_addr = translator->translate_address(addr, false, is_user);
        
        // Check memory region
        if (phys_addr < 0x4000)
            return read_rom(phys_addr);
        else if (phys_addr >= 0xF800)
            return read_device(phys_addr);
        else
            return read_ram(phys_addr);
    }

    void write_word(uint16_t addr, uint16_t data, bool is_user) {
        uint32_t phys_addr = translator->translate_address(addr, true, is_user);
        
        if (phys_addr >= 0xF800)
            write_device(phys_addr, data);
        else if (phys_addr >= 0x4000)
            write_ram(phys_addr, data);
        // ROM writes are ignored
    }
};

To test memory management in VS Code:

cd src/memory
g++ -o test_mmu test_mmu.cpp memory_manager.cpp address_translator.cpp memory_controller.cpp
./test_mmu

Magic-1 Emulator Technical Information - Part 4: Device Emulation Layer

UART Device Implementation

#include <queue>
#include <cstdint>

class UART {
private:
    // UART Registers
    struct {
        uint8_t data;          // Data register
        uint8_t int_enable;    // Interrupt enable
        uint8_t fifo_ctrl;     // FIFO control
        uint8_t line_ctrl;     // Line control
        uint8_t modem_ctrl;    // Modem control
        uint8_t line_status;   // Line status
        uint8_t modem_status;  // Modem status
    } regs;

    std::queue<uint8_t> rx_fifo;
    std::queue<uint8_t> tx_fifo;

public:
    // UART Status Bits
    static const uint8_t LSR_DR   = 0x01;  // Data Ready
    static const uint8_t LSR_THRE = 0x20;  // TX Holding Register Empty
    static const uint8_t LSR_TEMT = 0x40;  // TX Empty
};

Real-Time Clock Emulation

class RTC {
private:
    uint8_t control;       // Control register
    uint8_t data;         // Data register
    uint32_t ticks;       // Clock ticks
    bool interrupt_flag;   // Interrupt pending

public:
    void update(uint32_t cycles) {
        ticks += cycles;
        if (ticks >= TICKS_PER_INTERRUPT) {
            interrupt_flag = true;
            ticks = 0;
        }
    }

    uint8_t read_register(uint16_t addr) {
        switch(addr & 0x01) {
            case 0: return control;
            case 1: 
                interrupt_flag = false;
                return data;
            default: return 0;
        }
    }
};

CF Card Interface

class CFCard {
private:
    // CF Card Registers
    struct {
        uint8_t data;          // Data register
        uint8_t error;         // Error register
        uint8_t sector_count;  // Sector count
        uint8_t lba[4];        // LBA 0-3
        uint8_t command;       // Command register
        uint8_t status;        // Status register
    } regs;

    // Internal state
    std::vector<uint8_t> storage;  // CF card contents
    bool busy;                     // Busy status
    uint32_t current_sector;       // Current sector being accessed

public:
    bool load_image(const char* filename) {
        FILE* fp = fopen(filename, "rb");
        if (!fp) return false;
        
        storage.resize(128 * 1024 * 1024);  // 128MB
        size_t bytes = fread(storage.data(), 1, storage.size(), fp);
        fclose(fp);
        return bytes > 0;
    }
};

Test the device emulation in VS Code's integrated terminal:

cd src/devices
g++ -o test_devices test_devices.cpp uart.cpp rtc.cpp cf_card.cpp
./test_devices

Magic-1 Emulator Technical Information - Part 5: CPU Core Implementation

Core CPU Class Definition

#pragma once

class Magic1CPU {
private:
    // Core Registers
    struct {
        uint16_t msw;          // Machine Status Word
        uint16_t pc;           // Program Counter
        uint16_t sp;           // Stack Pointer
        uint16_t dp;           // Data Pointer
        uint16_t a;            // Accumulator
        uint16_t b;            // General Purpose
        uint16_t c;            // General Purpose
        uint16_t mdr;          // Memory Data Register
        uint16_t mar;          // Memory Address Register
        uint16_t ptb;          // Page Table Base
    } regs;

    // ALU Unit
    struct {
        uint16_t result;
        bool carry;
        bool zero;
        bool negative;
        bool overflow;
    } alu;

    // Microcode State
    struct {
        uint16_t pc;           // Microcode Program Counter
        uint64_t ir;           // Current Microinstruction
        bool executing;        // Microcode executing flag
    } microcode;

    // System State
    bool interrupt_pending;
    uint8_t current_mode;      // User/Kernel mode
    bool halted;
};

ALU Implementation

class ALU {
public:
    enum Operation {
        ADD = 0,
        SUB = 1,
        AND = 2,
        OR  = 3,
        XOR = 4,
        SHL = 5,
        SHR = 6,
        ASR = 7
    };

    struct Result {
        uint16_t value;
        bool carry;
        bool zero;
        bool negative;
        bool overflow;
    };

    Result execute(Operation op, uint16_t a, uint16_t b, bool carry_in) {
        Result r;
        switch(op) {
            case ADD:
                r = add(a, b, carry_in);
                break;
            case SUB:
                r = subtract(a, b, carry_in);
                break;
            // ...implement other operations...
        }
        return r;
    }
};

Instruction Execution

class InstructionExecutor {
public:
    void execute_cycle() {
        // Fetch phase
        uint16_t opcode = fetch();
        
        // Decode phase
        decode(opcode);
        
        // Execute phase - controlled by microcode
        while(microcode.executing) {
            execute_microinstruction();
        }
        
        // Check interrupts
        if (interrupt_pending && (regs.msw & MSW_INT_ENABLE)) {
            handle_interrupt();
        }
    }

private:
    uint16_t fetch() {
        uint16_t instr = memory->read_word(regs.pc);
        regs.pc += 2;
        return instr;
    }
};

To test the CPU implementation:

cd src/core
g++ -o test_cpu test_cpu.cpp cpu.cpp alu.cpp instruction.cpp
./test_cpu

Check the test output in VS Code's integrated terminal.

Magic-1 Emulator Technical Information - Part 6: System Bus and Memory Interface

System Bus Controller

The bus controller manages all data transfers between CPU, memory and devices.

class SystemBus {
    // Bus signals
    struct BusSignals {
        uint16_t address;      // Address lines
        uint16_t data;         // Data lines
        bool read;             // Read strobe
        bool write;            // Write strobe
        bool memreq;           // Memory request
        bool ioreq;            // I/O request
        bool wait;             // Wait state
    } signals;

    // Device select decoding
    enum DeviceSelect {
        SEL_ROM     = 0x00,   // 0x0000-0x3FFF
        SEL_SRAM    = 0x40,   // 0x4000-0x7FFF
        SEL_RAM     = 0x80,   // 0x8000-0xF7FF
        SEL_DEVICES = 0xF8    // 0xF800-0xFFFF
    };

    // Connected devices
    std::vector<Device*> devices;
    MemoryController* memory;
};

Memory Interface

Memory controller implementing the Magic-1 memory map:

class MemoryController {
private:
    // Memory regions
    struct MemoryMap {
        uint8_t* rom;          // 16KB ROM
        uint8_t* device_sram;  // 16KB Device SRAM
        uint8_t* main_ram;     // Main Memory
        uint8_t* device_page;  // Device Page
    } memory;

    // Memory timing
    struct Timing {
        int rom_wait_states;
        int sram_wait_states;
        int ram_wait_states;
        int device_wait_states;
    } timing;

public:
    // Memory access methods
    uint16_t read_word(uint16_t address) {
        switch(get_region(address)) {
            case SEL_ROM:
                return read_rom(address);
            case SEL_SRAM:
                return read_sram(address);
            case SEL_RAM:
                return read_ram(address);
            case SEL_DEVICES:
                return read_device(address);
            default:
                return 0xFFFF;
        }
    }
};

Device Interface Base Class

class Device {
public:
    virtual uint16_t read(uint16_t address) = 0;
    virtual void write(uint16_t address, uint16_t data) = 0;
    virtual void reset() = 0;
    virtual void update(uint32_t cycles) = 0;
    virtual bool interrupt_pending() = 0;
    
protected:
    uint16_t base_address;
    uint16_t address_mask;
    bool interrupt_enable;
};

Test the bus and memory system using VS Code's integrated terminal:

cd /src/bus
g++ -o test_bus test_bus.cpp system_bus.cpp ../memory/memory_controller.cpp
./test_bus

Magic-1 Emulator Technical Information - Part 7: Bootloader and System Initialization

Bootloader Handler

Creates a bootloader manager to handle loading and execution of the original Magic-1 bootloader:

class BootloaderManager {
private:
    static constexpr uint16_t BOOT_START = 0x0000;
    static constexpr uint16_t BOOT_SIZE = 0x4000;
    static constexpr uint16_t STACK_START = 0x8000;

    uint8_t* boot_rom;
    Magic1CPU* cpu;
    MemoryController* memory;

public:
    bool load_bootloader(const char* filename) {
        FILE* fp = fopen(filename, "rb");
        if (!fp) return false;

        boot_rom = new uint8_t[BOOT_SIZE];
        size_t bytes = fread(boot_rom, 1, BOOT_SIZE, fp);
        fclose(fp);

        if (bytes != BOOT_SIZE) {
            delete[] boot_rom;
            return false;
        }

        // Copy bootloader to ROM area
        memory->write_block(BOOT_START, boot_rom, BOOT_SIZE);
        return true;
    }

    void initialize_system() {
        // Set initial CPU state
        cpu->reset();
        cpu->write_register(REG_PC, BOOT_START);
        cpu->write_register(REG_SP, STACK_START);
        cpu->write_register(REG_MSW, 0x0000); // Kernel mode, interrupts off

        // Initialize devices
        memory->reset();
        // Start execution
        cpu->run();
    }
};

System State Manager

Manages the overall system initialization state:

class SystemState {
private:
    struct {
        bool rom_loaded;
        bool microcode_loaded;
        bool cf_image_loaded;
        bool system_initialized;
    } state_flags;

    Magic1CPU* cpu;
    MemoryController* memory;
    BootloaderManager* bootloader;
    std::vector<Device*> devices;

public:
    bool initialize_system() {
        if (!load_required_files()) {
            return false;
        }

        // Initialize hardware components
        initialize_memory();
        initialize_devices();
        
        // Load bootloader
        bootloader->load_bootloader("bootloader.bin");
        
        // Start system
        bootloader->initialize_system();
        return true;
    }

    bool load_required_files() {
        const char* prom_files[5] = {
            "prom0.hex", "prom1.hex", "prom2.hex",
            "prom3.hex", "prom4.hex"
        };
        
        if (!load_microcode(prom_files)) {
            return false;
        }

        if (!load_cf_image("system.img")) {
            return false;
        }

        return true;
    }
};

Test the bootloader initialization in VS Code's integrated terminal:

cd src/boot
g++ -o test_boot test_boot.cpp bootloader.cpp ../core/system_state.cpp
./test_boot

Magic-1 Emulator Technical Information - Part 8: Interrupt Handling System

Interrupt Controller Implementation

class InterruptController {
private:
    static constexpr uint8_t NUM_INTERRUPTS = 8;
    
    struct InterruptVector {
        uint16_t address;      // Interrupt vector address
        uint8_t priority;      // Interrupt priority level
        bool pending;          // Interrupt pending flag
        bool enabled;          // Interrupt enable flag
    };
    
    InterruptVector vectors[NUM_INTERRUPTS] = {
        {0x0000, 5, false, false},  // IRQ5 (RTC)
        {0x0002, 4, false, false},  // IRQ4
        {0x0004, 3, false, false},  // IRQ3 (UART0)
        {0x0006, 2, false, false},  // IRQ2 (UART1)
        {0x0008, 1, false, false},  // IRQ1 (IDE)
        {0x000A, 0, false, false},  // IRQ0
        {0x000C, 6, false, false},  // DMA
        {0x000E, 7, false, false}   // SYSCALL
    };

Interrupt Handler

class InterruptHandler {
private:
    InterruptController* int_ctrl;
    Magic1CPU* cpu;
    
    void handle_interrupt(uint8_t vector) {
        // Save current state
        uint16_t saved_msw = cpu->read_register(REG_MSW);
        uint16_t saved_pc = cpu->read_register(REG_PC);
        
        // Push state to stack
        cpu->write_memory(cpu->read_register(REG_SP) - 2, saved_msw);
        cpu->write_memory(cpu->read_register(REG_SP) - 4, saved_pc);
        cpu->write_register(REG_SP, cpu->read_register(REG_SP) - 4);
        
        // Enter interrupt handler
        cpu->write_register(REG_MSW, saved_msw & ~MSW_INT_ENABLE);
        cpu->write_register(REG_PC, vectors[vector].address);
    }
};

System Exception Handler

class ExceptionHandler {
public:
    enum Exception {
        EXC_PAGE_FAULT = 0,
        EXC_PROTECTION = 1,
        EXC_INVALID_OPCODE = 2,
        EXC_PRIVILEGED = 3,
        EXC_UNALIGNED = 4
    };
    
    void handle_exception(Exception exc) {
        uint16_t vector_address = 0x0010 + (exc * 2);
        interrupt_handler->handle_interrupt(vector_address);
    }
};

To test the interrupt system in VS Code:

cd src/core
g++ -o test_interrupts test_interrupts.cpp interrupt_controller.cpp interrupt_handler.cpp
./test_interrupts

Magic-1 Emulator Technical Information - Part 9: Device I/O System

Base Device Interface

class DeviceInterface {
    virtual uint16_t read_port(uint16_t port) = 0;
    virtual void write_port(uint16_t port, uint16_t data) = 0;
    virtual void reset() = 0;
    virtual bool has_interrupt() = 0;
};

Device Port Manager

class PortManager {
private:
    struct PortMapping {
        uint16_t base_address;
        uint16_t port_count;
        DeviceInterface* device;
    };
    
    std::vector<PortMapping> port_map;

public:
    void register_device(uint16_t base, uint16_t count, DeviceInterface* dev) {
        port_map.push_back({base, count, dev});
    }

    uint16_t io_read(uint16_t port) {
        for (const auto& mapping : port_map) {
            if (port >= mapping.base_address && 
                port < mapping.base_address + mapping.port_count) {
                return mapping.device->read_port(port - mapping.base_address);
            }
        }
        return 0xFFFF;  // Unmapped port
    }
};

Device Memory Map

namespace DeviceMap {
    // UART Ports
    constexpr uint16_t UART0_BASE = 0xFFF0;
    constexpr uint16_t UART1_BASE = 0xFFE0;
    
    // Real-Time Clock
    constexpr uint16_t RTC_BASE = 0xFFD0;
    
    // CF Card Interface
    constexpr uint16_t CF_BASE = 0xFF98;
    
    // IDE Interface
    constexpr uint16_t IDE_BASE = 0xFFB0;
    
    // Front Panel
    constexpr uint16_t FP_BASE = 0xFFA0;
}

To test the I/O system in VS Code's integrated terminal:

cd src/devices
g++ -o test_io test_io.cpp port_manager.cpp device_interface.cpp
./test_io

Magic-1 Emulator Technical Information - Part 10: System Debug Infrastructure

Core Debug Interface

class DebugInterface {
    struct DebugState {
        std::vector<uint16_t> breakpoints;
        bool single_step;
        bool trace_enabled;
        uint32_t instruction_count;
        std::vector<uint16_t> watch_addresses;
    };

    // Debug command handler
    enum Command {
        CMD_STEP,       // Single step
        CMD_CONTINUE,   // Continue execution
        CMD_BREAK,      // Set breakpoint
        CMD_WATCH,      // Watch memory
        CMD_DUMP,       // Dump state
        CMD_TRACE       // Toggle trace
    };
};

CPU State Monitor

class CPUMonitor {
public:
    struct CPUState {
        uint16_t registers[16];
        uint16_t msw;
        uint16_t pc;
        bool halted;
        uint64_t current_microinstruction;
    };

    void dump_state() {
        printf("CPU State:\n");
        printf("PC: %04X  MSW: %04X\n", state.pc, state.msw);
        printf("Registers:\n");
        for (int i = 0; i < 8; i++) {
            printf("R%d: %04X  ", i, state.registers[i]);
            if (i % 4 == 3) printf("\n");
        }
    }
};

Memory Monitor

class MemoryMonitor {
public:
    void dump_memory(uint16_t start, uint16_t length) {
        for (uint16_t addr = start; addr < start + length; addr += 16) {
            printf("%04X: ", addr);
            for (int i = 0; i < 16; i++) {
                printf("%02X ", memory->read_byte(addr + i));
                if (i == 7) printf(" ");
            }
            printf("\n");
        }
    }

    void set_watchpoint(uint16_t address) {
        watchpoints.push_back(address);
    }
};

To test the debug infrastructure in VS Code:

  1. Open integrated terminal
  2. Run these commands:
cd src/debug
g++ -o test_debug test_debug.cpp debug_interface.cpp cpu_monitor.cpp memory_monitor.cpp
./test_debug

Magic-1 Emulator Technical Information - Part 11: System Configuration and Command Interface

System Configuration Manager

class SystemConfig {
    struct Configuration {
        // Memory configuration
        uint32_t rom_size;
        uint32_t ram_size;
        uint32_t page_size;
        
        // Device settings
        uint32_t uart_baud_rate;
        bool uart_console_enabled;
        bool rtc_enabled;
        
        // Debug options
        bool debug_enabled;
        bool trace_enabled;
        std::string log_file;
    };

    bool load_config(const std::string& filename) {
        std::ifstream config_file(filename);
        if (!config_file.is_open()) {
            return false;
        }

        // Parse JSON configuration
        try {
            json config = json::parse(config_file);
            config_data.rom_size = config["memory"]["rom_size"];
            config_data.ram_size = config["memory"]["ram_size"];
            // ...parse other settings...
        } catch (json::exception& e) {
            return false;
        }
        return true;
    }
};

Command Line Interface

class CommandInterface {
private:
    enum Command {
        CMD_HELP,
        CMD_LOAD,
        CMD_RUN,
        CMD_STEP,
        CMD_BREAK,
        CMD_DUMP,
        CMD_QUIT
    };

    std::map<std::string, Command> command_map = {
        {"help", CMD_HELP},
        {"load", CMD_LOAD},
        {"run", CMD_RUN},
        {"step", CMD_STEP},
        {"break", CMD_BREAK},
        {"dump", CMD_DUMP},
        {"quit", CMD_QUIT}
    };

public:
    void process_command(const std::string& cmd_line) {
        std::vector<std::string> tokens = tokenize(cmd_line);
        if (tokens.empty()) return;

        auto it = command_map.find(tokens[0]);
        if (it == command_map.end()) {
            printf("Unknown command: %s\n", tokens[0].c_str());
            return;
        }

        execute_command(it->second, tokens);
    }
};

Configuration File Example

Create a config.json in the project root:

{
    "memory": {
        "rom_size": 16384,
        "ram_size": 131072,
        "page_size": 2048
    },
    "devices": {
        "uart": {
            "console_enabled": true,
            "baud_rate": 9600
        },
        "rtc_enabled": true
    },
    "debug": {
        "enabled": true,
        "trace": false,
        "log_file": "magic1.log"
    }
}

Test the configuration system in VS Code's integrated terminal:

cd src/config
g++ -o test_config test_config.cpp system_config.cpp
./test_config ../../config.json

Magic-1 Emulator Technical Information - Part 12: Testing Infrastructure

Unit Test Framework

Let's create a comprehensive test framework for the Magic-1 emulator:

class Magic1TestFramework {
    struct TestCase {
        std::string name;
        std::function<bool()> test_func;
        std::string expected;
        std::string actual;
    };

    std::vector<TestCase> test_cases;
    int passed = 0;
    int failed = 0;

public:
    void add_test(const std::string& name, std::function<bool()> test) {
        test_cases.push_back({name, test, "", ""});
    }

    void run_all_tests() {
        for (auto& test : test_cases) {
            bool result = test.test_func();
            if (result) passed++; 
            else failed++;
            
            printf("%s: %s\n", test.name.c_str(), 
                   result ? "PASSED" : "FAILED");
        }
    }
};

CPU Test Suite

class CPUTests : public Magic1TestFramework {
public:
    CPUTests(Magic1CPU* cpu) : cpu(cpu) {
        add_test("Register Operations", [this]() {
            return test_registers();
        });
        
        add_test("ALU Operations", [this]() {
            return test_alu();
        });
        
        add_test("Memory Access", [this]() {
            return test_memory_access();
        });
    }

private:
    Magic1CPU* cpu;
    
    bool test_registers() {
        cpu->write_register(REG_A, 0x1234);
        return cpu->read_register(REG_A) == 0x1234;
    }
};

Memory Test Suite

class MemoryTests : public Magic1TestFramework {
public:
    void test_page_mapping() {
        // Setup test page
        uint16_t virt_addr = 0x1000;
        uint16_t phys_addr = 0x4000;
        mmu->map_page(virt_addr, phys_addr);
        
        // Test read/write through mapping
        memory->write_byte(virt_addr, 0x55);
        ASSERT_EQ(memory->read_byte(virt_addr), 0x55);
    }
};

Run the tests using VS Code's integrated terminal:

cd src/test
g++ -o run_tests test_main.cpp cpu_tests.cpp memory_tests.cpp
./run_tests

Test results will appear in VS Code's output pane.

Magic-1 Emulator Technical Information - Part 13: System Performance Monitoring

Performance Monitor Implementation

Create a performance monitoring system to track CPU, memory, and I/O metrics:

class PerformanceMonitor {
private:
    struct Metrics {
        // CPU metrics
        uint64_t total_cycles;
        uint64_t instructions_executed;
        uint32_t interrupts_handled;
        
        // Memory metrics
        uint32_t memory_reads;
        uint32_t memory_writes;
        uint32_t page_faults;
        
        // Cache metrics
        uint32_t cache_hits;
        uint32_t cache_misses;
        
        // I/O metrics
        uint32_t io_operations;
        uint32_t uart_bytes;
        uint32_t cf_sectors;
    };

    Metrics current;
    std::vector<Metrics> history;
};

Performance Data Collection

class PerformanceCollector {
public:
    void sample_metrics() {
        auto now = std::chrono::steady_clock::now();
        
        // Collect CPU metrics
        metrics.instructions_per_second = 
            calculate_ips(cpu->get_instruction_count(), now);
            
        // Memory subsystem metrics
        metrics.page_fault_rate = 
            calculate_rate(mmu->get_page_faults(), now);
            
        // I/O metrics
        metrics.io_throughput = 
            calculate_throughput(io_controller->get_bytes_transferred(), now);
    }
    
    void generate_report(const std::string& filename) {
        std::ofstream report(filename);
        report << "Magic-1 Performance Report\n";
        report << "========================\n\n";
        report << "Instructions/sec: " << metrics.instructions_per_second << "\n";
        report << "Page fault rate: " << metrics.page_fault_rate << "/sec\n";
        report << "I/O throughput: " << metrics.io_throughput << " bytes/sec\n";
    }
};

Test the performance monitoring in VS Code:

  1. Build the performance monitoring system:
cd src/perf
g++ -o perf_test performance_monitor.cpp perf_collector.cpp test_perf.cpp
  1. Run performance tests:
./perf_test
cat perf_report.txt

The performance data will be displayed in VS Code's integrated terminal and written to perf_report.txt.

Magic-1 Emulator Enhanced Features

1. Built-in Debugger Implementation

class Magic1Debugger {
    enum DebugCommand {
        STEP,           // Single step
        CONTINUE,       // Continue execution
        BREAKPOINT,     // Set/clear breakpoint
        EXAMINE,        // Examine memory/registers
        MODIFY,         // Modify memory/registers
        DISASSEMBLE,    // Show disassembly
        MICROCODE      // Show current microinstruction
    };

    struct DebugState {
        bool running;
        bool single_step;
        std::vector<uint16_t> breakpoints;
        uint16_t last_pc;
        uint64_t current_micro;
    };
};

2. Instruction Set Editor

class InstructionSetEditor {
public:
    struct Instruction {
        uint16_t opcode;
        std::string mnemonic;
        std::vector<uint64_t> microcode_sequence;
        bool privileged;
    };

    // Load current instruction set
    void load_instruction_set(const std::string& filename) {
        // Parse instruction definitions
        // Format: opcode,mnemonic,microcode_sequence,privileged
    }

    // Save modified instruction set
    void save_instruction_set(const std::string& filename) {
        // Write instruction definitions
    }
};

3. Microcode Editor

class MicrocodeEditor {
public:
    // Edit microcode instruction
    void edit_microinstruction(uint16_t address, uint64_t new_instruction) {
        microcode_rom[address] = new_instruction;
        update_prom_files();
    }

    // Generate new PROM files
    void update_prom_files() {
        for(int prom = 0; prom < 5; prom++) {
            std::string filename = fmt::format("prom{}.hex", prom);
            write_prom_file(filename, prom);
        }
    }
};

4. Serial Communication Interface

class Magic1SerialInterface {
private:
    static constexpr int BAUD_RATE = 9600;
    int serial_fd;

public:
    bool connect_to_magic1(const std::string& port) {
        serial_fd = open(port.c_str(), O_RDWR);
        if (serial_fd < 0) return false;

        // Configure serial port
        struct termios tty;
        tcgetattr(serial_fd, &tty);
        cfsetospeed(&tty, B9600);
        cfsetispeed(&tty, B9600);
        // 8N1 configuration
        tty.c_cflag &= ~PARENB;
        tty.c_cflag &= ~CSTOPB;
        tty.c_cflag &= ~CSIZE;
        tty.c_cflag |= CS8;
        
        return tcsetattr(serial_fd, TCSANOW, &tty) == 0;
    }

    void send_command(const std::string& cmd) {
        write(serial_fd, cmd.c_str(), cmd.length());
    }

    std::string receive_response() {
        char buffer[1024];
        ssize_t n = read(serial_fd, buffer, sizeof(buffer)-1);
        if (n > 0) {
            buffer[n] = '\0';
            return std::string(buffer);
        }
        return "";
    }
};

To test in VS Code's integrated terminal:

# Build enhanced features
cd src
g++ -o magic1_enhanced main.cpp debugger/*.cpp editor/*.cpp serial/*.cpp

# Run with serial connection
./magic1_enhanced --serial /dev/ttyUSB0

The debugger interface, instruction set editor, and serial communication can be accessed through the emulator's command interface.

Magic-1 Emulator Enhanced Features - Part 1: Core Infrastructure

Debugger Core Implementation

Let's create the base debugger infrastructure:

#pragma once

#include <vector>
#include <string>
#include <map>

class DebuggerCore {
    // Debug states
    enum class State {
        RUNNING,
        STOPPED,
        STEPPING,
        WAITING_INPUT
    };

    // Breakpoint definition
    struct Breakpoint {
        uint16_t address;
        bool enabled;
        uint32_t hit_count;
        std::string condition;
    };

    // Register snapshot
    struct RegisterState {
        uint16_t msw;         // Machine Status Word
        uint16_t pc;          // Program Counter
        uint16_t sp;          // Stack Pointer
        uint16_t a, b, c;     // General Purpose Registers
        uint64_t microcode;   // Current microinstruction
    };

public:
    // Core debugger API
    bool set_breakpoint(uint16_t addr, const std::string& condition = "");
    bool step_instruction();
    bool run_until_break();
    RegisterState get_state();
    void dump_memory(uint16_t start, uint16_t length);
};

Memory Inspector Module

#pragma once

class MemoryInspector {
public:
    enum class Format {
        HEX,
        DECIMAL,
        ASCII,
        INSTRUCTION
    };

    // Memory view window
    struct MemoryView {
        uint16_t start_address;
        uint16_t length;
        Format display_format;
        bool show_symbols;
    };

    std::string format_memory(const MemoryView& view) {
        std::stringstream output;
        for(uint16_t addr = view.start_address; 
            addr < view.start_address + view.length; 
            addr += 16) {
            
            output << fmt::format("{:04X}: ", addr);
            
            // Format data according to view settings
            for(int i = 0; i < 16; i++) {
                uint8_t value = memory->read_byte(addr + i);
                switch(view.display_format) {
                    case Format::HEX:
                        output << fmt::format("{:02X} ", value);
                        break;
                    // ...other format handlers...
                }
            }
            output << "\n";
        }
        return output.str();
    }
};

To test in VS Code:

cd src/debugger
g++ -o test_debugger test_debugger.cpp core.cpp memory_inspector.cpp
./test_debugger

The output will appear in VS Code's integrated terminal.

Magic-1 Emulator Enhanced Features - Part 2: Instruction Set Editor

Main Editor Interface

class InstructionSetEditor {
private:
    struct InstructionDef {
        uint16_t opcode;
        std::string mnemonic;
        std::vector<uint64_t> microcode;
        bool privileged;
        std::string description;
    };

    std::map<uint16_t, InstructionDef> instruction_set;
    std::string current_file;
    bool modified;

public:
    bool load_instruction_set(const std::string& filename) {
        std::ifstream file(filename);
        if (!file) return false;

        nlohmann::json j;
        file >> j;

        instruction_set.clear();
        for (const auto& inst : j["instructions"]) {
            InstructionDef def;
            def.opcode = inst["opcode"];
            def.mnemonic = inst["mnemonic"];
            def.microcode = inst["microcode"].get<std::vector<uint64_t>>();
            def.privileged = inst["privileged"];
            instruction_set[def.opcode] = def;
        }
        current_file = filename;
        modified = false;
        return true;
    }
};

Instruction Validator

class InstructionValidator {
public:
    struct ValidationResult {
        bool valid;
        std::string error;
    };

    ValidationResult validate_instruction(const InstructionDef& inst) {
        ValidationResult result;
        result.valid = true;

        // Check opcode range
        if (inst.opcode > 0xFF) {
            result.valid = false;
            result.error = "Opcode exceeds 8-bit range";
            return result;
        }

        // Validate microcode sequence
        for (const auto& micro : inst.microcode) {
            if (!validate_microinstruction(micro)) {
                result.valid = false;
                result.error = "Invalid microinstruction";
                return result;
            }
        }
        return result;
    }
};

Command Line Interface

class EditorCLI {
public:
    void run() {
        while (true) {
            std::string cmd = readline("ISE> ");
            if (cmd == "quit") break;
            
            if (cmd == "load") {
                std::string filename = readline("Filename: ");
                if (!editor.load_instruction_set(filename)) {
                    printf("Error loading instruction set\n");
                }
                continue;
            }

            if (cmd == "edit") {
                edit_instruction();
                continue;
            }

            if (cmd == "save") {
                editor.save_current();
                continue;
            }
        }
    }
};

To test the instruction set editor in VS Code:

cd src/editor
g++ -o ise instruction_editor.cpp instruction_validator.cpp editor_cli.cpp
./ise

The editor provides an interactive interface in VS Code's integrated terminal for modifying the Magic-1's instruction set.

Magic-1 Emulator Enhanced Features - Part 3: Microcode Editor

Microcode Editor Core

class MicrocodeEditor {
private:
    // 56-bit microinstruction format
    struct MicroInstruction {
        uint8_t next;         // Next address field
        uint8_t control;      // Control signals
        uint8_t alu_op;       // ALU operation
        uint8_t bus_ctrl;     // Bus control
        uint8_t reg_ctrl;     // Register control
        uint8_t mem_ctrl;     // Memory control
        uint8_t misc;         // Miscellaneous control
    };

    // PROM storage
    struct PromContent {
        uint8_t data[512];    // 512 bytes per PROM
        bool modified;
        std::string filename;
    } proms[5];

public:
    void load_prom_files(const std::vector<std::string>& filenames) {
        for(int i = 0; i < 5; i++) {
            std::ifstream file(filenames[i], std::ios::binary);
            file.read((char*)proms[i].data, 512);
            proms[i].filename = filenames[i];
            proms[i].modified = false;
        }
    }

    MicroInstruction decode_instruction(uint16_t address) {
        MicroInstruction mi;
        mi.next = proms[0].data[address];
        mi.control = proms[1].data[address];
        mi.alu_op = proms[2].data[address];
        mi.bus_ctrl = proms[3].data[address];
        mi.misc = proms[4].data[address];
        return mi;
    }
};

Microcode Visualization

class MicrocodeVisualizer {
public:
    std::string format_instruction(const MicroInstruction& mi) {
        std::stringstream ss;
        ss << fmt::format("Address: {:03X}\n", mi.next);
        ss << "Control Signals:\n";
        ss << fmt::format("  ALU:     {:08b}\n", mi.alu_op);
        ss << fmt::format("  Bus:     {:08b}\n", mi.bus_ctrl);
        ss << fmt::format("  Reg:     {:08b}\n", mi.reg_ctrl);
        ss << fmt::format("  Memory:  {:08b}\n", mi.mem_ctrl);
        ss << fmt::format("  Misc:    {:08b}\n", mi.misc);
        return ss.str();
    }
};

Test the microcode editor in VS Code's integrated terminal:

cd src/microcode/editor
g++ -o micedit microcode_editor.cpp microcode_visualizer.cpp
./micedit

This will open an interactive microcode editor. You can:

  1. Load PROM files
  2. View and edit microinstructions
  3. Save modified PROM contents
  4. Visualize microcode execution flow

Type 'next' for Part 4: Serial Communication Implementation.

Magic-1 Emulator Enhanced Features - Part 4: Serial Communication Interface

Core Serial Communication Module

First, let's create the serial interface for communicating with the real Magic-1:

#pragma once

#include <termios.h>
#include <fcntl.h>
#include <unistd.h>
#include <string>
#include <vector>

class Magic1Serial {
private:
    int serial_fd;
    struct termios original_tty;
    
    struct SerialConfig {
        std::string port;
        int baud_rate;
        int data_bits;
        int stop_bits;
        bool parity;
    } config;

public:
    bool connect(const std::string& port = "/dev/ttyUSB0") {
        serial_fd = open(port.c_str(), O_RDWR | O_NOCTTY);
        if (serial_fd < 0) return false;

        // Save original terminal settings
        tcgetattr(serial_fd, &original_tty);
        
        // Configure new settings
        struct termios tty = original_tty;
        cfsetospeed(&tty, B9600);
        cfsetispeed(&tty, B9600);
        
        // 8N1 configuration
        tty.c_cflag &= ~PARENB;  // No parity
        tty.c_cflag &= ~CSTOPB;  // 1 stop bit
        tty.c_cflag &= ~CSIZE;   
        tty.c_cflag |= CS8;      // 8 bits
        
        return tcsetattr(serial_fd, TCSANOW, &tty) == 0;
    }
};

Command Protocol Implementation

#pragma once

class Magic1Protocol {
public:
    enum CommandType {
        CMD_READ_MEMORY,
        CMD_WRITE_MEMORY,
        CMD_READ_REGISTER,
        CMD_WRITE_REGISTER,
        CMD_EXECUTE,
        CMD_HALT
    };

    struct Command {
        CommandType type;
        uint16_t address;
        uint16_t data;
        uint8_t length;
    };

    std::vector<uint8_t> encode_command(const Command& cmd) {
        std::vector<uint8_t> packet;
        packet.push_back(0xFF);  // Start marker
        packet.push_back(static_cast<uint8_t>(cmd.type));
        packet.push_back(cmd.address >> 8);
        packet.push_back(cmd.address & 0xFF);
        // ...encode remaining fields...
        return packet;
    }
};

Serial Monitor Interface

#pragma once

class SerialMonitor {
private:
    Magic1Serial* serial;
    Magic1Protocol* protocol;
    
    struct MonitorState {
        bool connected;
        std::vector<uint8_t> rx_buffer;
        std::vector<uint8_t> tx_buffer;
        uint32_t errors;
    } state;

public:
    void start_monitoring() {
        while (state.connected) {
            // Read from serial port
            uint8_t buffer[256];
            ssize_t n = read(serial->get_fd(), buffer, sizeof(buffer));
            
            if (n > 0) {
                process_received_data(buffer, n);
            }
            
            // Process any pending commands
            process_command_queue();
        }
    }
};

To test the serial communication in VS Code:

  1. Create a test file:
#include "magic1_serial.h"
#include "magic1_protocol.h"
#include "serial_monitor.h"

int main() {
    Magic1Serial serial;
    if (!serial.connect("/dev/ttyUSB0")) {
        fprintf(stderr, "Failed to connect to Magic-1\n");
        return 1;
    }
    
    // Test communication
    Magic1Protocol::Command cmd;
    cmd.type = Magic1Protocol::CMD_READ_MEMORY;
    cmd.address = 0x0000;
    cmd.length = 16;
    
    auto packet = protocol.encode_command(cmd);
    serial.send(packet);
    
    return 0;
}
  1. Compile and run:
cd src/serial
g++ -o test_serial test_serial.cpp magic1_serial.cpp magic1_protocol.cpp serial_monitor.cpp
./test_serial

Type 'next' for Part 5: User Interface Implementation.

Magic-1 Emulator Enhanced Features - Part 5: User Interface Implementation

Terminal User Interface

Let's create a terminal-based UI for the Magic-1 emulator using ncurses:

#pragma once

#include <ncurses.h>
#include <panel.h>
#include <vector>
#include <string>

class TerminalUI {
private:
    // Windows for different views
    WINDOW *reg_win;      // Register display
    WINDOW *code_win;     // Code/disassembly view
    WINDOW *micro_win;    // Microcode view
    WINDOW *mem_win;      // Memory dump
    WINDOW *cmd_win;      // Command input
    
    // Window dimensions and positions
    struct {
        int rows, cols;
        int reg_height;
        int code_height;
        int micro_height;
        int mem_height;
        int cmd_height;
    } layout;

public:
    void init() {
        // Initialize ncurses
        initscr();
        start_color();
        noecho();
        cbreak();
        keypad(stdscr, TRUE);

        // Create color pairs
        init_pair(1, COLOR_WHITE, COLOR_BLUE);    // Headers
        init_pair(2, COLOR_GREEN, COLOR_BLACK);   // Register values
        init_pair(3, COLOR_YELLOW, COLOR_BLACK);  // Memory addresses
        init_pair(4, COLOR_RED, COLOR_BLACK);     // Breakpoints
    }
};

UI Layout Manager

#pragma once

class LayoutManager {
public:
    void create_windows() {
        getmaxyx(stdscr, layout.rows, layout.cols);
        
        // Create register window
        reg_win = newwin(layout.reg_height, layout.cols, 0, 0);
        box(reg_win, 0, 0);
        mvwprintw(reg_win, 0, 2, " Registers ");
        
        // Create code window
        code_win = newwin(layout.code_height, layout.cols/2, 
                         layout.reg_height, 0);
        box(code_win, 0, 0);
        mvwprintw(code_win, 0, 2, " Disassembly ");
        
        // Create microcode window
        micro_win = newwin(layout.micro_height, layout.cols/2, 
                          layout.reg_height, layout.cols/2);
        box(micro_win, 0, 0);
        mvwprintw(micro_win, 0, 2, " Microcode ");
    }

    void update_display() {
        update_panels();
        doupdate();
    }
};

To test the UI in VS Code's integrated terminal:

# Install ncurses development package
sudo apt-get install libncurses5-dev

# Compile and run
cd src/ui
g++ -o magic1ui terminal_ui.cpp layout_manager.cpp -lncurses -lpanel
./magic1ui

Magic-1 Emulator Enhanced Features - Part 6: Integration with Debugger

Debugger UI Integration

Create a new file to integrate the debugger with the terminal UI:

#pragma once

class DebuggerUI {
    struct {
        WINDOW* debug_win;     // Debugger control window
        WINDOW* watch_win;     // Watch window
        WINDOW* stack_win;     // Stack trace window
        WINDOW* vars_win;      // Variables window
    } windows;

    struct {
        bool running;
        bool stepping;
        std::vector<uint16_t> breakpoints;
        std::map<uint16_t, std::string> watches;
    } debug_state;

    void update_debug_display() {
        // Update debugger control window
        werase(windows.debug_win);
        box(windows.debug_win, 0, 0);
        mvwprintw(windows.debug_win, 0, 2, " Debug Control ");
        mvwprintw(windows.debug_win, 1, 2, "F5: Continue");
        mvwprintw(windows.debug_win, 2, 2, "F10: Step Over");
        mvwprintw(windows.debug_win, 3, 2, "F11: Step Into");
        wrefresh(windows.debug_win);

        // Update watch window
        werase(windows.watch_win);
        box(windows.watch_win, 0, 0);
        mvwprintw(windows.watch_win, 0, 2, " Watches ");
        int row = 1;
        for(const auto& watch : debug_state.watches) {
            mvwprintw(windows.watch_win, row++, 2, 
                     "0x%04X: %s", watch.first, watch.second.c_str());
        }
        wrefresh(windows.watch_win);
    }
};

Key Command Handler

#pragma once

class KeyHandler {
public:
    void process_debug_keys(int key) {
        switch(key) {
            case KEY_F(5):  // Continue
                debugger->continue_execution();
                break;
                
            case KEY_F(10): // Step Over
                debugger->step_over();
                break;
                
            case KEY_F(11): // Step Into
                debugger->step_into();
                break;
                
            case 'b':       // Toggle breakpoint
                uint16_t addr = get_current_address();
                debugger->toggle_breakpoint(addr);
                break;
        }
        update_display();
    }
};

Test the debugger UI integration in VS Code's integrated terminal:

cd src/ui
g++ -o debug_ui debugger_ui.cpp key_handler.cpp -lncurses
./debug_ui

Magic-1 Emulator Enhanced Features - Part 7: Enhanced Memory Visualization

Let's create an advanced memory visualization system that integrates with our debugger.

Memory View Implementation

#include <ncurses.h>
#include <vector>
#include <string>

class MemoryVisualizer {
private:
    WINDOW* mem_window;
    uint16_t current_address;
    int view_mode;  // 0=hex, 1=disasm, 2=mixed

    struct MemoryRegion {
        uint16_t start;
        uint16_t end;
        std::string name;
        bool read_only;
    };

    std::vector<MemoryRegion> memory_map = {
        {0x0000, 0x3FFF, "ROM", true},
        {0x4000, 0x7FFF, "Device SRAM", false},
        {0x8000, 0xF7FF, "Main Memory", false},
        {0xF800, 0xFFFF, "Device Page", false}
    };

public:
    void draw_memory_view() {
        werase(mem_window);
        box(mem_window, 0, 0);
        mvwprintw(mem_window, 0, 2, " Memory View [%s] ", 
                  get_region_name(current_address).c_str());

        for(int i = 0; i < 16; i++) {
            // Address column
            mvwprintw(mem_window, i+1, 2, "%04X:", current_address + (i*16));
            
            // Hex dump
            for(int j = 0; j < 16; j++) {
                uint8_t byte = memory->read_byte(current_address + (i*16) + j);
                mvwprintw(mem_window, i+1, 8 + (j*3), "%02X", byte);
            }
            
            // ASCII representation
            for(int j = 0; j < 16; j++) {
                uint8_t byte = memory->read_byte(current_address + (i*16) + j);
                mvwaddch(mem_window, i+1, 57 + j, 
                        isprint(byte) ? byte : '.');
            }
        }
        wrefresh(mem_window);
    }
};

Memory Region Highlighter

class RegionHighlighter {
public:
    void highlight_region(uint16_t address) {
        init_pair(1, COLOR_WHITE, COLOR_BLUE);   // ROM
        init_pair(2, COLOR_GREEN, COLOR_BLACK);  // SRAM
        init_pair(3, COLOR_YELLOW, COLOR_BLACK); // Main Memory
        init_pair(4, COLOR_RED, COLOR_BLACK);    // Device Page

        int color = get_region_color(address);
        wattron(mem_window, COLOR_PAIR(color));
        // Draw highlighted region
        wattroff(mem_window, COLOR_PAIR(color));
    }
};

Test the memory visualization in VS Code's integrated terminal:

cd src/visualization
g++ -o memview memory_view.cpp region_highlighter.cpp -lncurses
./memview

Magic-1 Emulator Enhanced Features - Part 8: Microcode Visualization and Analysis Tools

Microcode Visualizer Implementation

Let's create tools to visualize and analyze microcode execution:

class MicrocodeVisualizer {
    struct MicrocodeState {
        uint64_t current_instruction;
        uint16_t micro_pc;
        uint16_t next_address;
        bool executing;
    };

    WINDOW* micro_win;
    std::vector<std::string> field_names = {
        "Next Address", "Register Latch", "MAR Control",
        "MDR Control", "ALU Op", "Bus Control", "Misc Control"
    };

public:
    void display_current_microinstruction(const MicrocodeState& state) {
        werase(micro_win);
        box(micro_win, 0, 0);
        mvwprintw(micro_win, 0, 2, " Microcode View [PC: %03X] ", 
                  state.micro_pc);

        // Display all microinstruction fields
        int row = 1;
        for(const auto& field : decode_microinstruction(state.current_instruction)) {
            mvwprintw(micro_win, row++, 2, "%-12s: %08b", 
                     field.name.c_str(), field.value);
        }
        wrefresh(micro_win);
    }
};

Microcode Flow Analyzer

class MicrocodeFlowAnalyzer {
    struct FlowNode {
        uint16_t address;
        std::vector<uint16_t> next_addresses;
        bool is_conditional;
        bool is_terminal;
    };

    std::map<uint16_t, FlowNode> flow_graph;

public:
    void analyze_microcode_flow(uint16_t start_address) {
        flow_graph.clear();
        std::queue<uint16_t> to_analyze;
        to_analyze.push(start_address);

        while(!to_analyze.empty()) {
            uint16_t current = to_analyze.front();
            to_analyze.pop();

            if(flow_graph.count(current)) continue;

            FlowNode node;
            node.address = current;
            auto instruction = decode_microinstruction(
                microcode_rom[current]);

            // Analyze next address logic
            analyze_next_addresses(instruction, node);

            flow_graph[current] = node;
            
            // Queue discovered addresses
            for(auto next : node.next_addresses) {
                if(!flow_graph.count(next)) {
                    to_analyze.push(next);
                }
            }
        }
    }
};

To test these tools in VS Code's integrated terminal:

cd src/microcode
g++ -o mcview visualizer/microcode_view.cpp analyzer/flow_analyzer.cpp -lncurses
./mcview

Magic-1 Emulator Enhanced Features - Part 9: Integrated Testing System

Let's create a comprehensive testing framework for the Magic-1 emulator.

Test Framework Core

#include <functional>
#include <vector>
#include <string>
#include <chrono>

class Magic1TestFramework {
private:
    struct TestCase {
        std::string name;
        std::string category;
        std::function<bool()> test_func;
        bool passed;
        std::string error_msg;
        std::chrono::milliseconds duration;
    };

    std::vector<TestCase> test_cases;
    bool verbose_output;

public:
    void add_test(const std::string& name, 
                 const std::string& category,
                 std::function<bool()> test) {
        test_cases.push_back({name, category, test, false, "", {}});
    }

    void run_all_tests() {
        int passed = 0, failed = 0;
        
        for(auto& test : test_cases) {
            auto start = std::chrono::steady_clock::now();
            try {
                test.passed = test.test_func();
                if(test.passed) passed++;
                else failed++;
            }
            catch(const std::exception& e) {
                test.passed = false;
                test.error_msg = e.what();
                failed++;
            }
            auto end = std::chrono::steady_clock::now();
            test.duration = std::chrono::duration_cast<std::chrono::milliseconds>
                          (end - start);
        }

        generate_test_report();
    }
};

CPU Test Implementation

#include "test_framework.h"

class CPUTest : public Magic1TestFramework {
public:
    CPUTest(Magic1CPU* cpu) : cpu(cpu) {
        add_test("Register Operations", "CPU", [this]() {
            return test_registers();
        });
        
        add_test("ALU Operations", "CPU", [this]() {
            return test_alu_operations();
        });
        
        add_test("Memory Access", "CPU", [this]() {
            return test_memory_access();
        });
    }

private:
    Magic1CPU* cpu;
    
    bool test_registers() {
        cpu->write_register(REG_A, 0x1234);
        return cpu->read_register(REG_A) == 0x1234;
    }
};

To run tests in VS Code:

  1. Open the integrated terminal
  2. Execute:
cd src/test
g++ -o run_tests test_main.cpp cpu_test.cpp memory_test.cpp microcode_test.cpp
./run_tests --verbose

The test results will appear in VS Code's output pane.

Magic-1 Emulator Enhanced Features - Part 10: System State Analysis Tools

Let's create tools to analyze and monitor the Magic-1's system state.

State Analyzer Implementation

class SystemStateAnalyzer {
private:
    struct SystemState {
        // CPU State
        uint16_t msw;          // Machine Status Word
        uint16_t pc;           // Program Counter
        uint16_t registers[8]; // General registers
        
        // Memory State
        bool paging_enabled;
        uint16_t page_table_base;
        std::vector<bool> dirty_pages;
        
        // Device State
        bool uart_busy;
        bool rtc_interrupt_pending;
        bool cf_card_active;
    };

    // Track historical states for analysis
    std::vector<SystemState> state_history;
    size_t max_history_size = 1000;

public:
    void capture_current_state() {
        if (state_history.size() >= max_history_size) {
            state_history.erase(state_history.begin());
        }
        
        SystemState current;
        // Capture CPU state
        current.msw = cpu->get_msw();
        current.pc = cpu->get_pc();
        memcpy(current.registers, cpu->get_registers(), 
               sizeof(current.registers));
        
        state_history.push_back(current);
    }
    
    void analyze_transitions() {
        for (size_t i = 1; i < state_history.size(); i++) {
            detect_state_changes(state_history[i-1], state_history[i]);
        }
    }
};

State Change Detector

class StateChangeDetector {
public:
    struct StateChange {
        std::string component;
        std::string description;
        uint64_t timestamp;
        int severity;  // 0=info, 1=warning, 2=error
    };

    std::vector<StateChange> detect_state_changes(
        const SystemState& prev, 
        const SystemState& current) {
        
        std::vector<StateChange> changes;
        
        // Check mode changes
        if ((prev.msw & MSW_MODE_MASK) != 
            (current.msw & MSW_MODE_MASK)) {
            changes.push_back({
                "CPU",
                "Mode change: " + 
                mode_to_string(prev.msw) + " -> " +
                mode_to_string(current.msw),
                get_timestamp(),
                0
            });
        }
        
        // Check for unexpected transitions
        if (detect_anomaly(prev, current)) {
            changes.push_back({
                "System",
                "Anomalous state transition detected",
                get_timestamp(),
                2
            });
        }
        
        return changes;
    }
};

Test the state analysis tools in VS Code's integrated terminal:

cd src/analysis
g++ -o state_analyzer state_analyzer.cpp change_detector.cpp
./state_analyzer

The analyzer will show state transitions and any detected anomalies in the system's operation.

Magic-1 Emulator Enhanced Features - Part 11: Performance Profiling Tools

Let's create a performance profiling system for the Magic-1 emulator.

Core Performance Profiler

#include <chrono>
#include <map>
#include <string>
#include <vector>

class Magic1Profiler {
private:
    struct ProfileMetric {
        uint64_t cycles;
        uint64_t instructions;
        uint64_t memory_reads;
        uint64_t memory_writes;
        uint64_t cache_hits;
        uint64_t cache_misses;
        std::chrono::microseconds execution_time;
    };

    struct FunctionProfile {
        std::string name;
        uint16_t start_address;
        uint16_t end_address;
        uint32_t call_count;
        ProfileMetric metrics;
    };

    std::map<uint16_t, FunctionProfile> function_profiles;
    ProfileMetric current_metrics;
    bool profiling_active;

public:
    void start_profiling() {
        profiling_active = true;
        reset_metrics();
    }

    void update_metrics() {
        if (!profiling_active) return;
        
        current_metrics.cycles++;
        if (cpu->is_instruction_complete()) {
            current_metrics.instructions++;
        }
    }
};

Memory Access Profiler

class MemoryProfiler {
private:
    struct AccessPattern {
        uint16_t address;
        bool is_read;
        uint64_t timestamp;
        uint16_t size;
    };

    std::vector<AccessPattern> access_history;
    std::map<uint16_t, uint32_t> hotspots;

public:
    void record_access(uint16_t addr, bool read, uint16_t size) {
        if (access_history.size() >= MAX_HISTORY) {
            access_history.erase(access_history.begin());
        }
        
        access_history.push_back({
            addr,
            read,
            get_timestamp(),
            size
        });

        // Update hotspots
        hotspots[addr & 0xFFF0]++;
    }

    void generate_heatmap() {
        // Generate memory access heatmap
        for (const auto& spot : hotspots) {
            printf("0x%04X: %s\n", 
                   spot.first, 
                   generate_heat_bar(spot.second));
        }
    }
};

Test the profiling tools in VS Code's integrated terminal:

cd src/profiler
g++ -o profiler_test core_profiler.cpp memory_profiler.cpp -O2
./profiler_test

Magic-1 Emulator Enhanced Features - Part 12: Configuration Management System

Let's implement a flexible configuration system for the Magic-1 emulator.

Core Configuration Manager

#include <nlohmann/json.hpp>
#include <fstream>
#include <string>

class ConfigManager {
private:
    nlohmann/json config;
    std::string config_path;

    struct EmulatorConfig {
        // System Configuration
        struct {
            uint32_t rom_size;
            uint32_t ram_size;
            bool paging_enabled;
            std::string microcode_path;
        } system;

        // Device Configuration
        struct {
            std::string serial_port;
            int baud_rate;
            std::string cf_image_path;
        } devices;

        // Debug Configuration
        struct {
            bool debug_enabled;
            std::string log_level;
            std::string log_file;
            bool profile_enabled;
        } debug;
    } current_config;

public:
    bool load_config(const std::string& config_file) {
        try {
            std::ifstream f(config_file);
            config = nlohmann::json::parse(f);
            parse_config();
            return true;
        } catch (const std::exception& e) {
            return false;
        }
    }
};

Configuration File Example

Create a magic1_config.json in your project root:

{
    "system": {
        "rom_size": 16384,
        "ram_size": 131072,
        "paging_enabled": true,
        "microcode_path": "/path/to/proms/"
    },
    "devices": {
        "serial_port": "/dev/ttyUSB0",
        "baud_rate": 9600,
        "cf_image_path": "/path/to/cf_image.img"
    },
    "debug": {
        "enabled": true,
        "log_level": "INFO",
        "log_file": "magic1_emu.log",
        "profile_enabled": true
    }
}

Test the configuration system in VS Code:

  1. Create test file:
// filepath: src/config/test_config.cpp
#include "config_manager.h"
#include <iostream>

int main() {
    ConfigManager config;
    if (!config.load_config("../../magic1_config.json")) {
        std::cerr << "Failed to load configuration\n";
        return 1;
    }
    
    // Test configuration values
    config.print_current_config();
    return 0;
}
  1. Build and run in VS Code's integrated terminal:
cd src/config
g++ -o test_config test_config.cpp -I/usr/include/nlohmann
./test_config

Magic-1 Emulator Enhanced Features - Part 13: Logging and Error Handling System

Let's implement a robust logging and error handling system:

#include <spdlog/spdlog.h>
#include <spdlog/sinks/rotating_file_sink.h>
#include <spdlog/sinks/stdout_color_sinks.h>

class Magic1Logger {
private:
    std::shared_ptr<spdlog::logger> logger;
    static constexpr size_t MAX_FILE_SIZE = 1048576 * 5;  // 5MB
    static constexpr size_t MAX_FILES = 3;

public:
    bool init(const std::string& log_file) {
        try {
            auto console_sink = std::make_shared<spdlog::sinks::stdout_color_sink_mt>();
            auto file_sink = std::make_shared<spdlog::sinks::rotating_file_sink_mt>(
                log_file, MAX_FILE_SIZE, MAX_FILES);

            std::vector<spdlog::sink_ptr> sinks {console_sink, file_sink};
            logger = std::make_shared<spdlog::logger>("magic1", sinks.begin(), sinks.end());
            
            logger->set_pattern("[%Y-%m-%d %H:%M:%S.%e] [%^%l%$] [%t] %v");
            logger->set_level(spdlog::level::debug);
            
            return true;
        } catch (const spdlog::spdlog_ex& ex) {
            return false;
        }
    }
};

Create an error handling system:

class Magic1ErrorHandler {
public:
    enum class ErrorSeverity {
        INFO,
        WARNING,
        ERROR,
        FATAL
    };

    struct Error {
        ErrorSeverity severity;
        std::string message;
        std::string component;
        uint64_t timestamp;
        uint16_t pc;           // CPU state when error occurred
        uint16_t instruction;  // Current instruction
    };

    void handle_error(const Error& error) {
        logger->log(
            get_log_level(error.severity),
            "[{}] {} (PC: {:04X}, Inst: {:04X})",
            error.component,
            error.message,
            error.pc,
            error.instruction
        );

        if (error.severity == ErrorSeverity::FATAL) {
            throw std::runtime_error(error.message);
        }
    }
};

Test the logging system in VS Code's integrated terminal:

# Install spdlog
sudo apt-get install libspdlog-dev

# Compile and run test
cd src/logging
g++ -o test_logging test_logging.cpp -lspdlog
./test_logging

Check the log file and console output in VS Code's terminal/output panes.

Magic-1 Emulator Enhanced Features - Part 14: Real-time Monitoring System

Let's create a real-time monitoring system for the Magic-1 emulator.

System Monitor Core

#include <atomic>
#include <thread>
#include <queue>

class SystemMonitor {
private:
    struct MonitoringMetrics {
        // CPU Metrics
        uint32_t instructions_per_second;
        float cpu_utilization;
        uint16_t current_pc;
        
        // Memory Metrics
        uint32_t memory_reads;
        uint32_t memory_writes;
        float cache_hit_ratio;
        
        // Device Status
        bool uart_active;
        bool rtc_interrupt_pending;
        uint32_t cf_card_operations;
        
        // Timestamp
        std::chrono::system_clock::time_point timestamp;
    };

    std::atomic<bool> monitoring_active;
    std::thread monitor_thread;
    std::queue<MonitoringMetrics> metrics_queue;
    static constexpr size_t MAX_QUEUE_SIZE = 1000;

public:
    void start_monitoring() {
        monitoring_active = true;
        monitor_thread = std::thread([this]() {
            while(monitoring_active) {
                collect_metrics();
                std::this_thread::sleep_for(std::chrono::milliseconds(100));
            }
        });
    }
};

Real-time Statistics Collector

class StatisticsCollector {
public:
    struct SystemStatistics {
        // Performance Stats
        double avg_instructions_per_second;
        double avg_memory_operations_per_second;
        double avg_device_operations_per_second;
        
        // System Health
        float system_load;
        uint32_t error_count;
        uint32_t warning_count;
        
        // Time Window
        std::chrono::seconds window_size;
    };

    SystemStatistics collect_statistics() {
        SystemStatistics stats;
        auto now = std::chrono::steady_clock::now();
        
        // Calculate averages over time window
        stats.avg_instructions_per_second = 
            calculate_instruction_rate(now);
        stats.avg_memory_operations_per_second = 
            calculate_memory_operation_rate(now);
            
        return stats;
    }
};

To test the monitoring system in VS Code's integrated terminal:

cd src/monitor
g++ -o monitor_test system_monitor.cpp statistics_collector.cpp -pthread
./monitor_test

The monitoring system will display real-time statistics in VS Code's output pane.

Magic-1 Emulator Enhanced Features - Part 15: System Recovery and State Persistence

Let's implement a system for saving and restoring emulator state and handling recovery scenarios.

State Persistence Manager

class StatePersistenceManager {
    struct SystemState {
        // CPU State
        struct {
            uint16_t msw;
            uint16_t pc;
            uint16_t sp;
            uint16_t registers[8];
            uint64_t cycle_count;
        } cpu;

        // Memory State 
        struct {
            std::vector<uint8_t> ram;
            std::vector<uint8_t> device_sram;
            bool paging_enabled;
            uint16_t page_table_base;
        } memory;

        // Device State
        struct {
            uint8_t uart_registers[8];
            uint8_t rtc_state;
            std::vector<uint8_t> cf_card_buffer;
        } devices;

        // Timestamp and metadata
        uint64_t timestamp;
        std::string version;
        std::string description;
    };

    bool save_state(const std::string& filename) {
        try {
            nlohmann::json state;
            capture_current_state(state);
            
            std::ofstream file(filename);
            file << state.dump(4);
            return true;
        } catch (const std::exception& e) {
            logger->error("Failed to save state: {}", e.what());
            return false;
        }
    }
};

Recovery Handler

class RecoveryHandler {
    enum class RecoveryAction {
        CONTINUE,
        RESTART,
        RESTORE_CHECKPOINT,
        HALT
    };

    struct RecoveryPoint {
        uint64_t timestamp;
        std::string description;
        std::string state_file;
        bool valid;
    };

    RecoveryAction handle_error(const std::string& error) {
        logger->warn("Handling error: {}", error);
        
        // Try to recover from last valid state
        if (auto checkpoint = find_latest_checkpoint()) {
            if (restore_checkpoint(*checkpoint)) {
                return RecoveryAction::CONTINUE;
            }
        }
        
        return RecoveryAction::HALT;
    }
};

Test the recovery system in VS Code's integrated terminal:

cd src/recovery
g++ -o recovery_test state_manager.cpp recovery_handler.cpp
./recovery_test

This will demonstrate state saving/loading and recovery from simulated errors.

Magic-1 CF Card Image Editor

Let's create a system to edit the contents of CF card images while maintaining Magic-1 filesystem compatibility.

CF Card Image Manager

class CFCardImageManager {
private:
    struct FileEntry {
        char name[16];        // Magic-1 filename format
        uint16_t start_sector;
        uint16_t size;        // In sectors
        uint8_t attributes;   // File attributes
        uint8_t reserved[8];  // Reserved for filesystem
    };

    struct DirectoryBlock {
        uint16_t magic;       // Magic number for directory
        uint16_t num_entries;
        FileEntry entries[32];
        uint8_t reserved[32]; // Reserved for filesystem
    };

    std::vector<uint8_t> card_image;
    DirectoryBlock root_dir;
    static constexpr uint16_t SECTOR_SIZE = 512;
    static constexpr uint16_t DIR_START_SECTOR = 2;

public:
    bool mount_image(const std::string& filename) {
        std::ifstream file(filename, std::ios::binary);
        if (!file) return false;

        // Read entire CF card image
        card_image.assign(
            std::istreambuf_iterator<char>(file),
            std::istreambuf_iterator<char>());

        // Read root directory
        memcpy(&root_dir, 
               &card_image[DIR_START_SECTOR * SECTOR_SIZE],
               sizeof(DirectoryBlock));

        return root_dir.magic == 0x4D31; // "M1"
    }

    bool add_file(const std::string& host_path, 
                 const std::string& m1_filename) {
        // Validate filename length for Magic-1
        if (m1_filename.length() > 15) return false;

        // Read host file
        std::ifstream file(host_path, std::ios::binary);
        if (!file) return false;

        std::vector<uint8_t> contents(
            std::istreambuf_iterator<char>(file),
            std::istreambuf_iterator<char>());

        // Find free sectors
        uint16_t needed_sectors = 
            (contents.size() + SECTOR_SIZE - 1) / SECTOR_SIZE;
        uint16_t start_sector = find_free_sectors(needed_sectors);

        // Add directory entry
        FileEntry entry{};
        strncpy(entry.name, m1_filename.c_str(), 15);
        entry.start_sector = start_sector;
        entry.size = needed_sectors;

        // Write file contents to image
        for(uint16_t i = 0; i < needed_sectors; i++) {
            write_sector(start_sector + i,
                        &contents[i * SECTOR_SIZE]);
        }

        return true;
    }
};

Interactive CF Card Editor

class CFCardEditor {
public:
    void run_editor() {
        while(true) {
            std::cout << "CF Card Editor > ";
            std::string cmd;
            std::getline(std::cin, cmd);

            if(cmd == "ls") {
                list_files();
            }
            else if(cmd.substr(0,3) == "add") {
                add_file_interactive();
            }
            else if(cmd.substr(0,3) == "rm") {
                remove_file(cmd.substr(3));
            }
            else if(cmd == "help") {
                show_help();
            }
            else if(cmd == "exit") {
                break;
            }
        }
    }
};

Test the CF card editor in VS Code's integrated terminal:

cd src/cfcard
g++ -o cf_editor image_manager.cpp editor.cpp
./cf_editor system.img

This will open an interactive editor for the CF card image. You can:

  • List files
  • Add new files
  • Remove files
  • Extract files
  • View file contents

The editor maintains Magic-1 filesystem compatibility while allowing easy modification of the CF card contents.

Magic-1 Emulator Enhanced Features - Part 17: CF Card Filesystem Management

CF Card Filesystem Implementation

First, let's create a proper filesystem manager for the Magic-1 CF card:

#include <vector>
#include <string>
#include <cstdint>

class Magic1Filesystem {
private:
    // Magic-1 filesystem constants
    static constexpr uint16_t SECTOR_SIZE = 512;
    static constexpr uint16_t ROOT_DIR_SECTOR = 2;
    static constexpr uint16_t SECTORS_PER_IMAGE = 256;
    
    struct FileSystemHeader {
        uint16_t magic;           // Magic number 'M1'
        uint8_t version;          // Filesystem version
        uint8_t flags;            // Filesystem flags
        uint16_t total_sectors;   // Total sectors on device
        uint16_t free_sectors;    // Number of free sectors
        uint8_t reserved[8];      // Reserved for future use
    } __attribute__((packed));
    
    struct DirectoryEntry {
        char name[16];           // Zero-terminated filename
        uint16_t start_sector;   // Starting sector
        uint16_t sector_count;   // Number of sectors
        uint8_t attributes;      // File attributes
        uint8_t checksum;        // Entry checksum
        uint8_t reserved[8];     // Reserved for future use
    } __attribute__((packed));
    
public:
    bool mount(const std::vector<uint8_t>& image_data) {
        if (image_data.size() < SECTOR_SIZE * 3) {
            return false;
        }
        
        // Read filesystem header
        FileSystemHeader header;
        memcpy(&header, &image_data[SECTOR_SIZE], sizeof(header));
        
        // Verify magic number
        if (header.magic != 0x314D) { // '1M'
            return false;
        }
        
        // Read root directory
        read_directory(image_data);
        return true;
    }
    
    void list_files() {
        for (const auto& entry : directory) {
            if (entry.name[0] != 0) {
                printf("%-16s %5d sectors  %c%c%c\n",
                    entry.name,
                    entry.sector_count,
                    entry.attributes & 0x01 ? 'R' : '-',
                    entry.attributes & 0x02 ? 'W' : '-',
                    entry.attributes & 0x04 ? 'X' : '-');
            }
        }
    }
};

To test this implementation in VS Code:

  1. Create a test file:
#include "filesystem.h"
#include <iostream>

int main() {
    // Load CF card image
    std::ifstream cf_image("magic1.img", std::ios::binary);
    std::vector<uint8_t> image_data(
        (std::istreambuf_iterator<char>(cf_image)),
        std::istreambuf_iterator<char>()
    );
    
    Magic1Filesystem fs;
    if (!fs.mount(image_data)) {
        std::cerr << "Failed to mount filesystem\n";
        return 1;
    }
    
    fs.list_files();
    return 0;
}
  1. Build and run in VS Code's integrated terminal:
cd src/cfcard
g++ -o test_fs test_filesystem.cpp -Wall -Wextra
./test_fs

Magic-1 Emulator Enhanced Features - Part 18: File Operations Implementation

File System Operations

Let's implement comprehensive file operations for the Magic-1 CF card filesystem.

File Operations Manager

class Magic1FileOperations {
private:
    struct FileDescriptor {
        DirectoryEntry* entry;
        uint16_t current_sector;
        uint16_t sector_offset;
        uint8_t access_mode;
        bool modified;
    };

    std::vector<FileDescriptor> open_files;
    Magic1Filesystem* fs;

public:
    enum AccessMode {
        READ = 0x01,
        WRITE = 0x02,
        APPEND = 0x04
    };

    bool create_file(const char* name, uint16_t initial_size) {
        // Validate filename against Magic-1 constraints
        if (strlen(name) > 15 || !is_valid_filename(name)) {
            return false;
        }

        DirectoryEntry entry{};
        strncpy(entry.name, name, 15);
        entry.start_sector = allocate_sectors(initial_size);
        entry.sector_count = initial_size;
        entry.attributes = 0x03;  // RW access
        entry.checksum = calculate_checksum(&entry);

        return add_directory_entry(entry);
    }

    FileDescriptor* open_file(const char* name, uint8_t mode) {
        auto* entry = find_directory_entry(name);
        if (!entry) return nullptr;

        // Validate access permissions
        if ((mode & WRITE) && !(entry->attributes & 0x02)) {
            return nullptr;
        }

        FileDescriptor fd{};
        fd.entry = entry;
        fd.current_sector = entry->start_sector;
        fd.sector_offset = 0;
        fd.access_mode = mode;
        fd.modified = false;

        open_files.push_back(fd);
        return &open_files.back();
    }
};

File System Utility Functions

class Magic1FSUtils {
public:
    static bool is_valid_filename(const char* name) {
        // Magic-1 filename constraints
        if (!name || !*name) return false;
        
        // Check length and valid characters
        size_t len = strlen(name);
        if (len > 15) return false;

        for (size_t i = 0; i < len; i++) {
            char c = name[i];
            if (!isalnum(c) && c != '.' && c != '_') {
                return false;
            }
        }
        return true;
    }

    static uint8_t calculate_checksum(const DirectoryEntry* entry) {
        uint8_t sum = 0;
        const uint8_t* data = (const uint8_t*)entry;
        // Skip checksum field itself
        for (size_t i = 0; i < sizeof(DirectoryEntry)-1; i++) {
            sum += data[i];
        }
        return ~sum + 1;  // Two's complement
    }
};

To test these implementations in VS Code:

  1. Open integrated terminal
  2. Run these commands:
cd src/cfcard
g++ -o test_ops test_file_operations.cpp file_operations.cpp fs_utils.cpp -Wall -Wextra
./test_ops

Magic-1 Emulator Enhanced Features - Part 19: File Content Operations

File Content Manager

Let's implement functions to manipulate file contents while maintaining Magic-1 compatibility:

#include <vector>
#include <cstdint>
#include <string>

class FileContentManager {
private:
    static constexpr uint16_t SECTOR_SIZE = 512;
    static constexpr uint16_t MAX_FILE_SIZE = 65535;

    struct FileBuffer {
        std::vector<uint8_t> data;
        bool modified;
        uint16_t current_position;
    };

public:
    ssize_t read_file_content(FileDescriptor* fd, uint8_t* buffer, size_t count) {
        if (!(fd->access_mode & AccessMode::READ)) {
            return -1;
        }

        size_t bytes_read = 0;
        while (bytes_read < count) {
            // Read current sector
            uint8_t sector_buffer[SECTOR_SIZE];
            if (!read_sector(fd->current_sector, sector_buffer)) {
                break;
            }

            // Copy data from sector
            size_t remaining = SECTOR_SIZE - fd->sector_offset;
            size_t to_copy = std::min(remaining, count - bytes_read);
            memcpy(buffer + bytes_read, 
                   sector_buffer + fd->sector_offset, 
                   to_copy);

            bytes_read += to_copy;
            fd->sector_offset += to_copy;

            // Move to next sector if needed
            if (fd->sector_offset >= SECTOR_SIZE) {
                fd->current_sector++;
                fd->sector_offset = 0;
            }
        }

        return bytes_read;
    }

    bool write_file_content(FileDescriptor* fd, 
                          const uint8_t* buffer, 
                          size_t count) {
        if (!(fd->access_mode & AccessMode::WRITE)) {
            return false;
        }

        size_t bytes_written = 0;
        while (bytes_written < count) {
            uint8_t sector_buffer[SECTOR_SIZE];
            
            // Read existing sector if we're not overwriting completely
            if (fd->sector_offset > 0 || 
                (count - bytes_written) < SECTOR_SIZE) {
                read_sector(fd->current_sector, sector_buffer);
            }

            // Copy data to sector buffer
            size_t remaining = SECTOR_SIZE - fd->sector_offset;
            size_t to_copy = std::min(remaining, count - bytes_written);
            memcpy(sector_buffer + fd->sector_offset,
                   buffer + bytes_written,
                   to_copy);

            // Write sector back
            if (!write_sector(fd->current_sector, sector_buffer)) {
                return false;
            }

            bytes_written += to_copy;
            fd->sector_offset += to_copy;
            fd->modified = true;

            // Move to next sector if needed
            if (fd->sector_offset >= SECTOR_SIZE) {
                fd->current_sector++;
                fd->sector_offset = 0;
            }
        }

        return true;
    }
};

Test these operations in VS Code's integrated terminal:

cd src/cfcard
g++ -o test_content file_content_manager.cpp file_operations.cpp fs_utils.cpp
./test_content

The test program will demonstrate reading and writing file contents while maintaining Magic-1 filesystem compatibility.

Magic-1 Emulator Enhanced Features - Part 20: File System Integrity

File System Integrity Checker

Let's implement a comprehensive integrity checking and repair system for the Magic-1 CF card filesystem:

class FilesystemIntegrityChecker {
private:
    struct IntegrityReport {
        uint32_t total_sectors;
        uint32_t used_sectors;
        uint32_t free_sectors;
        uint32_t bad_sectors;
        std::vector<std::string> errors;
        std::vector<std::string> warnings;
    };

    Magic1Filesystem* fs;
    IntegrityReport report;

public:
    bool check_filesystem_integrity() {
        report = IntegrityReport{};
        
        // Check filesystem header
        if (!verify_fs_header()) {
            report.errors.push_back("Invalid filesystem header");
            return false;
        }

        // Check directory structure
        verify_directory_entries();

        // Check sector allocation
        verify_sector_allocation();

        // Check file checksums
        verify_file_checksums();

        return report.errors.empty();
    }
};

Repair Functions

class FilesystemRepair {
public:
    enum class RepairAction {
        REBUILD_DIRECTORY,
        RECOVER_LOST_CLUSTERS,
        FIX_CHECKSUMS,
        REALLOCATE_BAD_SECTORS
    };

    bool repair_filesystem() {
        // Take backup before repairs
        if (!backup_filesystem()) {
            return false;
        }

        bool success = true;
        success &= rebuild_directory();
        success &= recover_lost_clusters();
        success &= fix_checksums();
        success &= reallocate_bad_sectors();

        return success;
    }

    bool rebuild_directory() {
        std::vector<DirectoryEntry> recovered_entries;
        
        // Scan all sectors for valid file headers
        for (uint32_t sector = 0; sector < fs->total_sectors; sector++) {
            if (is_valid_file_header(sector)) {
                DirectoryEntry entry = reconstruct_directory_entry(sector);
                recovered_entries.push_back(entry);
            }
        }

        return write_recovered_directory(recovered_entries);
    }
};

Test the integrity checker in VS Code's integrated terminal:

cd src/cfcard
g++ -o fsck fs_integrity.cpp fs_repair.cpp
./fsck magic1.img

This will check the filesystem integrity and attempt repairs if needed. The results will be shown in VS Code's output pane.

Magic-1 Emulator Enhanced Features - Part 21: Filesystem Backup and Restore

Let's implement a robust backup and restore system for the Magic-1 CF card filesystem.

Filesystem Backup Manager

First, let's create a backup manager that handles both full and incremental backups:

class Magic1BackupManager {
private:
    struct BackupHeader {
        uint32_t magic;          // 'M1BK'
        uint8_t version;         // Backup format version
        uint8_t backup_type;     // 0=full, 1=incremental
        uint32_t timestamp;      // Unix timestamp
        uint16_t num_files;      // Number of files in backup
        uint8_t checksum[32];    // SHA-256 of backup content
    } __attribute__((packed));

    struct BackupFileEntry {
        char name[16];           // Original filename
        uint32_t size;          // File size in bytes
        uint32_t timestamp;     // File modification time
        uint16_t attributes;    // Original file attributes
        uint8_t checksum[32];   // SHA-256 of file content
    } __attribute__((packed));

public:
    bool create_backup(const std::string& backup_path) {
        try {
            // Open backup file
            std::ofstream backup(backup_path, std::ios::binary);
            if (!backup) return false;

            // Write backup header
            BackupHeader header{
                .magic = 0x4B42314D,  // 'M1BK'
                .version = 1,
                .backup_type = 0,     // Full backup
                .timestamp = static_cast<uint32_t>(time(nullptr)),
                .num_files = count_files()
            };

            backup.write(reinterpret_cast<char*>(&header), sizeof(header));

            // Backup each file
            for (const auto& file : enumerate_files()) {
                if (!backup_file(backup, file)) {
                    return false;
                }
            }

            return true;
        } catch (const std::exception& e) {
            logger->error("Backup failed: {}", e.what());
            return false;
        }
    }
};

Restore Manager

Now let's implement the restore functionality:

class Magic1RestoreManager {
private:
    // Tracks restore progress
    struct RestoreProgress {
        uint32_t total_files;
        uint32_t restored_files;
        uint32_t failed_files;
        std::vector<std::string> errors;
    } progress;

public:
    bool restore_from_backup(const std::string& backup_path) {
        try {
            // Open and validate backup
            std::ifstream backup(backup_path, std::ios::binary);
            if (!backup || !validate_backup_header(backup)) {
                return false;
            }

            // Clear filesystem if full restore
            BackupHeader header;
            backup.read(reinterpret_cast<char*>(&header), sizeof(header));
            if (header.backup_type == 0) {
                format_filesystem();
            }

            // Restore files
            for (uint16_t i = 0; i < header.num_files; i++) {
                if (!restore_file(backup)) {
                    progress.failed_files++;
                } else {
                    progress.restored_files++;
                }
            }

            return progress.failed_files == 0;
        } catch (const std::exception& e) {
            logger->error("Restore failed: {}", e.what());
            return false;
        }
    }
};

Test the backup and restore functionality in VS Code's integrated terminal:

cd src/cfcard
g++ -o backup_test backup_manager.cpp restore_manager.cpp -lcrypto
./backup_test magic1.img

This will create a backup of your Magic-1 CF card image and verify its integrity. The backup file can be used to restore the filesystem to a known good state.

Magic-1 Emulator Enhanced Features - Part 22: Filesystem Versioning and Snapshots

Snapshot Management System

First, let's implement a versioning system for the Magic-1 filesystem:

class Magic1VersionControl {
private:
    struct SnapshotHeader {
        uint32_t magic;          // 'M1SN'
        uint32_t version;        // Snapshot version number
        uint32_t timestamp;      // Unix timestamp
        uint32_t parent_version; // Previous version (0 if none)
        uint8_t description[64]; // User-provided description
        uint8_t checksum[32];    // SHA-256 of snapshot content
    };

    struct FileVersion {
        char name[16];          // Magic-1 filename
        uint32_t version;       // File version number
        uint32_t size;          // File size in bytes
        uint8_t checksum[32];   // Content checksum
    };

public:
    bool create_snapshot(const std::string& description) {
        try {
            SnapshotHeader header{
                .magic = 0x4E53314D,  // 'M1SN'
                .version = get_next_version(),
                .timestamp = static_cast<uint32_t>(time(nullptr)),
                .parent_version = current_version
            };
            
            strncpy(reinterpret_cast<char*>(header.description), 
                   description.c_str(), 63);

            // Store snapshot in special system area
            uint32_t snapshot_sector = find_snapshot_sector();
            write_snapshot_header(snapshot_sector, header);
            
            // Save current file versions
            std::vector<FileVersion> files;
            for (const auto& file : enumerate_files()) {
                files.push_back(create_file_version(file));
            }
            
            write_file_versions(snapshot_sector + 1, files);
            update_current_version(header.version);
            
            return true;
        } catch (const std::exception& e) {
            logger->error("Snapshot creation failed: {}", e.what());
            return false;
        }
    }
};

To test the versioning system in VS Code's integrated terminal:

# Compile and run the version control test
cd src/cfcard
g++ -o version_test version_control.cpp -lcrypto
./version_test magic1.img

This will demonstrate:

  1. Creating snapshots
  2. Managing versions
  3. Tracking file changes
  4. Restoring previous versions

The snapshot system maintains compatibility with the Magic-1 filesystem by storing version data in reserved system sectors.

Magic-1 Emulator SLIP Implementation

Let's implement SLIP (Serial Line Internet Protocol) support for the Magic-1 emulator to enable network connectivity similar to the real hardware.

SLIP Protocol Implementation

class SlipProtocol {
private:
    static constexpr uint8_t SLIP_END = 0xC0;
    static constexpr uint8_t SLIP_ESC = 0xDB;
    static constexpr uint8_t SLIP_ESC_END = 0xDC;
    static constexpr uint8_t SLIP_ESC_ESC = 0xDD;

    // Buffer for packet assembly
    std::vector<uint8_t> receive_buffer;
    std::vector<uint8_t> transmit_buffer;

public:
    // Encode packet for SLIP transmission
    std::vector<uint8_t> encode_packet(const std::vector<uint8_t>& packet) {
        std::vector<uint8_t> encoded;
        encoded.push_back(SLIP_END);  // Start packet

        for(uint8_t byte : packet) {
            if(byte == SLIP_END) {
                encoded.push_back(SLIP_ESC);
                encoded.push_back(SLIP_ESC_END);
            } else if(byte == SLIP_ESC) {
                encoded.push_back(SLIP_ESC);
                encoded.push_back(SLIP_ESC_ESC);
            } else {
                encoded.push_back(byte);
            }
        }

        encoded.push_back(SLIP_END);  // End packet
        return encoded;
    }

    // Decode received SLIP data
    std::optional<std::vector<uint8_t>> decode_packet(uint8_t byte) {
        static bool escape = false;
        
        if(byte == SLIP_END) {
            if(!receive_buffer.empty()) {
                auto packet = receive_buffer;
                receive_buffer.clear();
                return packet;
            }
            return std::nullopt;
        }

        if(byte == SLIP_ESC) {
            escape = true;
            return std::nullopt;
        }

        if(escape) {
            if(byte == SLIP_ESC_END) {
                receive_buffer.push_back(SLIP_END);
            } else if(byte == SLIP_ESC_ESC) {
                receive_buffer.push_back(SLIP_ESC);
            }
            escape = false;
        } else {
            receive_buffer.push_back(byte);
        }

        return std::nullopt;
    }
};

UART Integration with SLIP

class UartSlip : public UartDevice {
private:
    SlipProtocol slip;
    TunInterface tun;  // Virtual network interface
    bool slip_enabled;

public:
    UartSlip() : slip_enabled(false) {
        // Initialize TUN interface for network connectivity
        if(tun.create("magic1")) {
            slip_enabled = true;
        }
    }

    void write_data(uint8_t data) override {
        if(!slip_enabled) {
            UartDevice::write_data(data);
            return;
        }

        // Process SLIP data
        if(auto packet = slip.decode_packet(data)) {
            // Forward decoded packet to TUN interface
            tun.write_packet(*packet);
        }
    }

    uint8_t read_data() override {
        if(!slip_enabled) {
            return UartDevice::read_data();
        }

        // Check TUN interface for outgoing packets
        if(auto packet = tun.read_packet()) {
            auto encoded = slip.encode_packet(*packet);
            // Queue encoded data for transmission
            transmit_buffer.insert(
                transmit_buffer.end(),
                encoded.begin(),
                encoded.end()
            );
        }

        // Return next byte from transmit buffer
        if(!transmit_buffer.empty()) {
            uint8_t data = transmit_buffer.front();
            transmit_buffer.erase(transmit_buffer.begin());
            return data;
        }

        return 0;
    }
};

Test the SLIP implementation in VS Code's integrated terminal:

# Install TUN/TAP prerequisites
sudo apt-get install uml-utilities

# Build and test SLIP implementation
cd src/network
g++ -o slip_test slip.cpp uart_slip.cpp tun_interface.cpp
sudo ./slip_test

# Create TUN interface (needs root)
sudo ip tuntap add mode tun name magic1
sudo ip link set magic1 up
sudo ip addr add 192.168.7.1/24 dev magic1

This implementation allows the emulator to:

  1. Communicate using SLIP protocol
  2. Create a virtual network interface
  3. Exchange packets with the host system
  4. Maintain compatibility with the real Magic-1's networking capabilities

Magic-1 Network Stack Implementation - TUN/TAP Interface

Let's implement the network stack for Magic-1 emulator using TUN/TAP interfaces.

Core Network Interface

#include <fcntl.h>
#include <linux/if.h>
#include <linux/if_tun.h>
#include <sys/ioctl.h>
#include <vector>

class TunInterface {
private:
    int tun_fd;
    std::string interface_name;
    static constexpr int MTU = 1500;

public:
    bool create(const std::string& name) {
        struct ifreq ifr;
        int err;

        tun_fd = open("/dev/net/tun", O_RDWR);
        if (tun_fd < 0) {
            return false;
        }

        memset(&ifr, 0, sizeof(ifr));
        ifr.ifr_flags = IFF_TUN | IFF_NO_PI;
        strncpy(ifr.ifr_name, name.c_str(), IFNAMSIZ);

        err = ioctl(tun_fd, TUNSETIFF, &ifr);
        if (err < 0) {
            close(tun_fd);
            return false;
        }

        interface_name = name;
        return true;
    }

    std::vector<uint8_t> read_packet() {
        std::vector<uint8_t> buffer(MTU);
        int len = read(tun_fd, buffer.data(), buffer.size());
        if (len > 0) {
            buffer.resize(len);
            return buffer;
        }
        return std::vector<uint8_t>();
    }

    bool write_packet(const std::vector<uint8_t>& packet) {
        return write(tun_fd, packet.data(), packet.size()) == 
               static_cast<ssize_t>(packet.size());
    }
};

Network Configuration Script

Create a setup script for the TUN interface:

#!/bin/bash

# Create TUN interface
sudo ip tuntap add dev magic1 mode tun
sudo ip link set magic1 up

# Configure IP addressing
sudo ip addr add 192.168.7.1/24 dev magic1

# Enable IP forwarding
sudo sysctl -w net.ipv4.ip_forward=1

# Setup NAT for internet access
sudo iptables -t nat -A POSTROUTING -s 192.168.7.0/24 -o eth0 -j MASQUERADE

Make the script executable and run it:

chmod +x scripts/setup_network.sh
sudo ./scripts/setup_network.sh

This creates the network interface and sets up routing for the Magic-1 emulator. The emulator will be able to communicate with the host system and access the internet through NAT, just like the real Magic-1.

Magic-1 Network Stack - SLIP Handler Implementation

Let's implement a robust SLIP handler that integrates with both the emulator's UART and the host system's network stack.

Core SLIP Handler

#include <queue>
#include <mutex>
#include <condition_variable>

class SlipHandler {
private:
    enum class SlipState {
        IDLE,
        RECEIVING,
        ESCAPING
    };

    struct SlipStatistics {
        uint32_t packets_received;
        uint32_t packets_sent;
        uint32_t errors;
        uint32_t bytes_received;
        uint32_t bytes_sent;
    } stats;

    std::queue<std::vector<uint8_t>> tx_queue;
    std::vector<uint8_t> rx_buffer;
    SlipState state;
    std::mutex mutex;
    std::condition_variable cv;

public:
    void process_byte(uint8_t byte) {
        std::lock_guard<std::mutex> lock(mutex);
        
        switch(state) {
            case SlipState::IDLE:
                if(byte == SLIP_END) {
                    state = SlipState::RECEIVING;
                    rx_buffer.clear();
                }
                break;

            case SlipState::RECEIVING:
                if(byte == SLIP_END) {
                    if(!rx_buffer.empty()) {
                        handle_complete_packet();
                    }
                    state = SlipState::IDLE;
                } else if(byte == SLIP_ESC) {
                    state = SlipState::ESCAPING;
                } else {
                    rx_buffer.push_back(byte);
                }
                break;

            case SlipState::ESCAPING:
                if(byte == SLIP_ESC_END) {
                    rx_buffer.push_back(SLIP_END);
                } else if(byte == SLIP_ESC_ESC) {
                    rx_buffer.push_back(SLIP_ESC);
                }
                state = SlipState::RECEIVING;
                break;
        }
    }
};

UART Integration Layer

class UartSlipInterface {
private:
    SlipHandler slip;
    TunInterface tun;
    bool slip_enabled;
    std::thread network_thread;

public:
    void handle_uart_interrupt() {
        if(!slip_enabled) return;

        // Handle received data from UART
        while(uart->has_data()) {
            uint8_t data = uart->read_data();
            slip.process_byte(data);
        }

        // Check for network packets to send
        if(auto packet = tun.read_packet()) {
            enqueue_packet(*packet);
        }
    }
};

Test the SLIP implementation in VS Code's integrated terminal:

# Build the SLIP handler
cd src/network
g++ -o slip_test slip_handler.cpp uart_slip_interface.cpp -pthread

# Run tests
./slip_test

This implementation:

  • Handles SLIP protocol encapsulation/decapsulation
  • Manages packet queuing and transmission
  • Provides statistics and error tracking
  • Integrates with the Magic-1's UART emulation
  • Maintains thread safety for concurrent operation

Magic-1 Network Stack - Packet Handler Implementation

Let's create a robust packet handling system that integrates with the SLIP protocol and TUN interface.

First, create the packet handler:

#include <atomic>
#include <thread>
#include <queue>
#include <mutex>

class PacketHandler {
    struct PacketStats {
        std::atomic<uint64_t> packets_received{0};
        std::atomic<uint64_t> packets_sent{0};
        std::atomic<uint64_t> bytes_received{0};
        std::atomic<uint64_t> bytes_sent{0};
        std::atomic<uint64_t> errors{0};
    } stats;

    struct NetworkPacket {
        std::vector<uint8_t> data;
        uint64_t timestamp;
        bool outbound;
    };

    std::queue<NetworkPacket> tx_queue;
    std::queue<NetworkPacket> rx_queue;
    std::mutex queue_mutex;
    std::atomic<bool> running{false};
    std::thread worker_thread;

public:
    void start() {
        running = true;
        worker_thread = std::thread([this]() {
            while (running) {
                process_queues();
                std::this_thread::sleep_for(std::chrono::milliseconds(1));
            }
        });
    }

    void queue_packet(const std::vector<uint8_t>& data, bool outbound) {
        std::lock_guard<std::mutex> lock(queue_mutex);
        auto& queue = outbound ? tx_queue : rx_queue;
        queue.push({data, get_timestamp(), outbound});
    }

private:
    void process_queues() {
        std::lock_guard<std::mutex> lock(queue_mutex);
        
        // Process outbound packets
        while (!tx_queue.empty()) {
            auto packet = tx_queue.front();
            if (send_packet(packet)) {
                stats.packets_sent++;
                stats.bytes_sent += packet.data.size();
            } else {
                stats.errors++;
            }
            tx_queue.pop();
        }

        // Process inbound packets
        while (!rx_queue.empty()) {
            auto packet = rx_queue.front();
            if (process_received_packet(packet)) {
                stats.packets_received++;
                stats.bytes_received += packet.data.size();
            } else {
                stats.errors++;
            }
            rx_queue.pop();
        }
    }
};

Create a test file to verify the packet handler:

#include "packet_handler.h"
#include <gtest/gtest.h>

TEST(PacketHandlerTest, BasicPacketHandling) {
    PacketHandler handler;
    
    // Create test packet
    std::vector<uint8_t> test_data = {0x45, 0x00, 0x00, 0x28}; // IPv4 header
    
    // Queue outbound packet
    handler.queue_packet(test_data, true);
    
    // Verify statistics
    EXPECT_EQ(handler.get_stats().packets_sent, 1);
    EXPECT_EQ(handler.get_stats().bytes_sent, test_data.size());
    EXPECT_EQ(handler.get_stats().errors, 0);
}

Run the tests in VS Code's integrated terminal:

cd src/network
g++ -o test_packet test_packet_handler.cpp -lgtest -lgtest_main -pthread
./test_packet

Magic-1 Network Stack - Statistics and Monitoring

Let's implement network monitoring and statistics tracking for the Magic-1 emulator's network stack.

Network Statistics Manager

#include <atomic>
#include <chrono>
#include <string>
#include <map>

class NetworkStats {
private:
    struct InterfaceStats {
        std::atomic<uint64_t> rx_packets{0};
        std::atomic<uint64_t> tx_packets{0};
        std::atomic<uint64_t> rx_bytes{0};
        std::atomic<uint64_t> tx_bytes{0};
        std::atomic<uint64_t> rx_errors{0};
        std::atomic<uint64_t> tx_errors{0};
        std::atomic<uint64_t> collisions{0};
        std::chrono::steady_clock::time_point last_update;
    };

    std::map<std::string, InterfaceStats> interfaces;
    std::mutex stats_mutex;

public:
    void update_stats(const std::string& interface, 
                     const std::vector<uint8_t>& packet, 
                     bool is_tx) {
        std::lock_guard<std::mutex> lock(stats_mutex);
        auto& stats = interfaces[interface];
        
        if (is_tx) {
            stats.tx_packets++;
            stats.tx_bytes += packet.size();
        } else {
            stats.rx_packets++;
            stats.rx_bytes += packet.size();
        }
        stats.last_update = std::chrono::steady_clock::now();
    }

    std::string get_stats_report() {
        std::stringstream ss;
        std::lock_guard<std::mutex> lock(stats_mutex);

        for (const auto& [iface, stats] : interfaces) {
            ss << fmt::format("Interface: {}\n", iface);
            ss << fmt::format("  RX: {} packets, {} bytes\n", 
                            stats.rx_packets.load(), 
                            stats.rx_bytes.load());
            ss << fmt::format("  TX: {} packets, {} bytes\n", 
                            stats.tx_packets.load(), 
                            stats.tx_bytes.load());
            ss << fmt::format("  Errors: RX={}, TX={}\n", 
                            stats.rx_errors.load(), 
                            stats.tx_errors.load());
        }
        return ss.str();
    }
};

Network Monitor Implementation

#include <ncurses.h>

class NetworkMonitor {
private:
    NetworkStats& stats;
    WINDOW* stats_win;
    bool running;
    std::thread update_thread;

public:
    NetworkMonitor(NetworkStats& stats) : stats(stats) {
        initscr();
        start_color();
        init_pair(1, COLOR_GREEN, COLOR_BLACK);
        init_pair(2, COLOR_RED, COLOR_BLACK);
        
        stats_win = newwin(LINES-2, COLS-2, 1, 1);
        box(stats_win, 0, 0);
    }

    void start() {
        running = true;
        update_thread = std::thread([this]() {
            while (running) {
                update_display();
                std::this_thread::sleep_for(
                    std::chrono::milliseconds(100));
            }
        });
    }

    void update_display() {
        werase(stats_win);
        box(stats_win, 0, 0);
        mvwprintw(stats_win, 0, 2, " Magic-1 Network Monitor ");
        
        std::string report = stats.get_stats_report();
        mvwprintw(stats_win, 2, 2, "%s", report.c_str());
        
        wrefresh(stats_win);
    }
};

Test the network monitoring in VS Code's integrated terminal:

cd src/network
g++ -o netmon network_monitor.cpp network_stats.cpp -lncurses -pthread
./netmon

This will show a real-time display of network statistics for the Magic-1 emulator's network interface.

Magic-1 Network Stack - Packet Capture and Analysis

Let's implement packet capture and analysis capabilities for debugging the Magic-1's network communications:

#include <pcap/pcap.h>
#include <thread>
#include <atomic>
#include <filesystem>

class PacketCapture {
private:
    pcap_t* pcap_handle;
    pcap_dumper_t* dumper;
    std::string capture_file;
    std::atomic<bool> capturing{false};
    std::thread capture_thread;
    
    struct CaptureStats {
        uint64_t packets_captured;
        uint64_t bytes_captured;
        std::chrono::steady_clock::time_point start_time;
    } stats;

public:
    bool start_capture(const std::string& interface_name) {
        char errbuf[PCAP_ERRBUF_SIZE];
        
        pcap_handle = pcap_create(interface_name.c_str(), errbuf);
        if (!pcap_handle) {
            return false;
        }

        // Set capture parameters
        pcap_set_snaplen(pcap_handle, 65535);
        pcap_set_promisc(pcap_handle, 1);
        pcap_set_timeout(pcap_handle, 1000);

        // Create output file
        capture_file = fmt::format("magic1_capture_{}.pcap", 
                                 std::time(nullptr));
        dumper = pcap_dump_open(pcap_handle, capture_file.c_str());

        capturing = true;
        capture_thread = std::thread(&PacketCapture::capture_loop, this);
        return true;
    }

    void capture_loop() {
        struct pcap_pkthdr* header;
        const u_char* packet;
        
        while (capturing) {
            int ret = pcap_next_ex(pcap_handle, &header, &packet);
            if (ret == 1) {
                pcap_dump((u_char*)dumper, header, packet);
                stats.packets_captured++;
                stats.bytes_captured += header->len;
            }
        }
    }
};

To build and test the packet capture:

  1. Install required dependencies:
sudo apt-get install libpcap-dev
  1. Create a test file:
#include "packet_capture.h"
#include <gtest/gtest.h>

TEST(PacketCaptureTest, BasicCapture) {
    PacketCapture capture;
    ASSERT_TRUE(capture.start_capture("magic1"));
    
    // Wait for some packets
    std::this_thread::sleep_for(std::chrono::seconds(5));
    
    auto stats = capture.get_stats();
    EXPECT_GT(stats.packets_captured, 0);
    EXPECT_GT(stats.bytes_captured, 0);
}
  1. Build and run in VS Code's integrated terminal:
cd src/network
g++ -o test_capture test_capture.cpp -lpcap -lgtest -lgtest_main -pthread
./test_capture

The captured packets can be analyzed using Wireshark or tcpdump to debug Magic-1's network communications.

Magic-1 Protocol Analysis System

Let's implement a protocol analyzer specifically for Magic-1's SLIP and network communications:

#include <memory>
#include <vector>
#include <string>

class ProtocolAnalyzer {
    struct Packet {
        uint64_t timestamp;
        std::vector<uint8_t> raw_data;
        uint16_t protocol;
        std::string source;
        std::string destination;
    };

    struct ProtocolStats {
        uint32_t slip_packets;
        uint32_t ip_packets;
        uint32_t tcp_packets;
        uint32_t udp_packets;
        uint32_t malformed;
    } stats;

public:
    enum class Protocol {
        SLIP = 0x1000,
        IP = 0x0800,
        TCP = 0x06,
        UDP = 0x11
    };

    std::string analyze_packet(const std::vector<uint8_t>& packet) {
        std::stringstream analysis;
        
        // SLIP frame analysis
        if (is_slip_frame(packet)) {
            stats.slip_packets++;
            analysis << format_slip_header(packet);
            
            // Extract IP packet from SLIP frame
            auto ip_packet = extract_ip_packet(packet);
            if (ip_packet) {
                stats.ip_packets++;
                analysis << format_ip_header(*ip_packet);
            }
        }
        
        return analysis.str();
    }
};

Create a live protocol analysis window:

#include <ncurses.h>
#include <panel.h>

class ProtocolDisplay {
private:
    WINDOW* packet_win;
    WINDOW* stats_win;
    std::queue<std::string> packet_log;
    static constexpr size_t MAX_LOG_ENTRIES = 100;

public:
    void init() {
        // Setup ncurses windows
        initscr();
        start_color();
        init_pair(1, COLOR_GREEN, COLOR_BLACK);  // SLIP
        init_pair(2, COLOR_BLUE, COLOR_BLACK);   // IP
        init_pair(3, COLOR_YELLOW, COLOR_BLACK); // TCP/UDP
        
        int max_y, max_x;
        getmaxyx(stdscr, max_y, max_x);
        
        packet_win = newwin(max_y-5, max_x, 0, 0);
        stats_win = newwin(5, max_x, max_y-5, 0);
        
        scrollok(packet_win, TRUE);
    }

    void update_display(const std::string& packet_analysis) {
        packet_log.push(packet_analysis);
        if (packet_log.size() > MAX_LOG_ENTRIES) {
            packet_log.pop();
        }
        
        werase(packet_win);
        for (const auto& entry : packet_log) {
            waddstr(packet_win, entry.c_str());
        }
        wrefresh(packet_win);
    }
};

Test the protocol analyzer in VS Code's integrated terminal:

cd src/network
g++ -o protocol_test protocol_analyzer.cpp protocol_display.cpp -lncurses
./protocol_test

This will show a live display of analyzed packets, with color-coded protocol information and statistics.

Magic-1 Protocol Analysis - SLIP-Specific Features

Let's enhance our protocol analyzer with SLIP-specific features for Magic-1's network communications.

First, create a dedicated SLIP analyzer:

class SlipAnalyzer {
public:
    struct SlipFrame {
        uint64_t timestamp;
        std::vector<uint8_t> raw_data;
        std::vector<uint8_t> decoded_data;
        bool valid_checksum;
        uint16_t frame_length;
        std::string direction;  // "Magic-1 -> Host" or "Host -> Magic-1"
    };

    struct SlipAnalysis {
        uint32_t total_frames;
        uint32_t valid_frames;
        uint32_t invalid_frames;
        double average_frame_size;
        uint32_t escape_sequences;
        std::vector<SlipFrame> recent_frames;
    } analysis;

    SlipAnalysis analyze_stream(const std::vector<uint8_t>& stream) {
        SlipAnalysis current;
        SlipFrame frame;
        bool in_frame = false;
        bool in_escape = false;

        for(const auto& byte : stream) {
            switch(byte) {
                case SLIP_END:
                    if(in_frame && !frame.raw_data.empty()) {
                        finalize_frame(frame, current);
                    }
                    frame = SlipFrame();
                    in_frame = true;
                    break;

                case SLIP_ESC:
                    in_escape = true;
                    current.escape_sequences++;
                    break;

                default:
                    if(in_frame) {
                        if(in_escape) {
                            handle_escape_sequence(byte, frame);
                            in_escape = false;
                        } else {
                            frame.raw_data.push_back(byte);
                        }
                    }
            }
        }

        return current;
    }
};

Now create a SLIP-specific display component:

class SlipDisplay {
private:
    WINDOW* main_win;
    WINDOW* detail_win;
    std::vector<SlipAnalyzer::SlipFrame> frame_history;
    static constexpr size_t MAX_HISTORY = 1000;

public:
    void update_display(const SlipAnalyzer::SlipAnalysis& analysis) {
        werase(main_win);
        box(main_win, 0, 0);
        mvwprintw(main_win, 0, 2, " Magic-1 SLIP Monitor ");

        // Display statistics
        mvwprintw(main_win, 2, 2, "Total Frames: %d", analysis.total_frames);
        mvwprintw(main_win, 3, 2, "Valid/Invalid: %d/%d", 
                 analysis.valid_frames, analysis.invalid_frames);
        mvwprintw(main_win, 4, 2, "Avg Frame Size: %.2f", 
                 analysis.average_frame_size);
        
        // Display recent frames
        int row = 6;
        for(const auto& frame : analysis.recent_frames) {
            display_frame(row++, frame);
        }
        
        wrefresh(main_win);
    }
};

Test the SLIP analyzer in VS Code's integrated terminal:

cd src/network
g++ -o slip_analyzer_test slip_analyzer.cpp slip_display.cpp -lncurses
./slip_analyzer_test

This implementation provides:

  • Real-time SLIP frame analysis
  • Frame validation and statistics
  • Escape sequence handling
  • Detailed frame inspection
  • Historical frame tracking

Let me help evaluate if the Magic-1 CPU implementation is complete. Let's check all required components:

Core CPU Components ✅

  • Register file implementation
  • ALU operations
  • Memory interface
  • Interrupt handling
  • Microcode execution

Missing Critical Components ❌

  1. Pipeline Implementation
  2. Flag Handling
  3. Privileged Instructions
  4. Complete Instruction Set

Let's implement these missing components:

1. Pipeline Implementation

class Magic1Pipeline {
    struct PipelineStage {
        uint16_t instruction;
        uint16_t pc;
        bool valid;
        bool stalled;
    };

    struct {
        PipelineStage fetch;
        PipelineStage decode;
        PipelineStage execute;
        PipelineStage memory;
        PipelineStage writeback;
    } stages;

public:
    void cycle() {
        writeback_stage();
        memory_stage();
        execute_stage();
        decode_stage();
        fetch_stage();
    }
};

2. Flag Handling

class Magic1Flags {
private:
    union {
        struct {
            uint8_t carry:1;
            uint8_t zero:1;
            uint8_t negative:1;
            uint8_t overflow:1;
            uint8_t interrupt_enable:1;
            uint8_t supervisor:1;
            uint8_t reserved:2;
        } bits;
        uint8_t value;
    } flags;

public:
    void update_alu_flags(uint16_t result, bool carry_out) {
        flags.bits.carry = carry_out;
        flags.bits.zero = (result == 0);
        flags.bits.negative = (result & 0x8000) != 0;
    }
};

3. Privileged Instructions

class Magic1PrivilegedOps {
public:
    bool execute_privileged(uint16_t opcode) {
        if (!is_supervisor_mode()) {
            trigger_privilege_violation();
            return false;
        }

        switch(opcode) {
            case 0xF0: return op_halt();
            case 0xF1: return op_iret();
            case 0xF2: return op_cli();
            case 0xF3: return op_sti();
            default: return false;
        }
    }
};

To complete the CPU implementation, you'll need to:

  1. Integrate these components into the main CPU class
  2. Implement remaining instruction set
  3. Add cycle-accurate timing
  4. Add test coverage

Magic-1 CPU Core Implementation

Let's properly implement the core CPU components maintaining accurate Magic-1 architecture specifications.

Core CPU Implementation

class Magic1CPU {
private:
    // CPU Registers
    struct {
        uint16_t msw;          // Machine Status Word
        uint16_t pc;           // Program Counter
        uint16_t sp;           // Stack Pointer
        uint16_t dp;           // Data Pointer
        uint16_t a;            // Accumulator
        uint16_t b;            // General Purpose
        uint16_t c;            // General Purpose
        uint16_t mdr;          // Memory Data Register
        uint16_t mar;          // Memory Address Register
    } regs;

    // CPU State
    struct {
        bool halted;
        bool waiting;
        bool interrupt_pending;
        uint8_t current_mode;   // 0=kernel, 1=user
        uint64_t cycle_count;
        uint16_t micro_pc;      // Microcode Program Counter
    } state;

    // Microcode ROM (56-bit instructions)
    uint64_t microcode_rom[512];

public:
    bool initialize() {
        // Load microcode PROMs
        if (!load_microcode_proms()) {
            return false;
        }

        // Initialize registers
        regs.msw = 0x0000;     // Kernel mode, interrupts disabled
        regs.pc = 0x0000;      // Start at ROM
        regs.sp = 0x8000;      // Initial stack pointer
        
        state.halted = false;
        state.waiting = false;
        state.current_mode = 0;
        state.cycle_count = 0;
        state.micro_pc = 0;

        return true;
    }

    void execute_cycle() {
        if (state.halted) return;

        // Fetch microinstruction
        uint64_t micro_inst = microcode_rom[state.micro_pc];
        
        // Execute microinstruction
        execute_microinstruction(micro_inst);
        
        // Update cycle count
        state.cycle_count++;
        
        // Check for interrupts
        check_interrupts();
    }

private:
    void execute_microinstruction(uint64_t inst) {
        // Decode microinstruction fields
        uint8_t next_addr = (inst >> 48) & 0xFF;
        uint8_t control = (inst >> 40) & 0xFF;
        uint8_t alu_op = (inst >> 32) & 0xFF;
        // ... decode remaining fields ...

        // Execute microinstruction operations
        if (control & CTRL_ALU_OP) execute_alu(alu_op);
        if (control & CTRL_MEM_OP) execute_memory();
        if (control & CTRL_REG_OP) execute_register();

        // Update microcode PC
        state.micro_pc = next_addr;
    }
};

Test the CPU implementation in VS Code's integrated terminal:

cd src/cpu
g++ -o test_cpu magic1_cpu.cpp magic1_cpu_test.cpp -lgtest -lgtest_main -pthread
./test_cpu

Magic-1 ALU and Instruction Set Implementation

Let's implement the ALU and core instruction set following the original Magic-1 specifications.

First, let's create the ALU:

class Magic1ALU {
private:
    struct ALUFlags {
        bool carry;
        bool zero;
        bool negative;
        bool overflow;
    } flags;

    uint16_t accumulator;
    uint16_t temp_register;

public:
    enum Operation {
        ADD = 0x00,
        SUB = 0x01,
        AND = 0x02,
        OR  = 0x03,
        XOR = 0x04,
        SHL = 0x05,
        SHR = 0x06,
        ASR = 0x07
    };

    uint16_t execute(Operation op, uint16_t a, uint16_t b) {
        uint16_t result = 0;
        flags = ALUFlags{};  // Clear flags

        switch(op) {
            case ADD: {
                uint32_t temp = static_cast<uint32_t>(a) + b;
                result = temp & 0xFFFF;
                flags.carry = temp > 0xFFFF;
                break;
            }
            case SUB: {
                result = a - b;
                flags.carry = a >= b;
                break;
            }
            case AND:
                result = a & b;
                break;
            case OR:
                result = a | b;
                break;
            case XOR:
                result = a ^ b;
                break;
            case SHL:
                result = a << (b & 0x0F);
                flags.carry = (a & 0x8000) != 0;
                break;
            case SHR:
                flags.carry = (a & 0x0001) != 0;
                result = a >> (b & 0x0F);
                break;
            case ASR:
                flags.carry = (a & 0x0001) != 0;
                result = static_cast<int16_t>(a) >> (b & 0x0F);
                break;
        }

        flags.zero = result == 0;
        flags.negative = (result & 0x8000) != 0;
        return result;
    }
};

Now let's create the instruction decoder:

class Magic1InstructionDecoder {
public:
    struct DecodedInstruction {
        uint8_t opcode;
        uint8_t reg_dest;
        uint8_t reg_src;
        uint16_t immediate;
        bool uses_immediate;
        uint16_t micro_start;  // Starting microcode address
    };

    DecodedInstruction decode(uint16_t instruction) {
        DecodedInstruction decoded{};
        
        decoded.opcode = (instruction >> 12) & 0x0F;
        decoded.reg_dest = (instruction >> 8) & 0x07;
        decoded.reg_src = (instruction >> 5) & 0x07;
        decoded.immediate = instruction & 0x1F;
        decoded.uses_immediate = (instruction & 0x0020) != 0;
        
        // Map to microcode start address
        decoded.micro_start = map_to_microcode[decoded.opcode];
        
        return decoded;
    }

private:
    // Microcode start addresses for each instruction
    static const uint16_t map_to_microcode[16] = {
        0x000,  // ADD
        0x020,  // SUB
        0x040,  // AND
        0x060,  // OR
        0x080,  // XOR
        0x0A0,  // LD
        0x0C0,  // ST
        0x0E0,  // JMP
        0x100,  // JSR
        0x120,  // RTS
        0x140,  // BRZ
        0x160,  // BNZ
        0x180,  // BRC
        0x1A0,  // BNC
        0x1C0,  // IN
        0x1E0   // OUT
    };
};

Test in VS Code's integrated terminal:

cd src/cpu
g++ -o test_alu alu_test.cpp instruction_decoder_test.cpp -lgtest -lgtest_main
./test_alu

Magic-1 Instruction Set and Microcode Implementation

Let's implement the core instruction set and microcode for Magic-1:

class MicrocodeExecutor {
    struct MicroInstruction {
        uint8_t next_address;    // Next microinstruction address
        uint8_t alu_operation;   // ALU operation to perform
        uint8_t register_load;   // Register load enables
        uint8_t register_read;   // Register read selects
        uint8_t memory_control;  // Memory control signals
        uint8_t bus_control;     // Bus control signals
        uint8_t misc_control;    // Miscellaneous control bits
    };

    // 56-bit microinstruction format
    union {
        struct {
            uint64_t next_addr:8;    // Next address field
            uint64_t alu_op:8;       // ALU operation
            uint64_t reg_load:8;     // Register load enables
            uint64_t reg_read:8;     // Register read select
            uint64_t mem_ctrl:8;     // Memory control
            uint64_t bus_ctrl:8;     // Bus control
            uint64_t misc_ctrl:8;    // Miscellaneous control
        } fields;
        uint64_t raw;
    } microword;

    // Control signal definitions
    enum ControlSignals {
        LD_MAR  = (1 << 0),    // Load Memory Address Register
        LD_MDR  = (1 << 1),    // Load Memory Data Register
        LD_PC   = (1 << 2),    // Load Program Counter
        LD_SP   = (1 << 3),    // Load Stack Pointer
        LD_IR   = (1 << 4),    // Load Instruction Register
        MEM_RD  = (1 << 5),    // Memory Read
        MEM_WR  = (1 << 6),    // Memory Write
        IO_RD   = (1 << 7)     // I/O Read
    };
};

Create the microcode ROM initialization:

class MicrocodeROM {
private:
    static constexpr uint16_t ROM_SIZE = 512;
    uint64_t rom[ROM_SIZE];

public:
    void initialize() {
        // ADD instruction microcode sequence
        rom[0x000] = 0x001000000000000; // Fetch: PC -> MAR
        rom[0x001] = 0x002000000000020; // Memory Read
        rom[0x002] = 0x003000000000100; // Load IR, Increment PC
        rom[0x003] = 0x004000000001000; // Decode
        rom[0x004] = 0x005000000010000; // Execute ADD
        rom[0x005] = 0x000000000100000; // Store result, Next instruction

        // SUB instruction microcode sequence
        rom[0x020] = 0x021000000000000; // Fetch: PC -> MAR
        // ... additional microcode sequences ...
    }

    uint64_t read(uint16_t address) {
        if (address < ROM_SIZE) {
            return rom[address];
        }
        return 0;
    }
};

Test the implementation in VS Code's integrated terminal:

cd src/cpu
g++ -o test_microcode microcode_test.cpp -lgtest -lgtest_main
./test_microcode

Magic-1 CPU Core Implementation

Let's implement the core microcode sequencing and control unit for the Magic-1:

class MicrocodeControl {
private:
    // Microinstruction fields (56-bit total)
    struct MicroControl {
        uint8_t next_addr;     // Next address (8 bits)
        uint8_t alu_op;        // ALU operation (8 bits)
        uint8_t reg_ctl;       // Register control (8 bits)
        uint8_t mar_ctl;       // MAR control (8 bits)
        uint8_t mdr_ctl;       // MDR control (8 bits)
        uint8_t bus_ctl;       // Bus control (8 bits)
        uint8_t misc_ctl;      // Miscellaneous control (8 bits)
    };

    // Control signals for register operations
    enum RegControl {
        REG_NONE = 0x00,
        REG_LOAD_A = 0x01,
        REG_LOAD_B = 0x02,
        REG_LOAD_C = 0x04,
        REG_LOAD_SP = 0x08,
        REG_LOAD_PC = 0x10,
        REG_LOAD_MDR = 0x20,
        REG_LOAD_MAR = 0x40
    };

public:
    MicroControl decode_microinstruction(uint64_t instruction) {
        MicroControl ctrl;
        // Extract control fields from 56-bit instruction
        ctrl.next_addr = (instruction >> 48) & 0xFF;
        ctrl.alu_op = (instruction >> 40) & 0xFF;
        ctrl.reg_ctl = (instruction >> 32) & 0xFF;
        ctrl.mar_ctl = (instruction >> 24) & 0xFF;
        ctrl.mdr_ctl = (instruction >> 16) & 0xFF;
        ctrl.bus_ctl = (instruction >> 8) & 0xFF;
        ctrl.misc_ctl = instruction & 0xFF;
        return ctrl;
    }
};

And the microcode ROM implementation:

class MicrocodeROM {
private:
    static constexpr size_t ROM_SIZE = 512;
    uint64_t rom[ROM_SIZE];

    // Microcode sequence starting addresses
    enum MicrocodeStart {
        FETCH_START = 0x000,
        ADD_START = 0x010,
        SUB_START = 0x020,
        AND_START = 0x030,
        OR_START = 0x040,
        XOR_START = 0x050,
        LOAD_START = 0x060,
        STORE_START = 0x070,
        JUMP_START = 0x080,
        JSR_START = 0x090,
        RTS_START = 0x0A0,
        INT_START = 0x0F0
    };

public:
    void initialize() {
        // Instruction fetch sequence (common to all instructions)
        rom[FETCH_START + 0] = 0x0100000040000000ULL;  // MAR ← PC
        rom[FETCH_START + 1] = 0x0200000020000000ULL;  // MDR ← Memory[MAR]
        rom[FETCH_START + 2] = 0x0300000010000000ULL;  // IR ← MDR, PC ← PC + 2
        rom[FETCH_START + 3] = 0x0400000000000000ULL;  // Decode and branch

        // ADD instruction sequence
        rom[ADD_START + 0] = 0x0110000001000000ULL;  // A ← A + B
        rom[ADD_START + 1] = 0x0000000000000000ULL;  // Return to fetch
        
        // More instruction sequences...
    }
};

Test the microcode implementation:

cd src/cpu
g++ -o test_microcode test_microcode.cpp microcode_control.cpp microcode_rom.cpp
./test_microcode

Magic-1 Instruction Execution Unit

Let's implement the core instruction execution unit for the Magic-1 CPU. This unit handles the actual execution of instructions based on the microcode sequences.

class InstructionExecutor {
private:
    // Current instruction state
    struct ExecutionState {
        uint16_t opcode;         // Current instruction opcode
        uint16_t micro_pc;       // Current microcode address
        bool executing;          // Currently executing instruction
        uint8_t cycle_count;     // Cycles in current instruction
        bool waiting_memory;     // Waiting for memory access
    } state;

    // Internal registers and buses
    struct DataPath {
        uint16_t alu_a_bus;     // ALU A input bus
        uint16_t alu_b_bus;     // ALU B input bus
        uint16_t alu_out;       // ALU output bus
        uint16_t data_bus;      // Main data bus
        uint16_t address_bus;   // Address bus
    } data_path;

public:
    void execute_cycle() {
        // Fetch current microinstruction
        uint64_t micro_inst = microcode_rom[state.micro_pc];
        
        // Decode microinstruction fields
        auto ctrl = decode_microinstruction(micro_inst);
        
        // Execute microinstruction control signals
        if(ctrl.reg_ctl & REG_LOAD_MAR) {
            load_mar();
        }
        
        if(ctrl.reg_ctl & REG_LOAD_MDR) {
            if(ctrl.bus_ctl & BUS_MEMORY_READ) {
                load_mdr_from_memory();
            } else {
                load_mdr_from_bus();
            }
        }
        
        // Perform ALU operation if requested
        if(ctrl.alu_op != ALU_NOP) {
            execute_alu_operation(ctrl.alu_op);
        }
        
        // Update microcode program counter
        state.micro_pc = ctrl.next_addr;
        
        // Check for instruction completion
        if(ctrl.misc_ctl & INST_COMPLETE) {
            state.executing = false;
        }
    }
};

You can test this implementation in VS Code's integrated terminal:

cd src/cpu
g++ -o test_executor test_executor.cpp instruction_executor.cpp
./test_executor

This implementation:

  • Handles microcode execution
  • Controls the datapath
  • Manages instruction timing
  • Coordinates memory access
  • Processes ALU operations

Magic-1 ALU and Control Unit Implementation

Let's implement the core ALU and control unit for accurate instruction execution:

class Magic1ALU {
    struct ALUState {
        uint16_t a_input;      // A input register
        uint16_t b_input;      // B input register
        uint16_t output;       // ALU output register
        bool carry;            // Carry flag
        bool zero;            // Zero flag
        bool negative;        // Negative flag
        bool overflow;        // Overflow flag
    } state;

    enum ALUOp {
        ADD = 0x00,    // Add with carry
        SUB = 0x01,    // Subtract with borrow
        AND = 0x02,    // Logical AND
        OR  = 0x03,    // Logical OR
        XOR = 0x04,    // Logical XOR
        SHL = 0x05,    // Shift left
        SHR = 0x06,    // Shift right logical
        ASR = 0x07     // Arithmetic shift right
    };

    uint16_t execute_op(uint8_t op) {
        switch(op) {
            case ADD:
                return add_with_carry();
            case SUB:
                return subtract_with_borrow();
            case AND:
                return state.a_input & state.b_input;
            case OR:
                return state.a_input | state.b_input;
            case XOR:
                return state.a_input ^ state.b_input;
            case SHL:
                state.carry = (state.a_input & 0x8000) != 0;
                return state.a_input << 1;
            case SHR:
                state.carry = (state.a_input & 0x0001) != 0;
                return state.a_input >> 1;
            case ASR:
                state.carry = (state.a_input & 0x0001) != 0;
                return (int16_t)state.a_input >> 1;
            default:
                return 0;
        }
    }
};
class ControlUnit {
    struct ControlSignals {
        uint8_t mar_control;    // Memory Address Register control
        uint8_t mdr_control;    // Memory Data Register control
        uint8_t reg_control;    // General register control
        uint8_t alu_control;    // ALU operation control
        uint8_t bus_control;    // System bus control
        bool mem_read;          // Memory read enable
        bool mem_write;         // Memory write enable
        bool io_enable;         // I/O operation enable
    } signals;

    // Current microinstruction state
    uint16_t micro_pc;         // Microcode program counter
    bool executing;            // Currently executing instruction
    uint8_t cycle_count;       // Current instruction cycle

public:
    void execute_cycle() {
        // Fetch microinstruction
        uint64_t micro_inst = fetch_microinstruction(micro_pc);
        
        // Decode and execute control signals
        decode_control_signals(micro_inst);
        execute_control_signals();
        
        // Update microcode PC
        micro_pc = calculate_next_address(micro_inst);
        cycle_count++;
    }
};

Test the implementation in VS Code's integrated terminal:

cd src/cpu
g++ -o test_cpu alu.cpp control_unit.cpp test_cpu.cpp -lgtest -lgtest_main
./test_cpu

This creates the core ALU and control unit components. The ALU handles all arithmetic and logical operations, while the control unit manages instruction execution through microcode sequencing.

Magic-1 CPU Implementation - Core Components

Let's implement the core CPU components with proper organization and documentation:

#pragma once
#include <cstdint>
#include <vector>

class Magic1CPU {
private:
    // Magic-1 Register File
    struct RegisterFile {
        uint16_t msw;          // Machine Status Word
        uint16_t pc;           // Program Counter
        uint16_t sp;           // Stack Pointer
        uint16_t dp;           // Data Pointer
        uint16_t a;            // Accumulator
        uint16_t b;            // General Purpose
        uint16_t c;            // General Purpose
        uint16_t mdr;          // Memory Data Register
        uint16_t mar;          // Memory Address Register
        uint16_t ir;           // Instruction Register
    } regs;

    // Magic-1 ALU
    struct ALU {
        uint16_t result;       // ALU result
        bool carry;            // Carry flag
        bool zero;            // Zero flag
        bool negative;        // Negative flag
        bool overflow;        // Overflow flag
        
        uint16_t execute(uint8_t op, uint16_t a, uint16_t b) {
            switch(op & 0x07) {
                case 0: return add(a, b);
                case 1: return sub(a, b);
                case 2: return a & b;
                case 3: return a | b;
                case 4: return a ^ b;
                case 5: return shift_left(a);
                case 6: return shift_right(a);
                case 7: return arithmetic_shift_right(a);
                default: return 0;
            }
        }
    } alu;

    // Magic-1 Microcode ROM (56-bit instructions)
    std::vector<uint64_t> microcode;
    uint16_t micro_pc;        // Microcode Program Counter

public:
    bool initialize() {
        microcode.resize(512, 0);  // 512 x 56-bit microcode ROM
        load_microcode();
        reset();
        return true;
    }

    void reset() {
        regs = {};               // Clear all registers
        regs.sp = 0x8000;        // Initial stack pointer
        regs.pc = 0x0000;        // Start at ROM
        micro_pc = 0;            // Reset microcode PC
    }

    void execute_cycle() {
        // Fetch current microinstruction
        uint64_t micro_inst = microcode[micro_pc];
        
        // Execute microinstruction
        execute_microinstruction(micro_inst);
        
        // Update microcode PC
        micro_pc = next_micro_address(micro_inst);
    }
};

Test this implementation in VS Code's integrated terminal:

cd src/cpu
g++ -o cpu_test magic1_cpu.cpp cpu_test.cpp -Wall -Wextra
./cpu_test

Magic-1 CPU Core Implementation

Let's implement the core CPU with proper instruction decoding and execution.

class Magic1CPU {
private:
    // 56-bit microinstruction format
    struct MicroInstruction {
        uint8_t next_addr;     // Next address field (8 bits)
        uint8_t alu_op;        // ALU operation (8 bits)
        uint8_t reg_src;       // Register source select (8 bits)
        uint8_t reg_dst;       // Register destination (8 bits)
        uint8_t mem_ctrl;      // Memory control (8 bits)
        uint8_t bus_ctrl;      // Bus control (8 bits)
        uint8_t flags;         // Control flags (8 bits)
    };

    // CPU Registers
    struct {
        uint16_t msw;          // Machine Status Word
        uint16_t pc;           // Program Counter
        uint16_t sp;           // Stack Pointer
        uint16_t a;            // Accumulator
        uint16_t b;            // General Purpose
        uint16_t c;            // General Purpose
        uint16_t mar;          // Memory Address Register
        uint16_t mdr;          // Memory Data Register
        uint16_t ir;           // Instruction Register
    } regs;

    // CPU State
    bool halted;               // CPU halted flag
    uint16_t micro_pc;         // Microcode Program Counter
    std::array<uint64_t, 512> microcode_rom;

public:
    void execute_cycle() {
        if (halted) return;

        // Fetch microinstruction
        uint64_t raw_micro = microcode_rom[micro_pc];
        MicroInstruction mi = decode_microinstruction(raw_micro);

        // Execute microinstruction phases
        if (mi.mem_ctrl & MEM_READ)  perform_memory_read();
        if (mi.mem_ctrl & MEM_WRITE) perform_memory_write();
        if (mi.alu_op != ALU_NOP)    perform_alu_operation(mi.alu_op);
        if (mi.reg_dst != REG_NONE)  update_registers(mi);

        // Update microcode PC
        micro_pc = calculate_next_address(mi);
    }

private:
    MicroInstruction decode_microinstruction(uint64_t raw) {
        MicroInstruction mi;
        mi.next_addr = (raw >> 48) & 0xFF;
        mi.alu_op = (raw >> 40) & 0xFF;
        mi.reg_src = (raw >> 32) & 0xFF;
        mi.reg_dst = (raw >> 24) & 0xFF;
        mi.mem_ctrl = (raw >> 16) & 0xFF;
        mi.bus_ctrl = (raw >> 8) & 0xFF;
        mi.flags = raw & 0xFF;
        return mi;
    }
};

Test this implementation in VS Code's integrated terminal:

cd src/cpu
g++ -o cpu_test magic1_cpu.cpp magic1_cpu_test.cpp -Wall -Wextra -std=c++17
./cpu_test

Magic-1 CPU - ALU and Control Logic Implementation

Let's implement the ALU and control logic for the Magic-1 CPU:

class Magic1ALU {
private:
    struct Flags {
        bool carry;      // Carry/borrow from arithmetic
        bool zero;       // Result is zero
        bool negative;   // Result is negative
        bool overflow;   // Arithmetic overflow occurred
    } flags;

public:
    enum Operation {
        ADD = 0x00,     // Add with carry
        SUB = 0x01,     // Subtract with borrow
        AND = 0x02,     // Logical AND
        OR  = 0x03,     // Logical OR
        XOR = 0x04,     // Logical XOR
        SHL = 0x05,     // Shift left
        SHR = 0x06,     // Shift right logical
        ASR = 0x07      // Arithmetic shift right
    };

    uint16_t execute(Operation op, uint16_t a, uint16_t b) {
        uint16_t result = 0;
        flags = Flags{};  // Clear flags

        switch(op) {
            case ADD: {
                uint32_t temp = static_cast<uint32_t>(a) + b;
                result = temp & 0xFFFF;
                flags.carry = (temp > 0xFFFF);
                break;
            }
            case SUB: {
                result = a - b;
                flags.carry = (a >= b);
                flags.overflow = ((a ^ b) & (a ^ result) & 0x8000) != 0;
                break;
            }
            case AND:
                result = a & b;
                break;
            case OR:
                result = a | b;
                break;
            case XOR:
                result = a ^ b;
                break;
            case SHL:
                flags.carry = (a & 0x8000) != 0;
                result = a << 1;
                break;
            case SHR:
                flags.carry = (a & 0x0001) != 0;
                result = a >> 1;
                break;
            case ASR:
                flags.carry = (a & 0x0001) != 0;
                result = (static_cast<int16_t>(a)) >> 1;
                break;
        }

        flags.zero = (result == 0);
        flags.negative = (result & 0x8000) != 0;
        return result;
    }
};

To test the ALU implementation in VS Code:

cd src/cpu
g++ -o alu_test magic1_alu_test.cpp -lgtest -lgtest_main -pthread
./alu_test

Magic-1 CPU - Instruction Decoder and Microsequencer

Let's implement the instruction decoder and microsequencer:

class Magic1Decoder {
    struct DecodedInstruction {
        uint8_t opcode;           // Primary opcode (4 bits)
        uint8_t reg_dest;         // Destination register (3 bits)
        uint8_t reg_src;          // Source register (3 bits)
        uint16_t immediate;       // Immediate value (5 bits)
        bool immediate_mode;      // Uses immediate value
        uint16_t micro_start;     // Starting microcode address
    };

    // Magic-1 opcode definitions
    enum Opcode {
        ADD = 0x0,    // Add
        SUB = 0x1,    // Subtract
        AND = 0x2,    // Logical AND
        OR  = 0x3,    // Logical OR
        XOR = 0x4,    // Logical XOR
        LD  = 0x5,    // Load
        ST  = 0x6,    // Store
        JMP = 0x7,    // Jump
        JSR = 0x8,    // Jump to Subroutine
        RTS = 0x9,    // Return from Subroutine
        BRZ = 0xA,    // Branch if Zero
        BNZ = 0xB,    // Branch if Not Zero
        BRC = 0xC,    // Branch if Carry
        BNC = 0xD,    // Branch if Not Carry
        IN  = 0xE,    // Input
        OUT = 0xF     // Output
    };

    // Microcode start addresses
    static constexpr uint16_t MICROCODE_BASE[] = {
        0x000,  // ADD
        0x020,  // SUB
        0x040,  // AND
        0x060,  // OR
        0x080,  // XOR
        0x0A0,  // LD
        0x0C0,  // ST
        0x0E0,  // JMP
        0x100,  // JSR
        0x120,  // RTS
        0x140,  // BRZ
        0x160,  // BNZ
        0x180,  // BRC
        0x1A0,  // BNC
        0x1C0,  // IN
        0x1E0   // OUT
    };

public:
    DecodedInstruction decode(uint16_t instruction) {
        DecodedInstruction d;
        d.opcode = (instruction >> 12) & 0x0F;
        d.reg_dest = (instruction >> 9) & 0x07;
        d.reg_src = (instruction >> 6) & 0x07;
        d.immediate = instruction & 0x1F;
        d.immediate_mode = (instruction & 0x20) != 0;
        d.micro_start = MICROCODE_BASE[d.opcode];
        return d;
    }
};

Test this implementation in VS Code's integrated terminal:

cd src/cpu
g++ -o decoder_test magic1_decoder_test.cpp -Wall -Wextra
./decoder_test

Magic-1 CPU - Microcode Sequencer Implementation

Let's implement the microcode sequencer for the Magic-1 CPU:

class MicrocodeSequencer {
private:
    struct SequencerState {
        uint16_t current_address;    // Current microcode address
        uint16_t next_address;       // Next microcode address
        bool sequence_active;        // Microcode sequence in progress
        uint8_t condition_flags;     // Current condition flags
    };

    // Microinstruction fields (56-bit total)
    struct MicroInstruction {
        uint8_t next_addr;     // Next address (8 bits)
        uint8_t alu_op;        // ALU operation (8 bits)
        uint8_t reg_src;       // Source register select (8 bits)
        uint8_t reg_dst;       // Destination register select (8 bits)
        uint8_t mem_ctl;       // Memory control (8 bits)
        uint8_t bus_ctl;       // Bus control (8 bits)
        uint8_t seq_ctl;       // Sequencer control (8 bits)
    };

public:
    uint16_t calculate_next_address(const MicroInstruction& current, uint8_t flags) {
        uint16_t next_addr = current.next_addr;

        // Check for conditional branching
        if (current.seq_ctl & SEQ_CONDITIONAL) {
            bool condition_met = evaluate_condition(current.seq_ctl, flags);
            if (condition_met) {
                next_addr = current.next_addr | 0x100;  // Take branch path
            }
        }

        // Check for sequence termination
        if (current.seq_ctl & SEQ_END) {
            state.sequence_active = false;
            next_addr = 0;  // Return to instruction fetch
        }

        return next_addr;
    }

private:
    bool evaluate_condition(uint8_t control, uint8_t flags) {
        switch (control & 0x0F) {
            case COND_ZERO:     return (flags & FLAG_ZERO) != 0;
            case COND_NONZERO:  return (flags & FLAG_ZERO) == 0;
            case COND_CARRY:    return (flags & FLAG_CARRY) != 0;
            case COND_NOCARRY:  return (flags & FLAG_CARRY) == 0;
            case COND_NEGATIVE: return (flags & FLAG_NEGATIVE) != 0;
            case COND_POSITIVE: return (flags & FLAG_NEGATIVE) == 0;
            default:            return false;
        }
    }
};

Test the microcode sequencer in VS Code's integrated terminal:

cd src/cpu
g++ -o sequencer_test magic1_sequencer_test.cpp -lgtest -lgtest_main -pthread
./sequencer_test

Magic-1 CPU - Control Signal Generator

Let's implement the control signal generator for the Magic-1 CPU:

class ControlSignalGenerator {
private:
    // Control signal definitions
    static constexpr uint8_t CTL_ALU_EN    = 0x80;  // Enable ALU operation
    static constexpr uint8_t CTL_MEM_RD    = 0x40;  // Memory read
    static constexpr uint8_t CTL_MEM_WR    = 0x20;  // Memory write
    static constexpr uint8_t CTL_IO_EN     = 0x10;  // Enable I/O operation
    static constexpr uint8_t CTL_REG_LD    = 0x08;  // Register load
    static constexpr uint8_t CTL_PC_INC    = 0x04;  // Increment PC
    static constexpr uint8_t CTL_SP_ADJ    = 0x02;  // Adjust stack pointer
    static constexpr uint8_t CTL_INT_ACK   = 0x01;  // Interrupt acknowledge

    struct ControlState {
        uint8_t current_signals;
        uint8_t next_signals;
        bool cycle_complete;
        bool interrupt_pending;
    } state;

public:
    uint8_t generate_control_signals(uint64_t microinstruction) {
        uint8_t signals = 0;
        
        // Extract control fields from microinstruction
        uint8_t alu_op = (microinstruction >> 40) & 0xFF;
        uint8_t mem_ctl = (microinstruction >> 16) & 0xFF;
        uint8_t seq_ctl = microinstruction & 0xFF;

        // Generate ALU control signals
        if (alu_op != 0) {
            signals |= CTL_ALU_EN;
        }

        // Generate memory control signals
        if (mem_ctl & 0x01) {
            signals |= CTL_MEM_RD;
        }
        if (mem_ctl & 0x02) {
            signals |= CTL_MEM_WR;
        }

        // Generate sequence control signals
        if (seq_ctl & 0x01) {
            signals |= CTL_PC_INC;
        }

        return signals;
    }
};

Test the control signal generator in VS Code's integrated terminal:

cd src/cpu
g++ -o control_test magic1_control_test.cpp -lgtest -lgtest_main -pthread
./control_test

Magic-1 CPU - Control Signal Generator

Let's implement the control signal generator for the Magic-1 CPU:

class ControlSignalGenerator {
private:
    // Control signal definitions
    static constexpr uint8_t CTL_ALU_EN    = 0x80;  // Enable ALU operation
    static constexpr uint8_t CTL_MEM_RD    = 0x40;  // Memory read
    static constexpr uint8_t CTL_MEM_WR    = 0x20;  // Memory write
    static constexpr uint8_t CTL_IO_EN     = 0x10;  // Enable I/O operation
    static constexpr uint8_t CTL_REG_LD    = 0x08;  // Register load
    static constexpr uint8_t CTL_PC_INC    = 0x04;  // Increment PC
    static constexpr uint8_t CTL_SP_ADJ    = 0x02;  // Adjust stack pointer
    static constexpr uint8_t CTL_INT_ACK   = 0x01;  // Interrupt acknowledge

    struct ControlState {
        uint8_t current_signals;
        uint8_t next_signals;
        bool cycle_complete;
        bool interrupt_pending;
    } state;

public:
    uint8_t generate_control_signals(uint64_t microinstruction) {
        uint8_t signals = 0;
        
        // Extract control fields from microinstruction
        uint8_t alu_op = (microinstruction >> 40) & 0xFF;
        uint8_t mem_ctl = (microinstruction >> 16) & 0xFF;
        uint8_t seq_ctl = microinstruction & 0xFF;

        // Generate ALU control signals
        if (alu_op != 0) {
            signals |= CTL_ALU_EN;
        }

        // Generate memory control signals
        if (mem_ctl & 0x01) {
            signals |= CTL_MEM_RD;
        }
        if (mem_ctl & 0x02) {
            signals |= CTL_MEM_WR;
        }

        // Generate sequence control signals
        if (seq_ctl & 0x01) {
            signals |= CTL_PC_INC;
        }

        return signals;
    }
};

Test the control signal generator in VS Code's integrated terminal:

cd src/cpu
g++ -o control_test magic1_control_test.cpp -lgtest -lgtest_main -pthread
./control_test

Magic-1 CPU - Register File and Data Path Implementation

Let's implement the register file and data path for the Magic-1 CPU:

class RegisterFile {
private:
    // Register definitions
    struct {
        uint16_t msw;          // Machine Status Word
        uint16_t pc;           // Program Counter
        uint16_t sp;           // Stack Pointer
        uint16_t a;            // Accumulator
        uint16_t b;            // General Purpose B
        uint16_t c;            // General Purpose C
        uint16_t mar;          // Memory Address Register
        uint16_t mdr;          // Memory Data Register
        uint16_t ir;           // Instruction Register
    } regs;

    // MSW bit definitions
    static constexpr uint16_t MSW_CARRY     = 0x0001;
    static constexpr uint16_t MSW_ZERO      = 0x0002;
    static constexpr uint16_t MSW_NEGATIVE  = 0x0004;
    static constexpr uint16_t MSW_OVERFLOW  = 0x0008;
    static constexpr uint16_t MSW_INTERRUPT = 0x0010;
    static constexpr uint16_t MSW_SUPER     = 0x0020;

public:
    uint16_t read_register(uint8_t reg_num) {
        switch(reg_num & 0x07) {
            case 0: return regs.a;
            case 1: return regs.b;
            case 2: return regs.c;
            case 3: return regs.sp;
            case 4: return regs.pc;
            case 5: return regs.mar;
            case 6: return regs.mdr;
            case 7: return regs.msw;
            default: return 0;
        }
    }

    void write_register(uint8_t reg_num, uint16_t value) {
        switch(reg_num & 0x07) {
            case 0: regs.a = value; break;
            case 1: regs.b = value; break;
            case 2: regs.c = value; break;
            case 3: regs.sp = value; break;
            case 4: regs.pc = value; break;
            case 5: regs.mar = value; break;
            case 6: regs.mdr = value; break;
            case 7: regs.msw = value & 0x003F; break;  // Only lower 6 bits
        }
    }
};
class DataPath {
private:
    RegisterFile registers;
    Magic1ALU alu;

    struct Buses {
        uint16_t a_bus;        // A bus (ALU input A)
        uint16_t b_bus;        // B bus (ALU input B)
        uint16_t c_bus;        // C bus (ALU output)
        uint16_t data_bus;     // Main data bus
        uint16_t address_bus;  // Address bus
    } buses;

public:
    void execute_datapath_cycle(uint64_t microinstruction) {
        // Extract control signals
        uint8_t src_reg = (microinstruction >> 32) & 0xFF;
        uint8_t dst_reg = (microinstruction >> 24) & 0xFF;
        uint8_t alu_op = (microinstruction >> 40) & 0xFF;

        // Drive source registers onto buses
        buses.a_bus = registers.read_register(src_reg & 0x07);
        buses.b_bus = registers.read_register((src_reg >> 4) & 0x07);

        // Perform ALU operation
        if(alu_op != 0) {
            buses.c_bus = alu.execute(static_cast<Magic1ALU::Operation>(alu_op), 
                                    buses.a_bus, buses.b_bus);
        }

        // Write result to destination register
        if(dst_reg != 0) {
            registers.write_register(dst_reg & 0x07, buses.c_bus);
        }
    }
};

Test the implementation in VS Code's integrated terminal:

cd src/cpu
g++ -o datapath_test magic1_datapath_test.cpp magic1_registers.cpp magic1_alu.cpp -lgtest -lgtest_main
./datapath_test

Magic-1 Memory Interface Implementation

Let's implement the memory interface for the Magic-1 CPU. This handles both main memory and device memory access.

class Memory {
private:
    static constexpr uint32_t ROM_SIZE = 16384;    // 16K ROM
    static constexpr uint32_t RAM_SIZE = 32768;    // 32K RAM
    static constexpr uint32_t ROM_BASE = 0x0000;
    static constexpr uint32_t RAM_BASE = 0x4000;
    static constexpr uint32_t DEVICE_BASE = 0xF800;

    std::vector<uint8_t> rom;
    std::vector<uint8_t> ram;
    
    struct MemoryStats {
        uint32_t reads;
        uint32_t writes;
        uint32_t rom_accesses;
        uint32_t ram_accesses;
        uint32_t device_accesses;
    } stats;

public:
    Memory() : rom(ROM_SIZE), ram(RAM_SIZE), stats{} {
        // Initialize memory arrays
        std::fill(rom.begin(), rom.end(), 0xFF);
        std::fill(ram.begin(), ram.end(), 0x00);
    }

    uint16_t read_word(uint16_t address) {
        stats.reads++;

        if (address >= DEVICE_BASE) {
            stats.device_accesses++;
            return read_device(address);
        }

        if (address >= RAM_BASE) {
            stats.ram_accesses++;
            uint16_t offset = address - RAM_BASE;
            return (ram[offset] << 8) | ram[offset + 1];
        }

        stats.rom_accesses++;
        return (rom[address] << 8) | rom[address + 1];
    }

    void write_word(uint16_t address, uint16_t data) {
        stats.writes++;

        if (address >= DEVICE_BASE) {
            stats.device_accesses++;
            write_device(address, data);
            return;
        }

        if (address >= RAM_BASE) {
            stats.ram_accesses++;
            uint16_t offset = address - RAM_BASE;
            ram[offset] = (data >> 8) & 0xFF;
            ram[offset + 1] = data & 0xFF;
        }
        // ROM writes are ignored
    }
};

Test this implementation in VS Code's integrated terminal:

cd src/memory
g++ -o memory_test magic1_memory_test.cpp -lgtest -lgtest_main
./memory_test

Magic-1 Memory Interface - Device Memory Implementation

Let's implement the device memory interface for the Magic-1 CPU.

class DeviceMemory {
private:
    // Device memory map constants
    static constexpr uint16_t UART_BASE     = 0xF800;  // First UART
    static constexpr uint16_t UART2_BASE    = 0xF808;  // Second UART (SLIP)
    static constexpr uint16_t RTC_BASE      = 0xF810;  // Real-time clock
    static constexpr uint16_t CF_BASE       = 0xF820;  // CF card interface
    static constexpr uint16_t TIMER_BASE    = 0xF830;  // System timer
    
    struct DeviceRegisters {
        // UART 1 registers
        uint8_t uart_data;     // Data register
        uint8_t uart_status;   // Status register
        uint8_t uart_control;  // Control register
        
        // UART 2 (SLIP) registers
        uint8_t slip_data;
        uint8_t slip_status;
        uint8_t slip_control;
        
        // CF card registers
        uint8_t cf_data;
        uint8_t cf_error;
        uint8_t cf_status;
        uint8_t cf_command;
        
        // RTC registers
        uint8_t rtc_seconds;
        uint8_t rtc_minutes;
        uint8_t rtc_hours;
        uint8_t rtc_control;
    } devices;

public:
    uint16_t read_device(uint16_t address) {
        switch(address & 0xFFF0) {
            case UART_BASE:
                return handle_uart_read(address & 0x0F);
            case UART2_BASE:
                return handle_slip_read(address & 0x0F);
            case CF_BASE:
                return handle_cf_read(address & 0x0F);
            case RTC_BASE:
                return handle_rtc_read(address & 0x0F);
            default:
                return 0xFFFF;  // Invalid device address
        }
    }

    void write_device(uint16_t address, uint16_t data) {
        switch(address & 0xFFF0) {
            case UART_BASE:
                handle_uart_write(address & 0x0F, data);
                break;
            case UART2_BASE:
                handle_slip_write(address & 0x0F, data);
                break;
            case CF_BASE:
                handle_cf_write(address & 0x0F, data);
                break;
            case RTC_BASE:
                handle_rtc_write(address & 0x0F, data);
                break;
        }
    }
};

Test this implementation in VS Code's integrated terminal:

cd src/memory
g++ -o device_test magic1_device_memory_test.cpp -lgtest -lgtest_main
./device_test

Magic-1 Device Handlers Implementation

Let's implement the core device handlers for UART, CF card, and RTC:

class Magic1UART {
    // UART registers
    struct {
        uint8_t data;         // Data register (R/W)
        uint8_t status;       // Status register (R)
        uint8_t control;      // Control register (W)
        uint8_t baud;        // Baud rate register (W)
    } regs;

    // Status register bits
    static constexpr uint8_t STATUS_RXRDY = 0x01;  // Receive data ready
    static constexpr uint8_t STATUS_TXRDY = 0x02;  // Transmit ready
    static constexpr uint8_t STATUS_RXOVR = 0x04;  // Receive overrun
    static constexpr uint8_t STATUS_FRERR = 0x08;  // Framing error

public:
    uint8_t read_register(uint8_t reg) {
        switch(reg) {
            case 0: // Data register
                regs.status &= ~STATUS_RXRDY;  // Clear receive ready
                return regs.data;
            case 1: // Status register
                return regs.status;
            default:
                return 0xFF;
        }
    }

    void write_register(uint8_t reg, uint8_t value) {
        switch(reg) {
            case 0: // Data register
                regs.data = value;
                regs.status |= STATUS_TXRDY;  // Set transmit ready
                transmit_byte(value);
                break;
            case 2: // Control register
                regs.control = value;
                break;
            case 3: // Baud rate
                regs.baud = value;
                update_baud_rate();
                break;
        }
    }
};
class Magic1CFCard {
    // CF card registers
    struct {
        uint8_t data;        // Data register
        uint8_t error;       // Error register
        uint8_t sector_cnt;  // Sector count
        uint8_t sector;      // Sector number
        uint8_t cyl_low;     // Cylinder low
        uint8_t cyl_high;    // Cylinder high
        uint8_t status;      // Status register
        uint8_t command;     // Command register
    } regs;

    // Status register bits
    static constexpr uint8_t STATUS_BUSY = 0x80;
    static constexpr uint8_t STATUS_READY = 0x40;
    static constexpr uint8_t STATUS_ERROR = 0x01;

public:
    uint8_t read_register(uint8_t reg) {
        switch(reg) {
            case 0: return regs.data;
            case 1: return regs.error;
            case 7: return regs.status;
            default: return 0xFF;
        }
    }

    void write_register(uint8_t reg, uint8_t value) {
        switch(reg) {
            case 0: 
                regs.data = value;
                break;
            case 7:
                regs.command = value;
                execute_command();
                break;
        }
    }
};

Test these implementations in VS Code's integrated terminal:

cd src/devices
g++ -o device_test magic1_uart_test.cpp magic1_cf_test.cpp -lgtest -lgtest_main
./device_test

Magic-1 Device Interrupt System Implementation

Let's implement the interrupt handling system for the Magic-1 devices.

First, create the interrupt controller:

class InterruptController {
    struct InterruptState {
        uint8_t pending_interrupts;    // Bitmap of pending interrupts
        uint8_t interrupt_mask;        // Interrupt enable mask
        bool interrupt_active;         // Currently servicing interrupt
    } state;

    // Interrupt sources
    enum InterruptSource {
        INT_UART1    = 0x01,    // UART1 interrupt
        INT_UART2    = 0x02,    // UART2 (SLIP) interrupt
        INT_RTC      = 0x04,    // Real-time clock interrupt
        INT_CF       = 0x08,    // CF card interrupt
        INT_TIMER    = 0x10     // System timer interrupt
    };

public:
    bool check_interrupts() {
        if (!state.interrupt_active && (state.pending_interrupts & state.interrupt_mask)) {
            uint8_t highest_priority = get_highest_priority_interrupt();
            if (highest_priority != 0) {
                state.interrupt_active = true;
                state.pending_interrupts &= ~highest_priority;
                return true;
            }
        }
        return false;
    }

    uint16_t get_interrupt_vector() {
        uint8_t interrupt = get_highest_priority_interrupt();
        switch(interrupt) {
            case INT_UART1: return 0x0010;
            case INT_UART2: return 0x0020;
            case INT_RTC:   return 0x0030;
            case INT_CF:    return 0x0040;
            case INT_TIMER: return 0x0050;
            default:        return 0x0000;
        }
    }
};

Now create the interrupt handler integration:

class DeviceManager {
    InterruptController interrupt_ctrl;
    Magic1UART uart1, uart2;
    Magic1CFCard cf_card;
    
    struct DeviceState {
        bool uart1_enabled;
        bool uart2_enabled;
        bool cf_enabled;
        uint8_t device_status;
    } state;

public:
    void handle_device_interrupts() {
        // Check UART1 status
        if (uart1.has_interrupt()) {
            interrupt_ctrl.raise_interrupt(InterruptController::INT_UART1);
        }

        // Check UART2 (SLIP) status
        if (uart2.has_interrupt()) {
            interrupt_ctrl.raise_interrupt(InterruptController::INT_UART2);
        }

        // Check CF card status
        if (cf_card.has_interrupt()) {
            interrupt_ctrl.raise_interrupt(InterruptController::INT_CF);
        }

        // Process pending interrupts
        if (interrupt_ctrl.check_interrupts()) {
            uint16_t vector = interrupt_ctrl.get_interrupt_vector();
            cpu->handle_interrupt(vector);
        }
    }
};

Test the implementation in VS Code's integrated terminal:

cd src/devices
g++ -o interrupt_test interrupt_controller_test.cpp device_manager_test.cpp -lgtest -lgtest_main
./interrupt_test

Magic-1 Device Memory Mapping Implementation

Let's implement the device memory mapping system for the Magic-1 CPU. This manages how devices appear in the CPU's address space.

class DeviceMemoryMap {
    struct DeviceRegion {
        uint16_t base_address;
        uint16_t size;
        std::string device_name;
        bool writable;
        bool readable;
    };

    std::vector<DeviceRegion> device_map = {
        {0xF800, 0x08, "UART1", true, true},
        {0xF808, 0x08, "UART2-SLIP", true, true},
        {0xF810, 0x08, "RTC", true, true},
        {0xF820, 0x10, "CF-Card", true, true},
        {0xF830, 0x08, "Timer", true, true}
    };

    struct MemoryStats {
        uint32_t device_reads;
        uint32_t device_writes;
        uint32_t invalid_accesses;
    } stats;

public:
    std::optional<uint16_t> read_device_memory(uint16_t address) {
        for (const auto& region : device_map) {
            if (address >= region.base_address && 
                address < (region.base_address + region.size)) {
                if (region.readable) {
                    stats.device_reads++;
                    return handle_device_read(address, region);
                }
            }
        }
        stats.invalid_accesses++;
        return std::nullopt;
    }

    bool write_device_memory(uint16_t address, uint16_t data) {
        for (const auto& region : device_map) {
            if (address >= region.base_address && 
                address < (region.base_address + region.size)) {
                if (region.writable) {
                    stats.device_writes++;
                    return handle_device_write(address, data, region);
                }
            }
        }
        stats.invalid_accesses++;
        return false;
    }
};

Test this implementation in VS Code's integrated terminal:

cd src/memory
g++ -o memmap_test device_memory_map_test.cpp -lgtest -lgtest_main
./memmap_test

This implementation:

  • Defines memory regions for each device
  • Handles device memory access
  • Tracks memory access statistics
  • Validates memory access permissions
  • Maps devices to their respective address spaces

Magic-1 Device Access Handler Implementation

Let's implement the device access handlers that manage detailed interactions with each device.

class DeviceHandlers {
private:
    // Device status tracking
    struct DeviceStatus {
        bool device_ready;
        bool interrupt_pending;
        uint8_t error_code;
        uint32_t access_count;
    };

    std::unordered_map<std::string, DeviceStatus> device_status;
    std::shared_ptr<InterruptController> interrupt_controller;

public:
    enum class DeviceResult {
        SUCCESS,
        NOT_READY,
        INVALID_OPERATION,
        TIMEOUT,
        ERROR
    };

    DeviceResult handle_device_access(uint16_t address, uint16_t* data, bool is_write) {
        // Determine device from address
        auto device = get_device_from_address(address);
        if (!device) {
            return DeviceResult::INVALID_OPERATION;
        }

        switch (device->type) {
            case DeviceType::UART1:
                return handle_uart_access(0, address, data, is_write);
            case DeviceType::UART2_SLIP:
                return handle_uart_access(1, address, data, is_write);
            case DeviceType::CF_CARD:
                return handle_cf_access(address, data, is_write);
            case DeviceType::RTC:
                return handle_rtc_access(address, data, is_write);
            default:
                return DeviceResult::INVALID_OPERATION;
        }
    }

    void update_device_status() {
        for (auto& [device_name, status] : device_status) {
            if (status.interrupt_pending) {
                interrupt_controller->raise_interrupt(device_name);
            }
        }
    }
};

Test this implementation in VS Code's integrated terminal:

cd src/devices
g++ -o handler_test device_handlers_test.cpp -lgtest -lgtest_main
./handler_test

The handler manages:

  • Device access validation
  • Status tracking
  • Error handling
  • Interrupt generation
  • Device-specific operations

Magic-1 Device-Specific Access Handlers

Let's implement the handlers for each Magic-1 device type:

class DeviceAccessHandlers {
private:
    // UART Status Register bits
    static constexpr uint8_t UART_RX_READY = 0x01;
    static constexpr uint8_t UART_TX_READY = 0x02;
    static constexpr uint8_t UART_ERROR    = 0x04;

    // CF Card Status Register bits
    static constexpr uint8_t CF_BUSY    = 0x80;
    static constexpr uint8_t CF_READY   = 0x40;
    static constexpr uint8_t CF_ERROR   = 0x01;
    static constexpr uint8_t CF_DRQ     = 0x08;

public:
    uint16_t handle_uart_read(uint8_t uart_num, uint8_t reg) {
        switch(reg) {
            case 0: // Data Register
                return read_uart_data(uart_num);
            case 1: // Status Register
                return get_uart_status(uart_num);
            case 2: // Control Register
                return uart_control[uart_num];
            default:
                return 0xFF;
        }
    }

    void handle_uart_write(uint8_t uart_num, uint8_t reg, uint8_t data) {
        switch(reg) {
            case 0: // Data Register
                write_uart_data(uart_num, data);
                break;
            case 2: // Control Register
                uart_control[uart_num] = data;
                update_uart_config(uart_num);
                break;
        }
    }

    uint16_t handle_cf_read(uint8_t reg) {
        switch(reg) {
            case 0: // Data Register
                return read_cf_data();
            case 1: // Error Register
                return cf_error;
            case 7: // Status Register
                return get_cf_status();
            default:
                return 0xFF;
        }
    }

    void handle_cf_write(uint8_t reg, uint8_t data) {
        switch(reg) {
            case 0: // Data Register
                write_cf_data(data);
                break;
            case 2: // Sector Count
                cf_sector_count = data;
                break;
            case 7: // Command Register
                execute_cf_command(data);
                break;
        }
    }
};

Test these handlers in VS Code's integrated terminal:

cd src/devices
g++ -o handler_test device_access_handlers_test.cpp -lgtest -lgtest_main
./handler_test

Magic-1 SLIP Protocol Handler Implementation

Let's implement the SLIP protocol handler for UART2:

class SlipHandler {
private:
    static constexpr uint8_t SLIP_END = 0xC0;
    static constexpr uint8_t SLIP_ESC = 0xDB;
    static constexpr uint8_t SLIP_ESC_END = 0xDC;
    static constexpr uint8_t SLIP_ESC_ESC = 0xDD;

    std::vector<uint8_t> rx_buffer;
    std::vector<uint8_t> tx_buffer;
    bool in_escape_sequence;
    bool packet_available;

    struct SlipStats {
        uint32_t packets_received;
        uint32_t packets_sent;
        uint32_t errors;
        uint64_t bytes_processed;
    } stats;

public:
    void process_byte(uint8_t byte) {
        if (byte == SLIP_END) {
            if (!rx_buffer.empty()) {
                packet_available = true;
                stats.packets_received++;
            }
            rx_buffer.clear();
            in_escape_sequence = false;
            return;
        }

        if (byte == SLIP_ESC) {
            in_escape_sequence = true;
            return;
        }

        if (in_escape_sequence) {
            if (byte == SLIP_ESC_END) {
                rx_buffer.push_back(SLIP_END);
            } else if (byte == SLIP_ESC_ESC) {
                rx_buffer.push_back(SLIP_ESC);
            } else {
                stats.errors++;
            }
            in_escape_sequence = false;
        } else {
            rx_buffer.push_back(byte);
        }
        stats.bytes_processed++;
    }

    std::vector<uint8_t> send_packet(const std::vector<uint8_t>& data) {
        std::vector<uint8_t> encoded;
        encoded.push_back(SLIP_END);

        for (uint8_t byte : data) {
            if (byte == SLIP_END) {
                encoded.push_back(SLIP_ESC);
                encoded.push_back(SLIP_ESC_END);
            } else if (byte == SLIP_ESC) {
                encoded.push_back(SLIP_ESC);
                encoded.push_back(SLIP_ESC_ESC);
            } else {
                encoded.push_back(byte);
            }
        }

        encoded.push_back(SLIP_END);
        stats.packets_sent++;
        return encoded;
    }
};

Test this implementation in VS Code's integrated terminal:

cd src/devices
g++ -o slip_test slip_handler_test.cpp -lgtest -lgtest_main
./slip_test

The SLIP handler:

  • Implements SLIP protocol encoding/decoding
  • Manages packet framing
  • Handles escape sequences
  • Tracks protocol statistics
  • Integrates with UART2 for network connectivity

Magic-1 SLIP Network Integration

Let's implement the network integration for the SLIP protocol. This ties together the UART2 and SLIP handler with the TUN/TAP interface.

First, create the network interface:

#include <fcntl.h>
#include <linux/if.h>
#include <linux/if_tun.h>
#include <sys/ioctl.h>

class SlipNetwork {
private:
    int tun_fd;
    std::string interface_name;
    SlipHandler slip;
    std::queue<std::vector<uint8_t>> tx_queue;
    std::atomic<bool> running{false};
    std::thread network_thread;

    static constexpr size_t MTU = 1500;
    static constexpr uint16_t UART2_BASE = 0xF808;

public:
    bool initialize() {
        struct ifreq ifr;
        tun_fd = open("/dev/net/tun", O_RDWR);
        if (tun_fd < 0) {
            return false;
        }

        memset(&ifr, 0, sizeof(ifr));
        ifr.ifr_flags = IFF_TUN | IFF_NO_PI;
        strncpy(ifr.ifr_name, "magic1", IFNAMSIZ);

        if (ioctl(tun_fd, TUNSETIFF, &ifr) < 0) {
            close(tun_fd);
            return false;
        }

        interface_name = ifr.ifr_name;
        start_network_thread();
        return true;
    }

    void process_uart_byte(uint8_t byte) {
        slip.process_byte(byte);
        if (slip.has_packet()) {
            auto packet = slip.get_packet();
            write(tun_fd, packet.data(), packet.size());
        }
    }

private:
    void network_thread_func() {
        std::vector<uint8_t> buffer(MTU);
        while (running) {
            int len = read(tun_fd, buffer.data(), buffer.size());
            if (len > 0) {
                auto slip_packet = slip.send_packet({buffer.begin(), 
                                                   buffer.begin() + len});
                std::lock_guard<std::mutex> lock(queue_mutex);
                tx_queue.push(slip_packet);
            }
        }
    }
};

Create a test file:

#include <gtest/gtest.h>
#include "slip_network.h"

TEST(SlipNetworkTest, Initialize) {
    SlipNetwork network;
    ASSERT_TRUE(network.initialize());
    
    // Test packet transmission
    std::vector<uint8_t> test_packet = {0x45, 0x00, 0x00, 0x28};
    network.send_packet(test_packet);
    
    // Verify UART2 received the SLIP-encoded packet
    ASSERT_TRUE(verify_uart2_output());
}

Run the tests in VS Code's integrated terminal:

cd src/network
g++ -o network_test slip_network_test.cpp -lgtest -lgtest_main -pthread
sudo ./network_test  # Needs root for TUN device creation

Magic-1 IP Protocol Layer Implementation

Let's create the IP packet handling layer that sits between the SLIP interface and TUN device:

#include <cstdint>
#include <vector>
#include <queue>
#include <mutex>

class IPHandler {
private:
    struct IPHeader {
        uint8_t version_ihl;    // Version (4 bits) + IHL (4 bits)
        uint8_t tos;            // Type of service
        uint16_t total_length;  // Total length
        uint16_t id;            // Identification
        uint16_t frag_offset;   // Flags + Fragment offset
        uint8_t ttl;            // Time to live
        uint8_t protocol;       // Protocol
        uint16_t checksum;      // Header checksum
        uint32_t src_addr;      // Source address
        uint32_t dst_addr;      // Destination address
    } __attribute__((packed));

    std::queue<std::vector<uint8_t>> packet_queue;
    std::mutex queue_mutex;
    uint16_t ip_id_counter{0};

public:
    bool process_packet(const std::vector<uint8_t>& packet) {
        if (packet.size() < sizeof(IPHeader)) {
            return false;
        }

        IPHeader* header = (IPHeader*)packet.data();
        
        // Verify IP version
        if ((header->version_ihl >> 4) != 4) {
            return false;
        }

        // Verify checksum
        uint16_t orig_checksum = header->checksum;
        header->checksum = 0;
        uint16_t calc_checksum = calculate_checksum((uint16_t*)header, 
                                                  sizeof(IPHeader)/2);
        if (calc_checksum != orig_checksum) {
            return false;
        }

        std::lock_guard<std::mutex> lock(queue_mutex);
        packet_queue.push(packet);
        return true;
    }

    std::vector<uint8_t> create_ip_packet(const std::vector<uint8_t>& payload,
                                        uint32_t dst_addr) {
        std::vector<uint8_t> packet(sizeof(IPHeader) + payload.size());
        IPHeader* header = (IPHeader*)packet.data();

        header->version_ihl = 0x45;  // IPv4, 5 words
        header->tos = 0;
        header->total_length = htons(packet.size());
        header->id = htons(ip_id_counter++);
        header->frag_offset = 0;
        header->ttl = 64;
        header->protocol = 6;  // TCP
        header->src_addr = htonl(0xC0A80701);  // 192.168.7.1
        header->dst_addr = htonl(dst_addr);
        
        // Copy payload
        memcpy(packet.data() + sizeof(IPHeader), 
               payload.data(), payload.size());

        // Calculate checksum
        header->checksum = calculate_checksum((uint16_t*)header, 
                                            sizeof(IPHeader)/2);

        return packet;
    }
};

Test this implementation in VS Code's integrated terminal:

cd src/network
g++ -o ip_test ip_handler_test.cpp -lgtest -lgtest_main
./ip_test

Magic-1 TCP Protocol Handler Implementation

Let's implement the TCP protocol handler for the Magic-1 network stack.

#include <cstdint>
#include <map>
#include <vector>
#include <mutex>

class TCPHandler {
private:
    struct TCPHeader {
        uint16_t src_port;      // Source port
        uint16_t dst_port;      // Destination port
        uint32_t seq_num;       // Sequence number
        uint32_t ack_num;       // Acknowledgment number
        uint16_t flags;         // Flags and data offset
        uint16_t window;        // Window size
        uint16_t checksum;      // Checksum
        uint16_t urgent_ptr;    // Urgent pointer
    } __attribute__((packed));

    struct TCPConnection {
        uint32_t remote_ip;
        uint16_t remote_port;
        uint16_t local_port;
        uint32_t seq_num;
        uint32_t ack_num;
        uint16_t window;
        enum State {
            CLOSED,
            LISTEN,
            SYN_SENT,
            SYN_RECEIVED,
            ESTABLISHED
        } state;
    };

    std::map<uint16_t, TCPConnection> connections;
    std::mutex conn_mutex;
    uint16_t next_port{1024};

public:
    bool process_packet(const std::vector<uint8_t>& packet, uint32_t src_ip) {
        if (packet.size() < sizeof(TCPHeader)) {
            return false;
        }

        const TCPHeader* header = reinterpret_cast<const TCPHeader*>(packet.data());
        std::lock_guard<std::mutex> lock(conn_mutex);

        // Look up connection
        auto it = connections.find(ntohs(header->dst_port));
        if (it == connections.end()) {
            return false;
        }

        // Process TCP flags
        bool syn = (ntohs(header->flags) & 0x0002) != 0;
        bool ack = (ntohs(header->flags) & 0x0010) != 0;
        
        return handle_tcp_state(it->second, header, syn, ack);
    }

private:
    bool handle_tcp_state(TCPConnection& conn, const TCPHeader* header, 
                         bool syn, bool ack) {
        switch (conn.state) {
            case TCPConnection::CLOSED:
                if (syn && !ack) {
                    return handle_syn_received(conn, header);
                }
                break;
            case TCPConnection::SYN_RECEIVED:
                if (ack) {
                    return handle_connection_established(conn, header);
                }
                break;
            case TCPConnection::ESTABLISHED:
                return handle_established_data(conn, header);
        }
        return false;
    }
};

Test this implementation in VS Code's integrated terminal:

cd src/network
g++ -o tcp_test tcp_handler_test.cpp -lgtest -lgtest_main
./tcp_test

Magic-1 Socket Interface Implementation

Let's implement the socket interface layer that will allow the Magic-1 to handle network connections.

#include <cstdint>
#include <array>
#include <memory>
#include <optional>

class SocketInterface {
private:
    static constexpr size_t MAX_SOCKETS = 8;
    
    struct Socket {
        enum class State {
            FREE,
            LISTENING,
            CONNECTING,
            CONNECTED,
            CLOSING
        };

        uint16_t local_port;
        uint16_t remote_port;
        uint32_t remote_ip;
        State state;
        std::vector<uint8_t> rx_buffer;
        std::vector<uint8_t> tx_buffer;
        uint32_t sequence_num;
        uint32_t ack_num;
    };

    std::array<Socket, MAX_SOCKETS> sockets;
    TCPHandler tcp_handler;
    IPHandler ip_handler;

public:
    int socket_open() {
        for (size_t i = 0; i < MAX_SOCKETS; i++) {
            if (sockets[i].state == Socket::State::FREE) {
                sockets[i].state = Socket::State::CONNECTING;
                return i;
            }
        }
        return -1;
    }

    bool socket_connect(int socket_id, uint32_t ip, uint16_t port) {
        if (!validate_socket(socket_id)) return false;

        auto& socket = sockets[socket_id];
        socket.remote_ip = ip;
        socket.remote_port = port;
        socket.local_port = allocate_local_port();

        // Create and send SYN packet
        std::vector<uint8_t> syn_packet = tcp_handler.create_syn_packet(
            socket.local_port,
            socket.remote_port,
            socket.sequence_num
        );

        return ip_handler.send_packet(syn_packet, socket.remote_ip);
    }
};

Let's create a test file for the socket interface:

#include <gtest/gtest.h>
#include "socket_interface.h"

class SocketInterfaceTest : public ::testing::Test {
protected:
    SocketInterface sockets;
};

TEST_F(SocketInterfaceTest, OpenSocket) {
    int socket_id = sockets.socket_open();
    ASSERT_GE(socket_id, 0);
    ASSERT_LT(socket_id, 8);
}

TEST_F(SocketInterfaceTest, ConnectSocket) {
    int socket_id = sockets.socket_open();
    ASSERT_TRUE(sockets.socket_connect(socket_id, 0xC0A80702, 80));
}

Build and run the tests in VS Code's integrated terminal:

cd src/network
g++ -o socket_test socket_interface_test.cpp -lgtest -lgtest_main
./socket_test

Magic-1 Network Buffer Management System

Let's implement a robust buffer management system for network operations:

#include <array>
#include <queue>
#include <mutex>
#include <memory>

class NetworkBufferManager {
private:
    static constexpr size_t BUFFER_SIZE = 1536;    // Larger than MTU
    static constexpr size_t NUM_BUFFERS = 32;      // Buffer pool size

    struct Buffer {
        std::array<uint8_t, BUFFER_SIZE> data;
        size_t length{0};
        size_t read_pos{0};
        bool in_use{false};
    };

    std::array<Buffer, NUM_BUFFERS> buffer_pool;
    std::queue<size_t> free_buffers;
    std::mutex buffer_mutex;

public:
    NetworkBufferManager() {
        for (size_t i = 0; i < NUM_BUFFERS; i++) {
            free_buffers.push(i);
        }
    }

    std::optional<size_t> allocate_buffer() {
        std::lock_guard<std::mutex> lock(buffer_mutex);
        if (free_buffers.empty()) {
            return std::nullopt;
        }
        
        size_t index = free_buffers.front();
        free_buffers.pop();
        buffer_pool[index].in_use = true;
        buffer_pool[index].length = 0;
        buffer_pool[index].read_pos = 0;
        return index;
    }

    void release_buffer(size_t index) {
        std::lock_guard<std::mutex> lock(buffer_mutex);
        if (index < NUM_BUFFERS && buffer_pool[index].in_use) {
            buffer_pool[index].in_use = false;
            free_buffers.push(index);
        }
    }
};

Test the buffer manager implementation:

#include <gtest/gtest.h>
#include "buffer_manager.h"

class BufferManagerTest : public ::testing::Test {
protected:
    NetworkBufferManager buffers;
};

TEST_F(BufferManagerTest, AllocateBuffer) {
    auto buffer_id = buffers.allocate_buffer();
    ASSERT_TRUE(buffer_id.has_value());
    EXPECT_LT(*buffer_id, 32);
}

TEST_F(BufferManagerTest, ExhaustBuffers) {
    for (int i = 0; i < 32; i++) {
        EXPECT_TRUE(buffers.allocate_buffer().has_value());
    }
    EXPECT_FALSE(buffers.allocate_buffer().has_value());
}

Build and run the tests in VS Code's integrated terminal:

cd src/network
g++ -o buffer_test buffer_manager_test.cpp -lgtest -lgtest_main -pthread
./buffer_test

Magic-1 Network Queue Management System

Let's implement a queue management system for the network stack that handles both incoming and outgoing packets efficiently.

#include <queue>
#include <mutex>
#include <condition_variable>
#include <chrono>

class NetworkQueueManager {
private:
    struct QueueEntry {
        size_t buffer_id;
        uint8_t priority;
        std::chrono::steady_clock::time_point timestamp;
    };

    static constexpr size_t MAX_QUEUE_SIZE = 64;
    static constexpr std::chrono::milliseconds QUEUE_TIMEOUT{100};

    std::queue<QueueEntry> tx_queue;
    std::queue<QueueEntry> rx_queue;
    std::mutex tx_mutex;
    std::mutex rx_mutex;
    std::condition_variable tx_cv;
    std::condition_variable rx_cv;
    NetworkBufferManager& buffer_mgr;

public:
    bool enqueue_tx(size_t buffer_id, uint8_t priority = 0) {
        std::lock_guard<std::mutex> lock(tx_mutex);
        if (tx_queue.size() >= MAX_QUEUE_SIZE) {
            return false;
        }

        tx_queue.push({buffer_id, priority, 
                      std::chrono::steady_clock::now()});
        tx_cv.notify_one();
        return true;
    }

    std::optional<size_t> dequeue_rx(bool wait = true) {
        std::unique_lock<std::mutex> lock(rx_mutex);
        if (wait) {
            rx_cv.wait_for(lock, QUEUE_TIMEOUT, 
                [this] { return !rx_queue.empty(); });
        }
        
        if (rx_queue.empty()) {
            return std::nullopt;
        }

        auto entry = rx_queue.front();
        rx_queue.pop();
        return entry.buffer_id;
    }
};

Let's test this implementation:

#include <gtest/gtest.h>
#include "queue_manager.h"

class NetworkQueueTest : public ::testing::Test {
protected:
    NetworkBufferManager buffer_mgr;
    NetworkQueueManager queue_mgr{buffer_mgr};
};

TEST_F(NetworkQueueTest, EnqueueDequeue) {
    auto buffer_id = buffer_mgr.allocate_buffer();
    ASSERT_TRUE(buffer_id.has_value());
    
    EXPECT_TRUE(queue_mgr.enqueue_tx(*buffer_id));
    auto dequeued = queue_mgr.dequeue_rx(false);
    EXPECT_FALSE(dequeued.has_value());
}

Build and run the tests in VS Code's integrated terminal:

cd src/network
g++ -o queue_test queue_manager_test.cpp -lgtest -lgtest_main -pthread
./queue_test

Magic-1 Network Scheduler Implementation

Let's create a network scheduler that manages packet flow and timing for the Magic-1's network stack.

#include <thread>
#include <atomic>
#include <chrono>
#include <functional>

class NetworkScheduler {
    struct ScheduledTask {
        std::function<void()> task;
        std::chrono::milliseconds interval;
        std::chrono::steady_clock::time_point next_run;
        bool recurring;
    };

    std::vector<ScheduledTask> tasks;
    std::atomic<bool> running{false};
    std::thread scheduler_thread;
    NetworkQueueManager& queue_mgr;
    NetworkBufferManager& buffer_mgr;

public:
    NetworkScheduler(NetworkQueueManager& q, NetworkBufferManager& b) 
        : queue_mgr(q), buffer_mgr(b) {
        
        // Add default tasks
        add_task(std::bind(&NetworkScheduler::process_tx_queue, this), 
                std::chrono::milliseconds(1), true);
        add_task(std::bind(&NetworkScheduler::process_rx_queue, this),
                std::chrono::milliseconds(1), true);
        add_task(std::bind(&NetworkScheduler::check_timeouts, this),
                std::chrono::milliseconds(100), true);
    }

    void start() {
        running = true;
        scheduler_thread = std::thread([this]() {
            while (running) {
                auto now = std::chrono::steady_clock::now();
                for (auto& task : tasks) {
                    if (now >= task.next_run) {
                        task.task();
                        if (task.recurring) {
                            task.next_run = now + task.interval;
                        }
                    }
                }
                std::this_thread::sleep_for(std::chrono::milliseconds(1));
            }
        });
    }
};

Let's test the scheduler:

#include <gtest/gtest.h>
#include "network_scheduler.h"

class NetworkSchedulerTest : public ::testing::Test {
protected:
    NetworkBufferManager buffer_mgr;
    NetworkQueueManager queue_mgr{buffer_mgr};
    NetworkScheduler scheduler{queue_mgr, buffer_mgr};
};

TEST_F(NetworkSchedulerTest, SchedulerStart) {
    scheduler.start();
    std::this_thread::sleep_for(std::chrono::milliseconds(100));
    
    // Test packet transmission
    auto buffer_id = buffer_mgr.allocate_buffer();
    ASSERT_TRUE(buffer_id.has_value());
    EXPECT_TRUE(queue_mgr.enqueue_tx(*buffer_id));
}

Build and run the tests in VS Code's integrated terminal:

cd src/network
g++ -o scheduler_test network_scheduler_test.cpp -lgtest -lgtest_main -pthread
./scheduler_test

Magic-1 Network Timing and Timeout Management

Let's implement a robust timing system to handle network timeouts and retransmissions.

class NetworkTimingManager {
    struct TimerEntry {
        uint32_t id;
        std::chrono::steady_clock::time_point expiry;
        std::function<void()> callback;
        bool recurring;
        std::chrono::milliseconds interval;
    };

    std::vector<TimerEntry> timers;
    std::mutex timer_mutex;
    uint32_t next_timer_id{1};

    // TCP timing constants
    static constexpr auto RTO_MIN = std::chrono::milliseconds(200);
    static constexpr auto RTO_MAX = std::chrono::seconds(2);
    static constexpr auto CONN_TIMEOUT = std::chrono::seconds(30);
    static constexpr auto ACK_DELAY = std::chrono::milliseconds(50);

public:
    uint32_t set_timer(std::chrono::milliseconds delay,
                      std::function<void()> callback,
                      bool recurring = false) {
        std::lock_guard<std::mutex> lock(timer_mutex);
        uint32_t id = next_timer_id++;
        
        timers.push_back({
            id,
            std::chrono::steady_clock::now() + delay,
            callback,
            recurring,
            delay
        });

        return id;
    }

    void check_timers() {
        std::lock_guard<std::mutex> lock(timer_mutex);
        auto now = std::chrono::steady_clock::now();
        
        timers.erase(
            std::remove_if(timers.begin(), timers.end(),
                [&](TimerEntry& timer) {
                    if (now >= timer.expiry) {
                        timer.callback();
                        if (timer.recurring) {
                            timer.expiry = now + timer.interval;
                            return false;
                        }
                        return true;
                    }
                    return false;
                }
            ),
            timers.end()
        );
    }
};

Test the timing manager implementation:

#include <gtest/gtest.h>
#include "timing_manager.h"

class NetworkTimingTest : public ::testing::Test {
protected:
    NetworkTimingManager timing;
    std::atomic<int> callback_count{0};
};

TEST_F(NetworkTimingTest, BasicTimer) {
    timing.set_timer(std::chrono::milliseconds(50),
        [this]() { callback_count++; });
    
    std::this_thread::sleep_for(std::chrono::milliseconds(100));
    timing.check_timers();
    EXPECT_EQ(callback_count, 1);
}

Build and run the tests in Visual Studio Code's integrated terminal:

cd src/network
g++ -o timing_test timing_manager_test.cpp -lgtest -lgtest_main -pthread
./timing_test

Magic-1 Network Retransmission System

Let's implement a retransmission system for reliable network communication.

#include <map>
#include <chrono>
#include <memory>

class RetransmissionManager {
private:
    struct RetransmitEntry {
        std::vector<uint8_t> packet;
        uint32_t sequence_number;
        uint8_t retry_count;
        std::chrono::steady_clock::time_point next_attempt;
        uint32_t rto;  // Retransmission Timeout in ms
    };

    std::map<uint32_t, RetransmitEntry> retransmit_queue;
    NetworkTimingManager& timing;
    NetworkBufferManager& buffers;
    
    // RTO calculation parameters
    uint32_t srtt{0};    // Smoothed RTT
    uint32_t rttvar{0};  // RTT variation
    static constexpr double ALPHA = 0.125;
    static constexpr double BETA = 0.25;
    static constexpr uint32_t MIN_RTO = 200;   // 200ms
    static constexpr uint32_t MAX_RTO = 2000;  // 2s
    static constexpr uint8_t MAX_RETRIES = 5;

public:
    void queue_for_retransmit(const std::vector<uint8_t>& packet, 
                             uint32_t seq_num) {
        RetransmitEntry entry{
            packet,
            seq_num,
            0,
            std::chrono::steady_clock::now() + 
                std::chrono::milliseconds(calculate_rto()),
            calculate_rto()
        };

        retransmit_queue[seq_num] = entry;
        schedule_retransmit(seq_num);
    }

    void update_rtt(uint32_t seq_num, uint32_t measured_rtt) {
        if (srtt == 0) {
            srtt = measured_rtt;
            rttvar = measured_rtt / 2;
        } else {
            rttvar = (1 - BETA) * rttvar + 
                    BETA * std::abs(srtt - measured_rtt);
            srtt = (1 - ALPHA) * srtt + ALPHA * measured_rtt;
        }
    }

private:
    uint32_t calculate_rto() {
        if (srtt == 0) return MIN_RTO;
        uint32_t rto = srtt + 4 * rttvar;
        return std::clamp(rto, MIN_RTO, MAX_RTO);
    }
};

Create a test file:

#include <gtest/gtest.h>
#include "retransmission_manager.h"

class RetransmissionTest : public ::testing::Test {
protected:
    NetworkBufferManager buffers;
    NetworkTimingManager timing;
    RetransmissionManager retransmit{timing, buffers};
};

TEST_F(RetransmissionTest, BasicRetransmit) {
    std::vector<uint8_t> test_packet{0x45, 0x00, 0x00, 0x28};
    uint32_t seq_num = 1000;
    
    retransmit.queue_for_retransmit(test_packet, seq_num);
    std::this_thread::sleep_for(std::chrono::milliseconds(250));
    
    // Verify packet was retransmitted
    EXPECT_TRUE(verify_retransmission(seq_num));
}

Build and run the tests in VS Code's integrated terminal:

cd src/network
g++ -o retransmit_test retransmission_manager_test.cpp -lgtest -lgtest_main -pthread
./retransmit_test

Magic-1 Project Status Overview

CPU Components

  • ✅ Basic CPU structure
  • ✅ Register file
  • ✅ ALU operations
  • ✅ Microcode execution
  • ✅ Memory interface
  • ✅ Basic instruction set
  • ❌ Complete pipeline implementation
  • ❌ Full interrupt handling

Memory System

  • ✅ Basic memory management
  • ✅ ROM/RAM separation
  • ✅ Device memory mapping
  • ❌ Memory protection
  • ❌ Bank switching

I/O Devices

  • ✅ UART basic implementation
  • ✅ UART2 SLIP support
  • ✅ CF card interface
  • ❌ Complete CF card filesystem
  • ❌ RTC implementation
  • ❌ Timer implementation

Network Stack

  • ✅ SLIP protocol handler
  • ✅ Basic IP handling
  • ✅ TCP framework
  • ❌ Complete TCP implementation
  • ❌ Socket interface
  • ❌ Network buffer management
  • ❌ Retransmission system

File System

  • ✅ Basic CF card access
  • ❌ Complete filesystem implementation
  • ❌ File operations
  • ❌ Directory structure
  • ❌ File permissions

Testing Infrastructure

  • ✅ Basic unit tests
  • ✅ CPU instruction tests
  • ❌ Integration tests
  • ❌ Network stack tests
  • ❌ File system tests

Documentation

  • ❌ Architecture overview
  • ❌ API documentation
  • ❌ Network protocol documentation
  • ❌ File system documentation
  • ❌ Usage examples

Magic-1 CPU Module Implementation

Let's complete the CPU module with proper pipeline implementation and interrupt handling.

class Magic1Pipeline {
    struct PipelineStage {
        uint16_t instruction;    // Current instruction
        uint16_t pc;            // Program counter for this stage
        bool valid;             // Stage contains valid instruction
        bool stalled;           // Stage is stalled
        
        // Pipeline registers
        uint16_t alu_result;    // ALU result
        uint16_t memory_data;   // Memory data
        uint16_t write_data;    // Data to write back
        uint8_t dest_reg;       // Destination register
    };

    struct {
        PipelineStage fetch;
        PipelineStage decode;
        PipelineStage execute;
        PipelineStage memory;
        PipelineStage writeback;
    } stages;

    // Pipeline control signals
    struct {
        bool flush_pipeline;    // Pipeline flush required
        bool stall_fetch;       // Stall fetch stage
        bool stall_decode;      // Stall decode stage
        bool forward_ex_mem;    // Forward from execute to memory
        bool forward_mem_wb;    // Forward from memory to writeback
    } control;

public:
    void cycle() {
        writeback_stage();
        memory_stage();
        execute_stage();
        decode_stage();
        fetch_stage();
        
        update_pipeline_control();
    }
};

Test the pipeline implementation:

#include <gtest/gtest.h>
#include "magic1_pipeline.h"

TEST(PipelineTest, BasicPipelineOperation) {
    Magic1Pipeline pipeline;
    
    // Test instruction through pipeline
    uint16_t test_instruction = 0x1234;  // ADD R1, R2
    pipeline.inject_instruction(test_instruction);
    
    // Cycle pipeline 5 times to move instruction through all stages
    for(int i = 0; i < 5; i++) {
        pipeline.cycle();
    }
    
    EXPECT_EQ(pipeline.get_writeback_result(), 0x5678);
}

Build and run the tests in VS Code's integrated terminal:

cd src/cpu
g++ -o pipeline_test magic1_pipeline_test.cpp -lgtest -lgtest_main
./pipeline_test

Type 'next' for implementing the interrupt handling system.

Magic-1 CPU Pipeline Implementation

Let's properly implement the CPU pipeline with full instruction handling and interrupt support.

Core Pipeline Implementation

#pragma once
#include <cstdint>
#include <array>

class Magic1Pipeline {
private:
    enum class StageType {
        FETCH,
        DECODE,
        EXECUTE,
        MEMORY,
        WRITEBACK
    };

    struct PipelineStage {
        uint16_t pc;              // Program counter
        uint16_t instruction;     // Current instruction
        uint16_t operand_a;      // First operand
        uint16_t operand_b;      // Second operand
        uint16_t result;         // Stage result
        bool valid;              // Stage contains valid data
        bool stalled;            // Stage is stalled
        uint8_t dest_reg;        // Destination register (if any)
    };

    // Pipeline registers
    std::array<PipelineStage, 5> pipeline;
    
    // Hazard detection unit
    struct HazardUnit {
        bool raw_hazard;         // Read after write
        bool war_hazard;         // Write after read
        bool waw_hazard;         // Write after write
        uint8_t stall_cycles;    // Number of stall cycles needed
    } hazards;

    // Forwarding unit
    struct ForwardingUnit {
        bool forward_ex_mem;     // Forward from execute to memory
        bool forward_mem_wb;     // Forward from memory to writeback
        uint8_t forward_src;     // Source stage for forwarding
        uint8_t forward_dst;     // Destination stage for forwarding
    } forwarding;

public:
    void cycle() {
        // Execute pipeline stages in reverse order
        handle_writeback();
        handle_memory();
        handle_execute();
        handle_decode();
        handle_fetch();

        // Update pipeline control signals
        update_hazards();
        update_forwarding();
    }

    bool is_stalled() const {
        return hazards.stall_cycles > 0;
    }

    uint16_t get_current_pc() const {
        return pipeline[0].pc;
    }
};

Test Implementation

#include <gtest/gtest.h>
#include "magic1_pipeline.h"

class PipelineTest : public ::testing::Test {
protected:
    Magic1Pipeline pipeline;
};

TEST_F(PipelineTest, BasicPipelineOperation) {
    // Test basic pipeline operation with simple instruction
    uint16_t test_instruction = 0x1234;  // ADD R1, R2
    pipeline.inject_instruction(test_instruction);

    // Cycle pipeline 5 times (one for each stage)
    for(int i = 0; i < 5; i++) {
        pipeline.cycle();
        EXPECT_FALSE(pipeline.is_stalled()) << "Pipeline unexpectedly stalled at cycle " << i;
    }

    // Verify instruction completed
    EXPECT_EQ(pipeline.get_last_result(), 0x5678);
}

TEST_F(PipelineTest, HazardDetection) {
    // Test RAW hazard detection
    uint16_t inst1 = 0x1234;  // ADD R1, R2
    uint16_t inst2 = 0x5678;  // ADD R3, R1

    pipeline.inject_instruction(inst1);
    pipeline.cycle();
    pipeline.inject_instruction(inst2);
    pipeline.cycle();

    EXPECT_TRUE(pipeline.is_stalled()) << "Pipeline should detect RAW hazard";
}

Build and run the tests in VS Code's integrated terminal:

cd src/cpu
g++ -o pipeline_test magic1_pipeline_test.cpp -lgtest -lgtest_main -pthread
./pipeline_test

Magic-1 CPU Instruction Decode and Execute Implementation

Let's implement the instruction decode and execute stages with proper handling of the Magic-1's instruction set.

class InstructionUnit {
private:
    struct DecodedInstruction {
        uint8_t opcode;           // Primary opcode (4 bits)
        uint8_t dest_reg;         // Destination register (3 bits)
        uint8_t src_reg;          // Source register (3 bits)
        uint16_t immediate;       // Immediate value (5 bits)
        bool uses_immediate;      // True if instruction uses immediate
        uint16_t micro_addr;      // Starting microcode address
    };

    // Magic-1 instruction set
    enum Opcode : uint8_t {
        ADD = 0x0,    // Add with carry
        SUB = 0x1,    // Subtract with borrow
        AND = 0x2,    // Logical AND
        OR  = 0x3,    // Logical OR
        XOR = 0x4,    // Logical XOR
        LD  = 0x5,    // Load
        ST  = 0x6,    // Store
        JMP = 0x7,    // Jump
        JSR = 0x8,    // Jump to subroutine
        RTS = 0x9,    // Return from subroutine
        BRZ = 0xA,    // Branch if zero
        BNZ = 0xB,    // Branch if not zero
        BRC = 0xC,    // Branch if carry
        BNC = 0xD,    // Branch if not carry
        IN  = 0xE,    // Input
        OUT = 0xF     // Output
    };

public:
    DecodedInstruction decode(uint16_t instruction) {
        DecodedInstruction decoded;
        decoded.opcode = (instruction >> 12) & 0x0F;
        decoded.dest_reg = (instruction >> 9) & 0x07;
        decoded.src_reg = (instruction >> 6) & 0x07;
        decoded.immediate = instruction & 0x1F;
        decoded.uses_immediate = (instruction & 0x20) != 0;
        decoded.micro_addr = get_microcode_start(decoded.opcode);
        return decoded;
    }
};

Now let's implement the execute stage:

class ExecuteUnit {
private:
    Magic1ALU alu;
    uint16_t flags;

public:
    uint16_t execute(const InstructionUnit::DecodedInstruction& inst,
                    uint16_t operand_a,
                    uint16_t operand_b) {
        switch(inst.opcode) {
            case InstructionUnit::ADD:
                return alu.add(operand_a, operand_b);
            case InstructionUnit::SUB:
                return alu.subtract(operand_a, operand_b);
            case InstructionUnit::AND:
                return alu.logical_and(operand_a, operand_b);
            case InstructionUnit::OR:
                return alu.logical_or(operand_a, operand_b);
            case InstructionUnit::XOR:
                return alu.logical_xor(operand_a, operand_b);
            case InstructionUnit::LD:
                return operand_b;  // Load value from memory/immediate
            case InstructionUnit::ST:
                return operand_a;  // Store value to memory
            default:
                return 0xFFFF;     // Invalid opcode
        }
    }
};

Test in VS Code's integrated terminal:

cd src/cpu
g++ -o instruction_test instruction_unit_test.cpp execute_unit_test.cpp -lgtest -lgtest_main
./instruction_test

Magic-1 CPU Memory and Writeback Stages

Let's implement the memory and writeback stages for the Magic-1 CPU.

class MemoryStage {
private:
    struct MemoryControl {
        bool read_enable;         // Enable memory read
        bool write_enable;        // Enable memory write  
        bool is_io_access;       // I/O vs memory access
        uint16_t address;        // Memory/IO address
        uint16_t write_data;     // Data to write
    };

    MemoryControl control;
    uint16_t last_result;
    bool waiting_for_memory;

public:
    uint16_t execute(const PipelineStage& stage) {
        // Generate memory control signals
        decode_memory_access(stage);
        
        if (control.read_enable) {
            waiting_for_memory = true;
            last_result = control.is_io_access ? 
                         read_io(control.address) :
                         read_memory(control.address);
            waiting_for_memory = false;
            return last_result;
        }
        
        if (control.write_enable) {
            if (control.is_io_access) {
                write_io(control.address, control.write_data);
            } else {
                write_memory(control.address, control.write_data);
            }
        }
        
        return stage.result;
    }
};

Now implement the writeback stage:

class WritebackStage {
private:
    RegisterFile& registers;
    uint16_t last_result;
    bool writeback_pending;

public:
    void execute(const PipelineStage& stage) {
        // Check if result should be written back
        if (stage.dest_reg != 0xFF) {
            writeback_pending = true;
            last_result = stage.result;
            
            // Write result to register file
            registers.write(stage.dest_reg, stage.result);
            
            // Update flags if needed
            if (stage.update_flags) {
                update_status_flags(stage.result);
            }
        }
        
        writeback_pending = false;
    }
};

Test the implementation:

#include <gtest/gtest.h>
#include "memory_stage.h"
#include "writeback_stage.h"

class PipelineStagesTest : public ::testing::Test {
protected:
    RegisterFile registers;
    MemoryStage memory;
    WritebackStage writeback{registers};
    
    void SetUp() override {
        // Initialize test environment
    }
};

TEST_F(PipelineStagesTest, MemoryRead) {
    PipelineStage stage{
        .instruction = 0x5123,  // LD R1, [R2]
        .operand_a = 0x1000,    // Memory address
        .dest_reg = 1
    };
    
    uint16_t result = memory.execute(stage);
    EXPECT_EQ(result, 0x5678);  // Expected memory content
}

Run the tests in VS Code's integrated terminal:

cd src/cpu
g++ -o stages_test pipeline_stages_test.cpp -lgtest -lgtest_main
./stages_test

Magic-1 Memory System Implementation

Let's implement the complete memory management system for the Magic-1.

#include <array>
#include <cstdint>
#include <vector>

class MemoryManager {
private:
    static constexpr uint32_t ROM_SIZE = 16384;    // 16K ROM
    static constexpr uint32_t RAM_SIZE = 32768;    // 32K RAM
    static constexpr uint32_t ROM_BASE = 0x0000;
    static constexpr uint32_t RAM_BASE = 0x4000;
    static constexpr uint32_t IO_BASE = 0xF800;

    std::vector<uint8_t> rom;
    std::vector<uint8_t> ram;
    
    struct MemoryStats {
        uint32_t rom_reads;
        uint32_t ram_reads;
        uint32_t ram_writes;
        uint32_t io_accesses;
    } stats;

    struct BankState {
        uint8_t current_bank;
        bool rom_enabled;
        bool ram_enabled;
    } bank_state;

public:
    MemoryManager() : 
        rom(ROM_SIZE, 0xFF),
        ram(RAM_SIZE, 0x00),
        stats{},
        bank_state{0, true, true} {}

    uint16_t read_word(uint16_t address) {
        if (address >= IO_BASE) {
            stats.io_accesses++;
            return handle_io_read(address);
        }

        if (address >= RAM_BASE && bank_state.ram_enabled) {
            stats.ram_reads++;
            return read_ram_word(address - RAM_BASE);
        }

        if (address < ROM_SIZE && bank_state.rom_enabled) {
            stats.rom_reads++;
            return read_rom_word(address);
        }

        return 0xFFFF;  // Bus error
    }

    void write_word(uint16_t address, uint16_t data) {
        if (address >= IO_BASE) {
            stats.io_accesses++;
            handle_io_write(address, data);
            return;
        }

        if (address >= RAM_BASE && bank_state.ram_enabled) {
            stats.ram_writes++;
            write_ram_word(address - RAM_BASE, data);
        }
        // ROM writes are ignored
    }
};

Create a test file:

#include <gtest/gtest.h>
#include "memory_manager.h"

class MemoryManagerTest : public ::testing::Test {
protected:
    MemoryManager mem;
};

TEST_F(MemoryManagerTest, ROMAccess) {
    // ROM should be readable but not writable
    uint16_t test_addr = 0x0100;
    uint16_t orig_value = mem.read_word(test_addr);
    mem.write_word(test_addr, 0x1234);
    EXPECT_EQ(mem.read_word(test_addr), orig_value);
}

TEST_F(MemoryManagerTest, RAMAccess) {
    // RAM should be readable and writable
    uint16_t test_addr = 0x4000;
    mem.write_word(test_addr, 0x5678);
    EXPECT_EQ(mem.read_word(test_addr), 0x5678);
}

Build and run the tests in VS Code's integrated terminal:

cd src/memory
g++ -o memory_test memory_manager_test.cpp -lgtest -lgtest_main
./memory_test

Magic-1 Memory Bank Switching Implementation

Let's implement a robust bank switching system for the Magic-1's memory management.

class BankManager {
private:
    struct BankControl {
        uint8_t current_bank;     // Current RAM bank (0-3)
        bool rom_overlay;         // ROM overlay enabled
        bool ram_write_protect;   // RAM write protection
        uint8_t bank_mask;        // Active bank mask
    } control;

    struct BankRegisters {
        uint8_t bank_select;      // Bank select register (0xF840)
        uint8_t bank_control;     // Bank control register (0xF841)
        uint8_t bank_status;      // Bank status register (0xF842)
    } registers;

public:
    uint16_t translate_address(uint16_t address) {
        if (address < 0x4000 && control.rom_overlay) {
            return address;  // ROM access
        }

        if (address >= 0x4000 && address < 0xF800) {
            uint32_t bank_offset = control.current_bank * 0x4000;
            return bank_offset + (address - 0x4000);
        }

        return address;  // I/O space or invalid
    }

    void write_control(uint16_t address, uint8_t value) {
        switch(address) {
            case 0xF840:
                registers.bank_select = value & 0x03;
                control.current_bank = registers.bank_select;
                break;
            case 0xF841:
                registers.bank_control = value;
                control.rom_overlay = (value & 0x01) != 0;
                control.ram_write_protect = (value & 0x02) != 0;
                break;
        }
    }
};

Create a test file:

#include <gtest/gtest.h>
#include "bank_manager.h"

class BankManagerTest : public ::testing::Test {
protected:
    BankManager banks;
};

TEST_F(BankManagerTest, BankSwitching) {
    // Test ROM overlay
    banks.write_control(0xF841, 0x01);  // Enable ROM overlay
    EXPECT_EQ(banks.translate_address(0x1000), 0x1000);

    // Test RAM bank selection
    banks.write_control(0xF840, 0x01);  // Select bank 1
    banks.write_control(0xF841, 0x00);  // Disable ROM overlay
    EXPECT_EQ(banks.translate_address(0x4000), 0x8000);
}

Build and run the tests in VS Code's integrated terminal:

cd src/memory
g++ -o bank_test bank_manager_test.cpp -lgtest -lgtest_main
./bank_test

Magic-1 Memory Protection System

Let's implement a comprehensive memory protection system for the Magic-1.

#include <array>
#include <bitset>

class MemoryProtection {
private:
    struct ProtectionEntry {
        bool read_enable;        // Read permission
        bool write_enable;       // Write permission
        bool execute_enable;     // Execute permission
        uint8_t privilege;       // Required privilege level (0-3)
    };

    std::array<ProtectionEntry, 16> protection_table;  // 16 4K pages
    std::bitset<16> dirty_pages;    // Track modified pages
    uint8_t current_privilege;       // Current CPU privilege level

public:
    bool check_access(uint16_t address, bool is_write, bool is_execute) {
        uint8_t page = (address >> 12) & 0x0F;
        const auto& entry = protection_table[page];

        // Check privilege level
        if (current_privilege > entry.privilege) {
            return false;
        }

        // Check access type
        if (is_write && !entry.write_enable) {
            return false;
        }
        if (is_execute && !entry.execute_enable) {
            return false;
        }
        if (!is_write && !is_execute && !entry.read_enable) {
            return false;
        }

        // Track page modifications
        if (is_write) {
            dirty_pages.set(page);
        }

        return true;
    }
};

Test implementation:

#include <gtest/gtest.h>
#include "protection_manager.h"

class MemoryProtectionTest : public ::testing::Test {
protected:
    MemoryProtection protection;
};

TEST_F(MemoryProtectionTest, BasicProtection) {
    // Test read protection
    EXPECT_TRUE(protection.check_access(0x1000, false, false));
    
    // Test write protection
    EXPECT_FALSE(protection.check_access(0x0000, true, false));
    
    // Test execute protection
    EXPECT_TRUE(protection.check_access(0x1000, false, true));
}

Build and test in VS Code's integrated terminal:

cd src/memory
g++ -o protection_test protection_manager_test.cpp -lgtest -lgtest_main
./protection_test

Magic-1 Memory Cache System Implementation

Let's implement a cache system for the Magic-1 memory subsystem.

#include <array>
#include <cstdint>

class CacheManager {
    struct CacheLine {
        bool valid;             // Valid bit
        bool dirty;             // Dirty bit
        uint16_t tag;          // Cache line tag
        uint16_t data[8];      // 16 bytes of data (8 words)
        uint8_t access_count;   // LRU counter
    };

    static constexpr size_t CACHE_SETS = 64;     // 64 sets
    static constexpr size_t WAYS = 2;            // 2-way set associative
    std::array<std::array<CacheLine, WAYS>, CACHE_SETS> cache;

public:
    uint16_t read_word(uint16_t address) {
        uint16_t tag = address >> 7;
        uint16_t set = (address >> 4) & 0x3F;
        uint16_t offset = address & 0x0F;

        // Check cache hit
        for (auto& line : cache[set]) {
            if (line.valid && line.tag == tag) {
                line.access_count++;
                return line.data[offset >> 1];
            }
        }

        // Cache miss - load from memory
        return handle_cache_miss(address, tag, set);
    }
};

Create a test file:

#include <gtest/gtest.h>
#include "cache_manager.h"

class CacheManagerTest : public ::testing::Test {
protected:
    CacheManager cache;
    
    void SetUp() override {
        // Initialize test data
    }
};

TEST_F(CacheManagerTest, CacheHit) {
    uint16_t test_addr = 0x1000;
    uint16_t value = cache.read_word(test_addr);
    
    // Second read should be a cache hit
    EXPECT_EQ(cache.read_word(test_addr), value);
    EXPECT_TRUE(cache.is_hit(test_addr));
}

Build and run tests in VS Code's integrated terminal:

cd src/memory
g++ -o cache_test cache_manager_test.cpp -lgtest -lgtest_main
./cache_test

Magic-1 Cache Coherency Implementation

Let's implement cache coherency for the Magic-1 memory system:

class CacheCoherencyManager {
private:
    struct CacheState {
        bool modified;     // Modified (dirty)
        bool exclusive;    // Exclusive access
        bool shared;      // Shared access
        bool invalid;     // Invalid state
    };

    struct CoherencyStats {
        uint32_t cache_hits;
        uint32_t cache_misses;
        uint32_t invalidations;
        uint32_t write_backs;
    } stats;

    std::array<CacheState, 8192> state_table;  // Track state for each cache line

public:
    enum class BusOperation {
        READ,           // Read request
        READ_EXCLUSIVE, // Read with intent to modify
        WRITE,         // Write request
        INVALIDATE,    // Invalidate request
        WRITEBACK      // Writeback to memory
    };

    bool handle_bus_operation(BusOperation op, uint16_t address) {
        auto& line_state = state_table[address >> 4];

        switch(op) {
            case BusOperation::READ:
                if (line_state.modified) {
                    perform_writeback(address);
                    line_state.modified = false;
                    line_state.shared = true;
                    stats.write_backs++;
                }
                return true;

            case BusOperation::WRITE:
                if (line_state.shared || line_state.exclusive) {
                    invalidate_cache_line(address);
                    stats.invalidations++;
                }
                return true;

            default:
                return false;
        }
    }
};

Create the test file:

#include <gtest/gtest.h>
#include "cache_coherency.h"

class CacheCoherencyTest : public ::testing::Test {
protected:
    CacheCoherencyManager coherency;
};

TEST_F(CacheCoherencyTest, ReadSharedData) {
    uint16_t test_addr = 0x1000;
    
    // First CPU reads data
    EXPECT_TRUE(coherency.handle_bus_operation(
        CacheCoherencyManager::BusOperation::READ, 
        test_addr
    ));

    // Second CPU reads same data
    EXPECT_TRUE(coherency.handle_bus_operation(
        CacheCoherencyManager::BusOperation::READ,
        test_addr
    ));

    // Verify data is in shared state
    EXPECT_TRUE(coherency.is_shared(test_addr));
}

Build and run the tests in VS Code's integrated terminal:

cd src/memory
g++ -o coherency_test cache_coherency_test.cpp -lgtest -lgtest_main
./coherency_test

Magic-1 Memory Bus Interface

Let's implement the memory bus interface for coordinated memory access.

class MemoryBus {
private:
    struct BusState {
        bool bus_busy;          // Bus currently in use
        uint16_t address;       // Current address on bus
        uint16_t data;         // Current data on bus
        uint8_t control;       // Bus control signals
        bool wait_state;       // CPU wait state required
    };

    // Bus masters and arbitration
    enum class BusMaster {
        CPU,
        DMA,
        REFRESH
    };

    BusState state;
    std::queue<BusMaster> bus_requests;
    BusMaster current_master;

public:
    // Bus control signals
    static constexpr uint8_t BUS_READ    = 0x01;
    static constexpr uint8_t BUS_WRITE   = 0x02;
    static constexpr uint8_t BUS_MEMREQ  = 0x04;
    static constexpr uint8_t BUS_IOREQ   = 0x08;
    static constexpr uint8_t BUS_REFRESH = 0x10;

    bool request_bus(BusMaster master) {
        if (state.bus_busy && current_master != master) {
            bus_requests.push(master);
            return false;
        }
        current_master = master;
        state.bus_busy = true;
        return true;
    }
};

Test implementation:

#include <gtest/gtest.h>
#include "memory_bus.h"

class MemoryBusTest : public ::testing::Test {
protected:
    MemoryBus bus;
};

TEST_F(MemoryBusTest, BusArbitration) {
    // CPU should get initial bus access
    EXPECT_TRUE(bus.request_bus(MemoryBus::BusMaster::CPU));
    
    // DMA request should be queued
    EXPECT_FALSE(bus.request_bus(MemoryBus::BusMaster::DMA));
    
    // After CPU releases, DMA should get access
    bus.release_bus();
    EXPECT_TRUE(bus.request_bus(MemoryBus::BusMaster::DMA));
}

Build and run the tests in VS Code's integrated terminal:

cd src/memory
g++ -o bus_test memory_bus_test.cpp -lgtest -lgtest_main
./bus_test

This implementation:

  • Manages bus access between multiple masters
  • Handles bus arbitration
  • Controls memory and I/O operations
  • Supports wait states for slow devices
  • Implements refresh cycles for DRAM

Magic-1 DMA Controller Implementation

Let's implement the Direct Memory Access controller for efficient memory transfers.

class DMAController {
    struct DMAChannel {
        uint16_t source_addr;      // Source address
        uint16_t dest_addr;        // Destination address
        uint16_t count;            // Transfer count
        uint8_t control;           // Channel control
        bool active;               // Channel active
        bool terminal_count;       // Transfer complete
    };

    static constexpr uint8_t NUM_CHANNELS = 4;
    std::array<DMAChannel, NUM_CHANNELS> channels;
    MemoryBus& bus;

public:
    // Control register bits
    static constexpr uint8_t DMA_ENABLE     = 0x80;
    static constexpr uint8_t DMA_DIRECTION  = 0x40;
    static constexpr uint8_t DMA_AUTOINIT   = 0x20;
    static constexpr uint8_t DMA_DECREMENT  = 0x10;

    void start_transfer(uint8_t channel) {
        if (channel >= NUM_CHANNELS) return;
        
        auto& ch = channels[channel];
        if (!ch.active && (ch.control & DMA_ENABLE)) {
            ch.active = true;
            process_channel(channel);
        }
    }
};

Create the test file:

#include <gtest/gtest.h>
#include "dma_controller.h"

class DMAControllerTest : public ::testing::Test {
protected:
    MemoryBus bus;
    DMAController dma{bus};

    void SetUp() override {
        // Initialize test memory areas
        uint8_t source_data[] = {0x12, 0x34, 0x56, 0x78};
        memcpy((void*)0x1000, source_data, sizeof(source_data));
    }
};

TEST_F(DMAControllerTest, BasicTransfer) {
    // Configure DMA channel 0
    dma.configure_channel(0, 0x1000, 0x2000, 4, DMAController::DMA_ENABLE);
    
    // Start transfer
    dma.start_transfer(0);
    
    // Verify transfer completed
    EXPECT_TRUE(dma.is_transfer_complete(0));
    EXPECT_EQ(memcmp((void*)0x1000, (void*)0x2000, 4), 0);
}

Build and run the tests in VS Code's integrated terminal:

cd src/memory
g++ -o dma_test dma_controller_test.cpp -lgtest -lgtest_main
./dma_test

Magic-1 DMA Channel Priority System

Let's implement the DMA channel priority and arbitration system:

class DMAChannelPriority {
private:
    struct ChannelPriority {
        uint8_t channel_id;
        uint8_t base_priority;
        uint8_t current_priority;
        bool round_robin;
        bool fixed_priority;
    };

    std::array<ChannelPriority, 4> priorities;
    uint8_t active_channel;
    bool rotating_priority;

public:
    void configure_priorities(uint8_t config) {
        rotating_priority = (config & 0x80) != 0;
        
        for (uint8_t i = 0; i < 4; i++) {
            priorities[i].channel_id = i;
            priorities[i].base_priority = (config >> (i * 2)) & 0x03;
            priorities[i].current_priority = priorities[i].base_priority;
            priorities[i].round_robin = rotating_priority;
            priorities[i].fixed_priority = !rotating_priority;
        }
    }

    uint8_t get_highest_priority_channel() {
        uint8_t highest_priority = 0;
        uint8_t selected_channel = 0xFF;

        for (const auto& channel : priorities) {
            if (channel.current_priority > highest_priority) {
                highest_priority = channel.current_priority;
                selected_channel = channel.channel_id;
            }
        }

        if (rotating_priority && selected_channel != 0xFF) {
            rotate_priorities(selected_channel);
        }

        return selected_channel;
    }
};

Create a test file:

class DMAPriorityTest : public ::testing::Test {
protected:
    DMAChannelPriority priority;
};

TEST_F(DMAPriorityTest, FixedPriority) {
    // Configure fixed priorities (0=highest, 3=lowest)
    priority.configure_priorities(0x00);  // Fixed priority mode
    
    // Check channel selection
    EXPECT_EQ(priority.get_highest_priority_channel(), 0);
}

TEST_F(DMAPriorityTest, RotatingPriority) {
    // Configure rotating priorities
    priority.configure_priorities(0x80);  // Rotating priority mode
    
    uint8_t first = priority.get_highest_priority_channel();
    uint8_t second = priority.get_highest_priority_channel();
    
    // Verify rotation
    EXPECT_NE(first, second);
}

Test in VS Code's integrated terminal:

cd src/memory
g++ -o priority_test dma_priority_test.cpp -lgtest -lgtest_main
./priority_test

Magic-1 DMA Transfer Modes Implementation

Let's implement the different DMA transfer modes for the Magic-1:

class DMATransferManager {
private:
    enum class TransferMode {
        SINGLE,             // Single byte/word transfer
        BLOCK,              // Block transfer
        DEMAND,            // Demand transfer
        CASCADE            // Cascade mode (chaining)
    };

    struct TransferState {
        uint16_t current_source;
        uint16_t current_dest;
        uint16_t remaining;
        TransferMode mode;
        bool auto_init;
        bool terminal_count;
    };

    std::array<TransferState, 4> channels;
    MemoryBus& bus;

public:
    void configure_transfer(uint8_t channel, uint8_t mode_reg) {
        if (channel >= channels.size()) return;
        
        auto& state = channels[channel];
        state.mode = static_cast<TransferMode>((mode_reg >> 6) & 0x03);
        state.auto_init = (mode_reg & 0x10) != 0;
        
        // Initialize transfer state
        init_transfer_state(channel);
    }

    bool execute_transfer(uint8_t channel) {
        auto& state = channels[channel];
        
        switch (state.mode) {
            case TransferMode::SINGLE:
                return execute_single_transfer(channel);
            case TransferMode::BLOCK:
                return execute_block_transfer(channel);
            case TransferMode::DEMAND:
                return execute_demand_transfer(channel);
            case TransferMode::CASCADE:
                return execute_cascade_transfer(channel);
        }
        return false;
    }
};

Create the test file:

#include <gtest/gtest.h>
#include "dma_transfer.h"

class DMATransferTest : public ::testing::Test {
protected:
    MemoryBus bus;
    DMATransferManager transfer{bus};
    
    void SetUp() override {
        // Initialize test memory
        uint8_t test_data[] = {0x11, 0x22, 0x33, 0x44};
        memcpy((void*)0x1000, test_data, sizeof(test_data));
    }
};

TEST_F(DMATransferTest, SingleTransfer) {
    // Configure single transfer mode
    transfer.configure_transfer(0, 0x40);  // Single transfer mode
    
    // Execute transfer
    EXPECT_TRUE(transfer.execute_transfer(0));
    
    // Verify single byte transferred
    EXPECT_EQ(*(uint8_t*)0x2000, 0x11);
}

Build and run tests in VS Code's integrated terminal:

cd src/memory
g++ -o transfer_test dma_transfer_test.cpp -lgtest -lgtest_main
./transfer_test

Magic-1 DMA Chaining System

Let's implement DMA channel chaining to allow complex memory transfer operations.

class DMAChainManager {
    struct ChainDescriptor {
        uint16_t next_descriptor;  // Address of next descriptor
        uint16_t source_addr;     // Source address
        uint16_t dest_addr;       // Destination address
        uint16_t count;           // Transfer count
        uint8_t control;          // Control flags
        bool last_in_chain;       // End of chain marker
    };

    static constexpr uint8_t CHAIN_ACTIVE = 0x80;
    static constexpr uint8_t CHAIN_AUTO   = 0x40;
    static constexpr uint8_t CHAIN_INT    = 0x20;

    std::array<ChainDescriptor*, 4> active_chains;
    MemoryBus& bus;

public:
    bool start_chain(uint8_t channel, uint16_t first_descriptor) {
        if (channel >= active_chains.size()) {
            return false;
        }

        auto descriptor = read_descriptor(first_descriptor);
        if (!descriptor) {
            return false;
        }

        active_chains[channel] = descriptor;
        return process_chain(channel);
    }

private:
    bool process_chain(uint8_t channel) {
        auto current = active_chains[channel];
        while (current && (current->control & CHAIN_ACTIVE)) {
            execute_transfer(current);
            
            if (current->last_in_chain) {
                break;
            }
            
            current = read_descriptor(current->next_descriptor);
        }
        return true;
    }
};

Create a test file:

class DMAChainTest : public ::testing::Test {
protected:
    MemoryBus bus;
    DMAChainManager chain{bus};

    void SetUp() override {
        // Setup test chain descriptors
        ChainDescriptor desc1 = {
            .next_descriptor = 0x1100,
            .source_addr = 0x2000,
            .dest_addr = 0x3000,
            .count = 16,
            .control = 0x80,
            .last_in_chain = false
        };

        ChainDescriptor desc2 = {
            .next_descriptor = 0,
            .source_addr = 0x2100,
            .dest_addr = 0x3100,
            .count = 16,
            .control = 0x80,
            .last_in_chain = true
        };

        memcpy((void*)0x1000, &desc1, sizeof(desc1));
        memcpy((void*)0x1100, &desc2, sizeof(desc2));
    }
};

TEST_F(DMAChainTest, ChainExecution) {
    EXPECT_TRUE(chain.start_chain(0, 0x1000));
    
    // Verify both transfers completed
    EXPECT_TRUE(verify_transfer(0x2000, 0x3000, 16));
    EXPECT_TRUE(verify_transfer(0x2100, 0x3100, 16));
}

Run tests in VS Code's integrated terminal:

cd src/memory
g++ -o chain_test dma_chain_test.cpp -lgtest -lgtest_main
./chain_test

Magic-1 DMA Interrupt System Implementation

Let's implement the DMA interrupt handling system with proper interrupt management and chaining support.

class DMAInterruptManager {
private:
    struct InterruptState {
        bool enabled;
        bool pending;
        bool in_service;
        uint8_t vector;
        uint8_t priority;
    };

    std::array<InterruptState, 4> channel_interrupts;
    uint8_t interrupt_mask;
    uint8_t pending_interrupts;
    uint8_t current_interrupt;

public:
    void enable_channel_interrupt(uint8_t channel, uint8_t vector) {
        if (channel < channel_interrupts.size()) {
            channel_interrupts[channel] = {
                .enabled = true,
                .pending = false,
                .in_service = false,
                .vector = vector,
                .priority = channel
            };
            interrupt_mask |= (1 << channel);
        }
    }

    uint8_t check_interrupts() {
        for (uint8_t i = 0; i < channel_interrupts.size(); i++) {
            if (channel_interrupts[i].pending && 
                channel_interrupts[i].enabled &&
                !channel_interrupts[i].in_service) {
                channel_interrupts[i].in_service = true;
                current_interrupt = i;
                return channel_interrupts[i].vector;
            }
        }
        return 0;
    }
};

Create the test file:

#include <gtest/gtest.h>
#include "dma_interrupt.h"

class DMAInterruptTest : public ::testing::Test {
protected:
    DMAInterruptManager interrupts;

    void SetUp() override {
        // Configure test interrupts
        for (uint8_t i = 0; i < 4; i++) {
            interrupts.enable_channel_interrupt(i, 0x40 + i);
        }
    }
};

TEST_F(DMAInterruptTest, InterruptPriority) {
    // Trigger multiple interrupts
    interrupts.trigger_interrupt(1);
    interrupts.trigger_interrupt(3);
    
    // Should get highest priority interrupt first
    EXPECT_EQ(interrupts.check_interrupts(), 0x41);
    
    // After acknowledging, should get next interrupt
    interrupts.acknowledge_interrupt(1);
    EXPECT_EQ(interrupts.check_interrupts(), 0x43);
}

Build and run the tests in VS Code's integrated terminal:

cd src/memory
g++ -o interrupt_test dma_interrupt_test.cpp -lgtest -lgtest_main
./interrupt_test

Magic-1 DMA Status and Control Registers Implementation

Let's implement the DMA status and control registers system:

class DMARegisters {
    struct ChannelRegisters {
        uint16_t base_address;    // Base address register
        uint16_t base_count;      // Base count register
        uint16_t current_address; // Current address register
        uint16_t current_count;   // Current count register
        uint8_t mode;            // Mode register
        uint8_t status;          // Status register
        uint8_t command;         // Command register
        uint8_t request;         // Request register
        uint8_t mask;           // Mask register
    };

    std::array<ChannelRegisters, 4> channels;

public:
    enum StatusBits {
        TC      = 0x80,  // Terminal count
        REQUEST = 0x40,  // Request pending
        BUSY    = 0x20,  // Channel busy
        DONE    = 0x10,  // Transfer complete
        ERROR   = 0x08   // Error detected
    };

    // Status register access methods
    uint8_t read_status(uint8_t channel) {
        if (channel >= channels.size()) {
            return 0xFF;
        }

        uint8_t status = channels[channel].status;
        // Clear status bits after read
        channels[channel].status &= ~(TC | REQUEST);
        return status;
    }

    void write_command(uint8_t channel, uint8_t value) {
        if (channel < channels.size()) {
            channels[channel].command = value;
            update_channel_state(channel);
        }
    }
};

Create the test file:

#include <gtest/gtest.h>
#include "dma_registers.h"

class DMARegistersTest : public ::testing::Test {
protected:
    DMARegisters regs;
};

TEST_F(DMARegistersTest, StatusRegister) {
    // Write test status
    regs.write_command(0, 0x80); // Set TC bit
    
    // Read and verify status
    uint8_t status = regs.read_status(0);
    EXPECT_EQ(status & DMARegisters::TC, DMARegisters::TC);
    
    // Verify TC bit cleared after read
    status = regs.read_status(0);
    EXPECT_EQ(status & DMARegisters::TC, 0);
}

Build and run the tests in VS Code's integrated terminal:

cd src/memory
g++ -o register_test dma_registers_test.cpp -lgtest -lgtest_main
./register_test

Magic-1 DMA Error Handling System

Let's implement an error handling system for the DMA controller that can detect and manage various error conditions.

class DMAErrorHandler {
private:
    struct ErrorState {
        uint8_t error_code;
        uint16_t error_address;
        uint8_t channel;
        bool requires_reset;
    };

    struct ErrorCounts {
        uint32_t bus_errors;
        uint32_t timeout_errors;
        uint32_t alignment_errors;
        uint32_t overrun_errors;
    } counts;

    std::array<ErrorState, 4> channel_errors;
    bool system_error_state;

public:
    enum ErrorCodes {
        ERR_NONE = 0x00,
        ERR_BUS = 0x01,
        ERR_TIMEOUT = 0x02,
        ERR_ALIGNMENT = 0x04,
        ERR_OVERRUN = 0x08,
        ERR_PROGRAMMING = 0x10
    };

    bool handle_error(uint8_t channel, uint8_t error_code, uint16_t address) {
        if (channel >= channel_errors.size()) {
            return false;
        }

        // Update error state
        channel_errors[channel] = {
            .error_code = error_code,
            .error_address = address,
            .channel = channel,
            .requires_reset = (error_code & (ERR_BUS | ERR_PROGRAMMING)) != 0
        };

        // Update statistics
        update_error_counts(error_code);

        // Handle critical errors
        if (channel_errors[channel].requires_reset) {
            system_error_state = true;
            return false;
        }

        return true;
    }
};

Create a test file:

#include <gtest/gtest.h>
#include "dma_error_handler.h"

class DMAErrorHandlerTest : public ::testing::Test {
protected:
    DMAErrorHandler error_handler;
};

TEST_F(DMAErrorHandlerTest, BusError) {
    bool result = error_handler.handle_error(0, 
                                           DMAErrorHandler::ERR_BUS, 
                                           0x1234);
    
    EXPECT_FALSE(result);
    EXPECT_TRUE(error_handler.requires_reset(0));
    EXPECT_EQ(error_handler.get_error_address(0), 0x1234);
}

TEST_F(DMAErrorHandlerTest, RecoverableError) {
    bool result = error_handler.handle_error(1, 
                                           DMAErrorHandler::ERR_TIMEOUT,
                                           0x5678);
    
    EXPECT_TRUE(result);
    EXPECT_FALSE(error_handler.requires_reset(1));
}

Build and run the tests in VS Code's integrated terminal:

cd src/memory
g++ -o error_test dma_error_handler_test.cpp -lgtest -lgtest_main
./error_test

Magic-1 DMA Diagnostic System Implementation

Let's create a comprehensive diagnostic system for the DMA controller.

class DMADiagnostics {
private:
    struct DiagnosticEntry {
        uint64_t timestamp;
        uint8_t channel;
        uint16_t address;
        uint16_t count;
        uint8_t status;
        std::string message;
    };

    std::deque<DiagnosticEntry> diagnostic_log;
    static constexpr size_t MAX_LOG_ENTRIES = 256;

public:
    void log_event(uint8_t channel, const std::string& message) {
        diagnostic_log.push_front({
            .timestamp = get_system_ticks(),
            .channel = channel,
            .address = get_channel_address(channel),
            .count = get_channel_count(channel),
            .status = get_channel_status(channel),
            .message = message
        });

        if (diagnostic_log.size() > MAX_LOG_ENTRIES) {
            diagnostic_log.pop_back();
        }
    }

    std::string generate_report() {
        std::stringstream report;
        report << "DMA Diagnostic Report\n";
        report << "====================\n\n";
        
        for (const auto& entry : diagnostic_log) {
            report << format_entry(entry) << "\n";
        }
        
        return report.str();
    }
};

Create the test file:

#include <gtest/gtest.h>
#include "dma_diagnostics.h"

class DMADiagnosticsTest : public ::testing::Test {
protected:
    DMADiagnostics diag;

    void SetUp() override {
        // Log some test events
        diag.log_event(0, "Transfer started");
        diag.log_event(0, "Transfer completed");
        diag.log_event(1, "Error detected");
    }
};

TEST_F(DMADiagnosticsTest, LoggingAndReporting) {
    std::string report = diag.generate_report();
    
    // Verify all events are logged
    EXPECT_TRUE(report.find("Transfer started") != std::string::npos);
    EXPECT_TRUE(report.find("Transfer completed") != std::string::npos);
    EXPECT_TRUE(report.find("Error detected") != std::string::npos);
}

Build and run the tests in VS Code's integrated terminal:

cd src/memory
g++ -o diagnostic_test dma_diagnostics_test.cpp -lgtest -lgtest_main
./diagnostic_test

This implementation provides:

  • Event logging with timestamps
  • Channel state tracking
  • Diagnostic report generation
  • Circular buffer for log entries
  • Detailed status information

Magic-1 DMA Performance Monitor Implementation

Let's implement a performance monitoring system for the DMA controller to track and analyze transfer metrics.

#include <chrono>
#include <array>
#include <vector>

class DMAPerformanceMonitor {
private:
    struct ChannelMetrics {
        uint64_t bytes_transferred;
        uint32_t transfers_completed;
        uint32_t bus_utilization;
        std::chrono::microseconds total_transfer_time;
        std::vector<uint32_t> transfer_latencies;
    };

    std::array<ChannelMetrics, 4> channel_metrics;
    std::chrono::steady_clock::time_point last_sample;

public:
    void record_transfer(uint8_t channel, uint16_t bytes, 
                        std::chrono::microseconds duration) {
        if (channel >= channel_metrics.size()) return;

        auto& metrics = channel_metrics[channel];
        metrics.bytes_transferred += bytes;
        metrics.transfers_completed++;
        metrics.total_transfer_time += duration;
        metrics.transfer_latencies.push_back(duration.count());

        update_bus_utilization(channel, duration);
    }

    float get_transfer_rate(uint8_t channel) {
        const auto& metrics = channel_metrics[channel];
        if (metrics.total_transfer_time.count() == 0) return 0.0f;

        return static_cast<float>(metrics.bytes_transferred) / 
               metrics.total_transfer_time.count() * 1000000.0f;  // Bytes/sec
    }
};

Create the test file:

#include <gtest/gtest.h>
#include "dma_performance.h"

class DMAPerformanceTest : public ::testing::Test {
protected:
    DMAPerformanceMonitor perf;
};

TEST_F(DMAPerformanceTest, TransferRateCalculation) {
    // Record a test transfer: 1KB in 1ms
    perf.record_transfer(0, 1024, std::chrono::microseconds(1000));
    
    // Expected rate: 1MB/sec
    float rate = perf.get_transfer_rate(0);
    EXPECT_NEAR(rate, 1048576.0f, 1.0f);
}

Build and run tests in VS Code's integrated terminal:

cd src/memory
g++ -o perf_test dma_performance_test.cpp -lgtest -lgtest_main -pthread
./perf_test

Magic-1 DMA Configuration System

Let's implement a robust configuration system for the DMA controller.

class DMAConfiguration {
private:
    struct DMAConfig {
        uint8_t channel_count;
        uint16_t buffer_size;
        bool auto_initialize;
        bool rotating_priority;
        uint8_t timing_mode;
    };

    struct ChannelConfig {
        uint16_t base_address;
        uint16_t transfer_size;
        uint8_t transfer_mode;
        bool auto_reload;
        uint8_t priority_level;
    };

    DMAConfig global_config;
    std::array<ChannelConfig, 4> channel_configs;

public:
    bool initialize(const DMAConfig& config) {
        if (!validate_config(config)) {
            return false;
        }

        global_config = config;
        configure_hardware();
        return true;
    }

    bool configure_channel(uint8_t channel, const ChannelConfig& config) {
        if (channel >= channel_configs.size()) {
            return false;
        }

        channel_configs[channel] = config;
        apply_channel_config(channel);
        return true;
    }
};

Create a test file:

#include <gtest/gtest.h>
#include "dma_config.h"

class DMAConfigurationTest : public ::testing::Test {
protected:
    DMAConfiguration config;
};

TEST_F(DMAConfigurationTest, BasicConfiguration) {
    DMAConfiguration::DMAConfig global_config {
        .channel_count = 4,
        .buffer_size = 1024,
        .auto_initialize = true,
        .rotating_priority = true,
        .timing_mode = 0
    };

    EXPECT_TRUE(config.initialize(global_config));

    DMAConfiguration::ChannelConfig channel_config {
        .base_address = 0x1000,
        .transfer_size = 512,
        .transfer_mode = 0,
        .auto_reload = true,
        .priority_level = 1
    };

    EXPECT_TRUE(config.configure_channel(0, channel_config));
}

Build and run the tests in VS Code's integrated terminal:

cd src/memory
g++ -o config_test dma_config_test.cpp -lgtest -lgtest_main
./config_test

Magic-1 DMA Hardware Interface Implementation

Let's implement the hardware interface layer for the DMA controller.

class DMAHardwareInterface {
private:
    // Hardware register offsets
    static constexpr uint16_t DMA_BASE = 0xF900;
    static constexpr uint16_t STATUS_REG = 0x00;
    static constexpr uint16_t COMMAND_REG = 0x01;
    static constexpr uint16_t MODE_REG = 0x02;
    static constexpr uint16_t MASK_REG = 0x03;

    // Control bits
    static constexpr uint8_t DMA_ENABLE = 0x80;
    static constexpr uint8_t DMA_RESET = 0x40;
    static constexpr uint8_t DMA_TC_INT = 0x20;

    struct HardwareState {
        bool enabled;
        bool reset_pending;
        uint8_t command_reg;
        uint8_t status_reg;
        std::array<uint16_t, 4> base_address;
        std::array<uint16_t, 4> count;
    } hw_state;

public:
    bool reset_hardware() {
        hw_state.reset_pending = true;
        write_register(COMMAND_REG, DMA_RESET);
        
        // Wait for reset to complete
        for(int i = 0; i < 100; i++) {
            if((read_register(STATUS_REG) & DMA_RESET) == 0) {
                hw_state.reset_pending = false;
                return true;
            }
        }
        return false;
    }

    void write_channel_registers(uint8_t channel, uint16_t address, uint16_t count) {
        uint16_t base = DMA_BASE + (channel * 4);
        write_register(base + 0, address & 0xFF);
        write_register(base + 1, (address >> 8) & 0xFF);
        write_register(base + 2, count & 0xFF);
        write_register(base + 3, (count >> 8) & 0xFF);
    }
};

Create a test file:

#include <gtest/gtest.h>
#include "dma_hardware.h"

class DMAHardwareTest : public ::testing::Test {
protected:
    DMAHardwareInterface hw;
};

TEST_F(DMAHardwareTest, HardwareReset) {
    EXPECT_TRUE(hw.reset_hardware());
    EXPECT_EQ(hw.read_register(0x00), 0x00);  // Status should be cleared
}

TEST_F(DMAHardwareTest, ChannelRegisters) {
    hw.write_channel_registers(0, 0x1234, 0x100);
    
    // Verify register contents
    EXPECT_EQ(hw.read_register(0xF900), 0x34);  // Address low
    EXPECT_EQ(hw.read_register(0xF901), 0x12);  // Address high
    EXPECT_EQ(hw.read_register(0xF902), 0x00);  // Count low
    EXPECT_EQ(hw.read_register(0xF903), 0x01);  // Count high
}

Build and run the tests in VS Code's integrated terminal:

cd src/memory
g++ -o hardware_test dma_hardware_test.cpp -lgtest -lgtest_main
./hardware_test

Magic-1 DMA Register Access Validation

Let's implement a robust validation system for DMA register access.

class DMARegisterValidator {
    struct RegisterAccess {
        uint16_t address;
        uint8_t mask;
        bool writable;
        bool privileged;
    };

    static const std::array<RegisterAccess, 8> REGISTER_MAP {{
        {0xF900, 0xFF, true,  false}, // Channel 0 address
        {0xF901, 0xFF, true,  false}, // Channel 0 count
        {0xF902, 0xFF, true,  true},  // Channel 0 control
        {0xF903, 0x0F, true,  true},  // Channel 0 status
        {0xF904, 0xFF, false, true},  // Global status
        {0xF905, 0x7F, true,  true},  // Command register
        {0xF906, 0x3F, true,  true},  // Mode register
        {0xF907, 0x0F, true,  true}   // Mask register
    }};

public:
    bool validate_read(uint16_t address, uint8_t* privilege_level) {
        for (const auto& reg : REGISTER_MAP) {
            if (reg.address == address) {
                return !reg.privileged || *privilege_level <= 1;
            }
        }
        return false;
    }

    bool validate_write(uint16_t address, uint8_t value, uint8_t privilege_level) {
        for (const auto& reg : REGISTER_MAP) {
            if (reg.address == address) {
                if (!reg.writable) return false;
                if (reg.privileged && privilege_level > 1) return false;
                if ((value & ~reg.mask) != 0) return false;
                return true;
            }
        }
        return false;
    }
};

Let's create the test file:

#include <gtest/gtest.h>
#include "dma_register_validator.h"

class DMARegisterValidatorTest : public ::testing::Test {
protected:
    DMARegisterValidator validator;
    uint8_t privilege_level = 0;
};

TEST_F(DMARegisterValidatorTest, ValidateReads) {
    EXPECT_TRUE(validator.validate_read(0xF900, &privilege_level));
    EXPECT_TRUE(validator.validate_read(0xF904, &privilege_level));
    EXPECT_FALSE(validator.validate_read(0xF910, &privilege_level));
}

TEST_F(DMARegisterValidatorTest, ValidateWrites) {
    EXPECT_TRUE(validator.validate_write(0xF900, 0x55, privilege_level));
    EXPECT_FALSE(validator.validate_write(0xF904, 0x55, privilege_level));
    EXPECT_FALSE(validator.validate_write(0xF900, 0xFF, 3));
}

Build and run the tests in VS Code's integrated terminal:

cd src/memory
g++ -o validator_test dma_register_validator_test.cpp -lgtest -lgtest_main
./validator_test

Magic-1 DMA Access Protection System

Let's implement a protection system for DMA access control.

class DMAProtectionManager {
private:
    struct ProtectionEntry {
        uint16_t start_address;
        uint16_t end_address;
        bool read_allowed;
        bool write_allowed;
        uint8_t required_privilege;
    };

    std::vector<ProtectionEntry> protection_map;
    uint8_t current_privilege_level{3};  // Default to lowest privilege

public:
    bool check_access(uint16_t address, bool is_write) {
        for (const auto& entry : protection_map) {
            if (address >= entry.start_address && 
                address <= entry.end_address) {
                
                if (current_privilege_level > entry.required_privilege) {
                    return false;
                }

                return is_write ? entry.write_allowed : entry.read_allowed;
            }
        }
        return false;  // Deny if no matching entry
    }

    void add_protection_region(uint16_t start, uint16_t end, 
                             bool read, bool write, uint8_t privilege) {
        protection_map.push_back({
            start, end, read, write, privilege
        });
    }
};

Create the test file:

#include <gtest/gtest.h>
#include "dma_protection.h"

class DMAProtectionTest : public ::testing::Test {
protected:
    DMAProtectionManager protection;

    void SetUp() override {
        // Set up test protection regions
        protection.add_protection_region(
            0x1000, 0x1FFF,    // ROM region
            true, false, 0      // Read-only, supervisor only
        );
        
        protection.add_protection_region(
            0x2000, 0x2FFF,    // RAM region
            true, true, 1       // Read-write, user mode allowed
        );
    }
};

TEST_F(DMAProtectionTest, AccessControl) {
    // Test ROM access
    EXPECT_TRUE(protection.check_access(0x1500, false));   // Read OK
    EXPECT_FALSE(protection.check_access(0x1500, true));   // Write blocked
    
    // Test RAM access
    EXPECT_TRUE(protection.check_access(0x2500, false));   // Read OK
    EXPECT_TRUE(protection.check_access(0x2500, true));    // Write OK
    
    // Test invalid region
    EXPECT_FALSE(protection.check_access(0x3000, false));  // Outside any region
}

Build and run the tests in VS Code's integrated terminal:

cd src/memory
g++ -o protection_test dma_protection_test.cpp -lgtest -lgtest_main
./protection_test

Magic-1 DMA Privilege Level Management

Let's implement a privilege level management system for the DMA controller.

class DMAPrivilegeManager {
private:
    enum PrivilegeLevel {
        SUPERVISOR = 0,    // Full system access
        PROTECTED = 1,     // Protected mode access
        USER = 2,         // User mode access
        RESTRICTED = 3     // Minimal access
    };

    struct PrivilegeState {
        uint8_t current_level;
        uint8_t requested_level;
        bool privilege_switch_pending;
        uint16_t privilege_stack[4];
        uint8_t stack_pointer;
    } state;

public:
    bool change_privilege_level(uint8_t new_level) {
        if (new_level > RESTRICTED || new_level < state.current_level) {
            return false;
        }

        state.privilege_stack[state.stack_pointer++] = state.current_level;
        state.current_level = new_level;
        return true;
    }

    bool check_privilege(uint8_t required_level) {
        return state.current_level <= required_level;
    }
};

Create the test file:

#include <gtest/gtest.h>
#include "dma_privilege.h"

class DMAPrivilegeTest : public ::testing::Test {
protected:
    DMAPrivilegeManager privilege;
};

TEST_F(DMAPrivilegeTest, PrivilegeLevelChange) {
    // Start at supervisor level
    EXPECT_TRUE(privilege.check_privilege(0));
    
    // Change to protected mode
    EXPECT_TRUE(privilege.change_privilege_level(1));
    EXPECT_TRUE(privilege.check_privilege(1));
    EXPECT_FALSE(privilege.check_privilege(0));
    
    // Cannot elevate privilege
    EXPECT_FALSE(privilege.change_privilege_level(0));
}

Build and run the tests in VS Code's integrated terminal:

cd src/memory
g++ -o privilege_test dma_privilege_test.cpp -lgtest -lgtest_main
./privilege_test

Magic-1 Project Status Overview

CPU Core Implementation (90% Complete)

✅ Basic CPU architecture ✅ Register file implementation ✅ ALU operations ✅ Pipeline stages ✅ Microcode execution ✅ Memory interface ✅ Instruction decoding ✅ Interrupt handling

Memory System (80% Complete)

✅ Memory management ✅ ROM/RAM separation ✅ DMA controller base ✅ DMA channel management ✅ DMA interrupt handling ✅ DMA error handling ✅ Memory protection ✅ Cache implementation ❌ Memory refresh system ❌ Full DMA security audit

I/O Devices (60% Complete)

✅ UART basic implementation ✅ UART2 SLIP support ✅ CF card interface basics ❌ Complete CF card filesystem ❌ RTC implementation ❌ Timer implementation ❌ Device enumeration ❌ I/O security

Network Stack (40% Complete)

✅ SLIP protocol handler ✅ Basic IP handling ✅ TCP framework ❌ Complete TCP implementation ❌ UDP support ❌ Network security ❌ Protocol validation ❌ Network diagnostics

File System (30% Complete)

✅ Basic CF card access ❌ File system structure ❌ Directory handling ❌ File operations ❌ Access permissions ❌ File system recovery ❌ Journaling

Testing Infrastructure (70% Complete)

✅ Basic unit tests ✅ CPU instruction tests ✅ Memory tests ✅ DMA tests ❌ Integration tests ❌ System tests ❌ Performance tests ❌ Security tests

Documentation (40% Complete)

✅ Basic architecture docs ❌ API documentation ❌ Protocol specifications ❌ Security guidelines ❌ User manual ❌ Developer guide

Magic-1 Memory System Implementation

Let's complete the remaining memory system components, starting with the memory refresh system.

class MemoryRefreshController {
    struct RefreshState {
        uint32_t refresh_counter;
        uint32_t refresh_rate;      // Refresh cycles per second
        bool refresh_pending;
        uint16_t last_refresh_row;
        std::chrono::steady_clock::time_point last_refresh;
    };

    RefreshState state;
    static constexpr uint32_t REFRESH_RATE_HZ = 64;  // 64 refreshes per ms
    static constexpr uint16_t TOTAL_ROWS = 256;      // 256 rows to refresh

public:
    bool check_refresh_needed() {
        auto now = std::chrono::steady_clock::now();
        auto elapsed = std::chrono::duration_cast<std::chrono::microseconds>(
            now - state.last_refresh).count();
            
        return elapsed >= (1000000 / (REFRESH_RATE_HZ * TOTAL_ROWS));
    }

    void perform_refresh_cycle() {
        state.last_refresh_row = (state.last_refresh_row + 1) % TOTAL_ROWS;
        state.last_refresh = std::chrono::steady_clock::now();
        state.refresh_counter++;
    }
};

Let's test this implementation:

#include <gtest/gtest.h>
#include "memory_refresh.h"

class MemoryRefreshTest : public ::testing::Test {
protected:
    MemoryRefreshController refresh;
};

TEST_F(MemoryRefreshTest, RefreshTiming) {
    // Should not need refresh immediately
    EXPECT_FALSE(refresh.check_refresh_needed());
    
    // Wait for refresh interval
    std::this_thread::sleep_for(std::chrono::microseconds(62));
    
    // Should need refresh now
    EXPECT_TRUE(refresh.check_refresh_needed());
}

Build and run the tests in VS Code's integrated terminal:

cd src/memory
g++ -o refresh_test memory_refresh_test.cpp -lgtest -lgtest_main -pthread
./refresh_test

Memory System - DMA Security Audit Implementation

Let's implement a comprehensive security audit system for the DMA controller.

#include <chrono>
#include <vector>
#include <mutex>
#include <sstream>

class DMASecurityAudit {
private:
    struct AuditEntry {
        std::chrono::system_clock::time_point timestamp;
        uint8_t channel;
        uint16_t address;
        uint16_t length;
        uint8_t privilege_level;
        std::string operation;
        bool violation;
    };

    std::vector<AuditEntry> audit_log;
    std::mutex log_mutex;
    static constexpr size_t MAX_LOG_ENTRIES = 1024;

public:
    void log_access(uint8_t channel, uint16_t address, uint16_t length, 
                   const std::string& op, uint8_t priv_level) {
        std::lock_guard<std::mutex> lock(log_mutex);
        
        audit_log.push_back({
            .timestamp = std::chrono::system_clock::now(),
            .channel = channel,
            .address = address,
            .length = length,
            .privilege_level = priv_level,
            .operation = op,
            .violation = check_violation(address, length, priv_level)
        });

        if (audit_log.size() > MAX_LOG_ENTRIES) {
            audit_log.erase(audit_log.begin());
        }
    }
};

Create a test file:

#include <gtest/gtest.h>
#include "dma_security_audit.h"

class DMASecurityAuditTest : public ::testing::Test {
protected:
    DMASecurityAudit audit;
};

TEST_F(DMASecurityAuditTest, LogAccess) {
    // Log a legitimate access
    audit.log_access(0, 0x1000, 256, "DMA_READ", 0);
    
    // Log a potential violation
    audit.log_access(1, 0xF000, 1024, "DMA_WRITE", 2);
    
    auto report = audit.generate_report();
    EXPECT_TRUE(report.find("DMA_READ") != std::string::npos);
    EXPECT_TRUE(report.find("VIOLATION") != std::string::npos);
}

Run the tests in VS Code's integrated terminal:

cd src/memory
g++ -o security_test dma_security_audit_test.cpp -lgtest -lgtest_main -pthread
./security_test

Magic-1 I/O System Implementation

Let's implement the complete I/O system starting with the UART controller.

#include <queue>
#include <mutex>
#include <array>

class UARTController {
private:
    struct UARTRegisters {
        uint8_t data;         // Data register (R/W)
        uint8_t status;       // Status register (R)
        uint8_t control;      // Control register (W)
        uint8_t baud;         // Baud rate register (W)
    };

    static constexpr uint8_t STATUS_RX_READY = 0x01;
    static constexpr uint8_t STATUS_TX_READY = 0x02;
    static constexpr uint8_t STATUS_ERROR    = 0x04;

    std::array<UARTRegisters, 2> uarts;
    std::array<std::queue<uint8_t>, 2> rx_buffers;
    std::array<std::queue<uint8_t>, 2> tx_buffers;
    std::mutex uart_mutex;

public:
    bool write_byte(uint8_t uart_num, uint8_t data) {
        if (uart_num >= uarts.size()) return false;
        
        std::lock_guard<std::mutex> lock(uart_mutex);
        if (tx_buffers[uart_num].size() < 16) {
            tx_buffers[uart_num].push(data);
            uarts[uart_num].status |= STATUS_TX_READY;
            return true;
        }
        return false;
    }
};

Create a test file:

#include <gtest/gtest.h>
#include "uart_controller.h"

class UARTControllerTest : public ::testing::Test {
protected:
    UARTController uart;
};

TEST_F(UARTControllerTest, BasicTransmit) {
    // Test writing to UART0
    EXPECT_TRUE(uart.write_byte(0, 0x55));
    
    // Verify byte was queued
    EXPECT_EQ(uart.get_tx_queue_size(0), 1);
    EXPECT_TRUE(uart.is_tx_ready(0));
}

TEST_F(UARTControllerTest, BufferOverflow) {
    // Fill buffer
    for (int i = 0; i < 16; i++) {
        EXPECT_TRUE(uart.write_byte(0, 0x55));
    }
    
    // Should fail on overflow
    EXPECT_FALSE(uart.write_byte(0, 0x55));
}

Build and run the tests in VS Code's integrated terminal:

cd src/io
g++ -o uart_test uart_controller_test.cpp -lgtest -lgtest_main -pthread
./uart_test

Magic-1 I/O System Implementation

Let's continue implementing the I/O system with an improved CF card interface.

class CFCardController {
private:
    struct CFRegisters {
        uint16_t data;          // Data register (R/W)
        uint8_t error;          // Error register (R)
        uint8_t sector_count;   // Sector count (R/W)
        uint8_t sector;         // Sector number (R/W)
        uint8_t cylinder_low;   // Cylinder low (R/W)
        uint8_t cylinder_high;  // Cylinder high (R/W)
        uint8_t status;         // Status register (R)
        uint8_t command;        // Command register (W)
    };

    CFRegisters regs;
    std::vector<uint8_t> sector_buffer;
    bool card_present{false};
    bool dma_enabled{false};

public:
    enum CFCommand {
        READ_SECTORS = 0x20,
        WRITE_SECTORS = 0x30,
        IDENTIFY = 0xEC,
        SET_FEATURES = 0xEF
    };

    bool initialize() {
        sector_buffer.resize(512);
        return probe_card();
    }

    bool read_sector(uint32_t lba, void* buffer) {
        if (!card_present) return false;

        regs.sector_count = 1;
        regs.sector = lba & 0xFF;
        regs.cylinder_low = (lba >> 8) & 0xFF;
        regs.cylinder_high = (lba >> 16) & 0xFF;
        regs.command = READ_SECTORS;

        return wait_for_completion() && read_buffer(buffer);
    }
};

Create the test file:

class CFCardControllerTest : public ::testing::Test {
protected:
    CFCardController cf;

    void SetUp() override {
        ASSERT_TRUE(cf.initialize());
    }
};

TEST_F(CFCardControllerTest, ReadSector) {
    uint8_t buffer[512];
    EXPECT_TRUE(cf.read_sector(0, buffer));
    
    // Verify sector signature
    EXPECT_EQ(buffer[510], 0x55);
    EXPECT_EQ(buffer[511], 0xAA);
}

TEST_F(CFCardControllerTest, WriteProtect) {
    uint8_t buffer[512] = {0};
    // Should fail on write-protected area
    EXPECT_FALSE(cf.write_sector(0, buffer));
}

Build and run the tests in VS Code's integrated terminal:

cd src/io
g++ -o cf_test cf_card_controller_test.cpp -lgtest -lgtest_main
./cf_test

Magic-1 Real-Time Clock Implementation

Let's implement the Real-Time Clock (RTC) interface for the Magic-1 system.

#include <chrono>
#include <ctime>

class RTCController {
private:
    struct RTCRegisters {
        uint8_t seconds;      // 0-59
        uint8_t minutes;      // 0-59
        uint8_t hours;        // 0-23
        uint8_t day;          // 1-31
        uint8_t month;        // 1-12
        uint8_t year;         // 0-99
        uint8_t century;      // 19-20
        uint8_t status;       // Status register
        uint8_t control;      // Control register
    } regs;

    bool battery_ok{true};
    bool clock_running{false};

public:
    bool initialize() {
        // Set initial time from system clock
        auto now = std::chrono::system_clock::now();
        auto time = std::chrono::system_clock::to_time_t(now);
        auto* tm = std::localtime(&time);

        regs.seconds = tm->tm_sec;
        regs.minutes = tm->tm_min;
        regs.hours = tm->tm_hour;
        regs.day = tm->tm_mday;
        regs.month = tm->tm_mon + 1;
        regs.year = tm->tm_year % 100;
        regs.century = 20;
        
        clock_running = true;
        return true;
    }

    uint8_t read_register(uint8_t reg) {
        switch(reg) {
            case 0: return regs.seconds;
            case 1: return regs.minutes;
            case 2: return regs.hours;
            case 3: return regs.day;
            case 4: return regs.month;
            case 5: return regs.year;
            case 6: return regs.century;
            case 7: return regs.status;
            default: return 0xFF;
        }
    }
};

Let's create a test file:

#include <gtest/gtest.h>
#include "rtc_controller.h"

class RTCControllerTest : public ::testing::Test {
protected:
    RTCController rtc;

    void SetUp() override {
        ASSERT_TRUE(rtc.initialize());
    }
};

TEST_F(RTCControllerTest, TimeFormat) {
    // Check valid ranges
    EXPECT_LE(rtc.read_register(0), 59);  // seconds
    EXPECT_LE(rtc.read_register(1), 59);  // minutes
    EXPECT_LE(rtc.read_register(2), 23);  // hours
    EXPECT_LE(rtc.read_register(3), 31);  // day
    EXPECT_LE(rtc.read_register(4), 12);  // month
    EXPECT_LE(rtc.read_register(5), 99);  // year
}

Build and run the tests in VS Code's integrated terminal:

cd src/io
g++ -o rtc_test rtc_controller_test.cpp -lgtest -lgtest_main
./rtc_test

Magic-1 Timer Interface Implementation

Let's implement the programmable timer interface for the Magic-1 system.

class TimerController {
    struct TimerChannel {
        uint16_t counter;       // Current counter value
        uint16_t reload;        // Reload value
        uint8_t control;        // Control register
        uint8_t status;         // Status register
        bool enabled;           // Timer enabled flag
        bool periodic;          // Periodic mode flag
    };

    static constexpr uint8_t NUM_CHANNELS = 3;
    std::array<TimerChannel, NUM_CHANNELS> channels;
    uint32_t clock_frequency;   // Timer base frequency in Hz

public:
    // Control register bits
    static constexpr uint8_t TIMER_ENABLE = 0x01;
    static constexpr uint8_t TIMER_PERIODIC = 0x02;
    static constexpr uint8_t TIMER_IRQ_EN = 0x04;
    static constexpr uint8_t TIMER_RELOAD = 0x08;

    bool initialize(uint32_t base_freq = 1000000) {
        clock_frequency = base_freq;
        for (auto& channel : channels) {
            channel = TimerChannel{};
        }
        return true;
    }

    void update_timers() {
        for (auto& channel : channels) {
            if (channel.enabled && channel.counter > 0) {
                channel.counter--;
                if (channel.counter == 0) {
                    handle_timer_expired(channel);
                }
            }
        }
    }
};

Create the test file:

#include <gtest/gtest.h>
#include "timer_controller.h"

class TimerControllerTest : public ::testing::Test {
protected:
    TimerController timer;

    void SetUp() override {
        ASSERT_TRUE(timer.initialize(1000000));  // 1MHz base clock
    }
};

TEST_F(TimerControllerTest, BasicOperation) {
    // Configure channel 0 for one-shot operation
    timer.configure_channel(0, 1000, false);  // 1ms timeout
    
    // Verify initial state
    EXPECT_EQ(timer.get_counter(0), 1000);
    EXPECT_TRUE(timer.is_enabled(0));
    
    // Simulate 500 clock cycles
    for (int i = 0; i < 500; i++) {
        timer.update_timers();
    }
    
    EXPECT_EQ(timer.get_counter(0), 500);
}

Build and run the tests in VS Code's integrated terminal:

cd src/io
g++ -o timer_test timer_controller_test.cpp -lgtest -lgtest_main
./timer_test

Magic-1 Device Enumeration System

Let's implement a device enumeration system to manage and discover I/O devices.

class DeviceEnumerator {
    struct DeviceInfo {
        uint16_t vendor_id;
        uint16_t device_id;
        uint16_t base_address;
        uint8_t irq_line;
        std::string description;
        bool active;
    };

    std::vector<DeviceInfo> device_map;
    static constexpr uint16_t IO_SCAN_START = 0xF800;
    static constexpr uint16_t IO_SCAN_END = 0xFFFF;

public:
    bool scan_devices() {
        device_map.clear();
        
        for (uint16_t addr = IO_SCAN_START; addr < IO_SCAN_END; addr += 8) {
            if (auto device = probe_address(addr)) {
                device_map.push_back(*device);
            }
        }
        return !device_map.empty();
    }

    std::optional<DeviceInfo> get_device_by_id(uint16_t vendor_id, 
                                              uint16_t device_id) {
        for (const auto& device : device_map) {
            if (device.vendor_id == vendor_id && 
                device.device_id == device_id) {
                return device;
            }
        }
        return std::nullopt;
    }
};

Let's create a test file:

#include <gtest/gtest.h>
#include "device_enumerator.h"

class DeviceEnumeratorTest : public ::testing::Test {
protected:
    DeviceEnumerator enumerator;
};

TEST_F(DeviceEnumeratorTest, DeviceScan) {
    EXPECT_TRUE(enumerator.scan_devices());
    
    // Check for UART0
    auto uart = enumerator.get_device_by_id(0x1234, 0x0001);
    ASSERT_TRUE(uart.has_value());
    EXPECT_EQ(uart->base_address, 0xF800);
    
    // Check for CF card controller
    auto cf = enumerator.get_device_by_id(0x1234, 0x0002);
    ASSERT_TRUE(cf.has_value());
    EXPECT_EQ(cf->base_address, 0xF820);
}

Build and run the tests in VS Code's integrated terminal:

cd src/io
g++ -o enumerator_test device_enumerator_test.cpp -lgtest -lgtest_main
./enumerator_test

Magic-1 I/O Security System Implementation

Let's implement a comprehensive I/O security system to manage device access permissions.

#include <bitset>
#include <unordered_map>
#include <vector>

class IOSecurityManager {
private:
    struct SecurityDescriptor {
        uint16_t port_base;
        uint16_t port_range;
        std::bitset<4> allowed_modes;  // Supervisor, Protected, User, Guest
        bool requires_auth;
        uint32_t access_count;
    };

    std::vector<SecurityDescriptor> security_map;
    std::unordered_map<uint16_t, uint32_t> access_violations;
    uint8_t current_mode{0};  // Default to supervisor mode

public:
    bool check_access(uint16_t port, bool is_write) {
        for (auto& desc : security_map) {
            if (port >= desc.port_base && 
                port < (desc.port_base + desc.port_range)) {
                
                if (!desc.allowed_modes[current_mode]) {
                    log_violation(port);
                    return false;
                }
                
                desc.access_count++;
                return true;
            }
        }
        return false;  // Port not found in security map
    }
};

Create the test file:

#include <gtest/gtest.h>
#include "io_security_manager.h"

class IOSecurityTest : public ::testing::Test {
protected:
    IOSecurityManager security;

    void SetUp() override {
        // Add test security descriptors
        security.add_descriptor({
            .port_base = 0xF800,    // UART ports
            .port_range = 8,
            .allowed_modes = 0b1111, // All modes allowed
            .requires_auth = false
        });

        security.add_descriptor({
            .port_base = 0xF820,    // CF card ports
            .port_range = 8,
            .allowed_modes = 0b0011, // Supervisor and protected only
            .requires_auth = true
        });
    }
};

TEST_F(IOSecurityTest, AccessControl) {
    // Test UART access (should be allowed in all modes)
    EXPECT_TRUE(security.check_access(0xF800, false));
    security.set_mode(3);  // Switch to guest mode
    EXPECT_TRUE(security.check_access(0xF800, false));

    // Test CF card access (should be restricted)
    EXPECT_FALSE(security.check_access(0xF820, true));
    security.set_mode(0);  // Switch to supervisor mode
    EXPECT_TRUE(security.check_access(0xF820, true));
}

Build and run the tests in VS Code's integrated terminal:

cd src/io
g++ -o security_test io_security_manager_test.cpp -lgtest -lgtest_main
./security_test

Magic-1 I/O Audit Logging System

Let's implement a comprehensive audit logging system for I/O operations.

#include <chrono>
#include <fstream>
#include <mutex>
#include <queue>

class IOAuditLogger {
private:
    struct AuditEntry {
        std::chrono::system_clock::time_point timestamp;
        uint16_t port;
        uint8_t operation;
        uint8_t privilege_level;
        bool successful;
        std::string device_name;
    };

    std::queue<AuditEntry> audit_queue;
    std::mutex queue_mutex;
    std::ofstream log_file;
    bool logging_enabled{false};

public:
    static constexpr size_t MAX_QUEUE_SIZE = 1024;

    bool initialize(const std::string& log_path = "/var/log/magic1_io.log") {
        log_file.open(log_path, std::ios::app);
        logging_enabled = log_file.is_open();
        return logging_enabled;
    }

    void log_access(uint16_t port, uint8_t op, uint8_t priv_level, 
                   bool success, const std::string& device) {
        std::lock_guard<std::mutex> lock(queue_mutex);
        
        if (audit_queue.size() >= MAX_QUEUE_SIZE) {
            flush_queue();
        }

        audit_queue.push({
            std::chrono::system_clock::now(),
            port,
            op,
            priv_level,
            success,
            device
        });
    }
};

Create the test file:

#include <gtest/gtest.h>
#include "io_audit_logger.h"

class IOAuditLoggerTest : public ::testing::Test {
protected:
    IOAuditLogger logger;
    const std::string TEST_LOG = "/tmp/test_io.log";

    void SetUp() override {
        ASSERT_TRUE(logger.initialize(TEST_LOG));
    }

    void TearDown() override {
        std::remove(TEST_LOG.c_str());
    }
};

TEST_F(IOAuditLoggerTest, LogAccess) {
    logger.log_access(0xF800, 0x01, 0x00, true, "UART0");
    logger.flush_queue();

    std::ifstream log_file(TEST_LOG);
    std::string line;
    std::getline(log_file, line);
    
    EXPECT_TRUE(line.find("UART0") != std::string::npos);
    EXPECT_TRUE(line.find("0xF800") != std::string::npos);
}

Build and run the tests in VS Code's integrated terminal:

cd src/io
g++ -o audit_test io_audit_logger_test.cpp -lgtest -lgtest_main -pthread
./audit_test

Magic-1 I/O Monitoring System Implementation

Let's create a monitoring system to track and analyze I/O operations in real-time.

#include <array>
#include <atomic>
#include <chrono>
#include <mutex>

class IOMonitor {
private:
    struct PortStatistics {
        std::atomic<uint32_t> read_count{0};
        std::atomic<uint32_t> write_count{0};
        std::atomic<uint32_t> error_count{0};
        std::chrono::microseconds total_access_time{0};
        uint32_t bandwidth_bytes{0};
        uint32_t peak_bandwidth{0};
    };

    std::array<PortStatistics, 256> port_stats;
    std::mutex monitor_mutex;
    bool monitoring_active{false};

public:
    void record_access(uint16_t port, bool is_write, size_t bytes,
                      std::chrono::microseconds duration) {
        if (!monitoring_active || port >= port_stats.size()) {
            return;
        }

        auto& stats = port_stats[port];
        if (is_write) {
            stats.write_count++;
        } else {
            stats.read_count++;
        }

        stats.total_access_time += duration;
        stats.bandwidth_bytes += bytes;
        update_peak_bandwidth(port, bytes, duration);
    }

private:
    void update_peak_bandwidth(uint16_t port, size_t bytes, 
                             std::chrono::microseconds duration) {
        uint32_t current_bandwidth = bytes * 1000000 / duration.count();
        auto& peak = port_stats[port].peak_bandwidth;
        if (current_bandwidth > peak) {
            peak = current_bandwidth;
        }
    }
};

Let's create a test file:

#include <gtest/gtest.h>
#include "io_monitor.h"

class IOMonitorTest : public ::testing::Test {
protected:
    IOMonitor monitor;

    void SetUp() override {
        monitor.start_monitoring();
    }
};

TEST_F(IOMonitorTest, AccessTracking) {
    // Simulate UART access
    monitor.record_access(0xF8, false, 1, 
                         std::chrono::microseconds(100));
    
    auto stats = monitor.get_port_statistics(0xF8);
    EXPECT_EQ(stats.read_count, 1);
    EXPECT_EQ(stats.write_count, 0);
    EXPECT_EQ(stats.total_access_time.count(), 100);
}

TEST_F(IOMonitorTest, BandwidthCalculation) {
    // Simulate high-speed transfer
    monitor.record_access(0xF8, true, 1024,
                         std::chrono::microseconds(1000));
    
    auto stats = monitor.get_port_statistics(0xF8);
    EXPECT_GE(stats.peak_bandwidth, 1024000); // At least 1.024 MB/s
}

Build and run the tests in VS Code's integrated terminal:

cd src/io
g++ -o monitor_test io_monitor_test.cpp -lgtest -lgtest_main -pthread
./monitor_test

Magic-1 I/O Performance Analysis System

Let's implement a performance analysis system for the I/O subsystem.

#include <chrono>
#include <map>
#include <deque>

class IOPerformanceAnalyzer {
private:
    struct PerformanceMetrics {
        uint64_t total_operations{0};
        uint64_t total_bytes{0};
        std::chrono::microseconds total_latency{0};
        std::deque<uint32_t> latency_history;
        std::map<uint32_t, uint32_t> latency_distribution;
    };

    std::map<uint16_t, PerformanceMetrics> port_metrics;
    static constexpr size_t HISTORY_SIZE = 1000;
    static constexpr uint32_t LATENCY_BUCKETS = 10;

public:
    void record_operation(uint16_t port, size_t bytes, 
                         std::chrono::microseconds latency) {
        auto& metrics = port_metrics[port];
        metrics.total_operations++;
        metrics.total_bytes += bytes;
        metrics.total_latency += latency;

        // Update latency history
        metrics.latency_history.push_back(latency.count());
        if (metrics.latency_history.size() > HISTORY_SIZE) {
            metrics.latency_history.pop_front();
        }

        // Update latency distribution
        uint32_t bucket = calculate_latency_bucket(latency.count());
        metrics.latency_distribution[bucket]++;
    }

    std::string generate_report(uint16_t port) const {
        std::stringstream report;
        const auto& metrics = port_metrics.at(port);
        
        report << "I/O Performance Report for Port 0x" 
               << std::hex << port << std::dec << "\n";
        report << "Total Operations: " << metrics.total_operations << "\n";
        report << "Average Latency: " 
               << calculate_average_latency(metrics) << " µs\n";
        report << "Throughput: " 
               << calculate_throughput(metrics) << " B/s\n";
        
        return report.str();
    }
};

Let's create the test file:

#include <gtest/gtest.h>
#include "io_performance_analyzer.h"

class IOPerformanceAnalyzerTest : public ::testing::Test {
protected:
    IOPerformanceAnalyzer analyzer;
};

TEST_F(IOPerformanceAnalyzerTest, BasicMetrics) {
    // Record some test operations
    for (int i = 0; i < 100; i++) {
        analyzer.record_operation(0xF8, 64, 
                                std::chrono::microseconds(100));
    }
    
    std::string report = analyzer.generate_report(0xF8);
    EXPECT_TRUE(report.find("Total Operations: 100") != std::string::npos);
    EXPECT_TRUE(report.find("Average Latency: 100") != std::string::npos);
}

Build and run the tests in VS Code's integrated terminal:

cd src/io
g++ -o perf_test io_performance_analyzer_test.cpp -lgtest -lgtest_main
./perf_test

Magic-1 I/O Bottleneck Detection System

Let's implement a system to detect and analyze I/O bottlenecks in real-time.

class IOBottleneckDetector {
private:
    struct BottleneckMetrics {
        float utilization;           // Port utilization (0-1)
        uint32_t queue_depth;        // Current queue depth
        uint32_t wait_time_us;       // Average wait time in microseconds
        uint32_t congestion_events;  // Number of congestion events
    };

    std::map<uint16_t, BottleneckMetrics> port_metrics;
    static constexpr float UTILIZATION_THRESHOLD = 0.85f;
    static constexpr uint32_t QUEUE_DEPTH_THRESHOLD = 32;

public:
    bool detect_bottleneck(uint16_t port) {
        auto& metrics = port_metrics[port];
        
        return (metrics.utilization > UTILIZATION_THRESHOLD) ||
               (metrics.queue_depth > QUEUE_DEPTH_THRESHOLD) ||
               (metrics.wait_time_us > 1000);  // 1ms threshold
    }

    void update_metrics(uint16_t port, uint32_t queue_size, 
                       uint32_t wait_time) {
        auto& metrics = port_metrics[port];
        metrics.queue_depth = queue_size;
        metrics.wait_time_us = wait_time;
        
        if (detect_bottleneck(port)) {
            metrics.congestion_events++;
            generate_alert(port, metrics);
        }
    }
};

Let's create the test file:

class IOBottleneckDetectorTest : public ::testing::Test {
protected:
    IOBottleneckDetector detector;
};

TEST_F(IOBottleneckDetectorTest, DetectHighUtilization) {
    // Simulate high utilization on UART port
    detector.update_metrics(0xF8, 10, 100);
    detector.set_utilization(0xF8, 0.95f);
    
    EXPECT_TRUE(detector.detect_bottleneck(0xF8));
}

TEST_F(IOBottleneckDetectorTest, DetectQueueCongestion) {
    // Simulate queue backup
    detector.update_metrics(0xF8, 64, 500);
    
    EXPECT_TRUE(detector.detect_bottleneck(0xF8));
    EXPECT_GT(detector.get_congestion_events(0xF8), 0);
}

Build and run the tests in VS Code's integrated terminal:

cd src/io
g++ -o bottleneck_test io_bottleneck_detector_test.cpp -lgtest -lgtest_main
./bottleneck_test

Magic-1 Project Status

Core Components Status

Component Progress Status
CPU Core 90%
Memory System 80%
I/O System 75% 🟨
File System 30%
Network Stack 40%

Detailed Implementation Status

CPU Core (90%)

  • ✅ Basic CPU structure
  • ✅ Register file
  • ✅ ALU operations
  • ✅ Pipeline stages
  • ✅ Interrupt handling
  • ❌ Advanced pipeline features

Memory System (80%)

  • ✅ Memory management
  • ✅ DMA controller
  • ✅ Cache system
  • ✅ Memory protection
  • ❌ Memory refresh

I/O System (75%)

  • ✅ UART controller
  • ✅ CF card interface
  • ✅ RTC controller
  • ✅ Timer interface
  • ✅ Device enumeration
  • ❌ Device security
  • ❌ Performance monitoring

File System (30%)

  • ✅ Basic CF card access
  • ❌ File system structure
  • ❌ Directory handling
  • ❌ File operations
  • ❌ Access control

Network Stack (40%)

  • ✅ SLIP protocol
  • ✅ Basic IP handling
  • ❌ TCP implementation
  • ❌ UDP support
  • ❌ Network security

Current Focus

  • Completing I/O system implementation
  • Implementing file system
  • Enhancing network stack

Next Steps

  1. Complete I/O performance monitoring
  2. Implement file system structure
  3. Enhance network stack

Continuing CPU Implementation - Advanced Pipeline Features

Let's enhance the CPU pipeline with advanced features including branch prediction and speculative execution.

class AdvancedPipeline {
private:
    struct BranchPredictor {
        uint16_t branch_history{0};
        std::array<uint8_t, 256> pattern_table;
        uint32_t correct_predictions{0};
        uint32_t total_predictions{0};
    } predictor;

    struct SpeculativeState {
        bool speculation_active{false};
        uint16_t checkpoint_pc;
        std::vector<uint16_t> register_backup;
        uint8_t speculation_depth{0};
    } spec_state;

public:
    bool predict_branch(uint16_t pc, uint16_t target) {
        uint8_t index = (predictor.branch_history ^ pc) & 0xFF;
        bool taken = predictor.pattern_table[index] > 1;
        
        if (taken) {
            begin_speculation(pc);
        }
        
        predictor.total_predictions++;
        return taken;
    }

    void update_prediction(bool actual_taken) {
        uint8_t index = predictor.branch_history & 0xFF;
        if (actual_taken) {
            if (predictor.pattern_table[index] < 3)
                predictor.pattern_table[index]++;
        } else {
            if (predictor.pattern_table[index] > 0)
                predictor.pattern_table[index]--;
        }
        
        predictor.branch_history = (predictor.branch_history << 1) | actual_taken;
    }
};

Create a test file:

#include <gtest/gtest.h>
#include "advanced_pipeline.h"

class AdvancedPipelineTest : public ::testing::Test {
protected:
    AdvancedPipeline pipeline;
};

TEST_F(AdvancedPipelineTest, BranchPrediction) {
    // Train predictor with a pattern
    for (int i = 0; i < 10; i++) {
        pipeline.predict_branch(0x1000, 0x1100);
        pipeline.update_prediction(true);
    }
    
    // Test prediction
    EXPECT_TRUE(pipeline.predict_branch(0x1000, 0x1100));
    
    // Verify prediction accuracy
    auto stats = pipeline.get_prediction_stats();
    EXPECT_GT(stats.accuracy, 0.8f);
}

Build and run tests in VS Code's integrated terminal:

cd src/cpu
g++ -o pipeline_test advanced_pipeline_test.cpp -lgtest -lgtest_main
./pipeline_test

Magic-1 CPU Instruction Reordering System

Let's implement an instruction reordering system to optimize CPU pipeline performance.

class InstructionReorderBuffer {
private:
    struct ReorderEntry {
        uint16_t instruction;
        uint16_t destination;
        uint16_t value;
        bool completed;
        bool is_branch;
        uint16_t branch_target;
    };

    std::array<ReorderEntry, 16> buffer;
    uint8_t head{0};
    uint8_t tail{0};
    uint8_t entries{0};

public:
    bool add_instruction(uint16_t inst, uint16_t dest) {
        if (entries >= buffer.size()) {
            return false;
        }

        buffer[tail] = {
            .instruction = inst,
            .destination = dest,
            .completed = false,
            .is_branch = (inst >> 12) == 0x7
        };

        tail = (tail + 1) % buffer.size();
        entries++;
        return true;
    }

    bool commit_next() {
        if (entries == 0 || !buffer[head].completed) {
            return false;
        }

        head = (head + 1) % buffer.size();
        entries--;
        return true;
    }
};

Let's create a test file:

#include <gtest/gtest.h>
#include "instruction_reorder.h"

class InstructionReorderTest : public ::testing::Test {
protected:
    InstructionReorderBuffer rob;
};

TEST_F(InstructionReorderTest, BasicOperation) {
    // Add instruction to buffer
    EXPECT_TRUE(rob.add_instruction(0x1234, 0x01));
    
    // Complete instruction
    EXPECT_TRUE(rob.complete_instruction(0x1234));
    
    // Commit instruction
    EXPECT_TRUE(rob.commit_next());
    
    // Buffer should be empty
    EXPECT_EQ(rob.get_entries(), 0);
}

Build and run the tests in VS Code's integrated terminal:

cd src/cpu
g++ -o reorder_test instruction_reorder_test.cpp -lgtest -lgtest_main
./reorder_test

Magic-1 Memory System - Memory Dependency Tracker

Let's implement a memory dependency tracking system to optimize memory operations.

class MemoryDependencyTracker {
    struct MemoryOperation {
        uint16_t address;
        bool is_write;
        uint32_t sequence_number;
        bool completed;
    };

    std::array<MemoryOperation, 32> pending_ops;
    uint32_t current_sequence{0};
    uint8_t head{0};
    uint8_t tail{0};

public:
    bool add_operation(uint16_t addr, bool is_write) {
        if (is_buffer_full()) {
            return false;
        }

        pending_ops[tail] = {
            .address = addr,
            .is_write = is_write,
            .sequence_number = current_sequence++,
            .completed = false
        };

        tail = (tail + 1) % pending_ops.size();
        return true;
    }

    bool check_dependency(uint16_t addr) {
        for (uint8_t i = head; i != tail; i = (i + 1) % pending_ops.size()) {
            const auto& op = pending_ops[i];
            if (!op.completed && op.address == addr && op.is_write) {
                return true;
            }
        }
        return false;
    }
};

Let's create the test file:

#include <gtest/gtest.h>
#include "memory_dependency_tracker.h"

class MemoryDependencyTrackerTest : public ::testing::Test {
protected:
    MemoryDependencyTracker tracker;
};

TEST_F(MemoryDependencyTrackerTest, DependencyDetection) {
    // Add write operation
    EXPECT_TRUE(tracker.add_operation(0x1000, true));
    
    // Check for dependency
    EXPECT_TRUE(tracker.check_dependency(0x1000));
    
    // Complete write operation
    tracker.complete_operation(0x1000);
    
    // Dependency should be resolved
    EXPECT_FALSE(tracker.check_dependency(0x1000));
}

Build and run the tests in VS Code's integrated terminal:

cd src/memory
g++ -o dependency_test memory_dependency_tracker_test.cpp -lgtest -lgtest_main
./dependency_test

Magic-1 Memory Access Reordering System

Let's implement a memory access reordering system to optimize memory operations based on dependencies and priorities.

class MemoryReorderUnit {
    struct MemoryRequest {
        uint16_t address;
        uint8_t operation;      // READ=1, WRITE=2
        uint8_t priority;       // 0=highest to 3=lowest
        uint32_t timestamp;
        bool ready;
        bool completed;
    };

    static constexpr size_t QUEUE_SIZE = 32;
    std::array<MemoryRequest, QUEUE_SIZE> request_queue;
    uint32_t current_timestamp{0};
    size_t head{0};
    size_t tail{0};

public:
    bool queue_request(uint16_t addr, uint8_t op, uint8_t priority) {
        if (is_full()) {
            return false;
        }

        request_queue[tail] = {
            .address = addr,
            .operation = op,
            .priority = priority,
            .timestamp = current_timestamp++,
            .ready = true,
            .completed = false
        };

        tail = (tail + 1) % QUEUE_SIZE;
        reorder_queue();
        return true;
    }

private:
    void reorder_queue() {
        // Sort based on priority and dependencies
        for (size_t i = head; i != tail; i = (i + 1) % QUEUE_SIZE) {
            for (size_t j = i + 1; j != tail; j = (j + 1) % QUEUE_SIZE) {
                if (should_swap(request_queue[i], request_queue[j])) {
                    std::swap(request_queue[i], request_queue[j]);
                }
            }
        }
    }
};

Create a test file to verify the functionality:

#include <gtest/gtest.h>
#include "memory_reorder_unit.h"

class MemoryReorderUnitTest : public ::testing::Test {
protected:
    MemoryReorderUnit reorder_unit;
};

TEST_F(MemoryReorderUnitTest, RequestOrdering) {
    // Queue several requests
    reorder_unit.queue_request(0x1000, 1, 2);  // Read, normal priority
    reorder_unit.queue_request(0x1004, 2, 0);  // Write, high priority
    reorder_unit.queue_request(0x1008, 1, 1);  // Read, medium priority

    // Verify execution order
    auto next = reorder_unit.get_next_request();
    ASSERT_TRUE(next.has_value());
    EXPECT_EQ(next->address, 0x1004);  // High priority write should be first

    next = reorder_unit.get_next_request();
    ASSERT_TRUE(next.has_value());
    EXPECT_EQ(next->address, 0x1008);  // Medium priority read should be second
}

Build and run the tests in VS Code's integrated terminal:

cd src/memory
g++ -o reorder_test memory_reorder_unit_test.cpp -lgtest -lgtest_main
./reorder_test

Magic-1 Project Status

Core Modules Status

Module Progress Notes
CPU 95% Advanced pipeline features completed
Memory 85% Memory reordering in progress
I/O 75% Device security needs completion
Network 40% Basic protocols implemented
File System 30% Basic framework only

Implementation Details

CPU Core (95%)

  • ✅ Basic architecture
  • ✅ Pipeline stages
  • ✅ Branch prediction
  • ✅ Instruction reordering
  • ✅ Interrupt handling
  • ❌ Power management

Memory System (85%)

  • ✅ Memory management
  • ✅ Cache system
  • ✅ DMA controller
  • ✅ Memory protection
  • ✅ Dependency tracking
  • ❌ Memory scheduling
  • ❌ Power optimization

I/O System (75%)

  • ✅ UART controller
  • ✅ CF card interface
  • ✅ RTC implementation
  • ✅ Device enumeration
  • ❌ Performance monitoring
  • ❌ Security features

Network Stack (40%)

  • ✅ SLIP protocol
  • ✅ Basic IP handling
  • ❌ TCP implementation
  • ❌ UDP support
  • ❌ Network security

File System (30%)

  • ✅ Basic CF card access
  • ❌ File system structure
  • ❌ Directory handling
  • ❌ File operations
  • ❌ Access control

Current Development Focus

  1. Memory system optimization
  2. I/O security implementation
  3. Network stack completion

Magic-1 File System Implementation

Let's implement a robust file system for the Magic-1 computer, starting with the core file system structure.

#include <cstdint>
#include <string>
#include <vector>

class FileSystem {
private:
    static constexpr uint32_t BLOCK_SIZE = 512;
    static constexpr uint32_t MAX_FILENAME = 32;
    static constexpr uint32_t MAX_FILES = 256;

    struct SuperBlock {
        uint32_t magic;           // File system magic number
        uint32_t total_blocks;    // Total blocks in filesystem
        uint32_t free_blocks;     // Number of free blocks
        uint32_t root_inode;      // Root directory inode number
        uint8_t fs_version;       // File system version
    } __attribute__((packed));

    struct Inode {
        uint16_t mode;            // File mode and permissions
        uint16_t uid;             // Owner ID
        uint32_t size;            // File size in bytes
        uint32_t access_time;     // Last access time
        uint32_t modify_time;     // Last modification time
        uint32_t create_time;     // Creation time
        uint32_t direct_blocks[8];// Direct block pointers
        uint32_t indirect_block;  // Single indirect block pointer
    } __attribute__((packed));

public:
    bool initialize_filesystem() {
        SuperBlock sb;
        sb.magic = 0x4D314653;    // 'M1FS'
        sb.total_blocks = get_device_size() / BLOCK_SIZE;
        sb.free_blocks = sb.total_blocks - 1;  // Minus superblock
        sb.root_inode = 1;
        sb.fs_version = 1;

        return write_superblock(sb);
    }
};

Let's create a test file:

#include <gtest/gtest.h>
#include "fs_core.h"

class FileSystemTest : public ::testing::Test {
protected:
    FileSystem fs;
    
    void SetUp() override {
        // Create test device
        system("dd if=/dev/zero of=test.fs bs=1M count=1");
    }

    void TearDown() override {
        system("rm -f test.fs");
    }
};

TEST_F(FileSystemTest, Initialization) {
    EXPECT_TRUE(fs.initialize_filesystem());
    
    // Verify superblock contents
    auto sb = fs.read_superblock();
    EXPECT_EQ(sb.magic, 0x4D314653);
    EXPECT_GT(sb.free_blocks, 0);
}

Build and run the tests in VS Code's integrated terminal:

cd src/filesystem
g++ -o fs_test fs_core_test.cpp -lgtest -lgtest_main
./fs_test

Magic-1 Directory System Implementation

Let's implement the directory handling system for our file system.

#include <string>
#include <vector>
#include <cstring>

struct DirectoryEntry {
    uint32_t inode;                  // Inode number
    uint16_t rec_len;               // Record length
    uint8_t name_len;               // Name length
    uint8_t file_type;              // File type
    char name[MAX_FILENAME];        // File name
} __attribute__((packed));

class DirectoryManager {
private:
    static constexpr uint8_t FT_REGULAR = 1;   // Regular file
    static constexpr uint8_t FT_DIRECTORY = 2; // Directory
    static constexpr uint8_t FT_SYMLINK = 3;   // Symbolic link

public:
    bool create_directory(const std::string& path) {
        if (path.empty() || path.length() > MAX_FILENAME) {
            return false;
        }

        DirectoryEntry dir = {
            .inode = allocate_inode(),
            .rec_len = sizeof(DirectoryEntry),
            .name_len = static_cast<uint8_t>(path.length()),
            .file_type = FT_DIRECTORY
        };
        strncpy(dir.name, path.c_str(), MAX_FILENAME - 1);

        return write_directory_entry(dir);
    }

    std::vector<DirectoryEntry> list_directory(uint32_t dir_inode) {
        std::vector<DirectoryEntry> entries;
        uint8_t buffer[BLOCK_SIZE];
        
        if (read_inode_data(dir_inode, buffer)) {
            size_t offset = 0;
            while (offset < BLOCK_SIZE) {
                DirectoryEntry* entry = (DirectoryEntry*)(buffer + offset);
                if (entry->inode != 0) {
                    entries.push_back(*entry);
                }
                offset += entry->rec_len;
            }
        }
        return entries;
    }
};

Let's create the test file:

#include <gtest/gtest.h>
#include "directory.h"

class DirectoryManagerTest : public ::testing::Test {
protected:
    DirectoryManager dir_mgr;
    FileSystem fs;

    void SetUp() override {
        ASSERT_TRUE(fs.initialize_filesystem());
    }
};

TEST_F(DirectoryManagerTest, CreateDirectory) {
    EXPECT_TRUE(dir_mgr.create_directory("test_dir"));
    
    auto entries = dir_mgr.list_directory(fs.get_root_inode());
    ASSERT_EQ(entries.size(), 1);
    EXPECT_STREQ(entries[0].name, "test_dir");
    EXPECT_EQ(entries[0].file_type, 2);  // Directory type
}

Run the tests in VS Code's integrated terminal:

cd src/filesystem
g++ -o dir_test directory_test.cpp -lgtest -lgtest_main
./dir_test

Magic-1 File Operations System

Let's implement the core file operations system for handling file creation, reading, and writing.

#include <cstdint>
#include <vector>
#include <memory>

class FileOperations {
private:
    struct FileHandle {
        uint32_t inode;
        uint32_t position;
        uint16_t mode;
        bool is_open;
    };

    static constexpr uint16_t O_READ = 0x0001;
    static constexpr uint16_t O_WRITE = 0x0002;
    static constexpr uint16_t O_CREATE = 0x0004;
    static constexpr uint16_t O_APPEND = 0x0008;

    std::vector<FileHandle> open_files;

public:
    int open_file(const std::string& path, uint16_t mode) {
        auto inode = lookup_path(path);
        
        if (!inode && !(mode & O_CREATE)) {
            return -1;
        }

        if (!inode) {
            inode = create_file(path);
        }

        FileHandle handle{
            .inode = *inode,
            .position = 0,
            .mode = mode,
            .is_open = true
        };

        open_files.push_back(handle);
        return open_files.size() - 1;
    }

    ssize_t read_file(int fd, uint8_t* buffer, size_t count) {
        if (!validate_fd(fd)) return -1;
        auto& handle = open_files[fd];
        
        if (!(handle.mode & O_READ)) return -1;

        return read_inode_data(handle.inode, 
                             buffer, 
                             count, 
                             handle.position);
    }
};

Let's create the test file:

#include <gtest/gtest.h>
#include "file_operations.h"

class FileOperationsTest : public ::testing::Test {
protected:
    FileOperations file_ops;
    FileSystem fs;

    void SetUp() override {
        ASSERT_TRUE(fs.initialize_filesystem());
    }
};

TEST_F(FileOperationsTest, CreateAndRead) {
    // Create and write to file
    int fd = file_ops.open_file("test.txt", O_CREATE | O_WRITE);
    ASSERT_GE(fd, 0);
    
    const char* test_data = "Hello, Magic-1!";
    EXPECT_EQ(file_ops.write_file(fd, 
              reinterpret_cast<const uint8_t*>(test_data), 
              strlen(test_data)), 
              strlen(test_data));
    
    file_ops.close_file(fd);

    // Read back the file
    fd = file_ops.open_file("test.txt", O_READ);
    ASSERT_GE(fd, 0);
    
    uint8_t buffer[64] = {0};
    EXPECT_EQ(file_ops.read_file(fd, buffer, sizeof(buffer)), strlen(test_data));
    EXPECT_STREQ(reinterpret_cast<char*>(buffer), test_data);
}

Build and run tests in VS Code's integrated terminal:

cd src/filesystem
g++ -o file_ops_test file_operations_test.cpp -lgtest -lgtest_main
./file_ops_test

Magic-1 File System Cache Implementation

Let's implement a file system cache layer to improve performance.

#include <unordered_map>
#include <list>
#include <memory>
#include <chrono>

class FileSystemCache {
private:
    struct CacheEntry {
        uint32_t block_number;
        std::vector<uint8_t> data;
        bool dirty;
        std::chrono::steady_clock::time_point last_access;
    };

    static constexpr size_t MAX_CACHE_SIZE = 64;  // Cache 64 blocks
    std::unordered_map<uint32_t, std::list<CacheEntry>::iterator> cache_map;
    std::list<CacheEntry> cache_list;  // LRU list

public:
    bool read_block(uint32_t block_num, uint8_t* buffer) {
        auto it = cache_map.find(block_num);
        if (it != cache_map.end()) {
            // Cache hit
            auto entry = it->second;
            std::copy(entry->data.begin(), entry->data.end(), buffer);
            update_lru(entry);
            return true;
        }

        // Cache miss - read from disk and cache
        return cache_block(block_num, buffer);
    }

    bool write_block(uint32_t block_num, const uint8_t* buffer) {
        auto it = cache_map.find(block_num);
        if (it != cache_map.end()) {
            // Update existing cache entry
            auto entry = it->second;
            std::copy(buffer, buffer + BLOCK_SIZE, entry->data.begin());
            entry->dirty = true;
            update_lru(entry);
            return true;
        }

        // Add new cache entry
        return add_to_cache(block_num, buffer);
    }
};

Let's create the test file:

#include <gtest/gtest.h>
#include "fs_cache.h"

class FileSystemCacheTest : public ::testing::Test {
protected:
    FileSystemCache cache;
};

TEST_F(FileSystemCacheTest, CacheOperations) {
    uint8_t write_buffer[BLOCK_SIZE];
    uint8_t read_buffer[BLOCK_SIZE];
    
    // Fill write buffer with test pattern
    for (size_t i = 0; i < BLOCK_SIZE; i++) {
        write_buffer[i] = i & 0xFF;
    }
    
    // Write to cache
    EXPECT_TRUE(cache.write_block(1, write_buffer));
    
    // Read back from cache
    EXPECT_TRUE(cache.read_block(1, read_buffer));
    
    // Verify data
    EXPECT_EQ(memcmp(write_buffer, read_buffer, BLOCK_SIZE), 0);
}

Build and run the tests in VS Code's integrated terminal:

cd src/filesystem
g++ -o cache_test fs_cache_test.cpp -lgtest -lgtest_main -pthread
./cache_test

Magic-1 File System Journal Implementation

Let's implement a journaling system to ensure file system consistency.

#include <vector>
#include <cstdint>
#include <chrono>

class FileSystemJournal {
    struct JournalHeader {
        uint32_t magic;          // Journal magic number 'M1JR'
        uint32_t sequence;       // Transaction sequence number
        uint32_t checksum;       // Journal checksum
    } __attribute__((packed));

    struct JournalEntry {
        uint32_t block_num;      // Block number being modified
        uint32_t timestamp;      // Entry timestamp
        uint8_t type;           // Entry type (CREATE/MODIFY/DELETE)
        uint8_t data[512];      // Block data
    } __attribute__((packed));

public:
    enum JournalEntryType {
        ENTRY_CREATE = 1,
        ENTRY_MODIFY = 2,
        ENTRY_DELETE = 3
    };

    bool begin_transaction() {
        auto header = create_journal_header();
        return write_journal_header(header);
    }

    bool log_operation(uint32_t block, JournalEntryType type, const uint8_t* data) {
        JournalEntry entry{
            .block_num = block,
            .timestamp = get_timestamp(),
            .type = static_cast<uint8_t>(type)
        };
        std::memcpy(entry.data, data, sizeof(entry.data));
        return write_journal_entry(entry);
    }
};

Let's create the test file:

#include <gtest/gtest.h>
#include "fs_journal.h"

class FileSystemJournalTest : public ::testing::Test {
protected:
    FileSystemJournal journal;
};

TEST_F(FileSystemJournalTest, BasicJournaling) {
    // Begin transaction
    EXPECT_TRUE(journal.begin_transaction());
    
    // Create test data
    uint8_t test_data[512];
    std::fill_n(test_data, 512, 0xAA);
    
    // Log a modification
    EXPECT_TRUE(journal.log_operation(1, 
        FileSystemJournal::ENTRY_MODIFY, 
        test_data));
    
    // Commit transaction
    EXPECT_TRUE(journal.commit_transaction());
    
    // Verify journal entry
    auto entries = journal.get_journal_entries();
    ASSERT_EQ(entries.size(), 1);
    EXPECT_EQ(entries[0].block_num, 1);
    EXPECT_EQ(entries[0].type, FileSystemJournal::ENTRY_MODIFY);
}

Build and run the tests in VS Code's integrated terminal:

cd src/filesystem
g++ -o journal_test fs_journal_test.cpp -lgtest -lgtest_main
./journal_test

The critical elements implemented so far:

  • ✅ Journal header structure
  • ✅ Journal entry structure
  • ✅ Transaction management
  • ✅ Operation logging
  • ❌ Recovery mechanism
  • ❌ Checkpoint system

Magic-1 System Implementation Status

Critical Elements Status

CPU Core (95% Complete)

  • ✅ Basic CPU architecture
  • ✅ Pipeline stages
  • ✅ Branch prediction
  • ✅ Instruction reordering
  • ✅ Interrupt handling
  • ❌ Power management features

Memory System (85% Complete)

  • ✅ Memory management
  • ✅ Cache implementation
  • ✅ DMA controller
  • ✅ Memory protection
  • ❌ Full memory scheduling
  • ❌ Memory power optimization

File System (70% Complete)

  • ✅ Basic file operations
  • ✅ Directory handling
  • ✅ File system cache
  • ❌ Journaling system
  • ❌ Recovery mechanisms
  • ❌ Access control

I/O System (75% Complete)

  • ✅ UART implementation
  • ✅ CF card interface
  • ✅ RTC controller
  • ✅ Device enumeration
  • ❌ Complete security features
  • ❌ Performance monitoring

Network Stack (40% Complete)

  • ✅ SLIP protocol
  • ✅ Basic IP handling
  • ❌ TCP implementation
  • ❌ UDP support
  • ❌ Network security
  • ❌ Protocol validation

Critical Missing Components

  1. File System:

    • Journal recovery system
    • Access control implementation
    • Quota management
  2. Network Stack:

    • Complete TCP implementation
    • Network security features
    • Error handling
  3. Memory System:

    • Memory scheduling optimization
    • Power management features
⚠️ **GitHub.com Fallback** ⚠️