Skip to content

Commit

Permalink
Fix test asset path + other minor fixes.
Browse files Browse the repository at this point in the history
  • Loading branch information
0mdc committed Apr 21, 2023
1 parent 6115ce3 commit 51abdd7
Show file tree
Hide file tree
Showing 6 changed files with 33 additions and 30 deletions.
3 changes: 2 additions & 1 deletion data/test_assets/urdf/skinned_prism.ao_config.json
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
{
"render_asset": "data/test_assets/objects/skinned_prism.glb"
"render_asset": "../objects/skinned_prism.glb",
"debug_render_primitives": false
}
35 changes: 17 additions & 18 deletions src/esp/assets/ResourceManager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1798,8 +1798,7 @@ bool ResourceManager::loadRenderAssetGeneral(const AssetInfo& info) {
scene->parentsAsArray()) {
nodes[parent.first()].emplace();
nodes[parent.first()]->componentID = parent.first();
nodes[parent.first()]->name =
fileImporter_->objectName(nodes[parent.first()]->componentID);
nodes[parent.first()]->name = fileImporter_->objectName(parent.first());
}

// Set transformations. Objects that are not part of the hierarchy are
Expand Down Expand Up @@ -1888,24 +1887,24 @@ scene::SceneNode* ResourceManager::createRenderAssetInstanceGeneralPrimitive(
// If the object has a skin and a rig (articulated object), link them together
// such as the model bones are driven by the articulated object links.
std::shared_ptr<gfx::InstanceSkinData> instanceSkinData = nullptr;
if (creation.rig &&
loadedAssetData.meshMetaData.skinIndex.first != ID_UNDEFINED) {
const auto& meshMetaData = loadedAssetData.meshMetaData;
if (creation.rig && meshMetaData.skinIndex.first != ID_UNDEFINED) {
ESP_CHECK(
!skins_.empty(),
"Cannot instantiate skinned model because no skin data is imported.");
const auto& skinData = skins_[loadedAssetData.meshMetaData.skinIndex.first];
const auto& skinData = skins_[meshMetaData.skinIndex.first];
instanceSkinData = std::make_shared<gfx::InstanceSkinData>(skinData);
mapSkinnedModelToArticulatedObject(loadedAssetData.meshMetaData.root,
creation.rig, instanceSkinData);
mapSkinnedModelToArticulatedObject(meshMetaData.root, creation.rig,
instanceSkinData);
ESP_CHECK(instanceSkinData->rootJointId != ID_UNDEFINED,
"Could not map skinned model to articulated object.");
}

addComponent(loadedAssetData.meshMetaData, // mesh metadata
newNode, // parent scene node
creation.lightSetupKey, // lightSetup key
drawables, // drawable group
loadedAssetData.meshMetaData.root, // mesh transform node
addComponent(meshMetaData, // mesh metadata
newNode, // parent scene node
creation.lightSetupKey, // lightSetup key
drawables, // drawable group
meshMetaData.root, // mesh transform node
visNodeCache, // a vector of scene nodes, the visNodeCache
computeAbsoluteAABBs, // compute absolute AABBs
staticDrawableInfo, // a vector of static drawable info
Expand Down Expand Up @@ -2472,8 +2471,8 @@ void ResourceManager::loadSkins(Importer& importer,
if (importer.skin3DCount() == 0)
return;

int skinStart = nextSkinID_;
int skinEnd = skinStart + importer.skin3DCount() - 1;
const int skinStart = nextSkinID_;
const int skinEnd = skinStart + importer.skin3DCount() - 1;
nextSkinID_ = skinEnd + 1;
loadedAssetData.meshMetaData.setSkinIndices(skinStart, skinEnd);

Expand Down Expand Up @@ -2914,15 +2913,15 @@ void ResourceManager::mapSkinnedModelToArticulatedObject(
// Find skin joint ID that matches the node
const auto& gfxBoneName = meshTransformNode.name;
const auto& boneNameJointIdMap = skinData->skinData->boneNameJointIdMap;
auto jointIt = boneNameJointIdMap.find(gfxBoneName);
const auto jointIt = boneNameJointIdMap.find(gfxBoneName);
if (jointIt != boneNameJointIdMap.end()) {
int jointId = jointIt->second;

// Find articulated object link ID that matches the node
const auto& linkIds = rig->getLinkIdsWithBase();
auto linkId = std::find_if(linkIds.begin(), linkIds.end(), [&](int i) {
return gfxBoneName == rig->getLinkName(i);
});
const auto linkId =
std::find_if(linkIds.begin(), linkIds.end(),
[&](int i) { return gfxBoneName == rig->getLinkName(i); });

// Map the articulated object link associated with the skin joint
if (linkId != linkIds.end()) {
Expand Down
4 changes: 2 additions & 2 deletions src/esp/assets/ResourceManager.h
Original file line number Diff line number Diff line change
Expand Up @@ -856,7 +856,7 @@ class ResourceManager {
const std::shared_ptr<gfx::InstanceSkinData>& skinData = nullptr);

/**
* @brief Recursive construction of instance skin and rig data.
* @brief Recursive construction of instance skinning data.
*
* Fills the fields of a @ref InstanceSkinData to enable skinned mesh rendering
* by associating each bone to a corresponding articulated object link.
Expand All @@ -865,7 +865,7 @@ class ResourceManager {
* @param creationInfo Creation information for the instance which contains
* the rig.
* @param skinData Structure holding the skin and rig configuration for the
* instance
* instance.
*/
void mapSkinnedModelToArticulatedObject(
const MeshTransformNode& meshTransformNode,
Expand Down
16 changes: 8 additions & 8 deletions src/esp/gfx/GenericDrawable.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -191,24 +191,24 @@ void GenericDrawable::draw(const Mn::Matrix4& transformationMatrix,

if (skinData_) {
// Gather joint transformations
auto& skin = skinData_->skinData->skin;
const auto& skin = skinData_->skinData->skin;
const auto& transformNodes = skinData_->jointIdToTransformNode;
auto& jointIdToArticulatedObjectNodes =
skinData_->jointIdToArticulatedObjectNode;
auto& transformNodes = skinData_->jointIdToTransformNode;

ESP_CHECK(jointTransformations_.size() == skin->joints().size(),
"Joint transformation count doesn't match bone count.");

// Undo root node transform so that the model origin matches the root
// articulated object link.
auto invRootTransform =
const auto invRootTransform =
jointIdToArticulatedObjectNodes[skinData_->rootJointId]
->absoluteTransformationMatrix()
.inverted();

Mn::Matrix4 lastTransform = Mn::Matrix4{Magnum::Math::IdentityInit};
auto lastTransform = Mn::Matrix4{Magnum::Math::IdentityInit};
for (std::size_t i = 0; i != jointTransformations_.size(); ++i) {
auto jointNodeIt = transformNodes.find(skin->joints()[i]);
const auto jointNodeIt = transformNodes.find(skin->joints()[i]);
if (jointNodeIt != transformNodes.end()) {
jointTransformations_[i] =
invRootTransform *
Expand All @@ -233,10 +233,10 @@ void GenericDrawable::draw(const Mn::Matrix4& transformationMatrix,
}

void GenericDrawable::updateShader() {
Mn::UnsignedInt lightCount = lightSetup_->size();
Mn::UnsignedInt jointCount =
const Mn::UnsignedInt lightCount = lightSetup_->size();
const Mn::UnsignedInt jointCount =
skinData_ ? skinData_->skinData->skin->joints().size() : 0;
Mn::UnsignedInt perVertexJointCount =
const Mn::UnsignedInt perVertexJointCount =
skinData_ ? skinData_->skinData->perVertexJointCount : 0;

if (skinData_) {
Expand Down
2 changes: 2 additions & 0 deletions src/esp/physics/bullet/BulletPhysicsManager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -188,6 +188,8 @@ int BulletPhysicsManager::addArticulatedObjectFromURDF(
articulatedObject->btMultiBody_->getLinkCollider(linkIx), linkObjectId);
}

// render visual shapes if either no skinned mesh is present or if the debug
// flag is enabled
bool renderVisualShapes =
!renderAssetPath || model->getDebugRenderPrimitives();
if (renderVisualShapes) {
Expand Down
3 changes: 2 additions & 1 deletion src/tests/SimTest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1078,7 +1078,8 @@ void SimTest::getRuntimePerfStats() {
void SimTest::testArticulatedObjectSkinned() {
ESP_DEBUG() << "Starting Test : testArticulatedObjectSkinned";

const std::string urdfFile = "data/test_assets/urdf/skinned_prism.urdf";
const std::string urdfFile =
Cr::Utility::Path::join(TEST_ASSETS, "urdf/skinned_prism.urdf");

// create a simulator
SimulatorConfiguration simConfig{};
Expand Down

0 comments on commit 51abdd7

Please sign in to comment.