15 #include <type_traits> 46 template <
typename InputType,
typename ComputeType>
67 int numIndices,
int const*
indices,
73 inline std::vector<int>
const&
GetHull()
const;
98 void ProcessFace(std::shared_ptr<Triangle>
const& supportTri,
100 std::map<std::shared_ptr<Triangle>,
int>
const& triNormalMap,
124 std::array<std::pair<ComputeType, int>, 4>& A,
int& numA)
const;
129 std::array<int, 4>
SortAngles(
std::array<std::pair<ComputeType, int>, 4>
const& A,
int numA)
const;
132 std::array<int, 4>
const& sort,
Vector3<ComputeType> const& N, std::vector<int>
const& polyline,
180 template <
typename InputType,
typename ComputeType>
193 mHalf((InputType)0.5)
197 template <
typename InputType,
typename ComputeType>
221 itMinBox.
extent[0] = (InputType)0;
222 itMinBox.
extent[1] = (InputType)0;
223 itMinBox.
extent[2] = (InputType)0;
236 InputType tmin = (InputType)0, tmax = (InputType)0;
237 int imin = 0, imax = 0;
255 itMinBox.
extent[0] = ((InputType)0.5)*(tmax - tmin);
256 itMinBox.
extent[1] = (InputType)0;
257 itMinBox.
extent[2] = (InputType)0;
281 std::vector<Vector2<InputType>> projection(
mNumPoints);
285 projection[i][0] =
Dot(basis[1], diff);
286 projection[i][1] =
Dot(basis[2], diff);
294 itMinBox.
center = origin + rectangle.
center[0] * basis[1] + rectangle.
center[1] * basis[2];
295 itMinBox.
axis[0] = rectangle.
axis[0][0] * basis[1] + rectangle.
axis[0][1] * basis[2];
296 itMinBox.
axis[1] = rectangle.
axis[1][0] * basis[1] + rectangle.
axis[1][1] * basis[2];
297 itMinBox.
axis[2] = basis[0];
300 itMinBox.
extent[2] = (InputType)0;
312 for (
int i = 0; i < 3; ++i, ++
h)
314 int index = element.first.V[i];
322 Box minBox, minBoxEdges;
328 std::thread doEdges([
this, &mesh, &minBoxEdges]()
344 minBox = minBoxEdges;
352 template <
typename InputType,
typename ComputeType>
355 int const*
indices,
bool useRotatingCalipers)
365 int numTriangles = numIndices / 3;
366 for (
int t = 0;
t < numTriangles; ++
t)
380 for (
int i = 0; i < 3; ++i, ++
h)
382 int index = element.first.V[i];
389 std::vector<Vector3<ComputeType>> computePoints(
mNumPoints);
392 for (
int j = 0; j < 3; ++j)
394 computePoints[i][j] = (ComputeType)
mPoints[i][j];
401 Box minBox, minBoxEdges;
407 std::thread doEdges([
this, &mesh, &minBoxEdges]()
422 minBox = minBoxEdges;
430 template <
typename InputType,
typename ComputeType>
inline 436 template <
typename InputType,
typename ComputeType>
inline 443 template <
typename InputType,
typename ComputeType>
inline 450 template <
typename InputType,
typename ComputeType>
inline 456 template <
typename InputType,
typename ComputeType>
467 std::vector<Vector3<ComputeType>> normal(tmap.size());
468 std::map<std::shared_ptr<Triangle>,
int> triNormalMap;
470 for (
auto const& element : tmap)
472 auto tri = element.second;
479 triNormalMap[tri] = index++;
487 unsigned int numFaces =
static_cast<unsigned int>(tmap.size());
492 std::vector<std::shared_ptr<Triangle>> triangles;
493 triangles.reserve(numFaces);
494 for (
auto const& element : tmap)
496 triangles.push_back(element.second);
500 unsigned int numFacesPerThread = numFaces /
mNumThreads;
505 imin[
t] =
t * numFacesPerThread;
506 imax[
t] = imin[
t] + numFacesPerThread - 1;
509 imax[mNumThreads - 1] = numFaces - 1;
512 std::vector<std::thread> process(mNumThreads);
515 process[
t] = std::thread([
this,
t, &imin, &imax, &triangles,
516 &normal, &triNormalMap, &emap, &localMinBox]()
518 for (
unsigned int i = imin[
t]; i <= imax[
t]; ++i)
520 auto const& supportTri = triangles[i];
521 ProcessFace(supportTri, normal, triNormalMap, emap, localMinBox[
t]);
534 minBox = localMinBox[
t];
540 for (
auto const& element : tmap)
542 auto const& supportTri = element.second;
543 ProcessFace(supportTri, normal, triNormalMap, emap, minBox);
548 template <
typename InputType,
typename ComputeType>
559 std::array<ComputeType, 3> sqrLenU;
562 auto e2 = emap.begin(),
end = emap.end();
563 for (; e2 !=
end; ++e2)
567 for (++e1; e1 !=
end; ++e1)
574 sqrLenU[1] =
Dot(U[1], U[1]);
577 for (++e0; e0 !=
end; ++e0)
580 sqrLenU[0] =
Dot(U[0], U[0]);
589 U[2] =
Cross(U[0], U[1]);
590 sqrLenU[2] = sqrLenU[0] * sqrLenU[1];
594 std::array<ComputeType, 3> umin, umax;
595 for (
int j = 0; j < 3; ++j)
604 for (
int j = 0; j < 3; ++j)
606 ComputeType dot =
Dot(diff, U[j]);
611 else if (dot > umax[j])
618 ComputeType volume = (umax[0] - umin[0]) / sqrLenU[0];
619 volume *= (umax[1] - umin[1]) / sqrLenU[1];
620 volume *= (umax[2] - umin[2]);
634 for (
int j = 0; j < 3; ++j)
637 minBox.
sqrLenU[j] = sqrLenU[j];
638 for (
int k = 0; k < 3; ++k)
640 minBox.
range[k][0] = umin[k];
641 minBox.
range[k][1] = umax[k];
652 template <
typename InputType,
typename ComputeType>
654 std::vector<
Vector3<ComputeType>>
const& normal, std::map<std::shared_ptr<Triangle>,
int>
const& triNormalMap,
664 int polylineStart = -1;
665 for (
auto const& edgeElement : emap)
667 auto const& edge = *edgeElement.second;
668 auto const& tri0 = edge.T[0].lock();
669 auto const& tri1 = edge.T[1].lock();
670 auto const& normal0 = normal[triNormalMap.find(tri0)->second];
671 auto const& normal1 = normal[triNormalMap.find(tri1)->second];
672 ComputeType dot0 =
Dot(supportNormal, normal0);
673 ComputeType dot1 =
Dot(supportNormal, normal1);
675 std::shared_ptr<Triangle> tri;
676 if (dot0 < mZero && dot1 >=
mZero)
680 else if (dot1 < mZero && dot0 >=
mZero)
691 for (
int j0 = 2, j1 = 0; j1 < 3; j0 = j1++)
693 if (tri->V[j1] == edge.V[0])
695 if (tri->V[j0] == edge.V[1])
697 polyline[edge.V[1]] = edge.V[0];
701 polyline[edge.V[0]] = edge.V[1];
703 polylineStart = edge.V[0];
714 int numClosedPolyline = 0;
715 int v = polylineStart;
716 for (
auto& cp : closedPolyline)
721 if (v == polylineStart)
726 closedPolyline.resize(numClosedPolyline);
747 localMinBox = faceBox;
751 template <
typename InputType,
typename ComputeType>
755 std::vector<int> tmpPolyline = polyline;
757 int const numPolyline =
static_cast<int>(polyline.size());
758 int numNoncollinear = 0;
762 for (
int i0 = 0, i1 = 1; i0 < numPolyline; ++i0)
765 mComputePoints[tmpPolyline[i1]] - mComputePoints[tmpPolyline[i0]];
767 ComputeType tsp =
DotCross(ePrev, eNext, N);
770 polyline[numNoncollinear++] = tmpPolyline[i0];
774 if (++i1 == numPolyline)
780 polyline.resize(numNoncollinear);
783 template <
typename InputType,
typename ComputeType>
800 int const numPolyline =
static_cast<int>(polyline.size());
801 for (
int i0 = numPolyline - 1, i1 = 0; i1 < numPolyline; i0 = i1++)
814 for (
int j = 0; j < numPolyline; ++j)
817 ComputeType dot =
Dot(U0, diff);
837 ComputeType sqrLenU1 =
Dot(U1, U1);
838 ComputeType volume = (max0 - min0) * max1 / sqrLenU1;
846 box.
range[0][0] = min0;
847 box.
range[0][1] = max0;
848 box.
range[1][1] = max1;
860 if (height < box.
range[2][0])
864 else if (height > box.
range[2][1])
874 template <
typename InputType,
typename ComputeType>
888 std::vector<bool> visited(polyline.size());
889 std::fill(visited.begin(), visited.end(),
false);
900 visited[minRct.index[0]] =
true;
904 for (
size_t i = 0; i < polyline.size(); ++i)
906 std::array<std::pair<ComputeType, int>, 4> A;
915 std::array<int, 4> sort =
SortAngles(A, numA);
919 if (!
UpdateSupport(A, numA, sort, N, polyline, visited, rct))
926 if (rct.
area < minRct.area)
935 box.
U[0] = minRct.U[0];
936 box.
U[1] = minRct.U[1];
938 box.
sqrLenU[0] = minRct.sqrLenU[0];
939 box.
sqrLenU[1] = minRct.sqrLenU[1];
959 if (height < box.
range[2][0])
963 else if (height > box.
range[2][1])
976 template <
typename InputType,
typename ComputeType>
986 rct.
index = { i1, i1, i1, i1 };
992 for (
int j = 0; j < 4; ++j)
998 for (
auto p : polyline)
1009 if (v[0] > support[1][0] ||
1010 (v[0] == support[1][0] && v[1] > support[1][1]))
1017 if (v[1] > support[2][1] ||
1018 (v[1] == support[2][1] && v[0] < support[2][0]))
1025 if (v[0] < support[3][0] ||
1026 (v[0] == support[3][0] && v[1] < support[3][1]))
1039 ComputeType scaledWidth = support[1][0] - support[3][0];
1040 ComputeType scaledHeight = support[2][1];
1041 rct.
area = scaledWidth * scaledHeight / rct.
sqrLenU[1];
1045 template <
typename InputType,
typename ComputeType>
1049 std::array<std::pair<ComputeType, int>, 4>& A,
int& numA)
const 1051 int const numPolyline =
static_cast<int>(polyline.size());
1053 for (
int k0 = 3, k1 = 0; k1 < 4; k0 = k1++)
1058 int lookup = (k0 & 1);
1060 ((k0 & 2) ? -rct.
U[lookup] : rct.
U[lookup]);
1061 int j0 = rct.
index[k0], j1 = j0 + 1;
1062 if (j1 == numPolyline)
1069 E =
Cross(Eperp, N);
1071 ComputeType csqrlen =
Dot(DxE, DxE);
1072 ComputeType dsqrlen = rct.
sqrLenU[lookup];
1073 ComputeType esqrlen =
Dot(E, E);
1074 ComputeType sinThetaSqr = csqrlen / (dsqrlen * esqrlen);
1075 A[numA++] = std::make_pair(sinThetaSqr, k0);
1081 template <
typename InputType,
typename ComputeType>
1083 std::array<std::pair<ComputeType, int>, 4>
const& A,
int numA)
const 1085 std::array<int, 4> sort = { 0, 1, 2, 3 };
1092 std::swap(sort[0], sort[1]);
1099 std::swap(sort[0], sort[1]);
1101 if (A[sort[0]].first > A[sort[2]].first)
1103 std::swap(sort[0], sort[2]);
1105 if (A[sort[1]].first > A[sort[2]].first)
1107 std::swap(sort[1], sort[2]);
1114 std::swap(sort[0], sort[1]);
1116 if (A[sort[2]].first > A[sort[3]].first)
1118 std::swap(sort[2], sort[3]);
1120 if (A[sort[0]].first > A[sort[2]].first)
1122 std::swap(sort[0], sort[2]);
1124 if (A[sort[1]].first > A[sort[3]].first)
1126 std::swap(sort[1], sort[3]);
1128 if (A[sort[1]].first > A[sort[2]].first)
1130 std::swap(sort[1], sort[2]);
1137 template <
typename InputType,
typename ComputeType>
1139 std::array<std::pair<ComputeType, int>, 4>
const& A,
int numA,
1141 std::vector<int>
const& polyline, std::vector<bool>& visited,
1146 int const numPolyline =
static_cast<int>(polyline.size());
1147 auto const& amin = A[sort[0]];
1148 for (
int k = 0; k < numA; ++k)
1150 auto const&
a = A[sort[k]];
1151 if (
a.first == amin.first)
1153 if (++rct.
index[
a.second] == numPolyline)
1165 if (visited[bottom])
1173 std::array<int, 4> nextIndex;
1174 for (
int k = 0; k < 4; ++k)
1176 nextIndex[k] = rct.
index[(amin.second + k) % 4];
1178 rct.
index = nextIndex;
1181 int j1 = rct.
index[0], j0 = j1 - 1;
1184 j1 = numPolyline - 1;
1189 rct.
U[0] =
Cross(rct.
U[1], N);
1201 ComputeType scaledWidth =
Dot(rct.
U[0], diff[0]);
1202 ComputeType scaledHeight =
Dot(rct.
U[1], diff[1]);
1203 rct.
area = scaledWidth * scaledHeight / rct.
sqrLenU[1];
1207 template <
typename InputType,
typename ComputeType>
1212 for (
int i = 0; i < 3; ++i)
1214 ComputeType average =
1216 center += (average / minBox.
sqrLenU[i]) * minBox.
U[i];
1222 for (
int i = 0; i < 3; ++i)
1225 sqrExtent[i] *= sqrExtent[i];
1226 sqrExtent[i] /= minBox.
sqrLenU[i];
1229 for (
int i = 0; i < 3; ++i)
1231 itMinBox.
center[i] = (InputType)center[i];
1232 itMinBox.
extent[i] = sqrt((InputType)sqrExtent[i]);
1240 cmax = std::max(cmax,
std::abs(axis[2]));
1241 ComputeType invCMax =
mOne / cmax;
1242 for (
int j = 0; j < 3; ++j)
1244 itMinBox.
axis[i][j] = (InputType)(axis[j] * invCMax);
Vector3< InputType > const * mPoints
Line3< InputType > const & GetLine() const
void ProcessFaces(ETManifoldMesh const &mesh, Box &minBox)
std::array< Vector< N, Real >, N > axis
EMap const & GetEdges() const
void ComputeBoxForFaceOrderNSqr(Vector3< ComputeType > const &N, std::vector< int > const &polyline, Box &box)
gte::BSNumber< UIntegerType > abs(gte::BSNumber< UIntegerType > const &number)
Vector3< ComputeType > U[2]
std::array< int, 4 > index
OrientedBox3< InputType > operator()(int numPoints, Vector3< InputType > const *points, bool useRotatingCalipers=!std::is_floating_point< ComputeType >::value)
PrimalQuery3< ComputeType > const & GetQuery() const
Vector3< ComputeType > const * mComputePoints
void ConvertTo(Box const &minBox, OrientedBox3< InputType > &itMinBox)
void ProcessFace(std::shared_ptr< Triangle > const &supportTri, std::vector< Vector3< ComputeType >> const &normal, std::map< std::shared_ptr< Triangle >, int > const &triNormalMap, ETManifoldMesh::EMap const &emap, Box &localMinBox)
GLsizei const GLfloat * value
InputType GetVolume() const
void RemoveCollinearPoints(Vector3< ComputeType > const &N, std::vector< int > &polyline)
std::vector< int > const & GetHull() const
ExtrudeRectangle SmallestRectangle(int i0, int i1, Vector3< ComputeType > const &N, std::vector< int > const &polyline)
Vector< N, Real > direction
Vector3< Real > const * GetVertices() const
GLboolean GLboolean GLboolean GLboolean a
std::vector< int > const & GetHull() const
void ProcessEdges(ETManifoldMesh const &mesh, Box &minBox)
GLfixed GLfixed GLint GLint GLfixed points
ETManifoldMesh::Triangle Triangle
GLsizei GLenum const void * indices
std::map< EdgeKey< false >, std::shared_ptr< Edge > > EMap
DualQuaternion< Real > Dot(DualQuaternion< Real > const &d0, DualQuaternion< Real > const &d1)
std::set< int > mUniqueIndices
std::array< int, 4 > SortAngles(std::array< std::pair< ComputeType, int >, 4 > const &A, int numA) const
virtual std::shared_ptr< Triangle > Insert(int v0, int v1, int v2)
Real Normalize(GVector< Real > &v, bool robust=false)
GLint GLsizei GLsizei height
bool UpdateSupport(std::array< std::pair< ComputeType, int >, 4 > const &A, int numA, std::array< int, 4 > const &sort, Vector3< ComputeType > const &N, std::vector< int > const &polyline, std::vector< bool > &visited, ExtrudeRectangle &rct)
DualQuaternion< Real > Cross(DualQuaternion< Real > const &d0, DualQuaternion< Real > const &d1)
Real DotCross(Vector< N, Real > const &v0, Vector< N, Real > const &v1, Vector< N, Real > const &v2)
ETManifoldMesh const & GetHullMesh() const
bool mUseRotatingCalipers
GLfloat GLfloat GLfloat GLfloat h
TMap const & GetTriangles() const
MinimumVolumeBox3(unsigned int numThreads=1, bool threadProcessEdges=false)
GLfloat GLfloat GLfloat v2
Vector3< ComputeType > U[3]
Real ComputeOrthogonalComplement(int numInputs, Vector2< Real > *v, bool robust=false)
Vector3< InputType > const * GetPoints() const
void ComputeBoxForFaceOrderN(Vector3< ComputeType > const &N, std::vector< int > const &polyline, Box &box)
Plane3< InputType > const & GetPlane() const
static Vector Unit(int d)
bool ComputeAngles(Vector3< ComputeType > const &N, std::vector< int > const &polyline, ExtrudeRectangle const &rct, std::array< std::pair< ComputeType, int >, 4 > &A, int &numA) const