Skip to content

Commit

Permalink
Fix triangulation with CDT and update migration guide (#623)
Browse files Browse the repository at this point in the history
* Fix triangle dir, lint, style
* update migration guide
* Test that Delaunay triangles wind clockwise (#624)

---------

Signed-off-by: Ian Chen <[email protected]>
Signed-off-by: Steve Peters <[email protected]>
Co-authored-by: Steve Peters <[email protected]>
  • Loading branch information
iche033 and scpeters authored Aug 15, 2024
1 parent bb52cce commit 39c6470
Show file tree
Hide file tree
Showing 6 changed files with 55 additions and 13 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -67,8 +67,8 @@ endif()
gz_find_package(FreeImage VERSION 3.9
REQUIRED_BY graphics
PRIVATE_FOR graphics)
#------------------------------------

#------------------------------------
# Find GDAL
gz_find_package(GDAL VERSION 3.0
PKGCONFIG gdal
Expand Down
16 changes: 16 additions & 0 deletions Migration.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,22 @@ Deprecated code produces compile-time warnings. These warning serve as
notification to users that their code should be upgraded. The next major
release will remove the deprecated code.

## Gazebo Common 5.X to 6.X

### Modifications

1. Removed the `graphics` component's dependency on the GTS
(GNU Triangulated Surface) library which was used for doing triangulation
and CSG Boolean operation by the `MeshManager`. The Delaunay triangulation
function now uses the CDT (Constrained Delaunay Triangulation) library.

### Deletions

1. **MeshManager.hh**
+ `void CreateBoolean(const std::string &_name, const Mesh *_m1,
const Mesh *_m2, const int _operation,
const gz::math::Pose3d &_offset = gz::math::Pose3d::Zero)`

## Gazebo Common 4.X to 5.X

### Deprecations
Expand Down
2 changes: 2 additions & 0 deletions graphics/src/CDT/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
URL: https://github.com/artem-ogre/CDT
commit: 46f1ce1f495a97617d90e8c833d0d29406335fdf
25 changes: 14 additions & 11 deletions graphics/src/DelaunayTriangulation.cc
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
/*
* Copyright (C) 2016 Open Source Robotics Foundation
* Copyright (C) 2024 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -42,37 +42,40 @@ bool gz::common::DelaunayTriangulation(
return false;
}

std::vector<CDT::V2d<double>> cdt_verts;
std::vector<CDT::Edge> cdt_edges;
std::vector<CDT::V2d<double>> cdtVerts;
std::vector<CDT::Edge> cdtEdges;

cdt_verts.reserve(_vertices.size());
cdt_edges.reserve(_edges.size());
cdtVerts.reserve(_vertices.size());
cdtEdges.reserve(_edges.size());

for (const auto &vert : _vertices)
{
cdt_verts.push_back({vert.X(), vert.Y()});
cdtVerts.push_back({vert.X(), vert.Y()});
}

for (const auto &edge : _edges)
{
cdt_edges.emplace_back(edge.X(), edge.Y());
cdtEdges.emplace_back(edge.X(), edge.Y());
}

CDT::Triangulation<double> cdt;
cdt.insertVertices(cdt_verts);
cdt.insertEdges(cdt_edges);
cdt.insertVertices(cdtVerts);
cdt.insertEdges(cdtEdges);
cdt.eraseOuterTrianglesAndHoles();

for (const auto & vert : cdt.vertices)
{
_subMesh->AddVertex(vert.x, vert.y, 0.0);
}

// Resulting triangles are counter-clockwise winding
// Add the indices so that they are clockwise winding
// in the submesh
for (const auto & tri : cdt.triangles)
{
_subMesh->AddIndex(tri.vertices[0]);
_subMesh->AddIndex(tri.vertices[1]);
_subMesh->AddIndex(tri.vertices[2]);
_subMesh->AddIndex(tri.vertices[1]);
_subMesh->AddIndex(tri.vertices[0]);
}

return true;
Expand Down
21 changes: 21 additions & 0 deletions graphics/src/DelaunayTriangulation_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -71,4 +71,25 @@ TEST_F(DelaunayTriangulation, DelaunayTriangulation)

// there should be 8 triangles.
EXPECT_EQ(subMesh.IndexCount() / 3u, 8u);

// verify that triangles have clockwise winding
for (int t = 0; t < subMesh.IndexCount() / 3u; ++t)
{
int vertexIndex1 = subMesh.Index(t*3 + 0);
int vertexIndex2 = subMesh.Index(t*3 + 1);
int vertexIndex3 = subMesh.Index(t*3 + 2);
// compute displacement from vertex 1 to 2
auto displacement12 =
subMesh.Vertex(vertexIndex2) - subMesh.Vertex(vertexIndex1);
// compute displacement from vertex 2 to 3
auto displacement23 =
subMesh.Vertex(vertexIndex3) - subMesh.Vertex(vertexIndex2);
// compute cross product (v2-v1) x (v3 - v2)
auto crossProduct_12_23 = displacement12.Cross(displacement23);
// X and Y components should be zero
EXPECT_DOUBLE_EQ(0.0, crossProduct_12_23.X());
EXPECT_DOUBLE_EQ(0.0, crossProduct_12_23.Y());
// Z component should be negative for a clockwise winding
EXPECT_LT(crossProduct_12_23.Z(), 0.0);
}
}
2 changes: 1 addition & 1 deletion graphics/src/MeshManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1576,8 +1576,8 @@ void MeshManager::Tesselate2DMesh(SubMesh *sm, int meshWidth, int meshHeight,
vInc = -vInc;
}
}
//////////////////////////////////////////////////

//////////////////////////////////////////////////
size_t MeshManager::AddUniquePointToVerticesTable(
std::vector<gz::math::Vector2d> &_vertices,
const gz::math::Vector2d &_p,
Expand Down

0 comments on commit 39c6470

Please sign in to comment.