Go to the documentation of this file.
75 #define CONCAVE_THRESH 0.05f
82 static unsigned int colors[8] =
98 if ( count == 8 ) count = 0;
100 assert( count >= 0 && count < 8 );
102 unsigned int color = colors[count];
134 static void intersect(
const double *p1,
const double *p2,
double *split,
const double *
plane)
142 dir[0] = p2[0] - p1[0];
143 dir[1] = p2[1] - p1[1];
144 dir[2] = p2[2] - p1[2];
147 double dot2 = dp1 -
plane[3];
149 double t = -(
plane[3] + dot2 ) / dot1;
151 split[0] = (dir[0]*t)+p1[0];
152 split[1] = (dir[1]*t)+p1[1];
153 split[2] = (dir[2]*t)+p1[2];
163 CTri(
const double *p1,
const double *p2,
const double *p3,
unsigned int i1,
unsigned int i2,
unsigned int i3)
204 void addTri(
unsigned int *indices,
unsigned int i1,
unsigned int i2,
unsigned int i3,
unsigned int &tcount)
const
206 indices[tcount*3+0] = i1;
207 indices[tcount*3+1] = i2;
208 indices[tcount*3+2] = i3;
214 unsigned int indices[8*3];
217 unsigned int tcount = 0;
219 addTri(indices,0,1,2,tcount);
220 addTri(indices,3,4,5,tcount);
222 addTri(indices,0,3,4,tcount);
223 addTri(indices,0,4,1,tcount);
225 addTri(indices,1,4,5,tcount);
226 addTri(indices,1,5,2,tcount);
228 addTri(indices,0,3,5,tcount);
229 addTri(indices,0,5,2,tcount);
231 const double *vertices =
mP1.
Ptr();
254 for (
unsigned int i=0; i<tcount; i++)
256 unsigned int i1 = indices[i*3+0];
257 unsigned int i2 = indices[i*3+1];
258 unsigned int i3 = indices[i*3+2];
260 const double *p1 = &vertices[ i1*3 ];
261 const double *p2 = &vertices[ i2*3 ];
262 const double *p3 = &vertices[ i3*3 ];
308 const double THRESH = 0.001f;
310 if ( dd > THRESH )
return false;
312 if ( dd > THRESH )
return false;
314 if ( dd > THRESH )
return false;
316 if ( dd > THRESH )
return false;
322 if ( i ==
mI1 || i ==
mI2 || i ==
mI3 )
return true;
329 unsigned int count = 0;
335 if ( count >= 2 ) ret =
true;
443 double neardot = 0.707f;
451 CTriVector::const_iterator i;
455 double near[3] = { 1e9, 1e9, 1e9 };
457 for (i=
tris.begin(); i!=
tris.end(); ++i)
459 const CTri &t = (*i);
480 if ( d1 > 0.001f || d2 > 0.001f || d3 > 0.001f )
503 CTriVector::const_iterator i;
504 for (i=input_mesh.begin(); i!=input_mesh.end(); ++i)
506 const CTri &c = (*i);
563 CTriVector::iterator i;
564 for (i=flist.begin(); i!=flist.end(); ++i)
595 const double *vertices,
597 const unsigned int *indices,
629 double dx = bmax[0] - bmin[0];
630 double dy = bmax[1] - bmin[1];
631 double dz = bmax[2] - bmin[2];
635 center.
x = bmin[0] + dx*0.5f;
636 center.
y = bmin[1] + dy*0.5f;
637 center.
z = bmin[2] + dz*0.5f;
639 double boundVolume = dx*dy*dz;
646 const unsigned int *source = result.
mIndices;
650 for (
unsigned int i=0; i<result.
mNumFaces; i++)
652 unsigned int i1 = *source++;
653 unsigned int i2 = *source++;
654 unsigned int i3 = *source++;
662 CTri t(p1,p2,p3,i1,i2,i3);
668 double totalVolume = 0;
672 const unsigned int *src = indices;
683 const unsigned int *src = indices;
684 for (
unsigned int i=0; i<tcount; i++)
687 unsigned int i1 = *src++;
688 unsigned int i2 = *src++;
689 unsigned int i3 = *src++;
691 const double *p1 = &vertices[i1*3];
692 const double *p2 = &vertices[i2*3];
693 const double *p3 = &vertices[i3*3];
695 CTri t(p1,p2,p3,i1,i2,i3);
696 input_mesh.push_back(t);
702 for (
unsigned int i=0; i<tcount; i++)
705 unsigned int i1 = *src++;
706 unsigned int i2 = *src++;
707 unsigned int i3 = *src++;
709 const double *p1 = &vertices[i1*3];
710 const double *p2 = &vertices[i2*3];
711 const double *p3 = &vertices[i3*3];
713 CTri t(p1,p2,p3,i1,i2,i3);
734 if ( ftris.size() && 0 )
750 double totalarea = 0;
755 CTriVector::iterator i;
756 for (i=ftris.begin(); i!=ftris.end(); ++i)
768 if ( totalarea > maxarea )
770 major_feature = flist;
776 for (
unsigned int i=0; i<ftris.size(); i++)
793 for (
unsigned int i=0; i<major_feature.size(); ++i)
795 major_feature[i].addWeighted(list,callback);
796 major_feature[i].debug(color,callback);
bool Concave(const Vector3d< double > &p, double &distance, Vector3d< double > &n) const
Type Distance(const Vector3d< Type > &a) const
bool featureMatch(CTri &m, const CTriVector &tris, ConvexDecompInterface *callback, const CTriVector &input_mesh)
double planeDistance(const Vector3d< double > &p) const
Vector3d< double > mNear1
void debug(unsigned int color, ConvexDecompInterface *callback)
unsigned int mNumOutputVertices
Vector3d< double > mNormal
bool computeSplitPlane(unsigned int vcount, const double *vertices, unsigned int tcount, const unsigned int *indices, ConvexDecompInterface *callback, double *plane)
HullError CreateConvexHull(const HullDesc &desc, HullResult &result)
double dot(const double3 &a, const double3 &b)
Vector3d< double > mNear2
void addWeighted(WpointVector &list, ConvexDecompInterface *callback)
double computeMeshVolume(const double *vertices, unsigned int tcount, const unsigned int *indices)
Vector3d< double > mNear3
HullError ReleaseResult(HullResult &result)
void NearestPointInTriangle(const Vector3d< Type > &point, const Vector3d< Type > &triangle0, const Vector3d< Type > &triangle1, const Vector3d< Type > &triangle2)
bool hasIndex(unsigned int i) const
double computeConcavity(unsigned int vcount, const double *vertices, unsigned int tcount, const unsigned int *indices, ConvexDecompInterface *callback, double *plane, double &volume)
Type Dot(const Vector3d< Type > &a) const
bool sharesEdge(const CTri &t) const
virtual void ConvexDebugPoint(const double *p, double dist, unsigned int color)
bool lineIntersectsTriangle(const double *rayStart, const double *rayEnd, const double *p1, const double *p2, const double *p3, double *sect)
std::vector< CTri > CTriVector
double getBoundingRegion(unsigned int vcount, const double *points, unsigned int pstride, double *bmin, double *bmax)
double computeMeshVolume2(const double *vertices, unsigned int tcount, const unsigned int *indices)
static void intersect(const double *p1, const double *p2, double *split, const double *plane)
Vector3d< double > mPoint
double ComputePlane(const Vector3d< double > &A, const Vector3d< double > &B, const Vector3d< double > &C)
unsigned int mMaxVertices
unsigned int mVertexStride
void SetHullFlag(HullFlag flag)
static Array< Tri * > tris
Wpoint(const Vector3d< double > &p, double w)
Type Area(const Vector3d< Type > &p1, const Vector3d< Type > &p2) const
virtual void ConvexDebugTri(const double *p1, const double *p2, const double *p3, unsigned int color)
std::vector< Wpoint > WpointVector
bool samePlane(const CTri &t) const
bool clip(const Vector3d< double > &start, Vector3d< double > &end) const
bool isFeatureTri(CTri &t, CTriVector &flist, double fc, ConvexDecompInterface *callback, unsigned int color)
unsigned int getDebugColor(void)
double Facing(const CTri &t)
double getVolume(ConvexDecompInterface *callback) const
static double DistToPt(const double *p, const double *plane)
void addTri(unsigned int *indices, unsigned int i1, unsigned int i2, unsigned int i3, unsigned int &tcount) const
CTri(const double *p1, const double *p2, const double *p3, unsigned int i1, unsigned int i2, unsigned int i3)
bool getBestFitPlane(unsigned int vcount, const double *points, unsigned int vstride, const double *weights, unsigned int wstride, double *plane)
double raySect(const Vector3d< double > &p, const Vector3d< double > &dir, Vector3d< double > §) const