Skip to content

Commit ad1d5ad

Browse files
SubMesh::RecalculateNormals improvement (#609)
Signed-off-by: Maksim Derbasov <[email protected]> Co-authored-by: Dmitry Skorobogaty <[email protected]>
1 parent 1ffd6ef commit ad1d5ad

File tree

3 files changed

+97
-13
lines changed

3 files changed

+97
-13
lines changed

graphics/include/gz/common/SubMesh.hh

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,6 @@
2020
#include <memory>
2121
#include <optional>
2222
#include <string>
23-
#include <vector>
2423

2524
#include <gz/math/Vector3.hh>
2625
#include <gz/math/Vector2.hh>
@@ -158,7 +157,7 @@ namespace gz
158157
public: gz::math::Vector3d Vertex(const unsigned int _index) const;
159158

160159
/// \brief Get the raw vertex pointer. This is unsafe, it is the
161-
/// caller's responsability to ensure it's not indexed out of bounds.
160+
/// caller's responsibility to ensure it's not indexed out of bounds.
162161
/// The valid range is [0; VertexCount())
163162
/// \return Raw vertices
164163
public: const gz::math::Vector3d* VertexPtr() const;
@@ -224,7 +223,7 @@ namespace gz
224223
public: int Index(const unsigned int _index) const;
225224

226225
/// \brief Get the raw index pointer. This is unsafe, it is the
227-
/// caller's responsability to ensure it's not indexed out of bounds.
226+
/// caller's responsibility to ensure it's not indexed out of bounds.
228227
/// The valid range is [0; IndexCount())
229228
/// \return Raw indices
230229
public: const unsigned int* IndexPtr() const;
@@ -416,7 +415,7 @@ namespace gz
416415
GZ_UTILS_IMPL_PTR(dataPtr)
417416
};
418417

419-
/// \brief Vertex to node weighted assignement for skeleton animation
418+
/// \brief Vertex to node weighted assignment for skeleton animation
420419
/// visualization
421420
class GZ_COMMON_GRAPHICS_VISIBLE NodeAssignment
422421
{

graphics/src/SubMesh.cc

Lines changed: 65 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -18,8 +18,8 @@
1818
#include <algorithm>
1919
#include <limits>
2020
#include <map>
21-
#include <optional>
2221
#include <string>
22+
#include <vector>
2323

2424
#include "gz/math/Helpers.hh"
2525

@@ -573,10 +573,67 @@ void SubMesh::FillArrays(double **_vertArr, int **_indArr) const
573573
}
574574
}
575575

576+
namespace {
577+
// Simple way to find neighbors by grouping all vertices
578+
// by X coordinate in (ordered) map. KD-tree maybe better
579+
// but not sure about construction overhead
580+
struct Neighbors
581+
{
582+
Neighbors(const std::vector<unsigned int> &_indices,
583+
const std::vector<gz::math::Vector3d> &_vertices)
584+
: vertices(_vertices)
585+
{
586+
for (unsigned int i = 0; i < _indices.size(); ++i)
587+
{
588+
const auto index = _indices[i];
589+
this->groups[_vertices[index].X()].push_back(index);
590+
}
591+
}
592+
593+
// When we have a concrete point to check, we are looking for
594+
// a group inside a map with a same X.
595+
// Then we check neighbors with the smaller X until
596+
// it's in tolerance of the math::equal function.
597+
// Starting from smallest X, which is in a tolerance range,
598+
// testing all points in group for equality. In case of equality,
599+
// call a Visitor with element index as an argument.
600+
// Continue until a greater side of X tolerance range reached.
601+
template<typename Visitor>
602+
void Visit(const gz::math::Vector3d &_point, Visitor _v) const
603+
{
604+
auto it = this->groups.find(_point.X());
605+
// find smaller acceptable value
606+
while (it != this->groups.begin())
607+
{
608+
auto prev = it;
609+
--prev;
610+
if (!gz::math::equal(prev->first, _point.X()))
611+
break;
612+
it = prev;
613+
}
614+
while (it != this->groups.end()
615+
&& gz::math::equal(it->first, _point.X()))
616+
{
617+
for (const auto index : it->second)
618+
if (this->vertices[index] == _point)
619+
_v(index);
620+
++it;
621+
}
622+
}
623+
624+
// Indexes of vertices grouped by X coordinate
625+
private: std::map<double, std::vector<unsigned int>> groups;
626+
// Const reference to a vertices vector
627+
private: const std::vector<gz::math::Vector3d> &vertices;
628+
};
629+
} // namespace
630+
576631
//////////////////////////////////////////////////
577632
void SubMesh::RecalculateNormals()
578633
{
579-
if (this->dataPtr->normals.size() < 3u)
634+
if (this->dataPtr->primitiveType != SubMesh::TRIANGLES
635+
|| this->dataPtr->indices.empty()
636+
|| this->dataPtr->indices.size() % 3u != 0)
580637
return;
581638

582639
// Reset all the normals
@@ -586,6 +643,8 @@ void SubMesh::RecalculateNormals()
586643
if (this->dataPtr->normals.size() != this->dataPtr->vertices.size())
587644
this->dataPtr->normals.resize(this->dataPtr->vertices.size());
588645

646+
Neighbors neighbors(this->dataPtr->indices, this->dataPtr->vertices);
647+
589648
// For each face, which is defined by three indices, calculate the normals
590649
for (unsigned int i = 0; i < this->dataPtr->indices.size(); i+= 3)
591650
{
@@ -597,14 +656,11 @@ void SubMesh::RecalculateNormals()
597656
this->dataPtr->vertices[this->dataPtr->indices[i+2]];
598657
gz::math::Vector3d n = gz::math::Vector3d::Normal(v1, v2, v3);
599658

600-
for (unsigned int j = 0; j < this->dataPtr->vertices.size(); ++j)
601-
{
602-
gz::math::Vector3d v = this->dataPtr->vertices[j];
603-
if (v == v1 || v == v2 || v == v3)
659+
for (const auto &point : {v1, v2, v3})
660+
neighbors.Visit(point, [&](const unsigned int index)
604661
{
605-
this->dataPtr->normals[j] += n;
606-
}
607-
}
662+
this->dataPtr->normals[index] += n;
663+
});
608664
}
609665

610666
// Normalize the results

graphics/src/SubMesh_TEST.cc

Lines changed: 29 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -585,3 +585,32 @@ TEST_F(SubMeshTest, Volume)
585585
boxSub.AddIndex(1);
586586
EXPECT_DOUBLE_EQ(0.0, boxSub.Volume());
587587
}
588+
589+
/////////////////////////////////////////////////
590+
TEST_F(SubMeshTest, NormalsRecalculation)
591+
{
592+
auto submesh = std::make_shared<common::SubMesh>();
593+
submesh->SetPrimitiveType(common::SubMesh::TRIANGLES);
594+
595+
constexpr unsigned int triangles = 16384;
596+
for (unsigned int i = 0; i < triangles; ++i) {
597+
// sub to X less than _epsilon from even triangles
598+
// expect that the 2nd vertex should be matched with
599+
// the 1st of next triangle
600+
const auto jitter = i % 2 ? 1e-7 : 0.0;
601+
submesh->AddVertex(i-jitter, i, i);
602+
submesh->AddVertex(i+1, i+1, i+1);
603+
submesh->AddVertex(i, i, -static_cast<double>(i));
604+
605+
submesh->AddIndex(3*i);
606+
submesh->AddIndex(3*i+1);
607+
submesh->AddIndex(3*i+2);
608+
}
609+
610+
ASSERT_EQ(submesh->IndexCount() % 3, 0u);
611+
submesh->RecalculateNormals();
612+
ASSERT_EQ(submesh->NormalCount(), submesh->VertexCount());
613+
// Same triangle, but different normals
614+
// because of neighbour vertex
615+
ASSERT_NE(submesh->Normal(0), submesh->Normal(1));
616+
}

0 commit comments

Comments
 (0)