Merge branch 'mp2-fixes'

This commit is contained in:
Phillip Stephens 2020-04-09 20:27:22 -07:00
commit 0085f0b16f
Signed by: Antidote
GPG Key ID: F8BEE4C83DACA60D
33 changed files with 1975 additions and 1293 deletions

File diff suppressed because it is too large Load Diff

View File

@ -4,7 +4,7 @@
#include <array>
#include "hecl/Blender/Connection.hpp"
#include "../DNAMP1/PATH.hpp"
#include "PATH.hpp"
namespace DataSpec {
logvisor::Module Log("AROTBuilder");
@ -278,10 +278,10 @@ void AROTBuilder::Node::pathCountNodesAndLookups(size_t& nodeCount, size_t& look
}
}
void AROTBuilder::Node::pathWrite(DNAMP1::PATH& path, const zeus::CAABox& curAABB) {
template <class PAKBridge>
void AROTBuilder::Node::pathWrite(DNAPATH::PATH<PAKBridge>& path, const zeus::CAABox& curAABB) {
if (childNodes.empty()) {
path.octree.emplace_back();
DNAMP1::PATH::OctreeNode& n = path.octree.back();
auto& n = path.octree.emplace_back();
n.isLeaf = 1;
n.aabb[0] = curAABB.min;
n.aabb[1] = curAABB.max;
@ -299,8 +299,7 @@ void AROTBuilder::Node::pathWrite(DNAMP1::PATH& path, const zeus::CAABox& curAAB
children[i] = path.octree.size() - 1;
}
path.octree.emplace_back();
DNAMP1::PATH::OctreeNode& n = path.octree.back();
auto& n = path.octree.emplace_back();
n.isLeaf = 0;
n.aabb[0] = curAABB.min;
n.aabb[1] = curAABB.max;
@ -311,6 +310,10 @@ void AROTBuilder::Node::pathWrite(DNAMP1::PATH& path, const zeus::CAABox& curAAB
}
}
template void AROTBuilder::Node::pathWrite(DNAPATH::PATH<DNAMP1::PAKBridge>& path, const zeus::CAABox& curAABB);
template void AROTBuilder::Node::pathWrite(DNAPATH::PATH<DNAMP2::PAKBridge>& path, const zeus::CAABox& curAABB);
template void AROTBuilder::Node::pathWrite(DNAPATH::PATH<DNAMP3::PAKBridge>& path, const zeus::CAABox& curAABB);
void AROTBuilder::build(std::vector<std::vector<uint8_t>>& secs, const zeus::CAABox& fullAabb,
const std::vector<zeus::CAABox>& meshAabbs, const std::vector<DNACMDL::Mesh>& meshes) {
/* Recursively split */
@ -406,15 +409,14 @@ std::pair<std::unique_ptr<uint8_t[]>, uint32_t> AROTBuilder::buildCol(const ColM
return {std::move(ret), totalSize};
}
void AROTBuilder::buildPath(DNAMP1::PATH& path) {
template <class PAKBridge>
void AROTBuilder::buildPath(DNAPATH::PATH<PAKBridge>& path) {
/* Accumulate total AABB and gather region boxes */
std::vector<zeus::CAABox> regionBoxes;
regionBoxes.reserve(path.regions.size());
zeus::CAABox fullAABB;
for (const DNAMP1::PATH::Region& r : path.regions) {
regionBoxes.emplace_back(r.aabb[0], r.aabb[1]);
fullAABB.accumulateBounds(regionBoxes.back());
}
for (const auto& r : path.regions)
fullAABB.accumulateBounds(regionBoxes.emplace_back(r.aabb[0], r.aabb[1]));
/* Recursively split */
BspNodeType dontCare;
@ -431,4 +433,8 @@ void AROTBuilder::buildPath(DNAMP1::PATH& path) {
rootNode.pathWrite(path, fullAABB);
}
template void AROTBuilder::buildPath(DNAPATH::PATH<DNAMP1::PAKBridge>& path);
template void AROTBuilder::buildPath(DNAPATH::PATH<DNAMP2::PAKBridge>& path);
template void AROTBuilder::buildPath(DNAPATH::PATH<DNAMP3::PAKBridge>& path);
} // namespace DataSpec

View File

@ -7,10 +7,12 @@
#include <set>
namespace DataSpec {
namespace DNAMP1 {
namespace DNAPATH {
template <class PAKBridge>
struct PATH;
}
struct AROTBuilder {
using ColMesh = hecl::blender::ColMesh;
@ -42,13 +44,15 @@ struct AROTBuilder {
void writeColNodes(uint8_t*& ptr, const zeus::CAABox& curAABB);
void pathCountNodesAndLookups(size_t& nodeCount, size_t& lookupCount);
void pathWrite(DNAMP1::PATH& path, const zeus::CAABox& curAABB);
template <class PAKBridge>
void pathWrite(DNAPATH::PATH<PAKBridge>& path, const zeus::CAABox& curAABB);
} rootNode;
void build(std::vector<std::vector<uint8_t>>& secs, const zeus::CAABox& fullAabb,
const std::vector<zeus::CAABox>& meshAabbs, const std::vector<DNACMDL::Mesh>& meshes);
std::pair<std::unique_ptr<uint8_t[]>, uint32_t> buildCol(const ColMesh& mesh, BspNodeType& rootOut);
void buildPath(DNAMP1::PATH& path);
template <class PAKBridge>
void buildPath(DNAPATH::PATH<PAKBridge>& path);
};
} // namespace DataSpec

View File

@ -521,8 +521,11 @@ void FinishBlenderMesh(hecl::blender::PyOutStream& os, unsigned matSetCount, int
" use_vert_dict = vert_dict[0]\n"
" merge_verts = [use_vert_dict[fv[od_entry['bm'].verts.layers.int['CMDLOriginalPosIdxs']]] for fv in "
"face.verts]\n"
" try:\n"
" if bm.faces.get(merge_verts) is not None:\n"
" continue\n"
" except:\n"
" continue\n"
" merge_face = bm.faces.new(merge_verts)\n"
" for i in range(len(face.loops)):\n"
" old = face.loops[i]\n"

View File

@ -4,6 +4,7 @@ make_dnalist(CMDL
FSM2
MAPA
MAPU
PATH
MayaSpline
EGMC
SAVWCommon
@ -19,6 +20,7 @@ set(DNACOMMON_SOURCES
CMDL.cpp
MAPA.cpp
MAPU.cpp
PATH.hpp PATH.cpp
STRG.hpp STRG.cpp
TXTR.hpp TXTR.cpp
ANCS.hpp ANCS.cpp

View File

@ -14,6 +14,8 @@ struct MayaSpline : public BigDNA {
Value<float> amplitude;
Value<atUint8> unk1;
Value<atUint8> unk2;
Vector<atVec2f, AT_DNA_COUNT(unk1 == 5)> unk1Floats;
Vector<atVec2f, AT_DNA_COUNT(unk2 == 5)> unk2Floats;
};
Vector<Knot, AT_DNA_COUNT(knotCount)> knots;

View File

@ -3,7 +3,7 @@
#include "zeus/CAABox.hpp"
#include "DataSpec/DNACommon/AROTBuilder.hpp"
namespace DataSpec::DNAMP1 {
namespace DataSpec::DNAPATH {
#define DUMP_OCTREE 0
@ -19,17 +19,17 @@ static void OutputOctreeNode(hecl::blender::PyOutStream& os, int idx, const zeus
"obj.scale = (%f,%f,%f)\n"
"obj.empty_display_type = 'CUBE'\n"
"obj.layers[1] = True\n"
"obj.layers[0] = False\n", idx,
pos.x(), pos.y(), pos.z(), extent.x(), extent.y(), extent.z());
"obj.layers[0] = False\n",
idx, pos.x(), pos.y(), pos.z(), extent.x(), extent.y(), extent.z());
}
#endif
void PATH::sendToBlender(hecl::blender::Connection& conn, std::string_view entryName, const zeus::CMatrix4f* xf,
const std::string& areaPath) {
template <class PAKBridge>
void PATH<PAKBridge>::sendToBlender(hecl::blender::Connection& conn, std::string_view entryName,
const zeus::CMatrix4f* xf, const std::string& areaPath) {
/* Open Py Stream and read sections */
hecl::blender::PyOutStream os = conn.beginPythonOut(true);
os <<
"import bpy\n"
os << "import bpy\n"
"import bmesh\n"
"from mathutils import Vector, Matrix\n"
"\n"
@ -71,8 +71,7 @@ void PATH::sendToBlender(hecl::blender::Connection& conn, std::string_view entry
" return len(material_index)-1\n"
"\n";
os.format(fmt("bpy.context.scene.name = '{}'\n"), entryName);
os <<
"# Clear Scene\n"
os << "# Clear Scene\n"
"if len(bpy.data.collections):\n"
" bpy.data.collections.remove(bpy.data.collections[0])\n"
"\n"
@ -91,8 +90,7 @@ void PATH::sendToBlender(hecl::blender::Connection& conn, std::string_view entry
for (atUint32 i = 0; i < r.nodeCount; ++i)
os.format(fmt("tri_verts.append(bm.verts[{}])\n"), r.nodeStart + i);
os.format(fmt(
"face = bm.faces.get(tri_verts)\n"
os.format(fmt("face = bm.faces.get(tri_verts)\n"
"if face is None:\n"
" face = bm.faces.new(tri_verts)\n"
" face.normal_flip()\n"
@ -152,15 +150,14 @@ void PATH::sendToBlender(hecl::blender::Connection& conn, std::string_view entry
zeus::simd_floats xfMtxF[4];
for (int i = 0; i < 4; ++i)
w.m[i].mSimd.copy_to(xfMtxF[i]);
os.format(fmt(
"mtx = Matrix((({},{},{},{}),({},{},{},{}),({},{},{},{}),(0.0,0.0,0.0,1.0)))\n"
os.format(fmt("mtx = Matrix((({},{},{},{}),({},{},{},{}),({},{},{},{}),(0.0,0.0,0.0,1.0)))\n"
"mtxd = mtx.decompose()\n"
"path_mesh_obj.rotation_mode = 'QUATERNION'\n"
"path_mesh_obj.location = mtxd[0]\n"
"path_mesh_obj.rotation_quaternion = mtxd[1]\n"
"path_mesh_obj.scale = mtxd[2]\n"),
xfMtxF[0][0], xfMtxF[1][0], xfMtxF[2][0], xfMtxF[3][0], xfMtxF[0][1], xfMtxF[1][1], xfMtxF[2][1], xfMtxF[3][1],
xfMtxF[0][2], xfMtxF[1][2], xfMtxF[2][2], xfMtxF[3][2]);
xfMtxF[0][0], xfMtxF[1][0], xfMtxF[2][0], xfMtxF[3][0], xfMtxF[0][1], xfMtxF[1][1], xfMtxF[2][1],
xfMtxF[3][1], xfMtxF[0][2], xfMtxF[1][2], xfMtxF[2][2], xfMtxF[3][2]);
}
#if DUMP_OCTREE
@ -179,8 +176,10 @@ void PATH::sendToBlender(hecl::blender::Connection& conn, std::string_view entry
os.close();
}
bool PATH::Extract(const SpecBase& dataSpec, PAKEntryReadStream& rs, const hecl::ProjectPath& outPath,
PAKRouter<PAKBridge>& pakRouter, const PAK::Entry& entry, bool force, hecl::blender::Token& btok,
template <class PAKBridge>
bool PATH<PAKBridge>::Extract(const SpecBase& dataSpec, PAKEntryReadStream& rs, const hecl::ProjectPath& outPath,
PAKRouter<PAKBridge>& pakRouter, const typename PAKBridge::PAKType::Entry& entry,
bool force, hecl::blender::Token& btok,
std::function<void(const hecl::SystemChar*)> fileChanged) {
PATH path;
path.read(rs);
@ -201,8 +200,9 @@ bool PATH::Extract(const SpecBase& dataSpec, PAKEntryReadStream& rs, const hecl:
return conn.saveBlend();
}
bool PATH::Cook(const hecl::ProjectPath& outPath, const hecl::ProjectPath& inPath,
const PathMesh& mesh, hecl::blender::Token& btok) {
template <class PAKBridge>
bool PATH<PAKBridge>::Cook(const hecl::ProjectPath& outPath, const hecl::ProjectPath& inPath, const PathMesh& mesh,
hecl::blender::Token& btok) {
athena::io::MemoryReader r(mesh.data.data(), mesh.data.size());
PATH path;
path.read(r);
@ -241,4 +241,8 @@ bool PATH::Cook(const hecl::ProjectPath& outPath, const hecl::ProjectPath& inPat
return true;
}
} // namespace DataSpec::DNAMP1
template struct PATH<DataSpec::DNAMP1::PAKBridge>;
template struct PATH<DataSpec::DNAMP2::PAKBridge>;
template struct PATH<DataSpec::DNAMP3::PAKBridge>;
} // namespace DataSpec::DNAPATH

112
DataSpec/DNACommon/PATH.hpp Normal file
View File

@ -0,0 +1,112 @@
#pragma once
#include "DataSpec/DNACommon/DNACommon.hpp"
#include "DataSpec/DNACommon/PAK.hpp"
#include "DataSpec/DNAMP1/DNAMP1.hpp"
#include "DataSpec/DNAMP2/DNAMP2.hpp"
#include "DataSpec/DNAMP3/DNAMP3.hpp"
namespace DataSpec::DNAPATH {
template <class PAKBridge>
struct RegionPointers {};
template <>
struct RegionPointers<DataSpec::DNAMP1::PAKBridge> : BigDNA {
AT_DECL_DNA
Value<atUint32> regionIdxPtr;
};
template <>
struct RegionPointers<DataSpec::DNAMP2::PAKBridge> : BigDNA {
AT_DECL_DNA
Value<atUint32> unk0;
Value<atUint32> unk1;
Value<atUint32> unk2;
Value<atUint32> regionIdxPtr;
};
template <>
struct RegionPointers<DataSpec::DNAMP3::PAKBridge> : BigDNA {
AT_DECL_DNA
Value<atUint32> unk0;
Value<atUint32> unk1;
Value<atUint32> unk2;
Value<atUint32> regionIdxPtr;
};
template <class PAKBridge>
struct AT_SPECIALIZE_PARMS(DataSpec::DNAMP1::PAKBridge, DataSpec::DNAMP2::PAKBridge, DataSpec::DNAMP3::PAKBridge) PATH
: BigDNA {
using PathMesh = hecl::blender::PathMesh;
AT_DECL_DNA
Value<atUint32> version;
struct Node : BigDNA {
AT_DECL_DNA
Value<atVec3f> position;
Value<atVec3f> normal;
};
Value<atUint32> nodeCount;
Vector<Node, AT_DNA_COUNT(nodeCount)> nodes;
struct Link : BigDNA {
AT_DECL_DNA
Value<atUint32> nodeIdx;
Value<atUint32> regionIdx;
Value<float> width2d;
Value<float> oneOverWidth2d;
};
Value<atUint32> linkCount;
Vector<Link, AT_DNA_COUNT(linkCount)> links;
struct Region : BigDNA {
AT_DECL_DNA
Value<atUint32> nodeCount;
Value<atUint32> nodeStart;
Value<atUint32> linkCount;
Value<atUint32> linkStart;
Value<atUint16> meshIndexMask;
Value<atUint16> meshTypeMask;
Value<float> height;
Value<atVec3f> normal;
Value<atUint32> regionIdx;
Value<atVec3f> centroid;
Value<atVec3f> aabb[2];
Value<RegionPointers<PAKBridge>> pointers;
};
Value<atUint32> regionCount;
Vector<Region, AT_DNA_COUNT(regionCount)> regions;
Vector<atUint32, AT_DNA_COUNT((((regionCount * (regionCount - 1)) / 2) + 31) / 32)> bitmap1;
Vector<atUint32, AT_DNA_COUNT(bitmap1.size())> bitmap2;
/* Unused in all games, removed in MP3 */
Vector<atUint32, AT_DNA_COUNT(std::is_same_v<PAKBridge, DataSpec::DNAMP3::PAKBridge>
? 0
: (((((regionCount * regionCount) + 31) / 32) - bitmap1.size()) * 2))>
bitmap3;
Value<atUint32> octreeRegionLookupCount;
Vector<atUint32, AT_DNA_COUNT(octreeRegionLookupCount)> octreeRegionLookup;
struct OctreeNode : BigDNA {
AT_DECL_DNA
Value<atUint32> isLeaf;
Value<atVec3f> aabb[2];
Value<atVec3f> centroid;
Value<atUint32> children[8];
Value<atUint32> regionCount;
Value<atUint32> regionStart;
};
Value<atUint32> octreeNodeCount;
Vector<OctreeNode, AT_DNA_COUNT(octreeNodeCount)> octree;
void sendToBlender(hecl::blender::Connection& conn, std::string_view entryName, const zeus::CMatrix4f* xf,
const std::string& areaPath);
static bool Extract(const SpecBase& dataSpec, PAKEntryReadStream& rs, const hecl::ProjectPath& outPath,
PAKRouter<PAKBridge>& pakRouter, const typename PAKBridge::PAKType::Entry& entry, bool force,
hecl::blender::Token& btok, std::function<void(const hecl::SystemChar*)> fileChanged);
static bool Cook(const hecl::ProjectPath& outPath, const hecl::ProjectPath& inPath, const PathMesh& mesh,
hecl::blender::Token& btok);
};
} // namespace DataSpec::DNAPATH

View File

@ -141,6 +141,5 @@ zeus::CVector3f RigInverter<CINFType>::restorePosition(atUint32 boneId, const ze
template class RigInverter<DNAMP1::CINF>;
template class RigInverter<DNAMP2::CINF>;
template class RigInverter<DNAMP3::CINF>;
} // namespace DataSpec::DNAANIM

View File

@ -34,8 +34,7 @@ void Material::AddTexture(Stream& out, GX::TexGenSrc type, int mtxIdx, uint32_t
else
texLabel = "Texture";
out.format(fmt(
"# Texture\n"
out.format(fmt("# Texture\n"
"tex_node = new_nodetree.nodes.new('ShaderNodeTexImage')\n"
"tex_node.label = '{} {}'\n"
"texture_nodes.append(tex_node)\n"),
@ -52,8 +51,7 @@ void Material::AddTexture(Stream& out, GX::TexGenSrc type, int mtxIdx, uint32_t
"tex_links.append(new_nodetree.links.new(tex_uv_node.outputs['Normal'], tex_node.inputs['Vector']))\n";
else if (type >= GX::TG_TEX0 && type <= GX::TG_TEX7) {
uint8_t texIdx = type - GX::TG_TEX0;
out.format(fmt(
"tex_uv_node = new_nodetree.nodes.new('ShaderNodeUVMap')\n"
out.format(fmt("tex_uv_node = new_nodetree.nodes.new('ShaderNodeUVMap')\n"
"tex_links.append(new_nodetree.links.new(tex_uv_node.outputs['UV'], tex_node.inputs['Vector']))\n"
"tex_uv_node.uv_map = 'UV_{}'\n"),
texIdx);
@ -72,8 +70,7 @@ void Material::AddTexture(Stream& out, GX::TexGenSrc type, int mtxIdx, uint32_t
void Material::AddTextureAnim(Stream& out, UVAnimation::Mode type, unsigned idx, const float* vals) {
switch (type) {
case UVAnimation::Mode::MvInvNoTranslation:
out.format(fmt(
"for link in list(tex_links):\n"
out.format(fmt("for link in list(tex_links):\n"
" if link.from_node.label == 'MTX_{}':\n"
" tex_links.remove(link)\n"
" soc_from = link.from_socket\n"
@ -88,8 +85,7 @@ void Material::AddTextureAnim(Stream& out, UVAnimation::Mode type, unsigned idx,
idx);
break;
case UVAnimation::Mode::MvInv:
out.format(fmt(
"for link in list(tex_links):\n"
out.format(fmt("for link in list(tex_links):\n"
" if link.from_node.label == 'MTX_{}':\n"
" tex_links.remove(link)\n"
" soc_from = link.from_socket\n"
@ -104,8 +100,7 @@ void Material::AddTextureAnim(Stream& out, UVAnimation::Mode type, unsigned idx,
idx);
break;
case UVAnimation::Mode::Scroll:
out.format(fmt(
"for link in list(tex_links):\n"
out.format(fmt("for link in list(tex_links):\n"
" if link.from_node.label == 'MTX_{}':\n"
" tex_links.remove(link)\n"
" soc_from = link.from_socket\n"
@ -122,8 +117,7 @@ void Material::AddTextureAnim(Stream& out, UVAnimation::Mode type, unsigned idx,
idx, vals[0], vals[1], vals[2], vals[3]);
break;
case UVAnimation::Mode::Rotation:
out.format(fmt(
"for link in list(tex_links):\n"
out.format(fmt("for link in list(tex_links):\n"
" if link.from_node.label == 'MTX_{}':\n"
" tex_links.remove(link)\n"
" soc_from = link.from_socket\n"
@ -140,8 +134,7 @@ void Material::AddTextureAnim(Stream& out, UVAnimation::Mode type, unsigned idx,
idx, vals[0], vals[1]);
break;
case UVAnimation::Mode::HStrip:
out.format(fmt(
"for link in list(tex_links):\n"
out.format(fmt("for link in list(tex_links):\n"
" if link.from_node.label == 'MTX_{}':\n"
" tex_links.remove(link)\n"
" soc_from = link.from_socket\n"
@ -160,8 +153,7 @@ void Material::AddTextureAnim(Stream& out, UVAnimation::Mode type, unsigned idx,
idx, vals[0], vals[1], vals[2], vals[3]);
break;
case UVAnimation::Mode::VStrip:
out.format(fmt(
"for link in list(tex_links):\n"
out.format(fmt("for link in list(tex_links):\n"
" if link.from_node.label == 'MTX_{}':\n"
" tex_links.remove(link)\n"
" soc_from = link.from_socket\n"
@ -180,8 +172,7 @@ void Material::AddTextureAnim(Stream& out, UVAnimation::Mode type, unsigned idx,
idx, vals[0], vals[1], vals[2], vals[3]);
break;
case UVAnimation::Mode::Model:
out.format(fmt(
"for link in list(tex_links):\n"
out.format(fmt("for link in list(tex_links):\n"
" if link.from_node.label == 'MTX_{}':\n"
" tex_links.remove(link)\n"
" soc_from = link.from_socket\n"
@ -196,8 +187,7 @@ void Material::AddTextureAnim(Stream& out, UVAnimation::Mode type, unsigned idx,
idx);
break;
case UVAnimation::Mode::CylinderEnvironment:
out.format(fmt(
"for link in list(tex_links):\n"
out.format(fmt("for link in list(tex_links):\n"
" if link.from_node.label == 'MTX_{}':\n"
" tex_links.remove(link)\n"
" soc_from = link.from_socket\n"
@ -214,8 +204,7 @@ void Material::AddTextureAnim(Stream& out, UVAnimation::Mode type, unsigned idx,
idx, vals[0], vals[1]);
break;
case UVAnimation::Mode::Eight:
out.format(fmt(
"for link in list(tex_links):\n"
out.format(fmt("for link in list(tex_links):\n"
" if link.from_node.label == 'MTX_{}':\n"
" tex_links.remove(link)\n"
" soc_from = link.from_socket\n"
@ -244,12 +233,12 @@ void Material::AddTextureAnim(Stream& out, UVAnimation::Mode type, unsigned idx,
}
void Material::AddKcolor(Stream& out, const GX::Color& col, unsigned idx) {
out.format(fmt(
"kcolors[{}] = ({}, {}, {}, {})\n"
out.format(fmt("kcolors[{}] = ({}, {}, {}, {})\n"
"kalphas[{}] = {}\n"
"\n"),
idx, (float)col.color[0] / (float)0xff, (float)col.color[1] / (float)0xff, (float)col.color[2] / (float)0xff,
(float)col.color[3] / (float)0xff, idx, (float)col.color[3] / (float)0xff);
idx, (float)col.color[0] / (float)0xff, (float)col.color[1] / (float)0xff,
(float)col.color[2] / (float)0xff, (float)col.color[3] / (float)0xff, idx,
(float)col.color[3] / (float)0xff);
}
template <class MAT>
@ -354,10 +343,9 @@ template <class MAT>
static void _DescribeTEV(const MAT& mat) {
for (uint32_t i = 0; i < mat.tevStageCount; ++i) {
const auto& stage = mat.tevStages[i];
fmt::print(stderr, fmt("A:{} B:{} C:{} D:{} -> {} | A:{} B:{} C:{} D:{} -> {}\n"),
ToString(stage.colorInA()), ToString(stage.colorInB()),
ToString(stage.colorInC()), ToString(stage.colorInD()), ToString(stage.colorOpOutReg()),
ToString(stage.alphaInA()), ToString(stage.alphaInB()),
fmt::print(stderr, fmt("A:{} B:{} C:{} D:{} -> {} | A:{} B:{} C:{} D:{} -> {}\n"), ToString(stage.colorInA()),
ToString(stage.colorInB()), ToString(stage.colorInC()), ToString(stage.colorInD()),
ToString(stage.colorOpOutReg()), ToString(stage.alphaInA()), ToString(stage.alphaInB()),
ToString(stage.alphaInC()), ToString(stage.alphaInD()), ToString(stage.alphaOpOutReg()));
}
bool hasInd = mat.flags.samusReflectionIndirectTexture();
@ -388,12 +376,10 @@ struct KColLink {
struct WhiteColorLink {
const char* shaderInput;
explicit WhiteColorLink(const char* shaderInput)
: shaderInput(shaderInput) {}
explicit WhiteColorLink(const char* shaderInput) : shaderInput(shaderInput) {}
};
static void _GenerateRootShader(Stream& out, int) {
/* End of shader links */
static void _GenerateRootShader(Stream& out, int) { /* End of shader links */
}
template <typename... Targs>
@ -401,8 +387,8 @@ static void _GenerateRootShader(Stream& out, int tidx, TexLink tex, Targs... arg
int texIdx = tex.texidx == -1 ? tidx : tex.texidx;
out << "texture_nodes[" << texIdx << "].name = '" << tex.shaderInput << "'\n";
out << "texture_nodes[" << texIdx << "].label = '" << tex.shaderInput << "'\n";
out << "new_nodetree.links.new(texture_nodes[" << texIdx << "].outputs['" <<
(tex.alpha ? "Alpha" : "Color") << "'], node.inputs['" << tex.shaderInput << "'])\n";
out << "new_nodetree.links.new(texture_nodes[" << texIdx << "].outputs['" << (tex.alpha ? "Alpha" : "Color")
<< "'], node.inputs['" << tex.shaderInput << "'])\n";
if (tex.texidx == -1)
++tidx;
_GenerateRootShader(out, tidx, args...);
@ -422,8 +408,8 @@ static void _GenerateRootShader(Stream& out, int tidx, ExtendedSpecularLink tex,
template <typename... Targs>
static void _GenerateRootShader(Stream& out, int tidx, KColLink kcol, Targs... args) {
out << "node.inputs['" << kcol.shaderInput << "'].default_value = " <<
(kcol.alpha ? "kalphas[" : "kcolors[") << kcol.kcidx << "]\n";
out << "node.inputs['" << kcol.shaderInput << "'].default_value = " << (kcol.alpha ? "kalphas[" : "kcolors[")
<< kcol.kcidx << "]\n";
_GenerateRootShader(out, tidx, args...);
}
@ -437,7 +423,9 @@ template <typename... Targs>
static void _GenerateRootShader(Stream& out, const char* type, Targs... args) {
out << "node = new_nodetree.nodes.new('ShaderNodeGroup')\n"
"node.name = 'Output'\n"
"node.node_tree = bpy.data.node_groups['" << type << "']\n"
"node.node_tree = bpy.data.node_groups['"
<< type
<< "']\n"
"gridder.place_node(node, 1)\n"
"new_nodetree.links.new(node.outputs['Surface'], blend_node.inputs['Surface'])\n";
_GenerateRootShader(out, 0, args...);
@ -470,8 +458,7 @@ static void _ConstructMaterial(Stream& out, const MAT& material, unsigned groupI
"\n";
/* Material Flags */
out.format(fmt(
"new_material.retro_depth_sort = {}\n"
out.format(fmt("new_material.retro_depth_sort = {}\n"
"new_material.retro_alpha_test = {}\n"
"new_material.retro_samus_reflection = {}\n"
"new_material.retro_depth_write = {}\n"
@ -484,8 +471,8 @@ static void _ConstructMaterial(Stream& out, const MAT& material, unsigned groupI
material.flags.samusReflection() ? "True" : "False", material.flags.depthWrite() ? "True" : "False",
material.flags.samusReflectionSurfaceEye() ? "True" : "False",
material.flags.shadowOccluderMesh() ? "True" : "False",
material.flags.samusReflectionIndirectTexture() ? "True" : "False", material.flags.lightmap() ? "True" : "False",
material.flags.shadowOccluderMesh() ? "0" : "1");
material.flags.samusReflectionIndirectTexture() ? "True" : "False",
material.flags.lightmap() ? "True" : "False", material.flags.shadowOccluderMesh() ? "0" : "1");
/* Texture Indices */
out << "tex_maps = []\n";
@ -537,131 +524,268 @@ static void _ConstructMaterial(Stream& out, const MAT& material, unsigned groupI
/* Select appropriate root shader and link textures */
uint32_t hash = _HashTextureConfig(material);
switch (hash) {
case 0x03FEE002: /* RetroShader: Diffuse, Emissive, Reflection, Alpha=1.0 */
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Emissive"_tex, "Reflection"_tex);
break;
case 0x0473AE40: /* RetroShader: Lightmap, Diffuse, Emissive, Alpha=1.0 */
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, "Emissive"_tex); break;
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, "Emissive"_tex);
break;
case 0x072D2CB3: /* RetroShader: Diffuse, Emissive, Reflection, Alpha=1.0 */
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Emissive"_tex, WhiteColorLink("Specular"), "Reflection"_tex); break;
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Emissive"_tex, WhiteColorLink("Specular"),
"Reflection"_tex);
break;
case 0x07AA75D7: /* RetroShader: Diffuse, Emissive, Alpha=DiffuseAlpha */
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Emissive"_tex, TexLink("Alpha", 0, true));
break;
case 0x0879D346: /* RetroShader: KColorDiffuse, Alpha=Texture */
_GenerateRootShader(out, "RetroShader", "Diffuse"_kcol, "Alpha"_tex); break;
_GenerateRootShader(out, "RetroShader", "Diffuse"_kcol, "Alpha"_tex);
break;
case 0x0DA256BB: /* Lightmap, Diffuse, Specular, Reflection, Alpha=KAlpha */
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, "Specular"_tex, "Reflection"_tex, "Alpha"_kcola); break;
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, "Specular"_tex, "Reflection"_tex,
"Alpha"_kcola);
break;
case 0x11C41DA4: /* RetroDynamicCharacterShader: Diffuse, DynamicMaskTex, Specular, Reflection, Alpha=1.0 */
_GenerateRootShader(out, "RetroDynamicCharacterShader", "Diffuse"_tex, "Emissive"_tex, "Specular"_tex, "Reflection"_tex); break;
_GenerateRootShader(out, "RetroDynamicCharacterShader", "Diffuse"_tex, "Emissive"_tex, "Specular"_tex,
"Reflection"_tex);
break;
case 0x1218F83E: /* RetroShader: ObjLightmap, Diffuse, ExtendedSpecular, Reflection, Alpha=DiffuseAlpha */
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, ExtendedSpecularLink(), "Reflection"_tex, TexLink("Alpha", 1, true)); break;
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, ExtendedSpecularLink(), "Reflection"_tex,
TexLink("Alpha", 1, true));
break;
case 0x129B8578: /* RetroShader: KColorDiffuse, Emissive, Alpha=KAlpha */
_GenerateRootShader(out, "RetroShader", "Diffuse"_kcol, "Emissive"_tex, "Alpha"_kcola); break;
_GenerateRootShader(out, "RetroShader", "Diffuse"_kcol, "Emissive"_tex, "Alpha"_kcola);
break;
case 0x15A00948: /* RetroShader: Diffuse, Emissive, Specular, ExtendedSpecular, Reflection, Alpha=1.0 */
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Emissive"_tex, "Specular"_tex, "ExtendedSpecular"_tex,
"Reflection"_tex);
break;
case 0x15A3E6E5: /* RetroShader: Diffuse, Alpha=KAlpha */
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Alpha"_kcola); break;
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Alpha"_kcola);
break;
case 0x1BEB3E15: /* RetroShader: Diffuse, Alpha=DiffuseAlpha */
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, TexLink("Alpha", 0, true)); break;
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, TexLink("Alpha", 0, true));
break;
case 0x2261E0EB: /* RetroShader: Diffuse, Emissive, Specular, Reflection, Alpha=1.0 */
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Emissive"_tex, "Specular"_tex, "Reflection"_tex); break;
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Emissive"_tex, "Specular"_tex, "Reflection"_tex);
break;
case 0x239C7724: /* RetroDynamicShader: Diffuse*Dynamic, Emissive*Dynamic, Alpha=1.0 */
_GenerateRootShader(out, "RetroDynamicShader", "Diffuse"_tex, "Emissive"_tex); break;
_GenerateRootShader(out, "RetroDynamicShader", "Diffuse"_tex, "Emissive"_tex);
break;
case 0x240C4C84: /* RetroShader: Lightmap, KColorDiffuse, Specular, Reflection, Alpha=KAlpha */
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_kcol, "Specular"_tex, "Reflection"_tex, "Alpha"_kcola); break;
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_kcol, "Specular"_tex, "Reflection"_tex,
"Alpha"_kcola);
break;
case 0x2523A379: /* RetroDynamicShader: Emissive*Dynamic, Specular, Reflection, Alpha=1.0 */
_GenerateRootShader(out, "RetroDynamicShader", "Emissive"_tex, "Specular"_tex, "Reflection"_tex); break;
_GenerateRootShader(out, "RetroDynamicShader", "Emissive"_tex, "Specular"_tex, "Reflection"_tex);
break;
case 0x25E85017: /* RetroShader: Lightmap, KColorDiffuse, Alpha=KAlpha */
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_kcol, "Alpha"_kcola); break;
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_kcol, "Alpha"_kcola);
break;
case 0x27FD5C6C: /* RetroShader: ObjLightmap, Diffuse, Specular, Reflection, Alpha=DiffuseAlpha */
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, "Specular"_tex, "Reflection"_tex, TexLink("Alpha", 1, true)); break;
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, "Specular"_tex, "Reflection"_tex,
TexLink("Alpha", 1, true));
break;
case 0x2AD9F535: /* RetroShader: Emissive, Reflection, Alpha=1.0 */
_GenerateRootShader(out, "RetroShader", "Emissive"_tex, WhiteColorLink("Specular"), "Reflection"_tex); break;
_GenerateRootShader(out, "RetroShader", "Emissive"_tex, WhiteColorLink("Specular"), "Reflection"_tex);
break;
case 0x2C9F5104: /* RetroShader: Diffuse, Specular, Reflection, Alpha=KAlpha */
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Specular"_tex, "Reflection"_tex, "Alpha"_kcola); break;
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Specular"_tex, "Reflection"_tex, "Alpha"_kcola);
break;
case 0x2D059429: /* RetroShader: Diffuse, Emissive, ExtendedSpecular, Reflection, Alpha=1.0 */
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Emissive"_tex, ExtendedSpecularLink(), "Reflection"_tex); break;
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Emissive"_tex, ExtendedSpecularLink(), "Reflection"_tex);
break;
case 0x30AC64BB: /* RetroShader: Diffuse, Specular, Reflection, Alpha=KAlpha, IndirectTex */
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Specular"_tex, "Reflection"_tex, "IndirectTex"_tex, "Alpha"_kcola); break;
case 0x39BC4809: /* RetroDynamicShader: ObjLightmap*Dynamic, Diffuse*Dynamic, Emissive*Dynamic, Specular, Reflection, Alpha=1.0 */
_GenerateRootShader(out, "RetroDynamicShader", "Lightmap"_tex, "Diffuse"_tex, "Emissive"_tex, "Specular"_tex, "Reflection"_tex); break;
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Specular"_tex, "Reflection"_tex, "IndirectTex"_tex,
"Alpha"_kcola);
break;
case 0x39BC4809: /* RetroDynamicShader: ObjLightmap*Dynamic, Diffuse*Dynamic, Emissive*Dynamic, Specular, Reflection,
Alpha=1.0 */
_GenerateRootShader(out, "RetroDynamicShader", "Lightmap"_tex, "Diffuse"_tex, "Emissive"_tex, "Specular"_tex,
"Reflection"_tex);
break;
case 0x3BF97299: /* RetroShader: Lightmap, Diffuse, Specular, Reflection, Alpha=KAlpha, IndirectTex */
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, "Specular"_tex, "Reflection"_tex, "IndirectTex"_tex, "Alpha"_kcola); break;
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, "Specular"_tex, "Reflection"_tex,
"IndirectTex"_tex, "Alpha"_kcola);
break;
case 0x4184FBCA: /* RetroShader: Lightmap, Diffuse, Emissive, DiffuseAlpha */
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, "Emissive"_tex, TexLink("Alpha", 1, true));
break;
case 0x47ECF3ED: /* RetroShader: Diffuse, Specular, Reflection, Emissive, Alpha=1.0 */
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Specular"_tex, "Reflection"_tex, "Emissive"_tex); break;
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Specular"_tex, "Reflection"_tex, "Emissive"_tex);
break;
case 0x4BBDFFA6: /* RetroShader: Diffuse, Emissive, Alpha=1.0 */
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Emissive"_tex); break;
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Emissive"_tex);
break;
case 0x4D4127A3: /* RetroShader: Lightmap, Diffuse, Specular, Reflection, Alpha=DiffuseAlpha */
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, "Specular"_tex, "Reflection"_tex, TexLink("Alpha", 1, true)); break;
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, "Specular"_tex, "Reflection"_tex,
TexLink("Alpha", 1, true));
break;
case 0x54A92F25: /* RetroShader: ObjLightmap, KColorDiffuse, Alpha=KAlpha */
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_kcol, "Alpha"_kcola); break;
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_kcol, "Alpha"_kcola);
break;
case 0x58BAA415: /* RetroShader: Lightmap, Diffuse, Emissive, Alpha=1.0 */
// TODO: Last stage assigns into unused reg2, perhaps for runtime material mod?
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, "Emissive"_tex);
break;
case 0x54C6204C:
_GenerateRootShader(out, "RetroShader"); break;
_GenerateRootShader(out, "RetroShader");
break;
case 0x5A62D5F0: /* RetroShader: Lightmap, Diffuse, UnusedExtendedSpecular?, Alpha=DiffuseAlpha */
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, TexLink("Alpha", 1, true)); break;
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, TexLink("Alpha", 1, true));
break;
case 0x5CB59821: /* RetroShader: Diffuse, UnusedSpecular?, Alpha=KAlpha */
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Alpha"_kcola); break;
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Alpha"_kcola);
break;
case 0x5D0F0069: /* RetroShader: Diffuse, Emissive, Alpha=DiffuseAlpha */
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Emissive"_tex, TexLink("Alpha", 0, true)); break;
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Emissive"_tex, TexLink("Alpha", 0, true));
break;
case 0x5D80E53C: /* RetroShader: Emissive, Specular, Reflection, Alpha=1.0 */
_GenerateRootShader(out, "RetroShader", "Emissive"_tex, "Specular"_tex, "Reflection"_tex); break;
_GenerateRootShader(out, "RetroShader", "Emissive"_tex, "Specular"_tex, "Reflection"_tex);
break;
case 0x5F0AB0E9: /* RetroShader: Lightmap, Diffuse, UnusedSpecular?, Alpha=DiffuseAlpha */
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, TexLink("Alpha", 1, true)); break;
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, TexLink("Alpha", 1, true));
break;
case 0x5F189425: /* RetroShader: Lightmap, Diffuse, UnusedSpecular?, Alpha=KAlpha */
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, "Alpha"_kcola); break;
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, "Alpha"_kcola);
break;
case 0x6601D113: /* RetroShader: Emissive, Alpha=1.0 */
_GenerateRootShader(out, "RetroShader", "Emissive"_tex); break;
_GenerateRootShader(out, "RetroShader", "Emissive"_tex);
break;
case 0x694287FA: /* RetroShader: Diffuse, Emissive, Reflection, Alpha=1.0 */
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Emissive"_tex, WhiteColorLink("Specular"), "Reflection"_tex); break;
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Emissive"_tex, WhiteColorLink("Specular"),
"Reflection"_tex);
break;
case 0x6D98D689: /* RetroDynamicAlphaShader: Diffuse*Dynamic, Specular, Reflection, Alpha=KAlpha*Dynamic */
_GenerateRootShader(out, "RetroDynamicAlphaShader", "Diffuse"_tex, "Specular"_tex, "Reflection"_tex, "Alpha"_kcola); break;
_GenerateRootShader(out, "RetroDynamicAlphaShader", "Diffuse"_tex, "Specular"_tex, "Reflection"_tex, "Alpha"_kcola);
break;
case 0x7252CB90: /* RetroShader: Lightmap, Diffuse, Alpha=KAlpha */
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, "Alpha"_kcola); break;
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, "Alpha"_kcola);
break;
case 0x72BEDDAC: /* RetroShader: DiffuseMod, Diffuse, Emissive, Specular, Reflection Alpha=1.0 */
_GenerateRootShader(out, "RetroShader", "DiffuseMod"_tex, "Diffuse"_tex, "Emissive"_tex, "Specular"_tex,
"Reflection"_tex);
break;
case 0x76BEA57E: /* RetroShader: Lightmap, Diffuse, Emissive, Specular, Reflection, Alpha=1.0, IndirectTex */
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, "Emissive"_tex, "Specular"_tex, "Reflection"_tex, "IndirectTex"_tex); break;
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, "Emissive"_tex, "Specular"_tex,
"Reflection"_tex, "IndirectTex"_tex);
break;
case 0x7D6A4487: /* RetroShader: Diffuse, Specular, Reflection, Alpha=DiffuseAlpha */
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Specular"_tex, "Reflection"_tex, TexLink("Alpha", 0, true)); break;
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Specular"_tex, "Reflection"_tex, TexLink("Alpha", 0, true));
break;
case 0x81106196: /* RetroDynamicShader: Emissive, Alpha=1.0 */
_GenerateRootShader(out, "RetroDynamicShader", "Emissive"_tex);
break;
case 0x84319328: /* RetroShader: Reflection, UnusedSpecular?, Alpha=1.0 */
_GenerateRootShader(out, "RetroShader", WhiteColorLink("Specular"), "Reflection"_tex); break;
_GenerateRootShader(out, "RetroShader", WhiteColorLink("Specular"), "Reflection"_tex);
break;
case 0x846215DA: /* RetroShader: Diffuse, Specular, Reflection, Alpha=DiffuseAlpha, IndirectTex */
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Specular"_tex, "Reflection"_tex, "IndirectTex"_tex, TexLink("Alpha", 0, true)); break;
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Specular"_tex, "Reflection"_tex, "IndirectTex"_tex,
TexLink("Alpha", 0, true));
break;
case 0x8C562AB1: /* RetroShader: Diffuse, Emissive, Alpha=1.0 */
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Emissive"_tex);
break;
case 0x8E916C01: /* RetroShader: NULL, all inputs 0 */
_GenerateRootShader(out, "RetroShader"); break;
_GenerateRootShader(out, "RetroShader");
break;
case 0x957709F8: /* RetroShader: Emissive, Alpha=1.0 */
_GenerateRootShader(out, "RetroShader", "Emissive"_tex); break;
_GenerateRootShader(out, "RetroShader", "Emissive"_tex);
break;
case 0x96ABB2D3: /* RetroShader: Lightmap, Diffuse, Alpha=DiffuseAlpha */
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, TexLink("Alpha", 1, true)); break;
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, TexLink("Alpha", 1, true));
break;
case 0x985A0B67: /* RetroShader: Diffuse, UnusedSpecular?, Alpha=DiffuseAlpha */
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, TexLink("Alpha", 0, true)); break;
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, TexLink("Alpha", 0, true));
break;
case 0x9B4453A2: /* RetroShader: Diffuse, Emissive, ExtendedSpecular, Reflection, Alpha=1.0 */
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Emissive"_tex, ExtendedSpecularLink(), "Reflection"_tex); break;
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Emissive"_tex, ExtendedSpecularLink(), "Reflection"_tex);
break;
case 0xA187C630: /* RetroShader: Diffuse, Emissive, UnusedReflection?, Alpha=1.0 */
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Emissive"_tex); break;
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Emissive"_tex);
break;
case 0xB26E9E2E: /* RetroShader: Diffuse, Emissive, Alpha=1.0 */
// TODO: Last two stages assign into unused reg2, perhaps for runtime material mod?
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Emissive"_tex);
break;
case 0xC0E3FF1F: /* RetroShader: KColorDiffuse, Specular, Reflection, Alpha=KAlpha */
_GenerateRootShader(out, "RetroShader", "Diffuse"_kcol, "Specular"_tex, "Reflection"_tex, "Alpha"_kcola);
break;
case 0xC138DCFA: /* RetroShader: Diffuse, Emissive, Alpha=1.0 */
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Emissive"_tex); break;
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Emissive"_tex);
break;
case 0xC3C8B1C8: /* RetroShader: KColorDiffuse, Alpha=KAlpha */
_GenerateRootShader(out, "RetroShader", "Diffuse"_kcol, "Alpha"_kcola); break;
_GenerateRootShader(out, "RetroShader", "Diffuse"_kcol, "Alpha"_kcola);
break;
case 0xC689C8C6: /* RetroShader: Diffuse, ExtendedSpecular, Reflection, Alpha=DiffuseAlpha */
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, ExtendedSpecularLink(), "Reflection"_tex, TexLink("Alpha", 0, true)); break;
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, ExtendedSpecularLink(), "Reflection"_tex,
TexLink("Alpha", 0, true));
break;
case 0xC6B18B28: /* RetroShader: Diffuse, Alpha=DiffuseAlpha */
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, TexLink("Alpha", 0, true)); break;
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, TexLink("Alpha", 0, true));
break;
case 0xCD92D4C5: /* RetroShader: Diffuse, Reflection, Alpha=KAlpha */
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, WhiteColorLink("Specular"), "Reflection"_tex, "Alpha"_kcola); break;
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, WhiteColorLink("Specular"), "Reflection"_tex, "Alpha"_kcola);
break;
case 0xCE06F3F2: /* RetroShader: Diffuse, Alpha */
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, TexLink("Alpha", 1, true));
break;
case 0xD73E7728: /* RetroShader: ObjLightmap, Diffuse, Alpha=DiffuseAlpha */
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, TexLink("Alpha", 1, true)); break;
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, TexLink("Alpha", 1, true));
break;
case 0xDB8F01AD: /* RetroDynamicShader: Diffuse*Dynamic, Emissive*Dynamic, UnusedSpecular?, Alpha=1.0 */
_GenerateRootShader(out, "RetroDynamicShader", "Diffuse"_tex, "Emissive"_tex); break;
_GenerateRootShader(out, "RetroDynamicShader", "Diffuse"_tex, "Emissive"_tex);
break;
case 0xE64D1085: /* RetroShader: Lightmap, Diffuse, Emissive, Reflection, Alpha=DiffuseAlpha */
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, "Emissive"_tex, "Reflection"_tex,
TexLink("Alpha", 1, true));
break;
case 0xE6784B10: /* RetroShader: Lightmap, Diffuse, Specular, Reflection, Alpha=DiffuseAlpha, IndirectTex */
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, "Specular"_tex, "Reflection"_tex, "IndirectTex"_tex, TexLink("Alpha", 1, true)); break;
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, "Specular"_tex, "Reflection"_tex,
"IndirectTex"_tex, TexLink("Alpha", 1, true));
break;
case 0xE68FF182: /* RetroShader: Diffuse, Emissive, Specular, Reflection, Alpha=1.0 */
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Emissive"_tex, "Specular"_tex, "Reflection"_tex); break;
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, "Emissive"_tex, "Specular"_tex, "Reflection"_tex);
break;
case 0xE92F1340: /* RetroShader: Diffuse, Alpha=DiffuseAlpha*AlphaMod */
_GenerateRootShader(out, "RetroShader", "Diffuse"_tex, TexLink("Alpha", 0, true), TexLink("AlphaMod", 1, true));
break;
case 0xEB4645CF: /* RetroDynamicAlphaShader: Diffuse*Dynamic, Alpha=DiffuseAlpha*Dynamic */
_GenerateRootShader(out, "RetroDynamicAlphaShader", "Diffuse"_tex, TexLink("Alpha", 0, true)); break;
_GenerateRootShader(out, "RetroDynamicAlphaShader", "Diffuse"_tex, TexLink("Alpha", 0, true));
break;
case 0xECEF8D1F: /* RetroDynamicShader: Diffuse*Dynamic, Emissive*Dynamic, Specular, Reflection, Alpha=1.0 */
_GenerateRootShader(out, "RetroDynamicShader", "Diffuse"_tex, "Emissive"_tex, "Specular"_tex, "Reflection"_tex); break;
_GenerateRootShader(out, "RetroDynamicShader", "Diffuse"_tex, "Emissive"_tex, "Specular"_tex, "Reflection"_tex);
break;
case 0xF1C26570: /* RetroShader: Lightmap, Diffuse, Specular, ExtendedSpecular, Reflection, Alpha=DiffuseAlpha */
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, "Specular"_tex, "ExtendedSpecular"_tex, "Reflection"_tex, TexLink("Alpha", 1, true)); break;
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, "Specular"_tex, "ExtendedSpecular"_tex,
"Reflection"_tex, TexLink("Alpha", 1, true));
break;
case 0xF345C16E: /* RetroShader: Emissive, Reflection, Alpha=1.0 */
_GenerateRootShader(out, "RetroShader", "Emissive"_tex, "Reflection"_tex);
break;
case 0xF4DA0A86: /* RetroShader: KColorDiffuse, Emissive, Alpha=KAlpha */
_GenerateRootShader(out, "RetroShader", "Diffuse"_kcol, "Emissive"_tex, "Alpha"_kcola); break;
break;
case 0xF559DB08: /* RetroShader: Lightmap, Diffuse, Emissive, Specular, Reflection, Alpha=1.0 */
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, "Emissive"_tex, "Specular"_tex, "Reflection"_tex); break;
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, "Emissive"_tex, "Specular"_tex,
"Reflection"_tex);
break;
case 0xF9324367: /* RetroShader: Lightmap, Diffuse, Emissive, Alpha=1.0 */
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, "Emissive"_tex); break;
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, "Emissive"_tex);
break;
case 0xFC2761B8: /* RetroShader: Lightmap, Diffuse, Alpha=DiffuseAlpha*AlphaMod */
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, TexLink("Alpha", 1, true),
TexLink("AlphaMod", 2, true));
break;
case 0xFD95D7FD: /* RetroShader: ObjLightmap, Diffuse, Alpha=DiffuseAlpha */
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, TexLink("Alpha", 1, true)); break;
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, TexLink("Alpha", 1, true));
break;
case 0xFFF3CEBB: /* RetroShader: Lightmap, Diffuse, Emissive, Alpha */
_GenerateRootShader(out, "RetroShader", "Lightmap"_tex, "Diffuse"_tex, "Emissive"_tex, TexLink("Alpha", 3, true));
break;
default:
_DescribeTEV(material);
Log.report(logvisor::Fatal, fmt("Unable to resolve shader hash {:08X}\n"), hash); break;
Log.report(logvisor::Fatal, fmt("Unable to resolve shader hash {:08X}\n"), hash);
break;
}
/* Has Lightmap? */
@ -682,8 +806,7 @@ void MaterialSet::ConstructMaterial(Stream& out, const MaterialSet::Material& ma
_ConstructMaterial(out, material, groupIdx, matIdx);
}
MaterialSet::Material::Material(const hecl::blender::Material& mat,
std::vector<hecl::ProjectPath>& texPathsOut,
MaterialSet::Material::Material(const hecl::blender::Material& mat, std::vector<hecl::ProjectPath>& texPathsOut,
int colorCount, bool lightmapUVs, bool matrixSkinning) {
/* TODO: Rewrite for new shader rep */
XXH32_state_t xxHash;
@ -1090,7 +1213,6 @@ void HMDLMaterialSet::Material::PASS::Enumerate(typename Op::StreamT& s) {
AT_SPECIALIZE_DNA(HMDLMaterialSet::Material::PASS)
std::string_view HMDLMaterialSet::Material::PASS::DNAType() {
return "DataSpec::DNAMP1::HMDLMaterialSet::Material::PASS"sv;
}

View File

@ -11,7 +11,6 @@ make_dnalist(PAK
CINF
CSKR
EVNT
PATH
CMDLMaterials
MREA
DeafBabe
@ -50,7 +49,7 @@ set(DNAMP1_SOURCES
ANIM.cpp
CINF.cpp
EVNT.cpp
PATH.cpp
PATH.hpp
CMDL.hpp CMDL.cpp
CMDLMaterials.cpp
DCLN.cpp

View File

@ -1,79 +1,6 @@
#pragma once
#include "DataSpec/DNACommon/DNACommon.hpp"
#include "DataSpec/DNACommon/PAK.hpp"
#include "DNAMP1.hpp"
#include "DataSpec/DNACommon/PATH.hpp"
namespace DataSpec::DNAMP1 {
struct PATH : BigDNA {
using PathMesh = hecl::blender::PathMesh;
AT_DECL_DNA
Value<atUint32> version;
struct Node : BigDNA {
AT_DECL_DNA
Value<atVec3f> position;
Value<atVec3f> normal;
};
Value<atUint32> nodeCount;
Vector<Node, AT_DNA_COUNT(nodeCount)> nodes;
struct Link : BigDNA {
AT_DECL_DNA
Value<atUint32> nodeIdx;
Value<atUint32> regionIdx;
Value<float> width2d;
Value<float> oneOverWidth2d;
};
Value<atUint32> linkCount;
Vector<Link, AT_DNA_COUNT(linkCount)> links;
struct Region : BigDNA {
AT_DECL_DNA
Value<atUint32> nodeCount;
Value<atUint32> nodeStart;
Value<atUint32> linkCount;
Value<atUint32> linkStart;
Value<atUint16> meshIndexMask;
Value<atUint16> meshTypeMask;
Value<float> height;
Value<atVec3f> normal;
Value<atUint32> regionIdx;
Value<atVec3f> centroid;
Value<atVec3f> aabb[2];
Value<atUint32> regionIdxPtr;
};
Value<atUint32> regionCount;
Vector<Region, AT_DNA_COUNT(regionCount)> regions;
Vector<atUint32, AT_DNA_COUNT((((regionCount * (regionCount - 1)) / 2) + 31) / 32)> bitmap1;
Vector<atUint32, AT_DNA_COUNT(bitmap1.size())> bitmap2;
Vector<atUint32, AT_DNA_COUNT(((((regionCount * regionCount) + 31) / 32) - bitmap1.size()) * 2)> bitmap3;
Value<atUint32> octreeRegionLookupCount;
Vector<atUint32, AT_DNA_COUNT(octreeRegionLookupCount)> octreeRegionLookup;
struct OctreeNode : BigDNA {
AT_DECL_DNA
Value<atUint32> isLeaf;
Value<atVec3f> aabb[2];
Value<atVec3f> centroid;
Value<atUint32> children[8];
Value<atUint32> regionCount;
Value<atUint32> regionStart;
};
Value<atUint32> octreeNodeCount;
Vector<OctreeNode, AT_DNA_COUNT(octreeNodeCount)> octree;
void sendToBlender(hecl::blender::Connection& conn, std::string_view entryName, const zeus::CMatrix4f* xf,
const std::string& areaPath);
static bool Extract(const SpecBase& dataSpec, PAKEntryReadStream& rs, const hecl::ProjectPath& outPath,
PAKRouter<PAKBridge>& pakRouter, const PAK::Entry& entry, bool force, hecl::blender::Token& btok,
std::function<void(const hecl::SystemChar*)> fileChanged);
static bool Cook(const hecl::ProjectPath& outPath, const hecl::ProjectPath& inPath,
const PathMesh& mesh, hecl::blender::Token& btok);
};
using PATH = DNAPATH::PATH<PAKBridge>;
} // namespace DataSpec::DNAMP1

View File

@ -1,5 +1,6 @@
#include "CINF.hpp"
#include "hecl/Blender/Connection.hpp"
#include "DataSpec/DNAMP3/DNAMP3.hpp"
namespace DataSpec::DNAMP2 {
@ -41,7 +42,8 @@ void CINF::sendVertexGroupsToBlender(hecl::blender::PyOutStream& os) const {
}
}
void CINF::sendCINFToBlender(hecl::blender::PyOutStream& os, const UniqueID32& cinfId) const {
template <class PAKBridge>
void CINF::sendCINFToBlender(hecl::blender::PyOutStream& os, const typename PAKBridge::PAKType::IDType& cinfId) const {
DNAANIM::RigInverter<CINF> inverter(*this);
os.format(fmt(
@ -66,9 +68,18 @@ void CINF::sendCINFToBlender(hecl::blender::PyOutStream& os, const UniqueID32& c
tailF[2], bone.m_origBone.id);
}
if constexpr (std::is_same_v<PAKBridge, DNAMP3::PAKBridge>) {
if (bones.size()) {
atUint32 nullId = bones[0].parentId;
for (const Bone& bone : bones)
if (bone.parentId != nullId)
os.format(fmt("arm_bone_table[{}].parent = arm_bone_table[{}]\n"), bone.id, bone.parentId);
}
} else {
for (const Bone& bone : bones)
if (bone.parentId != 97)
os.format(fmt("arm_bone_table[{}].parent = arm_bone_table[{}]\n"), bone.id, bone.parentId);
}
os << "bpy.ops.object.mode_set(mode='OBJECT')\n";
@ -76,7 +87,140 @@ void CINF::sendCINFToBlender(hecl::blender::PyOutStream& os, const UniqueID32& c
os.format(fmt("arm_obj.pose.bones['{}'].rotation_mode = 'QUATERNION'\n"),
*getBoneNameFromId(bone.m_origBone.id));
}
template void CINF::sendCINFToBlender<PAKBridge>(hecl::blender::PyOutStream& os, const UniqueID32& cinfId) const;
template void CINF::sendCINFToBlender<DNAMP3::PAKBridge>(hecl::blender::PyOutStream& os,
const UniqueID64& cinfId) const;
std::string CINF::GetCINFArmatureName(const UniqueID32& cinfId) { return fmt::format(fmt("CINF_{}"), cinfId); }
template <class UniqueID>
std::string CINF::GetCINFArmatureName(const UniqueID& cinfId) { return fmt::format(fmt("CINF_{}"), cinfId); }
template std::string CINF::GetCINFArmatureName(const UniqueID32& cinfId);
template std::string CINF::GetCINFArmatureName(const UniqueID64& cinfId);
int CINF::RecursiveAddArmatureBone(const Armature& armature, const BlenderBone* bone, int parent, int& curId,
std::unordered_map<std::string, atInt32>& idMap,
std::map<std::string, int>& nameMap) {
int selId;
auto search = idMap.find(bone->name);
if (search == idMap.end()) {
selId = curId++;
idMap.emplace(std::make_pair(bone->name, selId));
} else
selId = search->second;
bones.emplace_back();
Bone& boneOut = bones.back();
nameMap[bone->name] = selId;
boneOut.id = selId;
boneOut.parentId = parent;
boneOut.origin = bone->origin;
boneOut.linkedCount = bone->children.size() + 1;
boneOut.linked.reserve(boneOut.linkedCount);
const BlenderBone* child;
boneOut.linked.push_back(parent);
for (size_t i = 0; (child = armature.getChild(bone, i)); ++i)
boneOut.linked.push_back(RecursiveAddArmatureBone(armature, child, boneOut.id, curId, idMap, nameMap));
return boneOut.id;
}
CINF::CINF(const Armature& armature, std::unordered_map<std::string, atInt32>& idMap) {
idMap.reserve(armature.bones.size());
bones.reserve(armature.bones.size());
std::map<std::string, int> nameMap;
const BlenderBone* bone = armature.getRoot();
if (bone) {
if (bone->children.size()) {
int curId = 4;
const BlenderBone* child;
for (size_t i = 0; (child = armature.getChild(bone, i)); ++i)
RecursiveAddArmatureBone(armature, child, 3, curId, idMap, nameMap);
}
bones.emplace_back();
Bone& boneOut = bones.back();
nameMap[bone->name] = 3;
boneOut.id = 3;
boneOut.parentId = 2;
boneOut.origin = bone->origin;
idMap.emplace(std::make_pair(bone->name, 3));
if (bone->children.size()) {
boneOut.linkedCount = 2;
boneOut.linked = {2, 4};
} else {
boneOut.linkedCount = 1;
boneOut.linked = {2};
}
}
boneCount = bones.size();
names.reserve(nameMap.size());
nameCount = nameMap.size();
for (const auto& name : nameMap) {
names.emplace_back();
Name& nameOut = names.back();
nameOut.name = name.first;
nameOut.boneId = name.second;
}
boneIdCount = boneCount;
boneIds.reserve(boneIdCount);
for (auto it = bones.crbegin(); it != bones.crend(); ++it)
boneIds.push_back(it->id);
}
template <class PAKBridge>
bool CINF::Extract(const SpecBase& dataSpec, PAKEntryReadStream& rs, const hecl::ProjectPath& outPath,
PAKRouter<PAKBridge>& pakRouter, const typename PAKBridge::PAKType::Entry& entry, bool force,
hecl::blender::Token& btok, std::function<void(const hecl::SystemChar*)> fileChanged) {
if (!force && outPath.isFile())
return true;
auto& conn = btok.getBlenderConnection();
if (!conn.createBlend(outPath, hecl::blender::BlendType::Armature))
return false;
auto os = conn.beginPythonOut(true);
os.format(fmt("import bpy\n"
"from mathutils import Vector\n"
"bpy.context.scene.name = 'CINF_{}'\n"
"bpy.context.scene.hecl_arm_obj = bpy.context.scene.name\n"
"\n"
"# Clear Scene\n"
"if len(bpy.data.collections):\n"
" bpy.data.collections.remove(bpy.data.collections[0])\n"
"\n"), entry.id);
CINF cinf;
cinf.read(rs);
cinf.sendCINFToBlender<PAKBridge>(os, entry.id);
os.centerView();
os.close();
return conn.saveBlend();
}
template bool CINF::Extract(const SpecBase& dataSpec, PAKEntryReadStream& rs, const hecl::ProjectPath& outPath,
PAKRouter<PAKBridge>& pakRouter, const typename PAKBridge::PAKType::Entry& entry,
bool force, hecl::blender::Token& btok,
std::function<void(const hecl::SystemChar*)> fileChanged);
template bool CINF::Extract(const SpecBase& dataSpec, PAKEntryReadStream& rs, const hecl::ProjectPath& outPath,
PAKRouter<DNAMP3::PAKBridge>& pakRouter,
const typename DNAMP3::PAKBridge::PAKType::Entry& entry, bool force,
hecl::blender::Token& btok, std::function<void(const hecl::SystemChar*)> fileChanged);
bool CINF::Cook(const hecl::ProjectPath& outPath, const hecl::ProjectPath& inPath,
const hecl::blender::Armature& armature) {
std::unordered_map<std::string, atInt32> boneIdMap;
CINF cinf(armature, boneIdMap);
/* Write out CINF resource */
athena::io::TransactionalFileWriter w(outPath.getAbsolutePath());
cinf.write(w);
return true;
}
} // namespace DataSpec::DNAMP2

View File

@ -2,6 +2,7 @@
#include "DataSpec/DNACommon/DNACommon.hpp"
#include "DataSpec/DNACommon/RigInverter.hpp"
#include "DNAMP2.hpp"
namespace DataSpec::DNAMP2 {
@ -35,8 +36,27 @@ struct CINF : BigDNA {
atUint32 getBoneIdxFromId(atUint32 id) const;
const std::string* getBoneNameFromId(atUint32 id) const;
void sendVertexGroupsToBlender(hecl::blender::PyOutStream& os) const;
void sendCINFToBlender(hecl::blender::PyOutStream& os, const UniqueID32& cinfId) const;
static std::string GetCINFArmatureName(const UniqueID32& cinfId);
template <class PAKBridge>
void sendCINFToBlender(hecl::blender::PyOutStream& os, const typename PAKBridge::PAKType::IDType& cinfId) const;
template <class UniqueID>
static std::string GetCINFArmatureName(const UniqueID& cinfId);
CINF() = default;
using Armature = hecl::blender::Armature;
using BlenderBone = hecl::blender::Bone;
int RecursiveAddArmatureBone(const Armature& armature, const BlenderBone* bone, int parent, int& curId,
std::unordered_map<std::string, atInt32>& idMap, std::map<std::string, int>& nameMap);
CINF(const Armature& armature, std::unordered_map<std::string, atInt32>& idMap);
template <class PAKBridge>
static bool Extract(const SpecBase& dataSpec, PAKEntryReadStream& rs, const hecl::ProjectPath& outPath,
PAKRouter<PAKBridge>& pakRouter, const typename PAKBridge::PAKType::Entry& entry, bool force,
hecl::blender::Token& btok, std::function<void(const hecl::SystemChar*)> fileChanged);
static bool Cook(const hecl::ProjectPath& outPath, const hecl::ProjectPath& inPath,
const hecl::blender::Armature& armature);
};
} // namespace DataSpec::DNAMP2

View File

@ -23,6 +23,7 @@ set(DNAMP2_SOURCES
MREA.cpp
MAPA.hpp
MAPU.hpp
PATH.hpp
AFSM.hpp
STRG.hpp STRG.cpp)

View File

@ -4,9 +4,11 @@
#include "MLVL.hpp"
#include "CMDL.hpp"
#include "ANCS.hpp"
#include "CINF.hpp"
#include "MREA.hpp"
#include "MAPA.hpp"
#include "MAPU.hpp"
#include "PATH.hpp"
#include "AFSM.hpp"
#include "SAVW.hpp"
#include "AGSC.hpp"
@ -25,7 +27,9 @@ logvisor::Module Log("urde::DNAMP2");
static bool GetNoShare(std::string_view name) {
std::string lowerName(name);
std::transform(lowerName.begin(), lowerName.end(), lowerName.begin(), tolower);
if (!lowerName.compare(0, 7, "metroid"))
if (lowerName.compare(0, 7, "metroid") == 0)
return false;
if (lowerName.compare(0, 8, "frontend") == 0)
return false;
return true;
}
@ -170,6 +174,18 @@ void PAKBridge::addCMDLRigPairs(PAKRouter<PAKBridge>& pakRouter, CharacterAssoci
}
}
void PAKBridge::addPATHToMREA(PAKRouter<PAKBridge>& pakRouter,
std::unordered_map<UniqueID32, UniqueID32>& pathToMrea) const {
for (const auto& [id, entry] : m_pak.m_entries) {
if (entry.type == FOURCC('MREA')) {
PAKEntryReadStream rs = entry.beginReadStream(m_node);
UniqueID32 pathID = MREA::GetPATHId(rs);
if (pathID.isValid())
pathToMrea[pathID] = id;
}
}
}
static const atVec4f BottomRow = {{0.f, 0.f, 0.f, 1.f}};
void PAKBridge::addMAPATransforms(PAKRouter<PAKBridge>& pakRouter,
@ -189,6 +205,16 @@ void PAKBridge::addMAPATransforms(PAKRouter<PAKBridge>& pakRouter,
fmt::format(fmt(_SYS_STR("!name_{}.yaml")), mlvl.worldNameId));
for (const MLVL::Area& area : mlvl.areas) {
{
/* Get PATH transform */
const nod::Node* areaNode;
const PAK::Entry* areaEntry = pakRouter.lookupEntry(area.areaMREAId, &areaNode);
PAKEntryReadStream rs = areaEntry->beginReadStream(*areaNode);
UniqueID32 pathId = MREA::GetPATHId(rs);
if (pathId.isValid())
addTo[pathId] = zeus::CMatrix4f(area.transformMtx[0], area.transformMtx[1], area.transformMtx[2], BottomRow)
.transposed();
}
hecl::ProjectPath areaDirPath = pakRouter.getWorking(area.areaMREAId).getParentPath();
if (area.areaNameId.isValid())
pathOverrides[area.areaNameId] = hecl::ProjectPath(areaDirPath,
@ -234,6 +260,8 @@ ResExtractor<PAKBridge> PAKBridge::LookupExtractor(const nod::Node& pakNode, con
return {SAVWCommon::ExtractSAVW<SAVW>, {_SYS_STR(".yaml")}};
case SBIG('CMDL'):
return {CMDL::Extract, {_SYS_STR(".blend")}, 1};
case SBIG('CINF'):
return {CINF::Extract<PAKBridge>, {_SYS_STR(".blend")}, 1};
case SBIG('ANCS'):
return {ANCS::Extract, {_SYS_STR(".yaml"), _SYS_STR(".blend")}, 2};
case SBIG('MLVL'):
@ -244,6 +272,8 @@ ResExtractor<PAKBridge> PAKBridge::LookupExtractor(const nod::Node& pakNode, con
return {MAPA::Extract, {_SYS_STR(".blend")}, 4};
case SBIG('MAPU'):
return {MAPU::Extract, {_SYS_STR(".blend")}, 5};
case SBIG('PATH'):
return {PATH::Extract, {_SYS_STR(".blend")}, 5};
case SBIG('FSM2'):
return {DNAFSM2::ExtractFSM2<UniqueID32>, {_SYS_STR(".yaml")}};
case SBIG('FONT'):

View File

@ -31,6 +31,9 @@ public:
void addCMDLRigPairs(PAKRouter<PAKBridge>& pakRouter, CharacterAssociations<UniqueID32>& charAssoc) const;
void addPATHToMREA(PAKRouter<PAKBridge>& pakRouter,
std::unordered_map<UniqueID32, UniqueID32>& pathToMrea) const;
void addMAPATransforms(PAKRouter<PAKBridge>& pakRouter, std::unordered_map<UniqueID32, zeus::CMatrix4f>& addTo,
std::unordered_map<UniqueID32, hecl::ProjectPath>& pathOverrides) const;
};

View File

@ -26,12 +26,15 @@ void DeafBabe::BlenderInit(hecl::blender::PyOutStream& os) {
" 'Rubber':(0.09, 0.02, 0.01)}\n"
"\n"
"# Diffuse Color Maker\n"
"from mathutils import Color\n"
"def make_color(index, mat_type, name):\n"
" new_mat = bpy.data.materials.new(name)\n"
" if mat_type in TYPE_COLORS:\n"
" new_mat.diffuse_color = TYPE_COLORS[mat_type]\n"
" new_mat.diffuse_color = TYPE_COLORS[mat_type] + (1.0,)\n"
" else:\n"
" new_mat.diffuse_color.hsv = ((index / 6.0) % 1.0, 1.0-((index // 6) / 6.0), 1)\n"
" col = Color()\n"
" col.hsv = ((index / 6.0) % 1.0, 1.0-((index // 6) / 6.0), 1)\n"
" new_mat.diffuse_color = tuple(col) + (1.0,)\n"
" return new_mat\n"
"\n"
"bpy.types.Material.retro_unknown = bpy.props.BoolProperty(description='Retro: Unknown (U)')\n"

View File

@ -68,8 +68,7 @@ MREA::StreamReader::StreamReader(athena::io::IStreamReader& source, atUint32 blk
, m_blkCount(blkCount) {
m_blockInfos.reserve(blkCount);
for (atUint32 i = 0; i < blkCount; ++i) {
m_blockInfos.emplace_back();
BlockInfo& info = m_blockInfos.back();
BlockInfo& info = m_blockInfos.emplace_back();
info.read(source);
m_totalDecompLen += info.decompSize;
}
@ -98,11 +97,11 @@ void MREA::StreamReader::seek(atInt64 diff, athena::SeekOrigin whence) {
if (newAccum > target)
break;
dAccum = newAccum;
++bIdx;
if (info.compSize)
cAccum += ROUND_UP_32(info.compSize);
else
cAccum += info.decompSize;
++bIdx;
}
/* Seek source if needed */
@ -116,6 +115,41 @@ void MREA::StreamReader::seek(atInt64 diff, athena::SeekOrigin whence) {
m_posInBlk = target - dAccum;
}
void MREA::StreamReader::seekToSection(atUint32 sec, const std::vector<atUint32>& secSizes) {
/* Determine which block contains section */
atUint32 sAccum = 0;
atUint32 dAccum = 0;
atUint32 cAccum = 0;
atUint32 bIdx = 0;
for (BlockInfo& info : m_blockInfos) {
atUint32 newSAccum = sAccum + info.secCount;
if (newSAccum > sec)
break;
sAccum = newSAccum;
dAccum += info.decompSize;
if (info.compSize)
cAccum += ROUND_UP_32(info.compSize);
else
cAccum += info.decompSize;
++bIdx;
}
/* Seek source if needed */
if (bIdx != m_nextBlk - 1) {
m_source.seek(m_blkBase + cAccum, athena::SeekOrigin::Begin);
m_nextBlk = bIdx;
nextBlock();
}
/* Seek within block */
atUint32 target = dAccum;
while (sAccum != sec)
target += secSizes[sAccum++];
m_pos = target;
m_posInBlk = target - dAccum;
}
atUint64 MREA::StreamReader::readUBytesToBuf(void* buf, atUint64 len) {
atUint8* bufCur = reinterpret_cast<atUint8*>(buf);
atUint64 rem = len;
@ -296,5 +330,19 @@ bool MREA::Extract(const SpecBase& dataSpec, PAKEntryReadStream& rs, const hecl:
return conn.saveBlend();
}
UniqueID32 MREA::GetPATHId(PAKEntryReadStream& rs) {
/* Do extract */
Header head;
head.read(rs);
rs.seekAlign32();
/* MREA decompression stream */
StreamReader drs(rs, head.compressedBlockCount);
/* Skip to PATH */
drs.seekToSection(head.pathSecIdx, head.secSizes);
return {drs};
}
} // namespace DNAMP2
} // namespace DataSpec

View File

@ -43,6 +43,7 @@ struct MREA {
public:
StreamReader(athena::io::IStreamReader& source, atUint32 blkCount);
void seek(atInt64 diff, athena::SeekOrigin whence) override;
void seekToSection(atUint32 sec, const std::vector<atUint32>& secSizes);
atUint64 position() const override { return m_pos; }
atUint64 length() const override { return m_totalDecompLen; }
atUint64 readUBytesToBuf(void* buf, atUint64 len) override;
@ -118,6 +119,8 @@ struct MREA {
Value<atVec3f> aabb[2];
};
static UniqueID32 GetPATHId(PAKEntryReadStream& rs);
static bool Extract(const SpecBase& dataSpec, PAKEntryReadStream& rs, const hecl::ProjectPath& outPath,
PAKRouter<PAKBridge>& pakRouter, const DNAMP2::PAK::Entry& entry, bool,
hecl::blender::Token& btok, std::function<void(const hecl::SystemChar*)>);

6
DataSpec/DNAMP2/PATH.hpp Normal file
View File

@ -0,0 +1,6 @@
#pragma once
#include "DataSpec/DNACommon/PATH.hpp"
namespace DataSpec::DNAMP2 {
using PATH = DNAPATH::PATH<PAKBridge>;
} // namespace DataSpec::DNAMP2

View File

@ -1,48 +0,0 @@
#include "CINF.hpp"
#include "hecl/Blender/Connection.hpp"
namespace DataSpec::DNAMP3 {
void CINF::sendCINFToBlender(hecl::blender::PyOutStream& os, const UniqueID64& cinfId) const {
DNAANIM::RigInverter<CINF> inverter(*this);
os.format(fmt("arm = bpy.data.armatures.new('CINF_{}')\n"
"arm_obj = bpy.data.objects.new(arm.name, arm)\n"
"bpy.context.scene.collection.objects.link(arm_obj)\n"
"bpy.context.view_layer.objects.active = arm_obj\n"
"bpy.ops.object.mode_set(mode='EDIT')\n"
"arm_bone_table = {{}}\n"),
cinfId);
for (const DNAANIM::RigInverter<CINF>::Bone& bone : inverter.getBones()) {
zeus::simd_floats originF(bone.m_origBone.origin.simd);
zeus::simd_floats tailF(bone.m_tail.mSimd);
os.format(fmt(
"bone = arm.edit_bones.new('{}')\n"
"bone.head = ({},{},{})\n"
"bone.tail = ({},{},{})\n"
"bone.use_inherit_scale = False\n"
"arm_bone_table[{}] = bone\n"),
*getBoneNameFromId(bone.m_origBone.id), originF[0], originF[1], originF[2], tailF[0], tailF[1],
tailF[2], bone.m_origBone.id);
}
if (bones.size()) {
atUint32 nullId = bones[0].parentId;
for (const Bone& bone : bones)
if (bone.parentId != nullId)
os.format(fmt("arm_bone_table[{}].parent = arm_bone_table[{}]\n"), bone.id, bone.parentId);
}
os << "bpy.ops.object.mode_set(mode='OBJECT')\n";
for (const DNAANIM::RigInverter<CINF>::Bone& bone : inverter.getBones())
os.format(fmt("arm_obj.pose.bones['{}'].rotation_mode = 'QUATERNION'\n"),
*getBoneNameFromId(bone.m_origBone.id));
}
std::string CINF::GetCINFArmatureName(const UniqueID64& cinfId) {
return fmt::format(fmt("CINF_{}"), cinfId);
}
} // namespace DataSpec::DNAMP3

View File

@ -1,14 +1,8 @@
#pragma once
#include "DataSpec/DNACommon/DNACommon.hpp"
#include "../DNAMP2/CINF.hpp"
#include "DataSpec/DNAMP2/CINF.hpp"
namespace DataSpec::DNAMP3 {
struct CINF : DNAMP2::CINF {
Delete expl;
void sendCINFToBlender(hecl::blender::PyOutStream& os, const UniqueID64& cinfId) const;
static std::string GetCINFArmatureName(const UniqueID64& cinfId);
};
using CINF = DNAMP2::CINF;
} // namespace DataSpec::DNAMP3

View File

@ -6,341 +6,291 @@ using Stream = hecl::blender::PyOutStream;
namespace DataSpec::DNAMP3 {
using Material = MaterialSet::Material;
template <>
void MaterialSet::Material::SectionFactory::Enumerate<BigDNA::Read>(typename Read::StreamT& reader) {
DNAFourCC type;
type.read(reader);
switch (ISection::Type(type.toUint32())) {
case ISection::Type::PASS:
section = std::make_unique<SectionPASS>();
section->read(reader);
break;
case ISection::Type::CLR:
section = std::make_unique<SectionCLR>();
section->read(reader);
break;
case ISection::Type::INT:
section = std::make_unique<SectionINT>();
section->read(reader);
break;
default:
section.reset();
break;
}
}
template <>
void MaterialSet::Material::SectionFactory::Enumerate<BigDNA::Write>(typename Write::StreamT& writer) {
if (!section)
return;
writer.writeUBytes((atUint8*)&section->m_type, 4);
section->write(writer);
}
template <>
void MaterialSet::Material::SectionFactory::Enumerate<BigDNA::BinarySize>(typename BinarySize::StreamT& s) {
s += 4;
section->binarySize(s);
}
template <>
void MaterialSet::Material::Enumerate<BigDNA::Read>(typename Read::StreamT& reader) {
header.read(reader);
sections.clear();
do {
sections.emplace_back();
sections.back().read(reader);
} while (sections.back().section);
sections.pop_back();
chunks.clear();
do { chunks.emplace_back().read(reader); } while (!chunks.back().holds_alternative<END>());
chunks.pop_back();
}
template <>
void MaterialSet::Material::Enumerate<BigDNA::Write>(typename Write::StreamT& writer) {
header.write(writer);
for (const SectionFactory& section : sections)
section.write(writer);
writer.writeUBytes((atUint8*)"END ", 4);
for (const auto& chunk : chunks)
chunk.visit([&](auto& arg) { arg.write(writer); });
DNAFourCC(FOURCC('END ')).write(writer);
}
template <>
void MaterialSet::Material::Enumerate<BigDNA::BinarySize>(typename BinarySize::StreamT& s) {
header.binarySize(s);
for (const SectionFactory& section : sections)
section.binarySize(s);
for (const auto& chunk : chunks)
chunk.visit([&](auto& arg) { arg.binarySize(s); });
s += 4;
}
void MaterialSet::RegisterMaterialProps(Stream& out) {
out << "bpy.types.Material.retro_alpha_test = bpy.props.BoolProperty(name='Retro: Punchthrough Alpha')\n"
out << "bpy.types.Material.retro_enable_bloom = bpy.props.BoolProperty(name='Retro: Enable Bloom')\n"
"bpy.types.Material.retro_force_lighting_stage = bpy.props.BoolProperty(name='Retro: Force Lighting Stage')\n"
"bpy.types.Material.retro_pre_inca_transparency = bpy.props.BoolProperty(name='Retro: Pre-INCA Transparency')\n"
"bpy.types.Material.retro_alpha_test = bpy.props.BoolProperty(name='Retro: Alpha Test')\n"
"bpy.types.Material.retro_shadow_occluder = bpy.props.BoolProperty(name='Retro: Shadow Occluder')\n"
"bpy.types.Material.retro_lightmapped = bpy.props.BoolProperty(name='Retro: Lightmapped')\n"
"bpy.types.Material.retro_opac = bpy.props.IntProperty(name='Retro: OPAC')\n"
"bpy.types.Material.retro_blod = bpy.props.IntProperty(name='Retro: BLOD')\n"
"bpy.types.Material.retro_bloi = bpy.props.IntProperty(name='Retro: BLOI')\n"
"bpy.types.Material.retro_bnif = bpy.props.IntProperty(name='Retro: BNIF')\n"
"bpy.types.Material.retro_xrbr = bpy.props.IntProperty(name='Retro: XRBR')\n"
"bpy.types.Material.retro_solid_white = bpy.props.BoolProperty(name='Retro: Solid White Only')\n"
"bpy.types.Material.retro_reflection_alpha_target = bpy.props.BoolProperty(name='Retro: Reflection Alpha Target')\n"
"bpy.types.Material.retro_solid_color = bpy.props.BoolProperty(name='Retro: Solid Color Only')\n"
"bpy.types.Material.retro_exclude_scan = bpy.props.BoolProperty(name='Retro: Exclude From Scan Visor')\n"
"bpy.types.Material.retro_xray_opaque = bpy.props.BoolProperty(name='Retro: XRay Opaque')\n"
"bpy.types.Material.retro_xray_alpha_target = bpy.props.BoolProperty(name='Retro: XRay Alpha Target')\n"
"bpy.types.Material.retro_inca_color_mod = bpy.props.BoolProperty(name='Retro: INCA Color Mod')\n"
"\n";
}
void MaterialSet::ConstructMaterial(Stream& out, const PAKRouter<PAKBridge>& pakRouter, const PAK::Entry& entry,
const Material& material, unsigned groupIdx, unsigned matIdx) {
unsigned i;
out.format(fmt(
"new_material = bpy.data.materials.new('MAT_{}_{}')\n"
"new_material.use_shadows = True\n"
"new_material.use_transparent_shadows = True\n"
"new_material.diffuse_color = (1.0,1.0,1.0)\n"
"new_material.use_nodes = True\n"
"new_material.blend_method = 'BLEND'\n"
"new_nodetree = new_material.node_tree\n"
"material_node = new_nodetree.nodes['Material']\n"
"final_node = new_nodetree.nodes['Output']\n"
"\n"
"gridder = hecl.Nodegrid(new_nodetree)\n"
"gridder.place_node(final_node, 3)\n"
"gridder.place_node(material_node, 0)\n"
"material_node.material = new_material\n"
"\n"
"texture_nodes = []\n"
"kcolor_nodes = []\n"
"color_combiner_nodes = []\n"
"alpha_combiner_nodes = []\n"
"tex_links = []\n"
"tev_reg_sockets = [None]*4\n"
"\n"),
groupIdx, matIdx);
/* Material Flags */
out.format(fmt(
"new_material.retro_alpha_test = {}\n"
"new_material.retro_shadow_occluder = {}\n"
"new_material.diffuse_color = (1, 1, 1, {})\n"),
material.header.flags.alphaTest() ? "True" : "False",
material.header.flags.shadowOccluderMesh() ? "True" : "False",
material.header.flags.shadowOccluderMesh() ? "0" : "1");
/* Blend factors */
out << "blend_node = new_nodetree.nodes.new('ShaderNodeGroup')\n"
"blend_node.name = 'Blend'\n"
"gridder.place_node(blend_node, 2)\n";
if (material.header.flags.alphaBlending())
out << "blend_node.node_tree = bpy.data.node_groups['HECLBlendOutput']\n";
else if (material.header.flags.additiveBlending())
out << "blend_node.node_tree = bpy.data.node_groups['HECLAdditiveOutput']\n";
else {
out << "blend_node.node_tree = bpy.data.node_groups['HECLOpaqueOutput']\n"
"new_material.blend_method = 'OPAQUE'\n";
}
/* Texmap list */
out << "tex_maps = []\n"
"pnode = None\n"
"anode = None\n"
"rflv_tex_node = None\n";
/* Add PASSes */
i = 0;
unsigned texMapIdx = 0;
unsigned texMtxIdx = 0;
unsigned kColorIdx = 0;
Material::ISection* prevSection = nullptr;
for (const Material::SectionFactory& factory : material.sections) {
factory.section->constructNode(out, pakRouter, entry, prevSection, i++, texMapIdx, texMtxIdx, kColorIdx);
Material::SectionPASS* pass = Material::SectionPASS::castTo(factory.section.get());
if (!pass ||
(pass && Material::SectionPASS::Subtype(pass->subtype.toUint32()) != Material::SectionPASS::Subtype::RFLV))
prevSection = factory.section.get();
}
/* Connect final PASS */
out << "if pnode:\n"
" new_nodetree.links.new(pnode.outputs['Next Color'], final_node.inputs['Color'])\n"
"else:\n"
" new_nodetree.links.new(kcolor_nodes[-1][0].outputs[0], final_node.inputs['Color'])\n"
"if anode:\n"
" new_nodetree.links.new(anode.outputs['Value'], final_node.inputs['Alpha'])\n"
"elif pnode:\n"
" new_nodetree.links.new(pnode.outputs['Next Alpha'], final_node.inputs['Alpha'])\n"
"else:\n"
" new_nodetree.links.new(kcolor_nodes[-1][1].outputs[0], final_node.inputs['Alpha'])\n";
}
void Material::SectionPASS::constructNode(hecl::blender::PyOutStream& out, const PAKRouter<PAKBridge>& pakRouter,
const PAK::Entry& entry, const Material::ISection* prevSection, unsigned idx,
unsigned& texMapIdx, unsigned& texMtxIdx, unsigned& kColorIdx) const {
/* Add Texture nodes */
if (txtrId.isValid()) {
std::string texName = pakRouter.getBestEntryName(txtrId);
static void LoadTexture(Stream& out, const UniqueID64& tex,
const PAKRouter<PAKBridge>& pakRouter, const PAK::Entry& entry) {
std::string texName = pakRouter.getBestEntryName(tex);
const nod::Node* node;
const PAK::Entry* texEntry = pakRouter.lookupEntry(txtrId, &node);
const typename PAKRouter<PAKBridge>::EntryType* texEntry = pakRouter.lookupEntry(tex, &node);
hecl::ProjectPath txtrPath = pakRouter.getWorking(texEntry);
if (txtrPath.isNone()) {
if (!txtrPath.isNone()) {
txtrPath.makeDirChain(false);
PAKEntryReadStream rs = texEntry->beginReadStream(*node);
TXTR::Extract(rs, txtrPath);
}
hecl::SystemString resPath = pakRouter.getResourceRelativePath(entry, txtrId);
hecl::SystemString resPath = pakRouter.getResourceRelativePath(entry, tex);
hecl::SystemUTF8Conv resPathView(resPath);
out.format(fmt(
"if '{}' in bpy.data.textures:\n"
out.format(fmt("if '{}' in bpy.data.images:\n"
" image = bpy.data.images['{}']\n"
" texture = bpy.data.textures[image.name]\n"
"else:\n"
" image = bpy.data.images.load('''//{}''')\n"
" image.name = '{}'\n"
" texture = bpy.data.textures.new(image.name, 'IMAGE')\n"
" texture.image = image\n"
"tex_maps.append(texture)\n"
"\n"),
texName, texName, resPathView, texName);
if (uvAnim.size()) {
const UVAnimation& uva = uvAnim[0];
DNAMP1::MaterialSet::Material::AddTexture(out, GX::TexGenSrc(uva.unk1 + (uva.unk1 < 2 ? 0 : 2)), texMtxIdx,
texMapIdx++, false);
DNAMP1::MaterialSet::Material::AddTextureAnim(out, uva.anim.mode, texMtxIdx++, uva.anim.vals);
} else
DNAMP1::MaterialSet::Material::AddTexture(out, GX::TexGenSrc(uvSrc + 4), -1, texMapIdx++, false);
"\n"), texName, texName, resPathView, texName);
}
/* Special case for RFLV (environment UV mask) */
if (Subtype(subtype.toUint32()) == Subtype::RFLV) {
if (txtrId.isValid())
out << "rflv_tex_node = texture_nodes[-1]\n";
return;
}
void MaterialSet::ConstructMaterial(Stream& out, const PAKRouter<PAKBridge>& pakRouter, const PAK::Entry& entry,
const Material& material, unsigned groupIdx, unsigned matIdx) {
out.format(fmt("new_material = bpy.data.materials.new('MAT_{}_{}')\n"), groupIdx, matIdx);
out << "new_material.use_fake_user = True\n"
"new_material.use_nodes = True\n"
"new_material.use_backface_culling = True\n"
"new_material.show_transparent_back = False\n"
"new_material.blend_method = 'BLEND'\n"
"new_nodetree = new_material.node_tree\n"
"for n in new_nodetree.nodes:\n"
" new_nodetree.nodes.remove(n)\n"
"\n"
"gridder = hecl.Nodegrid(new_nodetree)\n"
"new_nodetree.nodes.remove(gridder.frames[2])\n"
"\n"
"texture_nodes = []\n"
"kcolors = {}\n"
"kalphas = {}\n"
"tex_links = []\n"
"\n";
/* Add PASS node */
bool linkRAS = false;
out << "prev_pnode = pnode\n"
"pnode = new_nodetree.nodes.new('ShaderNodeGroup')\n";
switch (Subtype(subtype.toUint32())) {
case Subtype::DIFF: {
out << "pnode.node_tree = bpy.data.node_groups['RetroPassDIFF']\n";
if (txtrId.isValid()) {
out << "new_material.hecl_lightmap = texture.name\n"
<< "texture.image.use_fake_user = True\n";
}
linkRAS = true;
/* Material Flags */
out.format(fmt(
"new_material.retro_enable_bloom = {}\n"
"new_material.retro_force_lighting_stage = {}\n"
"new_material.retro_pre_inca_transparency = {}\n"
"new_material.retro_alpha_test = {}\n"
"new_material.retro_shadow_occluder = {}\n"
"new_material.retro_solid_white = {}\n"
"new_material.retro_reflection_alpha_target = {}\n"
"new_material.retro_solid_color = {}\n"
"new_material.retro_exclude_scan = {}\n"
"new_material.retro_xray_opaque = {}\n"
"new_material.retro_xray_alpha_target = {}\n"
"new_material.retro_inca_color_mod = False\n"),
material.header.flags.enableBloom() ? "True" : "False",
material.header.flags.forceLightingStage() ? "True" : "False",
material.header.flags.preIncaTransparency() ? "True" : "False",
material.header.flags.alphaTest() ? "True" : "False",
material.header.flags.shadowOccluderMesh() ? "True" : "False",
material.header.flags.justWhite() ? "True" : "False",
material.header.flags.reflectionAlphaTarget() ? "True" : "False",
material.header.flags.justSolidColor() ? "True" : "False",
material.header.flags.excludeFromScanVisor() ? "True" : "False",
material.header.flags.xrayOpaque() ? "True" : "False",
material.header.flags.xrayAlphaTarget() ? "True" : "False");
out << "pnode = new_nodetree.nodes.new('ShaderNodeGroup')\n"
"pnode.name = 'Output'\n"
"pnode.node_tree = bpy.data.node_groups['RetroShaderMP3']\n"
"gridder.place_node(pnode, 1)\n";
if (material.header.flags.additiveIncandecence())
out << "pnode.inputs['Add INCA'].default_value = 1\n";
int texMtxIdx = 0;
for (const auto& chunk : material.chunks) {
if (const Material::PASS* pass = chunk.get_if<Material::PASS>()) {
LoadTexture(out, pass->txtrId, pakRouter, entry);
out << "# Texture\n"
"tex_node = new_nodetree.nodes.new('ShaderNodeTexImage')\n"
"texture_nodes.append(tex_node)\n"
"tex_node.image = image\n";
if (!pass->uvAnim.empty()) {
const auto& uva = pass->uvAnim[0];
switch (uva.uvSource) {
case Material::UVAnimationUVSource::Position:
default:
out << "tex_uv_node = new_nodetree.nodes.new('ShaderNodeTexCoord')\n"
"tex_links.append(new_nodetree.links.new(tex_uv_node.outputs['Window'], tex_node.inputs['Vector']))\n";
break;
case Material::UVAnimationUVSource::Normal:
out << "tex_uv_node = new_nodetree.nodes.new('ShaderNodeTexCoord')\n"
"tex_links.append(new_nodetree.links.new(tex_uv_node.outputs['Normal'], tex_node.inputs['Vector']))\n";
break;
case Material::UVAnimationUVSource::UV:
out.format(fmt("tex_uv_node = new_nodetree.nodes.new('ShaderNodeUVMap')\n"
"tex_links.append(new_nodetree.links.new(tex_uv_node.outputs['UV'], tex_node.inputs['Vector']))\n"
"tex_uv_node.uv_map = 'UV_{}'\n"), pass->uvSrc);
break;
}
case Subtype::RIML:
out << "pnode.node_tree = bpy.data.node_groups['RetroPassRIML']\n";
if (idx == 0)
linkRAS = true;
out.format(fmt("tex_uv_node.label = 'MTX_{}'\n"), texMtxIdx);
} else {
out.format(fmt("tex_uv_node = new_nodetree.nodes.new('ShaderNodeUVMap')\n"
"tex_links.append(new_nodetree.links.new(tex_uv_node.outputs['UV'], tex_node.inputs['Vector']))\n"
"tex_uv_node.uv_map = 'UV_{}'\n"), pass->uvSrc);
}
out << "gridder.place_node(tex_uv_node, 0)\n"
"gridder.place_node(tex_node, 0)\n"
"tex_uv_node.location[0] -= 120\n"
"tex_node.location[0] += 120\n"
"tex_node.location[1] += 176\n"
"\n";
if (!pass->uvAnim.empty()) {
const auto& uva = pass->uvAnim[0];
DNAMP1::MaterialSet::Material::AddTextureAnim(out, uva.anim.mode, texMtxIdx++, uva.anim.vals);
}
auto DoSwap = [&]() {
if (pass->flags.swapColorComponent() == Material::SwapColorComponent::Alpha) {
out << "swap_output = tex_node.outputs['Alpha']\n";
} else {
out << "separate_node = new_nodetree.nodes.new('ShaderNodeSeparateRGB')\n"
"gridder.place_node(separate_node, 0, False)\n"
"separate_node.location[0] += 350\n"
"separate_node.location[1] += 350\n"
"new_nodetree.links.new(tex_node.outputs['Color'], separate_node.inputs[0])\n";
out.format(fmt("swap_output = separate_node.outputs[{}]\n"), int(pass->flags.swapColorComponent()));
}
};
using Subtype = Material::PASS::Subtype;
switch (Subtype(pass->subtype.toUint32())) {
case Subtype::DIFF:
out << "new_nodetree.links.new(tex_node.outputs['Color'], pnode.inputs['DIFFC'])\n"
"new_nodetree.links.new(tex_node.outputs['Alpha'], pnode.inputs['DIFFA'])\n";
break;
case Subtype::BLOL:
out << "pnode.node_tree = bpy.data.node_groups['RetroPassBLOL']\n";
if (idx == 0)
linkRAS = true;
DoSwap();
out << "new_nodetree.links.new(swap_output, pnode.inputs['BLOL'])\n";
break;
case Subtype::BLOD:
out << "pnode.node_tree = bpy.data.node_groups['RetroPassBLOD']\n";
if (idx == 0)
linkRAS = true;
DoSwap();
out << "new_nodetree.links.new(swap_output, pnode.inputs['BLOD'])\n";
break;
case Subtype::CLR:
out << "pnode.node_tree = bpy.data.node_groups['RetroPassCLR']\n";
if (idx == 0)
linkRAS = true;
out << "new_nodetree.links.new(tex_node.outputs['Color'], pnode.inputs['CLR'])\n"
"new_nodetree.links.new(tex_node.outputs['Alpha'], pnode.inputs['CLRA'])\n";
break;
case Subtype::TRAN:
if (flags.TRANInvert())
out << "pnode.node_tree = bpy.data.node_groups['RetroPassTRANInv']\n";
else
out << "pnode.node_tree = bpy.data.node_groups['RetroPassTRAN']\n";
DoSwap();
if (pass->flags.TRANInvert())
out << "invert_node = new_nodetree.nodes.new('ShaderNodeInvert')\n"
"gridder.place_node(invert_node, 0, False)\n"
"invert_node.location[0] += 400\n"
"invert_node.location[1] += 350\n"
"new_nodetree.links.new(swap_output, invert_node.inputs['Color'])\n"
"swap_output = invert_node.outputs['Color']\n";
out << "new_nodetree.links.new(swap_output, pnode.inputs['TRAN'])\n";
break;
case Subtype::INCA:
out << "pnode.node_tree = bpy.data.node_groups['RetroPassINCA']\n";
out << "new_nodetree.links.new(tex_node.outputs['Color'], pnode.inputs['INCAC'])\n";
if (pass->flags.alphaContribution()) {
DoSwap();
out << "new_nodetree.links.new(swap_output, pnode.inputs['INCAA'])\n";
}
out.format(fmt("new_material.retro_inca_color_mod = {}\n"), pass->flags.INCAColorMod() ? "True" : "False");
break;
case Subtype::RFLV:
out << "pnode.node_tree = bpy.data.node_groups['RetroPassRFLV']\n";
out << "new_nodetree.links.new(tex_node.outputs['Color'], pnode.inputs['RFLV'])\n";
break;
case Subtype::RFLD:
out << "pnode.node_tree = bpy.data.node_groups['RetroPassRFLD']\n"
"if rflv_tex_node:\n"
" new_nodetree.links.new(rflv_tex_node.outputs['Color'], pnode.inputs['Mask Color'])\n"
" new_nodetree.links.new(rflv_tex_node.outputs['Value'], pnode.inputs['Mask Alpha'])\n";
out << "new_nodetree.links.new(tex_node.outputs['Color'], pnode.inputs['RFLD'])\n"
"new_nodetree.links.new(tex_node.outputs['Alpha'], pnode.inputs['RFLDA'])\n";
break;
case Subtype::LRLD:
out << "pnode.node_tree = bpy.data.node_groups['RetroPassLRLD']\n";
out << "new_nodetree.links.new(tex_node.outputs['Color'], pnode.inputs['LRLD'])\n";
break;
case Subtype::LURD:
out << "pnode.node_tree = bpy.data.node_groups['RetroPassLURD']\n";
out << "new_nodetree.links.new(tex_node.outputs['Color'], pnode.inputs['LURDC'])\n"
"new_nodetree.links.new(tex_node.outputs['Alpha'], pnode.inputs['LURDA'])\n";
break;
case Subtype::BLOI:
out << "pnode.node_tree = bpy.data.node_groups['RetroPassBLOI']\n";
DoSwap();
out << "new_nodetree.links.new(swap_output, pnode.inputs['BLOI'])\n";
break;
case Subtype::XRAY:
out << "pnode.node_tree = bpy.data.node_groups['RetroPassXRAY']\n";
break;
case Subtype::TOON:
out << "pnode.node_tree = bpy.data.node_groups['RetroPassTOON']\n";
DoSwap();
out << "new_nodetree.links.new(tex_node.outputs['Color'], pnode.inputs['XRAYC'])\n"
"new_nodetree.links.new(swap_output, pnode.inputs['XRAYA'])\n";
break;
default:
Log.report(logvisor::Fatal, fmt("Unknown PASS subtype"));
break;
}
out << "gridder.place_node(pnode, 2)\n";
if (txtrId.isValid()) {
out << "new_nodetree.links.new(texture_nodes[-1].outputs['Color'], pnode.inputs['Tex Color'])\n"
"new_nodetree.links.new(texture_nodes[-1].outputs['Value'], pnode.inputs['Tex Alpha'])\n";
}
if (linkRAS)
out << "new_nodetree.links.new(material_node.outputs['Color'], pnode.inputs['Prev Color'])\n"
"new_nodetree.links.new(material_node.outputs['Alpha'], pnode.inputs['Prev Alpha'])\n";
else if (prevSection) {
if (prevSection->m_type == ISection::Type::PASS &&
Subtype(static_cast<const SectionPASS*>(prevSection)->subtype.toUint32()) != Subtype::RFLV)
out << "new_nodetree.links.new(prev_pnode.outputs['Next Color'], pnode.inputs['Prev Color'])\n"
"new_nodetree.links.new(prev_pnode.outputs['Next Alpha'], pnode.inputs['Prev Alpha'])\n";
else if (prevSection->m_type == ISection::Type::CLR)
out << "new_nodetree.links.new(kcolor_nodes[-1][0].outputs[0], pnode.inputs['Prev Color'])\n"
"new_nodetree.links.new(kcolor_nodes[-1][1].outputs[0], pnode.inputs['Prev Alpha'])\n";
}
/* Row Break in gridder */
out << "gridder.row_break(2)\n";
}
void Material::SectionCLR::constructNode(hecl::blender::PyOutStream& out, const PAKRouter<PAKBridge>& pakRouter,
const PAK::Entry& entry, const Material::ISection* prevSection, unsigned idx,
unsigned& texMapIdx, unsigned& texMtxIdx, unsigned& kColorIdx) const {
DNAMP1::MaterialSet::Material::AddKcolor(out, color, kColorIdx++);
switch (Subtype(subtype.toUint32())) {
} else if (const Material::CLR* clr = chunk.get_if<Material::CLR>()) {
using Subtype = Material::CLR::Subtype;
athena::simd_floats vec4;
clr->color.toVec4f().simd.copy_to(vec4);
switch (Subtype(clr->subtype.toUint32())) {
case Subtype::CLR:
out.format(fmt("pnode.inputs['CLR'].default_value = ({}, {}, {}, 1.0)\n"
"pnode.inputs['CLRA'].default_value = {}\n"),
vec4[0], vec4[1], vec4[2], vec4[3]);
break;
case Subtype::DIFB:
out << "kc_node.label += ' DIFB'\n"
"ka_node.label += ' DIFB'\n";
out.format(fmt("pnode.inputs['DIFBC'].default_value = ({}, {}, {}, 1.0)\n"
"pnode.inputs['DIFBA'].default_value = {}\n"),
vec4[0], vec4[1], vec4[2], vec4[3]);
break;
default:
Log.report(logvisor::Fatal, fmt("Unknown CLR subtype"));
break;
}
}
void Material::SectionINT::constructNode(hecl::blender::PyOutStream& out, const PAKRouter<PAKBridge>& pakRouter,
const PAK::Entry& entry, const Material::ISection* prevSection, unsigned idx,
unsigned& texMapIdx, unsigned& texMtxIdx, unsigned& kColorIdx) const {
switch (Subtype(subtype.toUint32())) {
case Subtype::OPAC: {
GX::Color clr(value);
out.format(fmt(
"anode = new_nodetree.nodes.new('ShaderNodeValue')\n"
"anode.outputs['Value'].default_value = {}\n"),
float(clr[3]) / float(0xff));
out << "gridder.place_node(anode, 1)\n";
} break;
} else if (const Material::INT* val = chunk.get_if<Material::INT>()) {
using Subtype = Material::INT::Subtype;
switch (Subtype(val->subtype.toUint32())) {
case Subtype::OPAC:
out.format(fmt("pnode.inputs['OPAC'].default_value = {}\n"), val->value / 255.f);
break;
case Subtype::BLOD:
out.format(fmt("new_material.retro_blod = {}\n"), value);
out.format(fmt("pnode.inputs['BLOD'].default_value = {}\n"), val->value / 255.f);
break;
case Subtype::BLOI:
out.format(fmt("new_material.retro_bloi = {}\n"), value);
out.format(fmt("pnode.inputs['BLOI'].default_value = {}\n"), val->value / 255.f);
break;
case Subtype::BNIF:
out.format(fmt("new_material.retro_bnif = {}\n"), value);
out.format(fmt("pnode.inputs['BNIF'].default_value = {}\n"), val->value / 255.f);
break;
case Subtype::XRBR:
out.format(fmt("new_material.retro_xrbr = {}\n"), value);
out.format(fmt("pnode.inputs['XRBR'].default_value = {}\n"), val->value / 255.f);
break;
default:
Log.report(logvisor::Fatal, fmt("Unknown INT subtype"));
break;
}
}
}
}
} // namespace DataSpec::DNAMP3
AT_SPECIALIZE_TYPED_VARIANT_BIGDNA(DataSpec::DNAMP3::MaterialSet::Material::PASS,
DataSpec::DNAMP3::MaterialSet::Material::CLR,
DataSpec::DNAMP3::MaterialSet::Material::INT,
DataSpec::DNAMP3::MaterialSet::Material::END)

View File

@ -18,6 +18,10 @@ struct MaterialSet : BigDNA {
void addMaterialEndOff(atUint32) { ++materialCount; }
struct Material : BigDNA {
enum class SwapColorComponent { Red, Green, Blue, Alpha };
enum class UVAnimationUVSource : atUint16 { Position, Normal, UV };
enum class UVAnimationMatrixConfig : atUint16 { NoMtxNoPost, MtxNoPost, NoMtxPost, MtxPost };
AT_DECL_EXPLICIT_DNA
using VAFlags = DNAMP1::MaterialSet::Material::VAFlags;
struct Header : BigDNA {
@ -26,8 +30,18 @@ struct MaterialSet : BigDNA {
struct Flags : BigDNA {
AT_DECL_DNA
Value<atUint32> flags;
bool alphaBlending() const { return (flags & 0x8) != 0; }
void setAlphaBlending(bool enabled) {
bool enableBloom() const { return (flags & 0x1) != 0; }
void setEnableBloom(bool enabled) {
flags &= ~0x1;
flags |= atUint32(enabled) << 0;
}
bool forceLightingStage() const { return (flags & 0x4) != 0; }
void setForceLightingStage(bool enabled) {
flags &= ~0x4;
flags |= atUint32(enabled) << 2;
}
bool preIncaTransparency() const { return (flags & 0x8) != 0; }
void setPreIncaTransparency(bool enabled) {
flags &= ~0x8;
flags |= atUint32(enabled) << 3;
}
@ -36,8 +50,8 @@ struct MaterialSet : BigDNA {
flags &= ~0x10;
flags |= atUint32(enabled) << 4;
}
bool additiveBlending() const { return (flags & 0x20) != 0; }
void setAdditiveBlending(bool enabled) {
bool additiveIncandecence() const { return (flags & 0x20) != 0; }
void setAdditiveIncandecence(bool enabled) {
flags &= ~0x20;
flags |= atUint32(enabled) << 5;
}
@ -46,6 +60,36 @@ struct MaterialSet : BigDNA {
flags &= ~0x100;
flags |= atUint32(enabled) << 8;
}
bool justWhite() const { return (flags & 0x200) != 0; }
void setJustWhite(bool enabled) {
flags &= ~0x200;
flags |= atUint32(enabled) << 9;
}
bool reflectionAlphaTarget() const { return (flags & 0x400) != 0; }
void setReflectionAlphaTarget(bool enabled) {
flags &= ~0x400;
flags |= atUint32(enabled) << 10;
}
bool justSolidColor() const { return (flags & 0x800) != 0; }
void setJustSolidColor(bool enabled) {
flags &= ~0x800;
flags |= atUint32(enabled) << 11;
}
bool excludeFromScanVisor() const { return (flags & 0x4000) != 0; }
void setExcludeFromScanVisor(bool enabled) {
flags &= ~0x4000;
flags |= atUint32(enabled) << 14;
}
bool xrayOpaque() const { return (flags & 0x8000) != 0; }
void setXRayOpaque(bool enabled) {
flags &= ~0x8000;
flags |= atUint32(enabled) << 15;
}
bool xrayAlphaTarget() const { return (flags & 0x10000) != 0; }
void setXRayAlphaTarget(bool enabled) {
flags &= ~0x10000;
flags |= atUint32(enabled) << 16;
}
bool lightmapUVArray() const { return false; } /* For polymorphic compatibility with MP1/2 */
} flags;
Value<atUint32> uniqueIdx;
@ -58,20 +102,12 @@ struct MaterialSet : BigDNA {
const Header::Flags& getFlags() const { return header.flags; }
const VAFlags& getVAFlags() const { return header.vaFlags; }
struct ISection : BigDNAV {
Delete expl;
enum class Type : atUint32 { PASS = SBIG('PASS'), CLR = SBIG('CLR '), INT = SBIG('INT ') } m_type;
ISection(Type type) : m_type(type) {}
virtual void constructNode(hecl::blender::PyOutStream& out, const PAKRouter<PAKBridge>& pakRouter,
const PAK::Entry& entry, const Material::ISection* prevSection, unsigned idx,
unsigned& texMapIdx, unsigned& texMtxIdx, unsigned& kColorIdx) const = 0;
enum class ChunkType : atUint32 {
PASS = 'PASS', CLR = 'CLR ', INT = 'INT ', END = 'END '
};
struct SectionPASS : ISection {
SectionPASS() : ISection(ISection::Type::PASS) {}
static SectionPASS* castTo(ISection* sec) {
return sec->m_type == Type::PASS ? static_cast<SectionPASS*>(sec) : nullptr;
}
AT_DECL_DNAV
struct PASS : hecl::TypedRecordBigDNA<ChunkType::PASS> {
AT_DECL_DNA
Value<atUint32> size;
enum class Subtype : atUint32 {
DIFF = SBIG('DIFF'),
@ -93,6 +129,21 @@ struct MaterialSet : BigDNA {
struct Flags : BigDNA {
AT_DECL_DNA
Value<atUint32> flags;
SwapColorComponent swapColorComponent() const { return SwapColorComponent(flags & 0x3); }
void setSwapColorComponent(SwapColorComponent comp) {
flags &= ~0x3;
flags |= atUint32(comp) << 0;
}
bool alphaContribution() const { return (flags & 0x4) != 0; }
void setAlphaContribution(bool enabled) {
flags &= ~0x4;
flags |= atUint32(enabled) << 2;
}
bool INCAColorMod() const { return (flags & 0x8) != 0; }
void setINCAColorMod(bool enabled) {
flags &= ~0x8;
flags |= atUint32(enabled) << 3;
}
bool TRANInvert() const { return (flags & 0x10) != 0; }
void setTRANInvert(bool enabled) {
flags &= ~0x10;
@ -104,36 +155,21 @@ struct MaterialSet : BigDNA {
Value<atUint32> uvAnimSize;
struct UVAnimation : BigDNA {
AT_DECL_DNA
Value<atUint16> unk1;
Value<atUint16> unk2;
Value<UVAnimationUVSource> uvSource;
Value<UVAnimationMatrixConfig> mtxConfig;
DNAMP1::MaterialSet::Material::UVAnimation anim;
};
Vector<UVAnimation, AT_DNA_COUNT(uvAnimSize != 0)> uvAnim;
void constructNode(hecl::blender::PyOutStream& out, const PAKRouter<PAKBridge>& pakRouter,
const PAK::Entry& entry, const Material::ISection* prevSection, unsigned idx,
unsigned& texMapIdx, unsigned& texMtxIdx, unsigned& kColorIdx) const override;
};
struct SectionCLR : ISection {
SectionCLR() : ISection(ISection::Type::CLR) {}
static SectionCLR* castTo(ISection* sec) {
return sec->m_type == Type::CLR ? static_cast<SectionCLR*>(sec) : nullptr;
}
AT_DECL_DNAV
struct CLR : hecl::TypedRecordBigDNA<ChunkType::CLR> {
AT_DECL_DNA
enum class Subtype : atUint32 { CLR = SBIG('CLR '), DIFB = SBIG('DIFB') };
DNAFourCC subtype;
GX::Color color;
void constructNode(hecl::blender::PyOutStream& out, const PAKRouter<PAKBridge>& pakRouter,
const PAK::Entry& entry, const Material::ISection* prevSection, unsigned idx,
unsigned& texMapIdx, unsigned& texMtxIdx, unsigned& kColorIdx) const override;
CLR() = default;
};
struct SectionINT : ISection {
SectionINT() : ISection(ISection::Type::INT) {}
static SectionINT* castTo(ISection* sec) {
return sec->m_type == Type::INT ? static_cast<SectionINT*>(sec) : nullptr;
}
AT_DECL_DNAV
struct INT : hecl::TypedRecordBigDNA<ChunkType::INT> {
AT_DECL_DNA
enum class Subtype : atUint32 {
OPAC = SBIG('OPAC'),
BLOD = SBIG('BLOD'),
@ -143,16 +179,12 @@ struct MaterialSet : BigDNA {
};
DNAFourCC subtype;
Value<atUint32> value;
void constructNode(hecl::blender::PyOutStream& out, const PAKRouter<PAKBridge>& pakRouter,
const PAK::Entry& entry, const Material::ISection* prevSection, unsigned idx,
unsigned& texMapIdx, unsigned& texMtxIdx, unsigned& kColorIdx) const override;
};
struct SectionFactory : BigDNA {
AT_DECL_EXPLICIT_DNA
std::unique_ptr<ISection> section;
struct END : hecl::TypedRecordBigDNA<ChunkType::END> {
AT_DECL_DNA
};
std::vector<SectionFactory> sections;
using Chunk = hecl::TypedVariantBigDNA<PASS, CLR, INT, END>;
std::vector<Chunk> chunks;
};
Vector<Material, AT_DNA_COUNT(materialCount)> materials;

View File

@ -14,11 +14,12 @@ set(DNAMP3_SOURCES
DNAMP3.hpp DNAMP3.cpp
PAK.cpp
ANIM.cpp
CINF.cpp
CINF.hpp
CHAR.cpp
CMDL.hpp CMDL.cpp
CMDLMaterials.cpp
CSKR.cpp
PATH.hpp
STRG.hpp STRG.cpp
MAPA.hpp
MREA.cpp)

View File

@ -9,6 +9,7 @@
#include "CHAR.hpp"
#include "MREA.hpp"
#include "MAPA.hpp"
#include "PATH.hpp"
#include "SAVW.hpp"
#include "HINT.hpp"
#include "DataSpec/DNACommon/TXTR.hpp"
@ -21,6 +22,8 @@ namespace DataSpec::DNAMP3 {
logvisor::Module Log("urde::DNAMP3");
static bool GetNoShare(std::string_view name) {
if (name == "UniverseArea.pak"sv)
return false;
std::string lowerName(name);
std::transform(lowerName.begin(), lowerName.end(), lowerName.begin(), tolower);
if (!lowerName.compare(0, 7, "metroid"))
@ -194,6 +197,16 @@ void PAKBridge::addMAPATransforms(PAKRouter<PAKBridge>& pakRouter,
fmt::format(fmt(_SYS_STR("!name_{}.yaml")), mlvl.worldNameId));
for (const MLVL::Area& area : mlvl.areas) {
{
/* Get PATH transform */
const nod::Node* areaNode;
const PAK::Entry* areaEntry = pakRouter.lookupEntry(area.areaMREAId, &areaNode);
PAKEntryReadStream rs = areaEntry->beginReadStream(*areaNode);
UniqueID64 pathId = MREA::GetPATHId(rs);
if (pathId.isValid())
addTo[pathId] = zeus::CMatrix4f(area.transformMtx[0], area.transformMtx[1], area.transformMtx[2], BottomRow)
.transposed();
}
hecl::ProjectPath areaDirPath = pakRouter.getWorking(area.areaMREAId).getParentPath();
if (area.areaNameId.isValid())
pathOverrides[area.areaNameId] = hecl::ProjectPath(areaDirPath,
@ -236,16 +249,20 @@ ResExtractor<PAKBridge> PAKBridge::LookupExtractor(const nod::Node& pakNode, con
return {SAVWCommon::ExtractSAVW<SAVW>, {_SYS_STR(".yaml")}};
case SBIG('HINT'):
return {HINT::Extract, {_SYS_STR(".yaml")}};
// case SBIG('CMDL'):
// return {CMDL::Extract, {_SYS_STR(".blend")}, 1};
// case SBIG('CHAR'):
// return {CHAR::Extract, {_SYS_STR(".yaml"), _SYS_STR(".blend")}, 2};
// case SBIG('MLVL'):
// return {MLVL::Extract, {_SYS_STR(".yaml"), _SYS_STR(".blend")}, 3};
// case SBIG('MREA'):
// return {MREA::Extract, {_SYS_STR(".blend")}, 4};
// case SBIG('MAPA'):
// return {MAPA::Extract, {_SYS_STR(".blend")}, 4};
case SBIG('CMDL'):
return {CMDL::Extract, {_SYS_STR(".blend")}, 1};
case SBIG('CINF'):
return {CINF::Extract<PAKBridge>, {_SYS_STR(".blend")}, 1};
case SBIG('CHAR'):
return {CHAR::Extract, {_SYS_STR(".yaml"), _SYS_STR(".blend")}, 2};
case SBIG('MLVL'):
return {MLVL::Extract, {_SYS_STR(".yaml"), _SYS_STR(".blend")}, 3};
case SBIG('MREA'):
return {MREA::Extract, {_SYS_STR(".blend")}, 4};
case SBIG('MAPA'):
return {MAPA::Extract, {_SYS_STR(".blend")}, 4};
case SBIG('PATH'):
return {PATH::Extract, {_SYS_STR(".blend")}, 5};
case SBIG('FSM2'):
return {DNAFSM2::ExtractFSM2<UniqueID64>, {_SYS_STR(".yaml")}};
case SBIG('FONT'):

View File

@ -14,16 +14,14 @@ MREA::StreamReader::StreamReader(athena::io::IStreamReader& source, atUint32 blk
m_blkCount = blkCount;
m_blockInfos.reserve(blkCount);
for (atUint32 i = 0; i < blkCount; ++i) {
m_blockInfos.emplace_back();
BlockInfo& info = m_blockInfos.back();
BlockInfo& info = m_blockInfos.emplace_back();
info.read(source);
m_totalDecompLen += info.decompSize;
}
source.seekAlign32();
m_secIdxs.reserve(secIdxCount);
for (atUint32 i = 0; i < secIdxCount; ++i) {
m_secIdxs.emplace_back();
std::pair<DNAFourCC, atUint32>& idx = m_secIdxs.back();
std::pair<DNAFourCC, atUint32>& idx = m_secIdxs.emplace_back();
idx.first.read(source);
idx.second = source.readUint32Big();
}
@ -39,6 +37,15 @@ void MREA::StreamReader::writeSecIdxs(athena::io::IStreamWriter& writer) const {
}
}
bool MREA::StreamReader::seekToSection(FourCC sec, const std::vector<atUint32>& secSizes) {
auto search = std::find_if(m_secIdxs.begin(), m_secIdxs.end(), [sec](const auto& s) { return s.first == sec; });
if (search != m_secIdxs.end()) {
DNAMP2::MREA::StreamReader::seekToSection(search->second, secSizes);
return true;
}
return false;
}
void MREA::ReadBabeDeadToBlender_3(hecl::blender::PyOutStream& os, athena::io::IStreamReader& rs) {
atUint32 bdMagic = rs.readUint32Big();
if (bdMagic != 0xBABEDEAD)
@ -254,5 +261,20 @@ bool MREA::ExtractLayerDeps(PAKEntryReadStream& rs, PAKBridge::Level::Area& area
return false;
}
UniqueID64 MREA::GetPATHId(PAKEntryReadStream& rs) {
/* Do extract */
Header head;
head.read(rs);
rs.seekAlign32();
/* MREA decompression stream */
StreamReader drs(rs, head.compressedBlockCount, head.secIndexCount);
/* Skip to PATH */
if (drs.seekToSection(FOURCC('PFL2'), head.secSizes))
return {drs};
return {};
}
} // namespace DNAMP3
} // namespace DataSpec

View File

@ -13,6 +13,7 @@ struct MREA {
StreamReader(athena::io::IStreamReader& source, atUint32 blkCount, atUint32 secIdxCount);
std::vector<std::pair<DNAFourCC, atUint32>>::const_iterator beginSecIdxs() { return m_secIdxs.begin(); }
void writeSecIdxs(athena::io::IStreamWriter& writer) const;
bool seekToSection(FourCC sec, const std::vector<atUint32>& secSizes);
};
struct Header : BigDNA {
@ -84,6 +85,8 @@ struct MREA {
static void ReadBabeDeadToBlender_3(hecl::blender::PyOutStream& os, athena::io::IStreamReader& rs);
static UniqueID64 GetPATHId(PAKEntryReadStream& rs);
static bool Extract(const SpecBase& dataSpec, PAKEntryReadStream& rs, const hecl::ProjectPath& outPath,
PAKRouter<PAKBridge>& pakRouter, const PAK::Entry& entry, bool, hecl::blender::Token& btok,
std::function<void(const hecl::SystemChar*)>);

6
DataSpec/DNAMP3/PATH.hpp Normal file
View File

@ -0,0 +1,6 @@
#pragma once
#include "DataSpec/DNACommon/PATH.hpp"
namespace DataSpec::DNAMP3 {
using PATH = DNAPATH::PATH<PAKBridge>;
} // namespace DataSpec::DNAMP3

View File

@ -6,9 +6,11 @@
#include "DNAMP2/MLVL.hpp"
#include "DNAMP2/STRG.hpp"
#include "DNAMP2/AGSC.hpp"
#include "DNAMP2/PATH.hpp"
#include "DNAMP2/MAPA.hpp"
#include "DNAMP1/CSNG.hpp"
#include "DNACommon/MAPU.hpp"
#include "DNACommon/PATH.hpp"
#include "hecl/ClientProcess.hpp"
#include "hecl/Blender/Connection.hpp"
@ -286,7 +288,11 @@ struct SpecMP2 : SpecBase {
hecl::blender::Token& btok, FCookProgress progress) override {}
void cookPathMesh(const hecl::ProjectPath& out, const hecl::ProjectPath& in, BlendStream& ds, bool fast,
hecl::blender::Token& btok, FCookProgress progress) override {}
hecl::blender::Token& btok, FCookProgress progress) override {
PathMesh mesh = ds.compilePathMesh();
ds.close();
DNAMP2::PATH::Cook(out, in, mesh, btok);
}
void cookActor(const hecl::ProjectPath& out, const hecl::ProjectPath& in, BlendStream& ds, bool fast,
hecl::blender::Token& btok, FCookProgress progress) override {}

View File

@ -4,7 +4,7 @@
#define MP1_USE_BOO 0
#endif
#ifndef MP1_VARIABLE_DELTA_TIME
#define MP1_VARIABLE_DELTA_TIME 0
#define MP1_VARIABLE_DELTA_TIME 1
#endif
#include "IMain.hpp"

2
hecl

@ -1 +1 @@
Subproject commit 0b42de34d0439ed46e393e0bb6de1b02641399a1
Subproject commit 87ad5cbc81dad92d54c60d388157ca6300475c19