73 template <
typename InputType,
typename ComputeType>
108 inline std::vector<int>
const&
GetIndices()
const;
116 bool GetHull(std::vector<int>& hull)
const;
128 bool GetAdjacencies(
int i, std::array<int, 4>& adjacencies)
const;
196 template <
typename InputType,
typename ComputeType>
210 template <
typename InputType,
typename ComputeType>
214 mEpsilon = std::max(epsilon, (InputType)0);
219 mPlane.constant = (InputType)0;
266 for (j = 0; j < 3; ++j)
287 std::set<Vector3<InputType>> processed;
288 for (i = 0; i < 4; ++i)
290 processed.insert(vertices[info.
extreme[i]]);
294 if (processed.find(vertices[i]) == processed.end())
302 processed.insert(vertices[i]);
308 std::map<std::shared_ptr<Tetrahedron>,
int> permute;
310 permute[
nullptr] = i++;
313 permute[element.second] = i++;
326 std::shared_ptr<Tetrahedron> tetra = element.second;
327 for (j = 0; j < 4; ++j, ++i)
338 template <
typename InputType,
typename ComputeType>
inline 344 template <
typename InputType,
typename ComputeType>
inline 350 template <
typename InputType,
typename ComputeType>
inline 356 template <
typename InputType,
typename ComputeType>
inline 362 template <
typename InputType,
typename ComputeType>
inline 368 template <
typename InputType,
typename ComputeType>
inline 374 template <
typename InputType,
typename ComputeType>
inline 380 template <
typename InputType,
typename ComputeType>
inline 386 template <
typename InputType,
typename ComputeType>
inline 392 template <
typename InputType,
typename ComputeType>
inline 398 template <
typename InputType,
typename ComputeType>
inline 404 template <
typename InputType,
typename ComputeType>
inline 410 template <
typename InputType,
typename ComputeType>
417 int numTriangles = 0;
426 if (numTriangles > 0)
443 hull.resize(3 * numTriangles);
444 int current = 0, i = 0;
445 for (
auto adj : mAdjacencies)
449 int tetra = i / 4,
face = i % 4;
450 for (
int j = 0; j < 4; ++j)
454 hull[current++] =
mIndices[4 * tetra + j];
459 std::swap(hull[current - 1], hull[current - 2]);
468 LogError(
"Unexpected. There must be at least one tetrahedron.");
473 LogError(
"The dimension must be 3.");
478 template <
typename InputType,
typename ComputeType>
483 int numTetrahedra =
static_cast<int>(
mIndices.size() / 4);
484 if (0 <= i && i < numTetrahedra)
495 LogError(
"The dimension must be 3.");
500 template <
typename InputType,
typename ComputeType>
505 int numTetrahedra =
static_cast<int>(
mIndices.size() / 4);
506 if (0 <= i && i < numTetrahedra)
517 LogError(
"The dimension must be 3.");
522 template <
typename InputType,
typename ComputeType>
529 int numTetrahedra =
static_cast<int>(
mIndices.size() / 4);
530 info.
path.resize(numTetrahedra);
545 for (
int i = 0; i < numTetrahedra; ++i)
547 int ibase = 4 * tetrahedron;
561 if (tetrahedron == -1)
576 if (tetrahedron == -1)
591 if (tetrahedron == -1)
606 if (tetrahedron == -1)
622 LogError(
"The dimension must be 3.");
627 template <
typename InputType,
typename ComputeType>
631 for (
int t = 0;
t < numTetrahedra; ++
t)
634 for (j = 0; j < 4; ++j)
637 int v0 = tetra->
V[opposite[j][0]];
638 int v1 = tetra->V[opposite[j][1]];
639 int v2 = tetra->V[opposite[j][2]];
643 auto adjTetra = tetra->S[j].lock();
670 LogError(
"Unexpected termination of GetContainingTetrahedron.");
674 template <
typename InputType,
typename ComputeType>
676 std::set<std::shared_ptr<Tetrahedron>>& candidates, std::set<
TriangleKey<true>>& boundary)
680 while (candidates.size() > 0)
682 std::shared_ptr<Tetrahedron> tetra = *candidates.begin();
683 candidates.erase(candidates.begin());
685 for (
int j = 0; j < 4; ++j)
687 auto adj = tetra->S[j].lock();
688 if (adj && candidates.find(adj) == candidates.end())
697 candidates.insert(adj);
702 int v0 = tetra->V[0];
703 int v1 = tetra->V[1];
704 int v2 = tetra->V[2];
705 int v3 = tetra->V[3];
706 if (!polyhedron.
Insert(v0, v1, v2, v3))
719 std::shared_ptr<Tetrahedron> tetra = element.second;
720 for (
int j = 0; j < 4; ++j)
722 if (!tetra->S[j].lock())
725 int v0 = tetra->
V[opposite[j][0]];
726 int v1 = tetra->V[opposite[j][1]];
727 int v2 = tetra->V[opposite[j][2]];
735 template <
typename InputType,
typename ComputeType>
739 std::shared_ptr<Tetrahedron> tetra = smap.begin()->second;
748 std::set<std::shared_ptr<Tetrahedron>> candidates;
749 candidates.insert(tetra);
754 std::set<TriangleKey<true>> boundary;
762 for (
auto const& key : boundary)
786 std::set<TriangleKey<true>> hull;
787 for (
auto const& element : smap)
789 std::shared_ptr<Tetrahedron>
t = element.second;
790 for (
int j = 0; j < 4; ++j)
795 int v0 = t->
V[opposite[j][0]];
796 int v1 = t->V[opposite[j][1]];
797 int v2 = t->V[opposite[j][2]];
807 std::set<std::shared_ptr<Tetrahedron>> candidates;
808 std::set<TriangleKey<true>> visible;
809 for (
auto const& key : hull)
817 if (iter != tmap.end() && iter->second->T[1].lock() ==
nullptr)
819 auto adj = iter->second->T[0].lock();
820 if (adj && candidates.find(adj) == candidates.end())
829 candidates.insert(adj);
841 LogError(
"Unexpected condition (ComputeType not exact?)");
849 std::set<TriangleKey<true>> boundary;
858 for (
auto const& key : boundary)
872 for (
auto const& key : visible)
TSManifoldMesh const & GetGraph() const
TSManifoldMesh::Tetrahedron Tetrahedron
int ToPlane(int i, int v0, int v1, int v2) const
bool Remove(int v0, int v1, int v2, int v3)
int GetNumTetrahedra() const
Plane3< InputType > const & GetPlane() const
bool operator()(int numVertices, Vector3< InputType > const *vertices, InputType epsilon)
Vector< N, Real > UnitCross(Vector< N, Real > const &v0, Vector< N, Real > const &v1, bool robust=false)
int ToCircumsphere(int i, int v0, int v1, int v2, int v3) const
bool GetAndRemoveInsertionPolyhedron(int i, std::set< std::shared_ptr< Tetrahedron >> &candidates, std::set< TriangleKey< true >> &boundary)
int GetNumUniqueVertices() const
std::vector< int > const & GetIndices() const
PrimalQuery3< ComputeType > mQuery
Vector3< InputType > const * mVertices
GLsizei GLenum const void * indices
bool GetHull(std::vector< int > &hull) const
#define LogError(message)
std::vector< Vector3< ComputeType > > mComputeVertices
GLfloat GLfloat GLfloat GLfloat v3
int GetContainingTetrahedron(Vector3< InputType > const &p, SearchInfo &info) const
InputType GetEpsilon() const
Vector3< Real > direction[3]
int GetNumVertices() const
Line3< InputType > const & GetLine() const
std::array< int, 4 > finalV
PrimalQuery3< ComputeType > const & GetQuery() const
std::vector< int > mAdjacencies
TMap const & GetTriangles() const
void Set(int numVertices, Vector3< Real > const *vertices)
Vector3< InputType > const * GetVertices() const
std::vector< int > mIndices
GLfloat GLfloat GLfloat v2
std::vector< int > const & GetAdjacencies() const
std::shared_ptr< Tetrahedron > Insert(int v0, int v1, int v2, int v3)
Plane3< InputType > mPlane
GLenum GLuint GLint GLenum face
SMap const & GetTetrahedra() const