PPU Decoder Cache improved

This commit is contained in:
Nekotekina 2015-08-10 22:39:52 +03:00
parent eb63558c6d
commit be9a599beb
13 changed files with 118 additions and 467 deletions

View file

@ -263,7 +263,10 @@ bool CPUThread::check_status()
{
CHECK_EMU_STATUS; // check at least once
if (!is_paused()) break;
if (!is_paused() && (m_state.load() & CPU_STATE_INTR) == 0)
{
break;
}
if (!lock)
{
@ -271,6 +274,11 @@ bool CPUThread::check_status()
continue;
}
if (!is_paused() && (m_state.load() & CPU_STATE_INTR) != 0 && handle_interrupt())
{
continue;
}
cv.wait(lock);
}

View file

@ -120,6 +120,8 @@ public:
// process m_state flags, returns true if the checker must return
bool check_status();
virtual bool handle_interrupt() { return false; }
std::string GetFName() const
{
return fmt::format("%s[0x%x] Thread (%s)", GetTypeString(), m_id, m_name);

View file

@ -8,3 +8,16 @@ enum FPSCR_RN
FPSCR_RN_PINF = 2,
FPSCR_RN_MINF = 3,
};
using ppu_inter_func_t = void(*)(class PPUThread& CPU, union ppu_opcode_t opcode);
struct ppu_decoder_cache_t
{
ppu_inter_func_t* const pointer;
ppu_decoder_cache_t();
~ppu_decoder_cache_t();
void initialize(u32 addr, u32 size);
};

View file

@ -136,8 +136,6 @@ union ppu_opcode_t
};
};
using ppu_inter_func_t = void(*)(PPUThread& CPU, ppu_opcode_t opcode);
namespace ppu_interpreter
{
void NULL_OP(PPUThread& CPU, ppu_opcode_t op);

View file

@ -22,445 +22,35 @@
u64 rotate_mask[64][64];
const ppu_inter_func_t g_ppu_inter_func_list[] =
{
ppu_interpreter::NULL_OP,
ppu_interpreter::NOP,
ppu_interpreter::TDI,
ppu_interpreter::TWI,
ppu_interpreter::MFVSCR,
ppu_interpreter::MTVSCR,
ppu_interpreter::VADDCUW,
ppu_interpreter::VADDFP,
ppu_interpreter::VADDSBS,
ppu_interpreter::VADDSHS,
ppu_interpreter::VADDSWS,
ppu_interpreter::VADDUBM,
ppu_interpreter::VADDUBS,
ppu_interpreter::VADDUHM,
ppu_interpreter::VADDUHS,
ppu_interpreter::VADDUWM,
ppu_interpreter::VADDUWS,
ppu_interpreter::VAND,
ppu_interpreter::VANDC,
ppu_interpreter::VAVGSB,
ppu_interpreter::VAVGSH,
ppu_interpreter::VAVGSW,
ppu_interpreter::VAVGUB,
ppu_interpreter::VAVGUH,
ppu_interpreter::VAVGUW,
ppu_interpreter::VCFSX,
ppu_interpreter::VCFUX,
ppu_interpreter::VCMPBFP,
ppu_interpreter::VCMPBFP_,
ppu_interpreter::VCMPEQFP,
ppu_interpreter::VCMPEQFP_,
ppu_interpreter::VCMPEQUB,
ppu_interpreter::VCMPEQUB_,
ppu_interpreter::VCMPEQUH,
ppu_interpreter::VCMPEQUH_,
ppu_interpreter::VCMPEQUW,
ppu_interpreter::VCMPEQUW_,
ppu_interpreter::VCMPGEFP,
ppu_interpreter::VCMPGEFP_,
ppu_interpreter::VCMPGTFP,
ppu_interpreter::VCMPGTFP_,
ppu_interpreter::VCMPGTSB,
ppu_interpreter::VCMPGTSB_,
ppu_interpreter::VCMPGTSH,
ppu_interpreter::VCMPGTSH_,
ppu_interpreter::VCMPGTSW,
ppu_interpreter::VCMPGTSW_,
ppu_interpreter::VCMPGTUB,
ppu_interpreter::VCMPGTUB_,
ppu_interpreter::VCMPGTUH,
ppu_interpreter::VCMPGTUH_,
ppu_interpreter::VCMPGTUW,
ppu_interpreter::VCMPGTUW_,
ppu_interpreter::VCTSXS,
ppu_interpreter::VCTUXS,
ppu_interpreter::VEXPTEFP,
ppu_interpreter::VLOGEFP,
ppu_interpreter::VMADDFP,
ppu_interpreter::VMAXFP,
ppu_interpreter::VMAXSB,
ppu_interpreter::VMAXSH,
ppu_interpreter::VMAXSW,
ppu_interpreter::VMAXUB,
ppu_interpreter::VMAXUH,
ppu_interpreter::VMAXUW,
ppu_interpreter::VMHADDSHS,
ppu_interpreter::VMHRADDSHS,
ppu_interpreter::VMINFP,
ppu_interpreter::VMINSB,
ppu_interpreter::VMINSH,
ppu_interpreter::VMINSW,
ppu_interpreter::VMINUB,
ppu_interpreter::VMINUH,
ppu_interpreter::VMINUW,
ppu_interpreter::VMLADDUHM,
ppu_interpreter::VMRGHB,
ppu_interpreter::VMRGHH,
ppu_interpreter::VMRGHW,
ppu_interpreter::VMRGLB,
ppu_interpreter::VMRGLH,
ppu_interpreter::VMRGLW,
ppu_interpreter::VMSUMMBM,
ppu_interpreter::VMSUMSHM,
ppu_interpreter::VMSUMSHS,
ppu_interpreter::VMSUMUBM,
ppu_interpreter::VMSUMUHM,
ppu_interpreter::VMSUMUHS,
ppu_interpreter::VMULESB,
ppu_interpreter::VMULESH,
ppu_interpreter::VMULEUB,
ppu_interpreter::VMULEUH,
ppu_interpreter::VMULOSB,
ppu_interpreter::VMULOSH,
ppu_interpreter::VMULOUB,
ppu_interpreter::VMULOUH,
ppu_interpreter::VNMSUBFP,
ppu_interpreter::VNOR,
ppu_interpreter::VOR,
ppu_interpreter::VPERM,
ppu_interpreter::VPKPX,
ppu_interpreter::VPKSHSS,
ppu_interpreter::VPKSHUS,
ppu_interpreter::VPKSWSS,
ppu_interpreter::VPKSWUS,
ppu_interpreter::VPKUHUM,
ppu_interpreter::VPKUHUS,
ppu_interpreter::VPKUWUM,
ppu_interpreter::VPKUWUS,
ppu_interpreter::VREFP,
ppu_interpreter::VRFIM,
ppu_interpreter::VRFIN,
ppu_interpreter::VRFIP,
ppu_interpreter::VRFIZ,
ppu_interpreter::VRLB,
ppu_interpreter::VRLH,
ppu_interpreter::VRLW,
ppu_interpreter::VRSQRTEFP,
ppu_interpreter::VSEL,
ppu_interpreter::VSL,
ppu_interpreter::VSLB,
ppu_interpreter::VSLDOI,
ppu_interpreter::VSLH,
ppu_interpreter::VSLO,
ppu_interpreter::VSLW,
ppu_interpreter::VSPLTB,
ppu_interpreter::VSPLTH,
ppu_interpreter::VSPLTISB,
ppu_interpreter::VSPLTISH,
ppu_interpreter::VSPLTISW,
ppu_interpreter::VSPLTW,
ppu_interpreter::VSR,
ppu_interpreter::VSRAB,
ppu_interpreter::VSRAH,
ppu_interpreter::VSRAW,
ppu_interpreter::VSRB,
ppu_interpreter::VSRH,
ppu_interpreter::VSRO,
ppu_interpreter::VSRW,
ppu_interpreter::VSUBCUW,
ppu_interpreter::VSUBFP,
ppu_interpreter::VSUBSBS,
ppu_interpreter::VSUBSHS,
ppu_interpreter::VSUBSWS,
ppu_interpreter::VSUBUBM,
ppu_interpreter::VSUBUBS,
ppu_interpreter::VSUBUHM,
ppu_interpreter::VSUBUHS,
ppu_interpreter::VSUBUWM,
ppu_interpreter::VSUBUWS,
ppu_interpreter::VSUMSWS,
ppu_interpreter::VSUM2SWS,
ppu_interpreter::VSUM4SBS,
ppu_interpreter::VSUM4SHS,
ppu_interpreter::VSUM4UBS,
ppu_interpreter::VUPKHPX,
ppu_interpreter::VUPKHSB,
ppu_interpreter::VUPKHSH,
ppu_interpreter::VUPKLPX,
ppu_interpreter::VUPKLSB,
ppu_interpreter::VUPKLSH,
ppu_interpreter::VXOR,
ppu_interpreter::MULLI,
ppu_interpreter::SUBFIC,
ppu_interpreter::CMPLI,
ppu_interpreter::CMPI,
ppu_interpreter::ADDIC,
ppu_interpreter::ADDIC_,
ppu_interpreter::ADDI,
ppu_interpreter::ADDIS,
ppu_interpreter::BC,
ppu_interpreter::HACK,
ppu_interpreter::SC,
ppu_interpreter::B,
ppu_interpreter::MCRF,
ppu_interpreter::BCLR,
ppu_interpreter::CRNOR,
ppu_interpreter::CRANDC,
ppu_interpreter::ISYNC,
ppu_interpreter::CRXOR,
ppu_interpreter::CRNAND,
ppu_interpreter::CRAND,
ppu_interpreter::CREQV,
ppu_interpreter::CRORC,
ppu_interpreter::CROR,
ppu_interpreter::BCCTR,
ppu_interpreter::RLWIMI,
ppu_interpreter::RLWINM,
ppu_interpreter::RLWNM,
ppu_interpreter::ORI,
ppu_interpreter::ORIS,
ppu_interpreter::XORI,
ppu_interpreter::XORIS,
ppu_interpreter::ANDI_,
ppu_interpreter::ANDIS_,
ppu_interpreter::RLDICL,
ppu_interpreter::RLDICR,
ppu_interpreter::RLDIC,
ppu_interpreter::RLDIMI,
ppu_interpreter::RLDC_LR,
ppu_interpreter::CMP,
ppu_interpreter::TW,
ppu_interpreter::LVSL,
ppu_interpreter::LVEBX,
ppu_interpreter::SUBFC,
ppu_interpreter::MULHDU,
ppu_interpreter::ADDC,
ppu_interpreter::MULHWU,
ppu_interpreter::MFOCRF,
ppu_interpreter::LWARX,
ppu_interpreter::LDX,
ppu_interpreter::LWZX,
ppu_interpreter::SLW,
ppu_interpreter::CNTLZW,
ppu_interpreter::SLD,
ppu_interpreter::AND,
ppu_interpreter::CMPL,
ppu_interpreter::LVSR,
ppu_interpreter::LVEHX,
ppu_interpreter::SUBF,
ppu_interpreter::LDUX,
ppu_interpreter::DCBST,
ppu_interpreter::LWZUX,
ppu_interpreter::CNTLZD,
ppu_interpreter::ANDC,
ppu_interpreter::TD,
ppu_interpreter::LVEWX,
ppu_interpreter::MULHD,
ppu_interpreter::MULHW,
ppu_interpreter::LDARX,
ppu_interpreter::DCBF,
ppu_interpreter::LBZX,
ppu_interpreter::LVX,
ppu_interpreter::NEG,
ppu_interpreter::LBZUX,
ppu_interpreter::NOR,
ppu_interpreter::STVEBX,
ppu_interpreter::SUBFE,
ppu_interpreter::ADDE,
ppu_interpreter::MTOCRF,
ppu_interpreter::STDX,
ppu_interpreter::STWCX_,
ppu_interpreter::STWX,
ppu_interpreter::STVEHX,
ppu_interpreter::STDUX,
ppu_interpreter::STWUX,
ppu_interpreter::STVEWX,
ppu_interpreter::SUBFZE,
ppu_interpreter::ADDZE,
ppu_interpreter::STDCX_,
ppu_interpreter::STBX,
ppu_interpreter::STVX,
ppu_interpreter::MULLD,
ppu_interpreter::SUBFME,
ppu_interpreter::ADDME,
ppu_interpreter::MULLW,
ppu_interpreter::DCBTST,
ppu_interpreter::STBUX,
ppu_interpreter::ADD,
ppu_interpreter::DCBT,
ppu_interpreter::LHZX,
ppu_interpreter::EQV,
ppu_interpreter::ECIWX,
ppu_interpreter::LHZUX,
ppu_interpreter::XOR,
ppu_interpreter::MFSPR,
ppu_interpreter::LWAX,
ppu_interpreter::DST,
ppu_interpreter::LHAX,
ppu_interpreter::LVXL,
ppu_interpreter::MFTB,
ppu_interpreter::LWAUX,
ppu_interpreter::DSTST,
ppu_interpreter::LHAUX,
ppu_interpreter::STHX,
ppu_interpreter::ORC,
ppu_interpreter::ECOWX,
ppu_interpreter::STHUX,
ppu_interpreter::OR,
ppu_interpreter::DIVDU,
ppu_interpreter::DIVWU,
ppu_interpreter::MTSPR,
ppu_interpreter::DCBI,
ppu_interpreter::NAND,
ppu_interpreter::STVXL,
ppu_interpreter::DIVD,
ppu_interpreter::DIVW,
ppu_interpreter::LVLX,
ppu_interpreter::LDBRX,
ppu_interpreter::LSWX,
ppu_interpreter::LWBRX,
ppu_interpreter::LFSX,
ppu_interpreter::SRW,
ppu_interpreter::SRD,
ppu_interpreter::LVRX,
ppu_interpreter::LSWI,
ppu_interpreter::LFSUX,
ppu_interpreter::SYNC,
ppu_interpreter::LFDX,
ppu_interpreter::LFDUX,
ppu_interpreter::STVLX,
ppu_interpreter::STDBRX,
ppu_interpreter::STSWX,
ppu_interpreter::STWBRX,
ppu_interpreter::STFSX,
ppu_interpreter::STVRX,
ppu_interpreter::STFSUX,
ppu_interpreter::STSWI,
ppu_interpreter::STFDX,
ppu_interpreter::STFDUX,
ppu_interpreter::LVLXL,
ppu_interpreter::LHBRX,
ppu_interpreter::SRAW,
ppu_interpreter::SRAD,
ppu_interpreter::LVRXL,
ppu_interpreter::DSS,
ppu_interpreter::SRAWI,
ppu_interpreter::SRADI,
ppu_interpreter::EIEIO,
ppu_interpreter::STVLXL,
ppu_interpreter::STHBRX,
ppu_interpreter::EXTSH,
ppu_interpreter::STVRXL,
ppu_interpreter::EXTSB,
ppu_interpreter::STFIWX,
ppu_interpreter::EXTSW,
ppu_interpreter::ICBI,
ppu_interpreter::DCBZ,
ppu_interpreter::LWZ,
ppu_interpreter::LWZU,
ppu_interpreter::LBZ,
ppu_interpreter::LBZU,
ppu_interpreter::STW,
ppu_interpreter::STWU,
ppu_interpreter::STB,
ppu_interpreter::STBU,
ppu_interpreter::LHZ,
ppu_interpreter::LHZU,
ppu_interpreter::LHA,
ppu_interpreter::LHAU,
ppu_interpreter::STH,
ppu_interpreter::STHU,
ppu_interpreter::LMW,
ppu_interpreter::STMW,
ppu_interpreter::LFS,
ppu_interpreter::LFSU,
ppu_interpreter::LFD,
ppu_interpreter::LFDU,
ppu_interpreter::STFS,
ppu_interpreter::STFSU,
ppu_interpreter::STFD,
ppu_interpreter::STFDU,
ppu_interpreter::LD,
ppu_interpreter::LDU,
ppu_interpreter::LWA,
ppu_interpreter::FDIVS,
ppu_interpreter::FSUBS,
ppu_interpreter::FADDS,
ppu_interpreter::FSQRTS,
ppu_interpreter::FRES,
ppu_interpreter::FMULS,
ppu_interpreter::FMADDS,
ppu_interpreter::FMSUBS,
ppu_interpreter::FNMSUBS,
ppu_interpreter::FNMADDS,
ppu_interpreter::STD,
ppu_interpreter::STDU,
ppu_interpreter::MTFSB1,
ppu_interpreter::MCRFS,
ppu_interpreter::MTFSB0,
ppu_interpreter::MTFSFI,
ppu_interpreter::MFFS,
ppu_interpreter::MTFSF,
ppu_interpreter::FCMPU,
ppu_interpreter::FRSP,
ppu_interpreter::FCTIW,
ppu_interpreter::FCTIWZ,
ppu_interpreter::FDIV,
ppu_interpreter::FSUB,
ppu_interpreter::FADD,
ppu_interpreter::FSQRT,
ppu_interpreter::FSEL,
ppu_interpreter::FMUL,
ppu_interpreter::FRSQRTE,
ppu_interpreter::FMSUB,
ppu_interpreter::FMADD,
ppu_interpreter::FNMSUB,
ppu_interpreter::FNMADD,
ppu_interpreter::FCMPO,
ppu_interpreter::FNEG,
ppu_interpreter::FMR,
ppu_interpreter::FNABS,
ppu_interpreter::FABS,
ppu_interpreter::FCTID,
ppu_interpreter::FCTIDZ,
ppu_interpreter::FCFID,
ppu_interpreter::UNK,
};
extern u32 ppu_get_tls(u32 thread);
extern void ppu_free_tls(u32 thread);
void* g_ppu_exec_map = nullptr;
thread_local const std::weak_ptr<ppu_decoder_cache_t> g_tls_ppu_decoder_cache = fxm::get<ppu_decoder_cache_t>();
void finalize_ppu_exec_map()
{
if (g_ppu_exec_map)
{
ppu_decoder_cache_t::ppu_decoder_cache_t()
#ifdef _WIN32
VirtualFree(g_ppu_exec_map, 0, MEM_RELEASE);
: pointer(static_cast<decltype(pointer)>(VirtualAlloc(NULL, 0x200000000, MEM_RESERVE, PAGE_NOACCESS)))
#else
munmap(g_ppu_exec_map, 0x100000000);
: pointer(static_cast<decltype(pointer)>(mmap(nullptr, 0x200000000, PROT_NONE, MAP_ANON | MAP_PRIVATE, -1, 0)))
#endif
g_ppu_exec_map = nullptr;
}
{
}
void initialize_ppu_exec_map()
ppu_decoder_cache_t::~ppu_decoder_cache_t()
{
finalize_ppu_exec_map();
#ifdef _WIN32
g_ppu_exec_map = VirtualAlloc(NULL, 0x100000000, MEM_RESERVE, PAGE_NOACCESS);
VirtualFree(pointer, 0, MEM_RELEASE);
#else
g_ppu_exec_map = mmap(nullptr, 0x100000000, PROT_NONE, MAP_ANON | MAP_PRIVATE, -1, 0);
munmap(pointer, 0x200000000);
#endif
}
void fill_ppu_exec_map(u32 addr, u32 size)
void ppu_decoder_cache_t::initialize(u32 addr, u32 size)
{
#ifdef _WIN32
VirtualAlloc((u8*)g_ppu_exec_map + addr, size, MEM_COMMIT, PAGE_READWRITE);
VirtualAlloc(pointer + addr / 4, size * 2, MEM_COMMIT, PAGE_READWRITE);
#else
mprotect((u8*)g_ppu_exec_map + addr, size, PROT_READ | PROT_WRITE);
mprotect(pointer + addr / 4, size * 2, PROT_READ | PROT_WRITE);
#endif
PPUInterpreter2* inter;
@ -473,19 +63,8 @@ void fill_ppu_exec_map(u32 addr, u32 size)
// decode PPU opcode
dec.Decode(vm::read32(pos));
u32 index = 0;
// find function index
for (; index < sizeof(g_ppu_inter_func_list) / sizeof(ppu_inter_func_t); index++)
{
if (inter->func == g_ppu_inter_func_list[index])
{
break;
}
}
// write index in memory
*(u32*)((u8*)g_ppu_exec_map + pos) = index;
// store function address
pointer[pos / 4] = inter->func;
}
}
@ -534,6 +113,8 @@ void PPUThread::init_regs()
CR.CR = 0x22000082;
VSCR.NJ = 1;
TB = 0;
//m_state |= CPU_STATE_INTR;
}
void PPUThread::init_stack()
@ -563,6 +144,11 @@ void PPUThread::close_stack()
}
}
bool PPUThread::handle_interrupt()
{
return false;
}
void PPUThread::do_run()
{
m_dec.reset();
@ -699,6 +285,15 @@ void PPUThread::task()
return custom_task(*this);
}
const auto decoder_cache = g_tls_ppu_decoder_cache.lock();
if (!decoder_cache)
{
throw EXCEPTION("PPU Decoder Cache not initialized");
}
const auto exec_map = decoder_cache->pointer;
if (m_dec)
{
while (true)
@ -716,19 +311,25 @@ void PPUThread::task()
{
while (true)
{
if (m_state.load() && check_status()) break;
// get cached interpreter function address
const auto func = exec_map[PC / 4];
// get interpreter function
const auto func = g_ppu_inter_func_list[*(u32*)((u8*)g_ppu_exec_map + PC)];
// check status
if (!m_state.load())
{
// call interpreter function
func(*this, { vm::read32(PC) });
// read opcode
const ppu_opcode_t opcode = { vm::read32(PC) };
// next instruction
PC += 4;
// call interpreter function
func(*this, opcode);
// next instruction
PC += 4;
continue;
}
if (check_status())
{
break;
}
}
}
}

View file

@ -550,6 +550,8 @@ public:
virtual void init_stack() override;
virtual void close_stack() override;
virtual bool handle_interrupt() override;
inline u8 GetCR(const u8 n) const
{
switch(n)

View file

@ -340,6 +340,28 @@ namespace fxm
return ptr;
}
// get fixed object of specified type (always returns an object, it's created if it doesn't exist)
template<typename T, typename... Args> std::enable_if_t<std::is_constructible<T, Args...>::value, std::shared_ptr<T>> get_always(Args&&... args)
{
extern std::mutex g_fx_mutex;
extern std::unordered_map<std::type_index, std::shared_ptr<void>> g_fx_map;
std::lock_guard<std::mutex> lock(g_fx_mutex);
const auto found = g_fx_map.find(typeid(T));
if (found == g_fx_map.end())
{
auto ptr = std::make_shared<T>(std::forward<Args>(args)...);
g_fx_map[typeid(T)] = ptr;
return ptr;
}
return std::static_pointer_cast<T>(found->second);
}
// check whether the object exists
template<typename T> bool check()
{
@ -351,7 +373,7 @@ namespace fxm
return g_fx_map.find(typeid(T)) != g_fx_map.end();
}
// get fixed object of specified type
// get fixed object of specified type (returns nullptr if it doesn't exist)
template<typename T> std::shared_ptr<T> get()
{
extern std::mutex g_fx_mutex;

View file

@ -16,8 +16,6 @@
SysCallBase sys_prx("sys_prx");
extern void fill_ppu_exec_map(u32 addr, u32 size);
lv2_prx_t::lv2_prx_t()
: id(idm::get_current_id())
{
@ -124,6 +122,8 @@ s32 prx_load_module(std::string path, u64 flags, vm::ptr<sys_prx_load_module_opt
}
}
const auto decoder_cache = fxm::get<ppu_decoder_cache_t>();
for (auto& seg : info.segments)
{
const u32 addr = seg.begin.addr();
@ -131,7 +131,7 @@ s32 prx_load_module(std::string path, u64 flags, vm::ptr<sys_prx_load_module_opt
if (vm::check_addr(addr, size))
{
fill_ppu_exec_map(addr, size);
decoder_cache->initialize(addr, size);
}
else
{

View file

@ -445,6 +445,11 @@ s32 sys_spu_thread_group_yield(u32 id)
return CELL_ESRCH;
}
if (group->type & SYS_SPU_THREAD_GROUP_TYPE_EXCLUSIVE_NON_CONTEXT) // this check may be inaccurate
{
return CELL_OK;
}
if (group->state != SPU_THREAD_GROUP_STATUS_RUNNING)
{
return CELL_ESTAT;

View file

@ -38,7 +38,6 @@ static const u16 bpdb_version = 0x1000;
extern std::atomic<u32> g_thread_count;
extern u64 get_system_time();
extern void finalize_ppu_exec_map();
extern void finalize_psv_modules();
Emulator::Emulator()
@ -407,8 +406,6 @@ void Emulator::Stop()
CurGameInfo.Reset();
RSXIOMem.Clear();
vm::close();
finalize_ppu_exec_map();
SendDbgCommand(DID_STOPPED_EMU);
}

View file

@ -4,6 +4,7 @@
#include "Emu/FS/vfsFile.h"
#include "Emu/FS/vfsDir.h"
#include "Emu/Memory/Memory.h"
#include "Emu/IdManager.h"
#include "Emu/System.h"
#include "Emu/SysCalls/SysCalls.h"
#include "Emu/SysCalls/Modules.h"
@ -15,9 +16,6 @@
using namespace PPU_instr;
extern void initialize_ppu_exec_map();
extern void fill_ppu_exec_map(u32 addr, u32 size);
namespace loader
{
namespace handlers
@ -549,21 +547,22 @@ namespace loader
// branch to initialization
make_branch(entry, m_ehdr.e_entry);
const auto decoder_cache = fxm::make<ppu_decoder_cache_t>();
for (u32 page = 0; page < 0x20000000; page += 4096)
{
// TODO: scan only executable areas
if (vm::check_addr(page, 4096))
{
decoder_cache->initialize(page, 4096);
}
}
ppu_thread main_thread(OPD.addr(), "main_thread");
main_thread.args({ Emu.GetPath()/*, "-emu"*/ }).run();
main_thread.gpr(11, OPD.addr()).gpr(12, Emu.GetMallocPageSize());
initialize_ppu_exec_map();
for (u32 page = 0; page < 0x20000000; page += 4096)
{
if (vm::check_addr(page, 4096))
{
fill_ppu_exec_map(page, 4096);
}
}
return ok;
}

View file

@ -470,6 +470,7 @@
<ClInclude Include="Emu\Audio\AudioThread.h" />
<ClInclude Include="Emu\Audio\Null\NullAudioThread.h" />
<ClInclude Include="Emu\Audio\XAudio2\XAudio2Thread.h" />
<ClInclude Include="Emu\Cell\Common.h" />
<ClInclude Include="Emu\Cell\MFC.h" />
<ClInclude Include="Emu\Cell\PPCDecoder.h" />
<ClInclude Include="Emu\Cell\PPCDisAsm.h" />

View file

@ -1864,5 +1864,8 @@
<ClInclude Include="Emu\SysCalls\lv2\sys_sync.h">
<Filter>Emu\SysCalls\lv2</Filter>
</ClInclude>
<ClInclude Include="Emu\Cell\Common.h">
<Filter>Emu\CPU\Cell</Filter>
</ClInclude>
</ItemGroup>
</Project>