Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

ColladaExporter, export submesh selected #802

Merged
merged 6 commits into from
May 17, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
80 changes: 47 additions & 33 deletions src/systems/collada_world_exporter/ColladaWorldExporter.cc
Original file line number Diff line number Diff line change
Expand Up @@ -112,12 +112,27 @@ class ignition::gazebo::systems::ColladaWorldExporterPrivate
ignition::common::MeshManager *meshManager =
ignition::common::MeshManager::Instance();

auto addSubmeshFunc = [&](int i, int k) {
subm = worldMesh.AddSubMesh(
*mesh->SubMeshByIndex(k).lock().get());
subm.lock()->SetMaterialIndex(i);
subm.lock()->Scale(scale);
subMeshMatrix.push_back(matrix);
auto addSubmeshFunc = [&](int _matIndex)
{
int newMatIndex = 0;
if (_matIndex != -1)
{
newMatIndex = worldMesh.IndexOfMaterial(
mesh->MaterialByIndex(_matIndex).get());
if (_matIndex < 0)
{
newMatIndex = worldMesh.AddMaterial(
mesh->MaterialByIndex(_matIndex));
}
}
else
{
newMatIndex = worldMesh.AddMaterial(mat);
}

subm.lock()->SetMaterialIndex(newMatIndex);
subm.lock()->Scale(scale);
subMeshMatrix.push_back(matrix);
};

if (_geom->Data().Type() == sdf::GeometryType::BOX)
Expand All @@ -126,9 +141,10 @@ class ignition::gazebo::systems::ColladaWorldExporterPrivate
{
mesh = meshManager->MeshByName("unit_box");
scale = _geom->Data().BoxShape()->Size();
int i = worldMesh.AddMaterial(mat);
subm = worldMesh.AddSubMesh(
*mesh->SubMeshByIndex(0).lock().get());

addSubmeshFunc(i, 0);
addSubmeshFunc(-1);
}
}
else if (_geom->Data().Type() == sdf::GeometryType::CYLINDER)
Expand All @@ -139,10 +155,10 @@ class ignition::gazebo::systems::ColladaWorldExporterPrivate
scale.X() = _geom->Data().CylinderShape()->Radius() * 2;
scale.Y() = scale.X();
scale.Z() = _geom->Data().CylinderShape()->Length();
subm = worldMesh.AddSubMesh(
*mesh->SubMeshByIndex(0).lock().get());

int i = worldMesh.AddMaterial(mat);

addSubmeshFunc(i, 0);
addSubmeshFunc(-1);
}
}
else if (_geom->Data().Type() == sdf::GeometryType::PLANE)
Expand All @@ -164,9 +180,10 @@ class ignition::gazebo::systems::ColladaWorldExporterPrivate
worldPose.Rot() = worldPose.Rot() * normalRot;

matrix = math::Matrix4d(worldPose);
subm = worldMesh.AddSubMesh(
*mesh->SubMeshByIndex(0).lock().get());

int i = worldMesh.AddMaterial(mat);
addSubmeshFunc(i, 0);
addSubmeshFunc(-1);
}
}
else if (_geom->Data().Type() == sdf::GeometryType::SPHERE)
Expand All @@ -179,8 +196,10 @@ class ignition::gazebo::systems::ColladaWorldExporterPrivate
scale.Y() = scale.X();
scale.Z() = scale.X();

int i = worldMesh.AddMaterial(mat);
addSubmeshFunc(i, 0);
subm = worldMesh.AddSubMesh(
*mesh->SubMeshByIndex(0).lock().get());

addSubmeshFunc(-1);
}
}
else if (_geom->Data().Type() == sdf::GeometryType::MESH)
Expand All @@ -200,27 +219,22 @@ class ignition::gazebo::systems::ColladaWorldExporterPrivate
return true;
}

for (unsigned int k = 0; k < mesh->SubMeshCount(); k++)
const auto subMeshName = _geom->Data().MeshShape()->Submesh();
scale = _geom->Data().MeshShape()->Scale();
if(subMeshName == "")
{
auto subMeshLock = mesh->SubMeshByIndex(k).lock();
int j = subMeshLock->MaterialIndex();

int i = 0;
if (j != -1)
for (unsigned int k = 0; k < mesh->SubMeshCount(); k++)
{
i = worldMesh.IndexOfMaterial(mesh->MaterialByIndex(j).get());
if (i < 0)
{
i = worldMesh.AddMaterial(mesh->MaterialByIndex(j));
}
auto subMeshLock = mesh->SubMeshByIndex(k).lock();
subm = worldMesh.AddSubMesh(*subMeshLock.get());
addSubmeshFunc(subMeshLock->MaterialIndex());
}
else
{
i = worldMesh.AddMaterial(mat);
}

scale = _geom->Data().MeshShape()->Scale();
addSubmeshFunc(i, k);
}
else
{
auto subMeshLock = mesh->SubMeshByName(subMeshName).lock();
subm = worldMesh.AddSubMesh(*subMeshLock.get());
addSubmeshFunc(subMeshLock->MaterialIndex());
}
}
else
Expand Down
11 changes: 11 additions & 0 deletions test/integration/collada_world_exporter.cc
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,11 @@

#include <gtest/gtest.h>

#include <ignition/common/ColladaLoader.hh>
#include <ignition/common/Console.hh>
#include <ignition/common/Filesystem.hh>
#include <ignition/common/Mesh.hh>
#include <ignition/common/SubMesh.hh>

#include "ignition/gazebo/Server.hh"
#include "ignition/gazebo/test_config.hh"
Expand Down Expand Up @@ -95,6 +98,14 @@ TEST_F(ColladaWorldExporterFixture, ExportWorldFromFuelWithSubmesh)
// The export directory should now exist.
EXPECT_TRUE(common::exists(outputPath));

// Original .dae file has two submeshes
// .sdf loads them together and a submesh alone
// Check that output has three nodes
common::ColladaLoader loader;
const common::Mesh *meshExported = loader.Load(common::joinPaths(
outputPath, "meshes", "collada_world_exporter_submesh_test.dae"));
EXPECT_EQ(3u, meshExported->SubMeshCount());

// Cleanup
common::removeAll(outputPath);
}
Expand Down
11 changes: 11 additions & 0 deletions test/worlds/models/mesh_with_submeshes/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,17 @@
<model name='scheme_resource_uri'>
<pose>0 0 1 0 0 0</pose>
<link name='the_link'>
<visual name='visual_submesh'>
<geometry>
<mesh>
<uri>model://mesh_with_submeshes/meshes/mesh_with_submeshes.dae</uri>
<submesh>
<name>node_0</name>
<center>false</center>
</submesh>
</mesh>
</geometry>
</visual>
<visual name='the_visual'>
<geometry>
<mesh>
Expand Down