From 2a262029fa5d22a895f2f7ee485fbca17dad0d45 Mon Sep 17 00:00:00 2001 From: Ashton Larkin <42042756+adlarkin@users.noreply.github.com> Date: Tue, 5 Apr 2022 11:02:34 -0600 Subject: [PATCH] Fix edge case handling for SubMesh::MaterialIndex (#319) Signed-off-by: Ashton Larkin <42042756+adlarkin@users.noreply.github.com> --- Migration.md | 6 ++++++ graphics/include/ignition/common/SubMesh.hh | 12 +++++++++-- graphics/src/ColladaExporter.cc | 22 +++++++++++---------- graphics/src/ColladaExporter_TEST.cc | 16 +++++++++------ graphics/src/SubMesh.cc | 13 +++++++++++- graphics/src/SubMesh_TEST.cc | 10 ++++++---- 6 files changed, 56 insertions(+), 23 deletions(-) diff --git a/Migration.md b/Migration.md index 1aa67f3a1..8b121ade8 100644 --- a/Migration.md +++ b/Migration.md @@ -7,6 +7,12 @@ release will remove the deprecated code. ## Ignition Common 4.X to 5.X +### Deprecations + +1. `Submesh::MaterialIndex` is deprecated. `SubMesh::GetMaterialIndex` should + be used instead, which properly handles submeshes having no material index + applied to them. + ### Additions 1. **geospatial** component that loads heightmap images and DEMs diff --git a/graphics/include/ignition/common/SubMesh.hh b/graphics/include/ignition/common/SubMesh.hh index 10878b653..d0ccd5062 100644 --- a/graphics/include/ignition/common/SubMesh.hh +++ b/graphics/include/ignition/common/SubMesh.hh @@ -18,6 +18,7 @@ #define IGNITION_COMMON_SUBMESH_HH_ #include +#include #include #include @@ -284,8 +285,15 @@ namespace ignition public: void SetMaterialIndex(const unsigned int _index); /// \brief Get the material index - /// \return The assigned material index. - public: unsigned int MaterialIndex() const; + /// \return The assigned material index. If no material index is assigned + /// to this submesh, std::numeric_limits::max() is returned. + /// \note This method is deprecated, use GetMaterialIndex instead + public: unsigned int IGN_DEPRECATED(5) MaterialIndex() const; + + /// \brief Get the material index + /// \return The assigned material index. Nullopt is returned if the + /// submesh has no assigned material index + public: std::optional GetMaterialIndex() const; /// \brief Return true if this submesh has the vertex /// \param[in] _v Vertex coordinate diff --git a/graphics/src/ColladaExporter.cc b/graphics/src/ColladaExporter.cc index 731cc010c..726639820 100644 --- a/graphics/src/ColladaExporter.cc +++ b/graphics/src/ColladaExporter.cc @@ -488,12 +488,17 @@ void ColladaExporter::Implementation::ExportGeometries( { for (unsigned int i = 0; i < this->subMeshCount; ++i) { - unsigned int materialIndex = - this->mesh->SubMeshByIndex(i).lock()->MaterialIndex(); + std::shared_ptr subMesh = this->mesh->SubMeshByIndex(i).lock(); + if (!subMesh) + continue; char meshId[100], materialId[100]; snprintf(meshId, sizeof(meshId), "mesh_%u", i); - snprintf(materialId, sizeof(materialId), "material_%u", materialIndex); + if (subMesh->GetMaterialIndex()) + { + snprintf(materialId, sizeof(materialId), "material_%u", + subMesh->GetMaterialIndex().value()); + } tinyxml2::XMLElement *geometryXml = _libraryGeometriesXml->GetDocument()->NewElement("geometry"); @@ -504,10 +509,6 @@ void ColladaExporter::Implementation::ExportGeometries( _libraryGeometriesXml->GetDocument()->NewElement("mesh"); geometryXml->LinkEndChild(meshXml); - std::shared_ptr subMesh = this->mesh->SubMeshByIndex(i).lock(); - if (!subMesh) - continue; - this->ExportGeometrySource(subMesh.get(), meshXml, POSITION, meshId); this->ExportGeometrySource(subMesh.get(), meshXml, NORMAL, meshId); if (subMesh->TexCoordCountBySet(0) != 0) @@ -887,9 +888,10 @@ void ColladaExporter::Implementation::ExportVisualScenes( snprintf(attributeValue, sizeof(attributeValue), "#%s", meshId); instanceGeometryXml->SetAttribute("url", attributeValue); - unsigned int materialIndex = - this->mesh->SubMeshByIndex(i).lock()->MaterialIndex(); - + const auto subMesh = this->mesh->SubMeshByIndex(i).lock(); + if (!subMesh->GetMaterialIndex()) + continue; + const auto materialIndex = subMesh->GetMaterialIndex().value(); const ignition::common::MaterialPtr material = this->mesh->MaterialByIndex(materialIndex); diff --git a/graphics/src/ColladaExporter_TEST.cc b/graphics/src/ColladaExporter_TEST.cc index 0f4c3b20d..b82f29831 100644 --- a/graphics/src/ColladaExporter_TEST.cc +++ b/graphics/src/ColladaExporter_TEST.cc @@ -227,20 +227,24 @@ TEST_F(ColladaExporter, ExportMeshWithSubmeshes) std::vector subMeshMatrix; math::Pose3d localPose = math::Pose3d::Zero; + const auto subMesh = boxMesh->SubMeshByIndex(0).lock(); + ASSERT_NE(nullptr, subMesh); + ASSERT_TRUE(subMesh->GetMaterialIndex().has_value()); int i = outMesh.AddMaterial( - boxMesh->MaterialByIndex( - boxMesh->SubMeshByIndex(0).lock()->MaterialIndex())); - subm = outMesh.AddSubMesh(*boxMesh->SubMeshByIndex(0).lock().get()); + boxMesh->MaterialByIndex(subMesh->GetMaterialIndex().value())); + subm = outMesh.AddSubMesh(*subMesh.get()); subm.lock()->SetMaterialIndex(i); localPose.SetX(10); math::Matrix4d matrix(localPose); subMeshMatrix.push_back(matrix); + const auto drillSubMesh = drillMesh->SubMeshByIndex(0).lock(); + ASSERT_NE(nullptr, drillSubMesh); + ASSERT_TRUE(drillSubMesh->GetMaterialIndex().has_value()); i = outMesh.AddMaterial( - drillMesh->MaterialByIndex( - drillMesh->SubMeshByIndex(0).lock()->MaterialIndex())); - subm = outMesh.AddSubMesh(*drillMesh->SubMeshByIndex(0).lock().get()); + drillMesh->MaterialByIndex(drillSubMesh->GetMaterialIndex().value())); + subm = outMesh.AddSubMesh(*drillSubMesh.get()); subm.lock()->SetMaterialIndex(i); localPose.SetX(-10); diff --git a/graphics/src/SubMesh.cc b/graphics/src/SubMesh.cc index 35fa615d9..8baf80466 100644 --- a/graphics/src/SubMesh.cc +++ b/graphics/src/SubMesh.cc @@ -16,7 +16,9 @@ */ #include +#include #include +#include #include #include "ignition/math/Helpers.hh" @@ -52,7 +54,7 @@ class ignition::common::SubMesh::Implementation /// \brief The material index for this mesh. Relates to the parent /// mesh material list. - public: int materialIndex = -1; + public: std::optional materialIndex = std::nullopt; /// \brief The name of the sub-mesh public: std::string name; @@ -493,6 +495,15 @@ void SubMesh::SetMaterialIndex(const unsigned int _index) ////////////////////////////////////////////////// unsigned int SubMesh::MaterialIndex() const +{ + if (this-dataPtr->materialIndex.has_value()) + return this->dataPtr->materialIndex.value(); + + return std::numeric_limits::max(); +} + +////////////////////////////////////////////////// +std::optional SubMesh::GetMaterialIndex() const { return this->dataPtr->materialIndex; } diff --git a/graphics/src/SubMesh_TEST.cc b/graphics/src/SubMesh_TEST.cc index 20772cf49..d36173ed7 100644 --- a/graphics/src/SubMesh_TEST.cc +++ b/graphics/src/SubMesh_TEST.cc @@ -31,7 +31,7 @@ class SubMeshTest : public common::testing::AutoLogFixture { }; TEST_F(SubMeshTest, SubMesh) { common::SubMeshPtr submesh(new common::SubMesh()); - EXPECT_TRUE(submesh != NULL); + ASSERT_NE(nullptr, submesh); submesh->SetName("new_submesh"); EXPECT_EQ(submesh->Name(), "new_submesh"); @@ -39,8 +39,10 @@ TEST_F(SubMeshTest, SubMesh) submesh->SetPrimitiveType(common::SubMesh::TRIANGLES); EXPECT_EQ(submesh->SubMeshPrimitiveType(), common::SubMesh::TRIANGLES); + EXPECT_FALSE(submesh->GetMaterialIndex().has_value()); submesh->SetMaterialIndex(3u); - EXPECT_EQ(submesh->MaterialIndex(), 3u); + ASSERT_TRUE(submesh->GetMaterialIndex().has_value()); + EXPECT_EQ(submesh->GetMaterialIndex(), 3u); // verify empty submesh EXPECT_EQ(submesh->Min(), math::Vector3d::Zero); @@ -238,9 +240,9 @@ TEST_F(SubMeshTest, SubMesh) // copy constructor common::SubMeshPtr submeshCopy(new common::SubMesh(*(submesh.get()))); - EXPECT_TRUE(submeshCopy != NULL); + ASSERT_NE(nullptr, submeshCopy); EXPECT_EQ(submeshCopy->Name(), submesh->Name()); - EXPECT_EQ(submeshCopy->MaterialIndex(), submesh->MaterialIndex()); + EXPECT_EQ(submeshCopy->GetMaterialIndex(), submesh->GetMaterialIndex()); EXPECT_EQ(submeshCopy->SubMeshPrimitiveType(), submesh->SubMeshPrimitiveType()); EXPECT_EQ(submeshCopy->VertexCount(), submesh->VertexCount());