Classes | Typedefs | Enumerations | Functions | Variables
ConvexDecomposition Namespace Reference

Classes

class  Array
 
class  ArrayRet
 
class  BuildMesh
 
class  CHull
 
class  CHullSort
 
class  ConvexBuilder
 
class  ConvexDecompInterface
 
class  ConvexH
 
class  ConvexHullTriangleInterface
 
class  ConvexHullVertex
 
class  ConvexResult
 
class  Coplanar
 
class  CTri
 
class  DecompDesc
 
class  double2
 
class  double3
 
class  double3x3
 
class  double4
 
class  double4x4
 
class  Edge
 
class  EdgeFlag
 
class  Eigen
 
class  FaceTri
 
class  FConvexResult
 
class  FHullResult
 
class  GeometryInterface
 
class  GeometryVertex
 
class  HullDesc
 
class  HullLibrary
 
class  HullResult
 
class  InPlaceParser
 
class  InPlaceParserInterface
 
class  int3
 
class  int4
 
class  Line
 
class  OBJ
 
class  PHullResult
 
class  Plane
 
class  plane
 
class  PlaneFlag
 
class  point
 
class  polygon
 
class  Quaternion
 
class  Rect3d
 
class  Tri
 
class  Vec2d
 
class  Vec3
 
class  Vector2d
 
class  Vector3d
 
class  VertexLess
 
class  VertexPool
 
class  VertexPosition
 
class  VertFlag
 
class  WavefrontObj
 
class  Wpoint
 

Typedefs

typedef std::vector< CHull * > CHullVector
 
typedef std::vector< CTriCTriVector
 
typedef std::vector< EdgeEdgeVector
 
typedef std::vector< double > FloatVector
 
typedef ConvexH::HalfEdge HalfEdge
 
typedef std::vector< int > IntVector
 
typedef std::vector< Vec2dVec2dVector
 
typedef std::vector< Vector2d< double > > Vector2dVector
 
typedef std::vector< Vector3d< double > > Vector3dVector
 
typedef void * VertexLookup
 
typedef std::vector< WpointWpointVector
 

Enumerations

enum  HullError { QE_OK, QE_FAIL }
 
enum  HullFlag { QF_TRIANGLES = (1<<0), QF_REVERSE_ORDER = (1<<1), QF_SKIN_WIDTH = (1<<2), QF_DEFAULT = 0 }
 
enum  PlaneTriResult { PTR_FRONT, PTR_BACK, PTR_SPLIT }
 
enum  RDIFF { RD_EQUAL, RD_LESS, RD_GREATER }
 
enum  SeparatorType { ST_DATA, ST_HARD, ST_SOFT, ST_EOS }
 

Functions

int above (double3 *vertices, const int3 &t, const double3 &p, double epsilon)
 
static void add (const double *p, double *dest, unsigned int tstride, unsigned int &pcount)
 
static void AddPoint (unsigned int &vcount, double *p, double x, double y, double z)
 
static double Area (const Vec2dVector &contour)
 
static double area2 (const double3 &v0, const double3 &v1, const double3 &v2)
 
int argmin (double a[], int n)
 
int AssertIntact (ConvexH &convex)
 
int b2b (const int3 &a, const int3 &b)
 
void b2bfix (Tri *s, Tri *t)
 
int BoxInside (const double3 &p, const double3 &bmin, const double3 &bmax)
 
int BoxIntersect (const double3 &v0, const double3 &v1, const double3 &bmin, const double3 &bmax, double3 *impact)
 
int calchull (double3 *verts, int verts_count, int *&tris_out, int &tris_count, int vlimit)
 
int calchullgen (double3 *verts, int verts_count, int vlimit)
 
int calchullpbev (double3 *verts, int verts_count, int vlimit, Array< Plane > &planes, double bevangle)
 
static int candidateplane (Plane *planes, int planes_count, ConvexH *convex, double epsilon)
 
void checkit (Tri *t)
 
double clampf (double a)
 
double3 cmul (const double3 &a, const double3 &b)
 
double4 cmul (const double4 &a, const double4 &b)
 
void computeBestFitABB (unsigned int vcount, const double *points, unsigned int pstride, double *sides, double *pos)
 
void computeBestFitABB (unsigned int vcount, const float *points, unsigned int pstride, float *sides, float *pos)
 
void computeBestFitOBB (unsigned int vcount, const double *points, unsigned int pstride, double *sides, double *matrix)
 
void computeBestFitOBB (unsigned int vcount, const double *points, unsigned int pstride, double *sides, double *pos, double *quat)
 
void computeBestFitOBB (unsigned int vcount, const float *points, unsigned int pstride, float *sides, float *pos, float *quat)
 
double computeBoundingSphere (unsigned int vcount, const double *points, double *center)
 
float computeBoundingSphere (unsigned int vcount, const float *points, float *center)
 
double computeConcavity (unsigned int vcount, const double *vertices, unsigned int tcount, const unsigned int *indices, ConvexDecompInterface *callback, double *plane, double &volume)
 
bool ComputeHull (unsigned int vcount, const double *vertices, PHullResult &result, unsigned int maxverts, double inflate)
 
double computeMeshVolume (const double *vertices, unsigned int tcount, const unsigned int *indices)
 
float computeMeshVolume (const float *vertices, unsigned int tcount, const unsigned int *indices)
 
double computeMeshVolume2 (const double *vertices, unsigned int tcount, const unsigned int *indices)
 
float computeMeshVolume2 (const float *vertices, unsigned int tcount, const unsigned int *indices)
 
void computeOBB (unsigned int vcount, const double *points, unsigned int pstride, double *sides, double *matrix)
 
static void computePlane (const double *A, const double *B, const double *C, double *plane)
 
double computeSphereVolume (double r)
 
bool computeSplitPlane (unsigned int vcount, const double *vertices, unsigned int tcount, const unsigned int *indices, ConvexDecompInterface *callback, double *plane)
 
ConvexHConvexHCrop (ConvexH &convex, const Plane &slice)
 
ConvexHConvexHDup (ConvexH *src)
 
ConvexHConvexHMakeCube (const REAL3 &bmin, const REAL3 &bmax)
 
int coplanar (const Plane &a, const Plane &b)
 
static void Copy (double *dest, const double *source)
 
static void Copy (float *dest, const float *source)
 
double3 cross (const double3 &a, const double3 &b)
 
void CrossProduct (const double *a, const double *b, double *cross)
 
void CrossProduct (const float *a, const float *b, float *cross)
 
double det (const double *p0, const double *p1, const double *p2, const double *p3)
 
double det (const double *p1, const double *p2, const double *p3)
 
float det (const float *p0, const float *p1, const float *p2, const float *p3)
 
float det (const float *p1, const float *p2, const float *p3)
 
double Determinant (const double3x3 &m)
 
double DistanceBetweenLines (const double3 &ustart, const double3 &udir, const double3 &vstart, const double3 &vdir, double3 *upoint=NULL, double3 *vpoint=NULL)
 
static double DistToPt (const double *p, const double *plane)
 
static double DistToPt (const double *p, const double *plane)
 
double dot (const double3 &a, const double3 &b)
 
double dot (const Quaternion &a, const Quaternion &b)
 
double DotProduct (const double *a, const double *b)
 
float DotProduct (const float *a, const float *b)
 
Triextrudable (double epsilon)
 
void extrude (Tri *t0, int v)
 
bool featureMatch (CTri &m, const CTriVector &tris, ConvexDecompInterface *callback, const CTriVector &input_mesh)
 
int4 FindSimplex (double3 *verts, int verts_count, Array< int > &allow)
 
double fm_capsuleVolume (double radius, double h)
 
void fm_computeNormalVector (double *n, const double *p1, const double *p2)
 
double fm_computePlane (const double *A, const double *B, const double *C, double *n)
 
bool fm_computeWindingOrder (const double *p1, const double *p2, const double *p3)
 
void fm_cross (double *cross, const double *a, const double *b)
 
double fm_cylinderVolume (double radius, double h)
 
double fm_distance (const double *p1, const double *p2)
 
double fm_distanceSquared (const double *p1, const double *p2)
 
double fm_distToPlane (const double *plane, const double *p)
 
double fm_dot (const double *p1, const double *p2)
 
void fm_eulerMatrix (double ax, double ay, double az, double *matrix)
 
void fm_eulerToQuat (double roll, double pitch, double yaw, double *quat)
 
void fm_getAABB (unsigned int vcount, const double *points, unsigned int pstride, double *bmin, double *bmax)
 
void fm_getTranslation (const double *matrix, double *t)
 
void fm_identity (double *matrix)
 
void fm_inverseRT (const double *matrix, const double *pos, double *t)
 
void fm_matrixToQuat (const double *matrix, double *quat)
 
void fm_normalize (double *n)
 
void fm_quatRotate (const double *quat, const double *v, double *r)
 
void fm_quatToMatrix (const double *quat, double *matrix)
 
void fm_rotate (const double *matrix, const double *v, double *t)
 
double fm_sphereVolume (double radius)
 
void fm_transform (const double *matrix, const double *v, double *t)
 
static const char * GetArg (const char **argv, int i, int argc)
 
bool getBestFitPlane (unsigned int vcount, const double *points, unsigned int vstride, const double *weights, unsigned int wstride, double *plane)
 
double getBoundingRegion (unsigned int vcount, const double *points, unsigned int pstride, double *bmin, double *bmax)
 
unsigned int getDebugColor (void)
 
double GetDist (double px, double py, double pz, const double *p2)
 
static PlaneTriResult getSidePlane (const double *p, const double *plane, double epsilon)
 
int hasedge (const int3 &t, int a, int b)
 
int hasvert (const int3 &t, int v)
 
bool hasVolume (double3 *verts, int p0, int p1, int p2, int p3)
 
double4 Homogenize (const double3 &v3, const double &w=1.0f)
 
static bool InsideTriangle (double Ax, double Ay, double Bx, double By, double Cx, double Cy, double Px, double Py)
 
double Interpolate (const double &f0, const double &f1, double alpha)
 
double3 Interpolate (const double3 &v0, const double3 &v1, double alpha)
 
Quaternion Interpolate (const Quaternion &q0, const Quaternion &q1, double alpha)
 
static void intersect (const double *p1, const double *p2, double *split, const double *plane)
 
static void intersect (const double *p1, const double *p2, double *split, const double *plane)
 
double3x3 Inverse (const double3x3 &a)
 
double4x4 Inverse (const double4x4 &m)
 
Quaternion Inverse (const Quaternion &q)
 
int isa (const int3 &a, const int3 &b)
 
bool isFeatureTri (CTri &t, CTriVector &flist, double fc, ConvexDecompInterface *callback, unsigned int color)
 
bool lineIntersectsTriangle (const double *rayStart, const double *rayEnd, const double *p1, const double *p2, const double *p3, double *sect)
 
double3 LineProject (const double3 &p0, const double3 &p1, const double3 &a)
 
double LineProjectTime (const double3 &p0, const double3 &p1, const double3 &a)
 
double magnitude (const double3 &v)
 
double4x4 MatrixFromQuatVec (const Quaternion &q, const double3 &v)
 
double4x4 MatrixLookAt (const double3 &eye, const double3 &at, const double3 &up)
 
double4x4 MatrixPerspectiveFov (double fovy, double Aspect, double zn, double zf)
 
double4x4 MatrixRigidInverse (const double4x4 &m)
 
double4x4 MatrixRotationZ (const double angle_radians)
 
double4x4 MatrixTranslation (const double3 &t)
 
double4x4 MatrixTranspose (const double4x4 &m)
 
template<class T >
Max (const T &a, const T &b)
 
template<class T >
int maxdir (const T *p, int count, const T &dir)
 
template<class T >
int maxdirfiltered (const T *p, int count, const T &dir, Array< int > &allow)
 
template<class T >
int maxdirsterid (const T *p, int count, const T &dir, Array< int > &allow)
 
template<class T >
Min (const T &a, const T &b)
 
double3 normalize (const double3 &v)
 
Quaternion normalize (Quaternion a)
 
double3 NormalOf (const double3 *vert, const int n)
 
int operator!= (const double3 &a, const double3 &b)
 
double3 operator* (const double s, const double3 &v)
 
double3 operator* (const double3 &v, const double s)
 
double3 operator* (const double3 &v, const double3x3 &m)
 
double3 operator* (const double3 &v, const Quaternion &q)
 
double3x3 operator* (const double3x3 &m, const double &s)
 
double3 operator* (const double3x3 &m, const double3 &v)
 
double3x3 operator* (const double3x3 &ma, const double3x3 &mb)
 
double4 operator* (const double4 &v, const double4x4 &m)
 
double4 operator* (const double4 &v, double s)
 
double4x4 operator* (const double4x4 &a, const double4x4 &b)
 
Quaternion operator* (const Quaternion &a, const Quaternion &b)
 
Quaternion operator* (const Quaternion &a, double s)
 
double3 operator* (const Quaternion &q, const double3 &v)
 
double4 operator* (double s, const double4 &v)
 
template<class Type >
Vector2d< Type > operator* (Type s, const Vector2d< Type > &v)
 
template<class Type >
Vector3d< Type > operator* (Type s, const Vector3d< Type > &v)
 
double3operator*= (double3 &v, const double s)
 
double3x3operator*= (double3x3 &a, const double &s)
 
Quaternionoperator*= (Quaternion &a, double s)
 
double2 operator+ (const double2 &a, const double2 &b)
 
double3 operator+ (const double3 &a, const double3 &b)
 
double3x3 operator+ (const double3x3 &a, const double3x3 &b)
 
double4 operator+ (const double4 &a, const double4 &b)
 
Quaternion operator+ (const Quaternion &a, const Quaternion &b)
 
double3operator+= (double3 &a, const double3 &b)
 
double3x3operator+= (double3x3 &a, const double3x3 &b)
 
double2 operator- (const double2 &a, const double2 &b)
 
double3 operator- (const double3 &a, const double3 &b)
 
double3 operator- (const double3 &v)
 
double3x3 operator- (const double3x3 &a, const double3x3 &b)
 
double4 operator- (const double4 &a, const double4 &b)
 
double3operator-= (double3 &a, const double3 &b)
 
double3x3operator-= (double3x3 &a, const double3x3 &b)
 
double3 operator/ (const double3 &v, const double s)
 
double3x3 operator/ (const double3x3 &a, const double &s)
 
double3operator/= (double3 &v, const double s)
 
int operator== (const double3 &a, const double3 &b)
 
int operator== (const double4 &a, const double4 &b)
 
int operator== (const double4x4 &a, const double4x4 &b)
 
int operator== (const int3 &a, const int3 &b)
 
int operator== (const Plane &a, const Plane &b)
 
double3 orth (const double3 &v)
 
static int overhull (Plane *planes, int planes_count, double3 *verts, int verts_count, int maxplanes, double3 *&verts_out, int &verts_count_out, int *&faces_out, int &faces_count_out, double inflate)
 
static int overhullv (double3 *verts, int verts_count, int maxplanes, double3 *&verts_out, int &verts_count_out, int *&faces_out, int &faces_count_out, double inflate, double bevangle, int vlimit)
 
bool overlapAABB (const double *bmin1, const double *bmax1, const double *bmin2, const double *bmax2)
 
unsigned int performConvexDecomposition (const DecompDesc &desc)
 
double Pitch (const double3 &v)
 
double Pitch (const Quaternion &q)
 
Plane PlaneFlip (const Plane &plane)
 
double3 PlaneLineIntersection (const Plane &plane, const double3 &p0, const double3 &p1)
 
double3 PlaneProject (const Plane &plane, const double3 &point)
 
int PlaneTest (const Plane &p, const REAL3 &v)
 
PlaneTriResult planeTriIntersection (const double *_plane, const double *triangle, unsigned int tstride, double epsilon, double *front, unsigned int &fcount, double *back, unsigned int &bcount)
 
int PolyHit (const double3 *vert, const int n, const double3 &v0, const double3 &v1, double3 *impact=NULL, double3 *normal=NULL)
 
static bool Process (const Vec2dVector &contour, Vec2dVector &result)
 
bool rayIntersectsTriangle (const double *p, const double *d, const double *v0, const double *v1, const double *v2, double &t)
 
static RDIFF relativeDiff (const double *a, const double *b, double magnitude)
 
void ReleaseHull (PHullResult &result)
 
void removeb2b (Tri *s, Tri *t)
 
double Roll (Quaternion q)
 
int3 roll3 (int3 a)
 
Quaternion RotationArc (double3 v0, double3 v1)
 
double3 Round (const double3 &a, double precision)
 
double Round (double a, double precision)
 
double3 safenormalize (const double3 &v)
 
static void Set (double *n, double x, double y, double z)
 
static void Set (float *n, float x, float y, float z)
 
int shareedge (const int3 &a, const int3 &b)
 
Quaternion slerp (Quaternion a, const Quaternion &b, double interp)
 
static bool Snip (const Vec2dVector &contour, int u, int v, int w, int n, int *V)
 
void Split_Polygon (polygon *poly, plane *part, polygon &front, polygon &back)
 
void splitRect (unsigned int axis, const Rect3d &source, Rect3d &b1, Rect3d &b2, const double *midpoint)
 
int SplitTest (ConvexH &convex, const Plane &plane)
 
double sqr (double a)
 
template<class T >
void Swap (T &a, T &b)
 
ConvexHtest_btbq ()
 
ConvexHtest_cube ()
 
double tetVolume (const double *p0, const double *p1, const double *p2, const double *p3)
 
float tetVolume (const float *p0, const float *p1, const float *p2, const float *p3)
 
double3 ThreePlaneIntersection (const Plane &p0, const Plane &p1, const Plane &p2)
 
double3x3 Transpose (const double3x3 &m)
 
unsigned int triangulate2d (unsigned int pcount, const double *vertices, double *triangles, unsigned int maxTri)
 
unsigned int triangulate3d (unsigned int pcount, const double *vertices, double *triangles, unsigned int maxTri, const double *plane)
 
unsigned int triangulate3d (unsigned int pcount, const unsigned int *indices, const double *vertices, double *triangles, unsigned int maxTri, const double *plane)
 
double3 TriNormal (const double3 &v0, const double3 &v1, const double3 &v2)
 
double3 vabs (const double3 &v)
 
double3 VectorMax (const double3 &a, const double3 &b)
 
double3 VectorMin (const double3 &a, const double3 &b)
 
Quaternion VirtualTrackBall (const double3 &cop, const double3 &cor, const double3 &dir0, const double3 &dir1)
 
VertexLookup Vl_createVertexLookup (void)
 
unsigned int Vl_getIndex (VertexLookup vlook, const double *pos)
 
unsigned int Vl_getVcount (VertexLookup vlook)
 
const double * Vl_getVertices (VertexLookup vlook)
 
void Vl_releaseVertexLookup (VertexLookup vlook)
 
double Yaw (const double3 &v)
 
double Yaw (const Quaternion &q)
 
Quaternion YawPitchRoll (double yaw, double pitch, double roll)
 

Variables

int countpolyhit =0
 
const double DEG_TO_RAD = ((2.0f * 3.14152654f) / 360.0f)
 
static const double EPSILON =0.0000000001f
 
const double FM_DEG_TO_RAD = ((2.0f * FM_PI) / 360.0f)
 
const double FM_PI = 3.141592654f
 
const double FM_RAD_TO_DEG = (360.0f / (2.0f * FM_PI))
 
double minadjangle = 3.0f
 
double planetestepsilon = PAPERWIDTH
 
const double RAD_TO_DEG = (360.0f / (2.0f * 3.141592654f))
 
double tmpp [3] = {0,0,0}
 
static Array< Tri * > tris
 

Detailed Description

Copyright (c) 2007 by John W. Ratcliff jratc.nosp@m.liff.nosp@m.@infi.nosp@m.nipl.nosp@m.ex.ne.nosp@m.t

Portions of this source has been released with the PhysXViewer application, as well as Rocket, CreateDynamics, ODF, and as a number of sample code snippets.

If you find this code useful or you are feeling particularily generous I would ask that you please go to http://www.amillionpixels.us and make a donation to Troy DeMolay.

DeMolay is a youth group for young men between the ages of 12 and 21.
It teaches strong moral principles, as well as leadership skills and public speaking. The donations page uses the 'pay for pixels' paradigm where, in this case, a pixel is only a single penny. Donations can be made for as small as $4 or as high as a $100 block. Each person who donates will get a link to their own site as well as acknowledgement on the donations blog located here http://www.amillionpixels.blogspot.com/

If you wish to contact me you can use the following methods:

Skype Phone: 636-486-4040 (let it ring a long time while it goes through switches) Skype ID: jratcliff63367 Yahoo: jratcliff63367 AOL: jratcliff1961 email: jratc.nosp@m.liff.nosp@m.@infi.nosp@m.nipl.nosp@m.ex.ne.nosp@m.t Personal website: http://jratcliffscarab.blogspot.com Coding Website: http://codesuppository.blogspot.com FundRaising Blog: http://amillionpixels.blogspot.com Fundraising site: http://www.amillionpixels.us New Temple Site: http://newtemple.blogspot.com

The MIT license:

Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions:

The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software.

THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.

Copyright (c) 2007 by John W. Ratcliff jratc.nosp@m.liff.nosp@m.@infi.nosp@m.nipl.nosp@m.ex.ne.nosp@m.t

Portions of this source has been released with the PhysXViewer application, as well as Rocket, CreateDynamics, ODF, and as a number of sample code snippets.

If you find this code useful or you are feeling particularily generous I would ask that you please go to http://www.amillionpixels.us and make a donation to Troy DeMolay.

DeMolay is a youth group for young men between the ages of 12 and 21. It teaches strong moral principles, as well as leadership skills and public speaking. The donations page uses the 'pay for pixels' paradigm where, in this case, a pixel is only a single penny. Donations can be made for as small as $4 or as high as a $100 block. Each person who donates will get a link to their own site as well as acknowledgement on the donations blog located here http://www.amillionpixels.blogspot.com/

If you wish to contact me you can use the following methods:

Skype Phone: 636-486-4040 (let it ring a long time while it goes through switches) Skype ID: jratcliff63367 Yahoo: jratcliff63367 AOL: jratcliff1961 email: jratc.nosp@m.liff.nosp@m.@infi.nosp@m.nipl.nosp@m.ex.ne.nosp@m.t Personal website: http://jratcliffscarab.blogspot.com Coding Website: http://codesuppository.blogspot.com FundRaising Blog: http://amillionpixels.blogspot.com Fundraising site: http://www.amillionpixels.us New Temple Site: http://newtemple.blogspot.com

The MIT license:

Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions:

The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software.

THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.

Typedef Documentation

◆ CHullVector

Definition at line 191 of file ConvexDecomposition.cpp.

◆ CTriVector

Definition at line 436 of file concavity.cpp.

◆ EdgeVector

Definition at line 110 of file ConvexDecomposition.cpp.

◆ FloatVector

Definition at line 76 of file cd_wavefront.cpp.

◆ HalfEdge

Definition at line 1673 of file cd_hull.cpp.

◆ IntVector

Definition at line 75 of file cd_wavefront.cpp.

◆ Vec2dVector

Definition at line 99 of file triangulate.cpp.

◆ Vector2dVector

Definition at line 1197 of file cd_vector.h.

◆ Vector3dVector

Definition at line 1196 of file cd_vector.h.

◆ VertexLookup

Definition at line 130 of file vlookup.h.

◆ WpointVector

Definition at line 121 of file concavity.cpp.

Enumeration Type Documentation

◆ HullError

Enumerator
QE_OK 
QE_FAIL 

Definition at line 197 of file cd_hull.h.

◆ HullFlag

Enumerator
QF_TRIANGLES 
QF_REVERSE_ORDER 
QF_SKIN_WIDTH 
QF_DEFAULT 

Definition at line 135 of file cd_hull.h.

◆ PlaneTriResult

Enumerator
PTR_FRONT 
PTR_BACK 
PTR_SPLIT 

Definition at line 63 of file planetri.h.

◆ RDIFF

Enumerator
RD_EQUAL 
RD_LESS 
RD_GREATER 

Definition at line 261 of file vlookup.cpp.

◆ SeparatorType

Enumerator
ST_DATA 
ST_HARD 
ST_SOFT 
ST_EOS 

Definition at line 91 of file cd_wavefront.cpp.

Function Documentation

◆ above()

int ConvexDecomposition::above ( double3 vertices,
const int3 t,
const double3 p,
double  epsilon 
)

Definition at line 2361 of file cd_hull.cpp.

◆ add()

static void ConvexDecomposition::add ( const double *  p,
double *  dest,
unsigned int  tstride,
unsigned int &  pcount 
)
static

Definition at line 89 of file planetri.cpp.

◆ AddPoint()

static void ConvexDecomposition::AddPoint ( unsigned int &  vcount,
double *  p,
double  x,
double  y,
double  z 
)
static

Definition at line 3165 of file cd_hull.cpp.

◆ Area()

double ConvexDecomposition::Area ( const Vec2dVector contour)
static

Definition at line 108 of file triangulate.cpp.

◆ area2()

static double ConvexDecomposition::area2 ( const double3 v0,
const double3 v1,
const double3 v2 
)
static

Definition at line 2693 of file cd_hull.cpp.

◆ argmin()

int ConvexDecomposition::argmin ( double  a[],
int  n 
)

Definition at line 607 of file cd_hull.cpp.

◆ AssertIntact()

int ConvexDecomposition::AssertIntact ( ConvexH convex)

Definition at line 1743 of file cd_hull.cpp.

◆ b2b()

int ConvexDecomposition::b2b ( const int3 a,
const int3 b 
)

Definition at line 2357 of file cd_hull.cpp.

◆ b2bfix()

void ConvexDecomposition::b2bfix ( Tri s,
Tri t 
)

Definition at line 2435 of file cd_hull.cpp.

◆ BoxInside()

int ConvexDecomposition::BoxInside ( const double3 p,
const double3 bmin,
const double3 bmax 
)

Definition at line 1382 of file cd_hull.cpp.

◆ BoxIntersect()

int ConvexDecomposition::BoxIntersect ( const double3 v0,
const double3 v1,
const double3 bmin,
const double3 bmax,
double3 impact 
)

Definition at line 1390 of file cd_hull.cpp.

◆ calchull()

int ConvexDecomposition::calchull ( double3 verts,
int  verts_count,
int *&  tris_out,
int &  tris_count,
int  vlimit 
)

Definition at line 2675 of file cd_hull.cpp.

◆ calchullgen()

int ConvexDecomposition::calchullgen ( double3 verts,
int  verts_count,
int  vlimit 
)

Definition at line 2572 of file cd_hull.cpp.

◆ calchullpbev()

int ConvexDecomposition::calchullpbev ( double3 verts,
int  verts_count,
int  vlimit,
Array< Plane > &  planes,
double  bevangle 
)

Definition at line 2698 of file cd_hull.cpp.

◆ candidateplane()

static int ConvexDecomposition::candidateplane ( Plane planes,
int  planes_count,
ConvexH convex,
double  epsilon 
)
static

Definition at line 2203 of file cd_hull.cpp.

◆ checkit()

void ConvexDecomposition::checkit ( Tri t)

Definition at line 2458 of file cd_hull.cpp.

◆ clampf()

double ConvexDecomposition::clampf ( double  a)

Definition at line 592 of file cd_hull.cpp.

◆ cmul() [1/2]

double3 ConvexDecomposition::cmul ( const double3 a,
const double3 b 
)

Definition at line 666 of file cd_hull.cpp.

◆ cmul() [2/2]

double4 ConvexDecomposition::cmul ( const double4 a,
const double4 b 
)

Definition at line 908 of file cd_hull.cpp.

◆ computeBestFitABB() [1/2]

void ConvexDecomposition::computeBestFitABB ( unsigned int  vcount,
const double *  points,
unsigned int  pstride,
double *  sides,
double *  pos 
)

Definition at line 242 of file bestfitobb.cpp.

◆ computeBestFitABB() [2/2]

void ConvexDecomposition::computeBestFitABB ( unsigned int  vcount,
const float *  points,
unsigned int  pstride,
float *  sides,
float *  pos 
)

Definition at line 328 of file bestfitobb.cpp.

◆ computeBestFitOBB() [1/3]

void ConvexDecomposition::computeBestFitOBB ( unsigned int  vcount,
const double *  points,
unsigned int  pstride,
double *  sides,
double *  matrix 
)

Definition at line 142 of file bestfitobb.cpp.

◆ computeBestFitOBB() [2/3]

void ConvexDecomposition::computeBestFitOBB ( unsigned int  vcount,
const double *  points,
unsigned int  pstride,
double *  sides,
double *  pos,
double *  quat 
)

Definition at line 231 of file bestfitobb.cpp.

◆ computeBestFitOBB() [3/3]

void ConvexDecomposition::computeBestFitOBB ( unsigned int  vcount,
const float *  points,
unsigned int  pstride,
float *  sides,
float *  pos,
float *  quat 
)

Definition at line 283 of file bestfitobb.cpp.

◆ computeBoundingSphere() [1/2]

double ConvexDecomposition::computeBoundingSphere ( unsigned int  vcount,
const double *  points,
double *  center 
)

Definition at line 99 of file fitsphere.cpp.

◆ computeBoundingSphere() [2/2]

float ConvexDecomposition::computeBoundingSphere ( unsigned int  vcount,
const float *  points,
float *  center 
)

Definition at line 244 of file fitsphere.cpp.

◆ computeConcavity()

double ConvexDecomposition::computeConcavity ( unsigned int  vcount,
const double *  vertices,
unsigned int  tcount,
const unsigned int *  indices,
ConvexDecompInterface callback,
double *  plane,
double &  volume 
)

Definition at line 594 of file concavity.cpp.

◆ ComputeHull()

bool ConvexDecomposition::ComputeHull ( unsigned int  vcount,
const double *  vertices,
PHullResult result,
unsigned int  maxverts,
double  inflate 
)

Definition at line 2880 of file cd_hull.cpp.

◆ computeMeshVolume() [1/2]

double ConvexDecomposition::computeMeshVolume ( const double *  vertices,
unsigned int  tcount,
const unsigned int *  indices 
)

Definition at line 67 of file meshvolume.cpp.

◆ computeMeshVolume() [2/2]

float ConvexDecomposition::computeMeshVolume ( const float *  vertices,
unsigned int  tcount,
const unsigned int *  indices 
)

Definition at line 162 of file meshvolume.cpp.

◆ computeMeshVolume2() [1/2]

double ConvexDecomposition::computeMeshVolume2 ( const double *  vertices,
unsigned int  tcount,
const unsigned int *  indices 
)

Definition at line 136 of file meshvolume.cpp.

◆ computeMeshVolume2() [2/2]

float ConvexDecomposition::computeMeshVolume2 ( const float *  vertices,
unsigned int  tcount,
const unsigned int *  indices 
)

Definition at line 231 of file meshvolume.cpp.

◆ computeOBB()

void ConvexDecomposition::computeOBB ( unsigned int  vcount,
const double *  points,
unsigned int  pstride,
double *  sides,
double *  matrix 
)

Definition at line 97 of file bestfitobb.cpp.

◆ computePlane()

static void ConvexDecomposition::computePlane ( const double *  A,
const double *  B,
const double *  C,
double *  plane 
)
static

Definition at line 79 of file splitplane.cpp.

◆ computeSphereVolume()

double ConvexDecomposition::computeSphereVolume ( double  r)

Definition at line 373 of file fitsphere.cpp.

◆ computeSplitPlane()

bool ConvexDecomposition::computeSplitPlane ( unsigned int  vcount,
const double *  vertices,
unsigned int  tcount,
const unsigned int *  indices,
ConvexDecompInterface callback,
double *  plane 
)

Definition at line 204 of file splitplane.cpp.

◆ ConvexHCrop()

ConvexH* ConvexDecomposition::ConvexHCrop ( ConvexH convex,
const Plane slice 
)

hmmm something to think about: i might be able to output this edge regarless of

Definition at line 1890 of file cd_hull.cpp.

◆ ConvexHDup()

ConvexH* ConvexDecomposition::ConvexHDup ( ConvexH src)

Definition at line 1685 of file cd_hull.cpp.

◆ ConvexHMakeCube()

ConvexH* ConvexDecomposition::ConvexHMakeCube ( const REAL3 bmin,
const REAL3 bmax 
)

Definition at line 1871 of file cd_hull.cpp.

◆ coplanar()

int ConvexDecomposition::coplanar ( const Plane a,
const Plane b 
)
inline

Definition at line 565 of file cd_hull.cpp.

◆ Copy() [1/2]

static void ConvexDecomposition::Copy ( double *  dest,
const double *  source 
)
inlinestatic

Definition at line 92 of file fitsphere.cpp.

◆ Copy() [2/2]

static void ConvexDecomposition::Copy ( float *  dest,
const float *  source 
)
inlinestatic

Definition at line 235 of file fitsphere.cpp.

◆ cross()

double3 ConvexDecomposition::cross ( const double3 a,
const double3 b 
)

Definition at line 672 of file cd_hull.cpp.

◆ CrossProduct() [1/2]

void ConvexDecomposition::CrossProduct ( const double *  a,
const double *  b,
double *  cross 
)
inline

Definition at line 89 of file meshvolume.cpp.

◆ CrossProduct() [2/2]

void ConvexDecomposition::CrossProduct ( const float *  a,
const float *  b,
float *  cross 
)
inline

Definition at line 184 of file meshvolume.cpp.

◆ det() [1/4]

double ConvexDecomposition::det ( const double *  p0,
const double *  p1,
const double *  p2,
const double *  p3 
)
inline

Definition at line 131 of file meshvolume.cpp.

◆ det() [2/4]

double ConvexDecomposition::det ( const double *  p1,
const double *  p2,
const double *  p3 
)
inline

Definition at line 62 of file meshvolume.cpp.

◆ det() [3/4]

float ConvexDecomposition::det ( const float *  p0,
const float *  p1,
const float *  p2,
const float *  p3 
)
inline

Definition at line 226 of file meshvolume.cpp.

◆ det() [4/4]

float ConvexDecomposition::det ( const float *  p1,
const float *  p2,
const float *  p3 
)
inline

Definition at line 157 of file meshvolume.cpp.

◆ Determinant()

double ConvexDecomposition::Determinant ( const double3x3 m)

Definition at line 786 of file cd_hull.cpp.

◆ DistanceBetweenLines()

double ConvexDecomposition::DistanceBetweenLines ( const double3 ustart,
const double3 udir,
const double3 vstart,
const double3 vdir,
double3 upoint = NULL,
double3 vpoint = NULL 
)

Definition at line 1485 of file cd_hull.cpp.

◆ DistToPt() [1/2]

static double ConvexDecomposition::DistToPt ( const double *  p,
const double *  plane 
)
inlinestatic

Definition at line 68 of file planetri.cpp.

◆ DistToPt() [2/2]

static double ConvexDecomposition::DistToPt ( const double *  p,
const double *  plane 
)
inlinestatic

Definition at line 124 of file concavity.cpp.

◆ dot() [1/2]

double ConvexDecomposition::dot ( const double3 a,
const double3 b 
)

Definition at line 661 of file cd_hull.cpp.

◆ dot() [2/2]

double ConvexDecomposition::dot ( const Quaternion a,
const Quaternion b 
)

Definition at line 1180 of file cd_hull.cpp.

◆ DotProduct() [1/2]

double ConvexDecomposition::DotProduct ( const double *  a,
const double *  b 
)
inline

Definition at line 96 of file meshvolume.cpp.

◆ DotProduct() [2/2]

float ConvexDecomposition::DotProduct ( const float *  a,
const float *  b 
)
inline

Definition at line 191 of file meshvolume.cpp.

◆ extrudable()

Tri* ConvexDecomposition::extrudable ( double  epsilon)

Definition at line 2507 of file cd_hull.cpp.

◆ extrude()

void ConvexDecomposition::extrude ( Tri t0,
int  v 
)

Definition at line 2472 of file cd_hull.cpp.

◆ featureMatch()

bool ConvexDecomposition::featureMatch ( CTri m,
const CTriVector tris,
ConvexDecompInterface callback,
const CTriVector input_mesh 
)

Definition at line 438 of file concavity.cpp.

◆ FindSimplex()

int4 ConvexDecomposition::FindSimplex ( double3 verts,
int  verts_count,
Array< int > &  allow 
)

Definition at line 2542 of file cd_hull.cpp.

◆ fm_capsuleVolume()

double ConvexDecomposition::fm_capsuleVolume ( double  radius,
double  h 
)

Definition at line 313 of file float_math.cpp.

◆ fm_computeNormalVector()

void ConvexDecomposition::fm_computeNormalVector ( double *  n,
const double *  p1,
const double *  p2 
)

Definition at line 414 of file float_math.cpp.

◆ fm_computePlane()

double ConvexDecomposition::fm_computePlane ( const double *  A,
const double *  B,
const double *  C,
double *  n 
)

Definition at line 358 of file float_math.cpp.

◆ fm_computeWindingOrder()

bool ConvexDecomposition::fm_computeWindingOrder ( const double *  p1,
const double *  p2,
const double *  p3 
)

Definition at line 422 of file float_math.cpp.

◆ fm_cross()

void ConvexDecomposition::fm_cross ( double *  cross,
const double *  a,
const double *  b 
)

Definition at line 407 of file float_math.cpp.

◆ fm_cylinderVolume()

double ConvexDecomposition::fm_cylinderVolume ( double  radius,
double  h 
)

Definition at line 308 of file float_math.cpp.

◆ fm_distance()

double ConvexDecomposition::fm_distance ( const double *  p1,
const double *  p2 
)

Definition at line 339 of file float_math.cpp.

◆ fm_distanceSquared()

double ConvexDecomposition::fm_distanceSquared ( const double *  p1,
const double *  p2 
)

Definition at line 348 of file float_math.cpp.

◆ fm_distToPlane()

double ConvexDecomposition::fm_distToPlane ( const double *  plane,
const double *  p 
)

Definition at line 397 of file float_math.cpp.

◆ fm_dot()

double ConvexDecomposition::fm_dot ( const double *  p1,
const double *  p2 
)

Definition at line 402 of file float_math.cpp.

◆ fm_eulerMatrix()

void ConvexDecomposition::fm_eulerMatrix ( double  ax,
double  ay,
double  az,
double *  matrix 
)

Definition at line 127 of file float_math.cpp.

◆ fm_eulerToQuat()

void ConvexDecomposition::fm_eulerToQuat ( double  roll,
double  pitch,
double  yaw,
double *  quat 
)

Definition at line 165 of file float_math.cpp.

◆ fm_getAABB()

void ConvexDecomposition::fm_getAABB ( unsigned int  vcount,
const double *  points,
unsigned int  pstride,
double *  bmin,
double *  bmax 
)

Definition at line 134 of file float_math.cpp.

◆ fm_getTranslation()

void ConvexDecomposition::fm_getTranslation ( const double *  matrix,
double *  t 
)

Definition at line 244 of file float_math.cpp.

◆ fm_identity()

void ConvexDecomposition::fm_identity ( double *  matrix)

Definition at line 102 of file float_math.cpp.

◆ fm_inverseRT()

void ConvexDecomposition::fm_inverseRT ( const double *  matrix,
const double *  pos,
double *  t 
)

Definition at line 86 of file float_math.cpp.

◆ fm_matrixToQuat()

void ConvexDecomposition::fm_matrixToQuat ( const double *  matrix,
double *  quat 
)

Definition at line 251 of file float_math.cpp.

◆ fm_normalize()

void ConvexDecomposition::fm_normalize ( double *  n)

Definition at line 448 of file float_math.cpp.

◆ fm_quatRotate()

void ConvexDecomposition::fm_quatRotate ( const double *  quat,
const double *  v,
double *  r 
)

Definition at line 228 of file float_math.cpp.

◆ fm_quatToMatrix()

void ConvexDecomposition::fm_quatToMatrix ( const double *  quat,
double *  matrix 
)

Definition at line 190 of file float_math.cpp.

◆ fm_rotate()

void ConvexDecomposition::fm_rotate ( const double *  matrix,
const double *  v,
double *  t 
)

Definition at line 331 of file float_math.cpp.

◆ fm_sphereVolume()

double ConvexDecomposition::fm_sphereVolume ( double  radius)

Definition at line 302 of file float_math.cpp.

◆ fm_transform()

void ConvexDecomposition::fm_transform ( const double *  matrix,
const double *  v,
double *  t 
)

Definition at line 324 of file float_math.cpp.

◆ GetArg()

static const char* ConvexDecomposition::GetArg ( const char **  argv,
int  i,
int  argc 
)
static

Definition at line 602 of file cd_wavefront.cpp.

◆ getBestFitPlane()

bool ConvexDecomposition::getBestFitPlane ( unsigned int  vcount,
const double *  points,
unsigned int  vstride,
const double *  weights,
unsigned int  wstride,
double *  plane 
)

Definition at line 292 of file bestfit.cpp.

◆ getBoundingRegion()

double ConvexDecomposition::getBoundingRegion ( unsigned int  vcount,
const double *  points,
unsigned int  pstride,
double *  bmin,
double *  bmax 
)

Definition at line 431 of file bestfit.cpp.

◆ getDebugColor()

unsigned int ConvexDecomposition::getDebugColor ( void  )

Definition at line 80 of file concavity.cpp.

◆ GetDist()

double ConvexDecomposition::GetDist ( double  px,
double  py,
double  pz,
const double *  p2 
)

Definition at line 3175 of file cd_hull.cpp.

◆ getSidePlane()

static PlaneTriResult ConvexDecomposition::getSidePlane ( const double *  p,
const double *  plane,
double  epsilon 
)
static

Definition at line 78 of file planetri.cpp.

◆ hasedge()

int ConvexDecomposition::hasedge ( const int3 t,
int  a,
int  b 
)

Definition at line 2366 of file cd_hull.cpp.

◆ hasvert()

int ConvexDecomposition::hasvert ( const int3 t,
int  v 
)

Definition at line 2375 of file cd_hull.cpp.

◆ hasVolume()

bool ConvexDecomposition::hasVolume ( double3 verts,
int  p0,
int  p1,
int  p2,
int  p3 
)

Definition at line 2533 of file cd_hull.cpp.

◆ Homogenize()

double4 ConvexDecomposition::Homogenize ( const double3 v3,
const double &  w = 1.0f 
)

Definition at line 939 of file cd_hull.cpp.

◆ InsideTriangle()

bool ConvexDecomposition::InsideTriangle ( double  Ax,
double  Ay,
double  Bx,
double  By,
double  Cx,
double  Cy,
double  Px,
double  Py 
)
static

Definition at line 122 of file triangulate.cpp.

◆ Interpolate() [1/3]

double ConvexDecomposition::Interpolate ( const double &  f0,
const double &  f1,
double  alpha 
)

Definition at line 601 of file cd_hull.cpp.

◆ Interpolate() [2/3]

double3 ConvexDecomposition::Interpolate ( const double3 v0,
const double3 v1,
double  alpha 
)

Definition at line 760 of file cd_hull.cpp.

◆ Interpolate() [3/3]

Quaternion ConvexDecomposition::Interpolate ( const Quaternion q0,
const Quaternion q1,
double  alpha 
)

Definition at line 1216 of file cd_hull.cpp.

◆ intersect() [1/2]

static void ConvexDecomposition::intersect ( const double *  p1,
const double *  p2,
double *  split,
const double *  plane 
)
static

Definition at line 103 of file planetri.cpp.

◆ intersect() [2/2]

static void ConvexDecomposition::intersect ( const double *  p1,
const double *  p2,
double *  split,
const double *  plane 
)
static

Definition at line 134 of file concavity.cpp.

◆ Inverse() [1/3]

double3x3 ConvexDecomposition::Inverse ( const double3x3 a)

Definition at line 792 of file cd_hull.cpp.

◆ Inverse() [2/3]

double4x4 ConvexDecomposition::Inverse ( const double4x4 m)

Definition at line 1023 of file cd_hull.cpp.

◆ Inverse() [3/3]

Quaternion ConvexDecomposition::Inverse ( const Quaternion q)

Definition at line 1125 of file cd_hull.cpp.

◆ isa()

int ConvexDecomposition::isa ( const int3 a,
const int3 b 
)

Definition at line 2353 of file cd_hull.cpp.

◆ isFeatureTri()

bool ConvexDecomposition::isFeatureTri ( CTri t,
CTriVector flist,
double  fc,
ConvexDecompInterface callback,
unsigned int  color 
)

Definition at line 547 of file concavity.cpp.

◆ lineIntersectsTriangle()

bool ConvexDecomposition::lineIntersectsTriangle ( const double *  rayStart,
const double *  rayEnd,
const double *  p1,
const double *  p2,
const double *  p3,
double *  sect 
)

Definition at line 123 of file raytri.cpp.

◆ LineProject()

double3 ConvexDecomposition::LineProject ( const double3 p0,
const double3 p1,
const double3 a 
)

Definition at line 1351 of file cd_hull.cpp.

◆ LineProjectTime()

double ConvexDecomposition::LineProjectTime ( const double3 p0,
const double3 p1,
const double3 a 
)

Definition at line 1360 of file cd_hull.cpp.

◆ magnitude()

double ConvexDecomposition::magnitude ( const double3 v)

Definition at line 724 of file cd_hull.cpp.

◆ MatrixFromQuatVec()

double4x4 ConvexDecomposition::MatrixFromQuatVec ( const Quaternion q,
const double3 v 
)

Definition at line 1302 of file cd_hull.cpp.

◆ MatrixLookAt()

double4x4 ConvexDecomposition::MatrixLookAt ( const double3 eye,
const double3 at,
const double3 up 
)

Definition at line 982 of file cd_hull.cpp.

◆ MatrixPerspectiveFov()

double4x4 ConvexDecomposition::MatrixPerspectiveFov ( double  fovy,
double  Aspect,
double  zn,
double  zf 
)

Definition at line 969 of file cd_hull.cpp.

◆ MatrixRigidInverse()

double4x4 ConvexDecomposition::MatrixRigidInverse ( const double4x4 m)

Definition at line 960 of file cd_hull.cpp.

◆ MatrixRotationZ()

double4x4 ConvexDecomposition::MatrixRotationZ ( const double  angle_radians)

Definition at line 1004 of file cd_hull.cpp.

◆ MatrixTranslation()

double4x4 ConvexDecomposition::MatrixTranslation ( const double3 t)

Definition at line 994 of file cd_hull.cpp.

◆ MatrixTranspose()

double4x4 ConvexDecomposition::MatrixTranspose ( const double4x4 m)

Definition at line 951 of file cd_hull.cpp.

◆ Max()

template<class T >
T ConvexDecomposition::Max ( const T &  a,
const T &  b 
)

Definition at line 339 of file cd_hull.cpp.

◆ maxdir()

template<class T >
int ConvexDecomposition::maxdir ( const T *  p,
int  count,
const T &  dir 
)
inline

Definition at line 2254 of file cd_hull.cpp.

◆ maxdirfiltered()

template<class T >
int ConvexDecomposition::maxdirfiltered ( const T *  p,
int  count,
const T &  dir,
Array< int > &  allow 
)

Definition at line 2267 of file cd_hull.cpp.

◆ maxdirsterid()

template<class T >
int ConvexDecomposition::maxdirsterid ( const T *  p,
int  count,
const T &  dir,
Array< int > &  allow 
)

Definition at line 2288 of file cd_hull.cpp.

◆ Min()

template<class T >
T ConvexDecomposition::Min ( const T &  a,
const T &  b 
)

Definition at line 345 of file cd_hull.cpp.

◆ normalize() [1/2]

double3 ConvexDecomposition::normalize ( const double3 v)

Definition at line 731 of file cd_hull.cpp.

◆ normalize() [2/2]

Quaternion ConvexDecomposition::normalize ( Quaternion  a)

Definition at line 1185 of file cd_hull.cpp.

◆ NormalOf()

double3 ConvexDecomposition::NormalOf ( const double3 vert,
const int  n 
)

◆ operator!=()

int ConvexDecomposition::operator!= ( const double3 a,
const double3 b 
)
inline

Definition at line 411 of file cd_hull.cpp.

◆ operator*() [1/16]

double3 ConvexDecomposition::operator* ( const double  s,
const double3 v 
)

Definition at line 650 of file cd_hull.cpp.

◆ operator*() [2/16]

double3 ConvexDecomposition::operator* ( const double3 v,
const double  s 
)

Definition at line 644 of file cd_hull.cpp.

◆ operator*() [3/16]

double3 ConvexDecomposition::operator* ( const double3 v,
const double3x3 m 
)

Definition at line 822 of file cd_hull.cpp.

◆ operator*() [4/16]

double3 ConvexDecomposition::operator* ( const double3 v,
const Quaternion q 
)

Definition at line 1169 of file cd_hull.cpp.

◆ operator*() [5/16]

double3x3 ConvexDecomposition::operator* ( const double3x3 m,
const double &  s 
)

Definition at line 837 of file cd_hull.cpp.

◆ operator*() [6/16]

double3 ConvexDecomposition::operator* ( const double3x3 m,
const double3 v 
)

Definition at line 827 of file cd_hull.cpp.

◆ operator*() [7/16]

double3x3 ConvexDecomposition::operator* ( const double3x3 ma,
const double3x3 mb 
)

Definition at line 832 of file cd_hull.cpp.

◆ operator*() [8/16]

double4 ConvexDecomposition::operator* ( const double4 v,
const double4x4 m 
)

Definition at line 888 of file cd_hull.cpp.

◆ operator*() [9/16]

double4 ConvexDecomposition::operator* ( const double4 v,
double  s 
)

Definition at line 914 of file cd_hull.cpp.

◆ operator*() [10/16]

double4x4 ConvexDecomposition::operator* ( const double4x4 a,
const double4x4 b 
)

Definition at line 946 of file cd_hull.cpp.

◆ operator*() [11/16]

Quaternion ConvexDecomposition::operator* ( const Quaternion a,
const Quaternion b 
)

Definition at line 1109 of file cd_hull.cpp.

◆ operator*() [12/16]

Quaternion ConvexDecomposition::operator* ( const Quaternion a,
double  s 
)

Definition at line 1120 of file cd_hull.cpp.

◆ operator*() [13/16]

double3 ConvexDecomposition::operator* ( const Quaternion q,
const double3 v 
)

Definition at line 1149 of file cd_hull.cpp.

◆ operator*() [14/16]

double4 ConvexDecomposition::operator* ( double  s,
const double4 v 
)

Definition at line 920 of file cd_hull.cpp.

◆ operator*() [15/16]

template<class Type >
Vector2d<Type> ConvexDecomposition::operator* ( Type  s,
const Vector2d< Type > &  v 
)

Definition at line 1203 of file cd_vector.h.

◆ operator*() [16/16]

template<class Type >
Vector3d<Type> ConvexDecomposition::operator* ( Type  s,
const Vector3d< Type > &  v 
)

Definition at line 1199 of file cd_vector.h.

◆ operator*=() [1/3]

double3 & ConvexDecomposition::operator*= ( double3 v,
const double  s 
)

Definition at line 700 of file cd_hull.cpp.

◆ operator*=() [2/3]

double3x3 & ConvexDecomposition::operator*= ( double3x3 a,
const double &  s 
)

Definition at line 868 of file cd_hull.cpp.

◆ operator*=() [3/3]

Quaternion & ConvexDecomposition::operator*= ( Quaternion a,
double  s 
)

Definition at line 1130 of file cd_hull.cpp.

◆ operator+() [1/5]

double2 ConvexDecomposition::operator+ ( const double2 a,
const double2 b 
)
inline

Definition at line 375 of file cd_hull.cpp.

◆ operator+() [2/5]

double3 ConvexDecomposition::operator+ ( const double3 a,
const double3 b 
)

Definition at line 626 of file cd_hull.cpp.

◆ operator+() [3/5]

double3x3 ConvexDecomposition::operator+ ( const double3x3 a,
const double3x3 b 
)

Definition at line 846 of file cd_hull.cpp.

◆ operator+() [4/5]

double4 ConvexDecomposition::operator+ ( const double4 a,
const double4 b 
)

Definition at line 926 of file cd_hull.cpp.

◆ operator+() [5/5]

Quaternion ConvexDecomposition::operator+ ( const Quaternion a,
const Quaternion b 
)

Definition at line 1175 of file cd_hull.cpp.

◆ operator+=() [1/2]

double3 & ConvexDecomposition::operator+= ( double3 a,
const double3 b 
)

Definition at line 682 of file cd_hull.cpp.

◆ operator+=() [2/2]

double3x3 & ConvexDecomposition::operator+= ( double3x3 a,
const double3x3 b 
)

Definition at line 854 of file cd_hull.cpp.

◆ operator-() [1/5]

double2 ConvexDecomposition::operator- ( const double2 a,
const double2 b 
)
inline

Definition at line 374 of file cd_hull.cpp.

◆ operator-() [2/5]

double3 ConvexDecomposition::operator- ( const double3 a,
const double3 b 
)

Definition at line 632 of file cd_hull.cpp.

◆ operator-() [3/5]

double3 ConvexDecomposition::operator- ( const double3 v)

Definition at line 638 of file cd_hull.cpp.

◆ operator-() [4/5]

double3x3 ConvexDecomposition::operator- ( const double3x3 a,
const double3x3 b 
)

Definition at line 850 of file cd_hull.cpp.

◆ operator-() [5/5]

double4 ConvexDecomposition::operator- ( const double4 a,
const double4 b 
)

Definition at line 933 of file cd_hull.cpp.

◆ operator-=() [1/2]

double3 & ConvexDecomposition::operator-= ( double3 a,
const double3 b 
)

Definition at line 691 of file cd_hull.cpp.

◆ operator-=() [2/2]

double3x3 & ConvexDecomposition::operator-= ( double3x3 a,
const double3x3 b 
)

Definition at line 861 of file cd_hull.cpp.

◆ operator/() [1/2]

double3 ConvexDecomposition::operator/ ( const double3 v,
const double  s 
)

Definition at line 656 of file cd_hull.cpp.

◆ operator/() [2/2]

double3x3 ConvexDecomposition::operator/ ( const double3x3 a,
const double &  s 
)

Definition at line 841 of file cd_hull.cpp.

◆ operator/=()

double3 & ConvexDecomposition::operator/= ( double3 v,
const double  s 
)

Definition at line 709 of file cd_hull.cpp.

◆ operator==() [1/5]

int ConvexDecomposition::operator== ( const double3 a,
const double3 b 
)
inline

Definition at line 410 of file cd_hull.cpp.

◆ operator==() [2/5]

int ConvexDecomposition::operator== ( const double4 a,
const double4 b 
)

Definition at line 893 of file cd_hull.cpp.

◆ operator==() [3/5]

int ConvexDecomposition::operator== ( const double4x4 a,
const double4x4 b 
)

Definition at line 1017 of file cd_hull.cpp.

◆ operator==() [4/5]

int ConvexDecomposition::operator== ( const int3 a,
const int3 b 
)

Definition at line 2336 of file cd_hull.cpp.

◆ operator==() [5/5]

int ConvexDecomposition::operator== ( const Plane a,
const Plane b 
)
inline

Definition at line 564 of file cd_hull.cpp.

◆ orth()

double3 ConvexDecomposition::orth ( const double3 v)

Definition at line 2279 of file cd_hull.cpp.

◆ overhull()

static int ConvexDecomposition::overhull ( Plane planes,
int  planes_count,
double3 verts,
int  verts_count,
int  maxplanes,
double3 *&  verts_out,
int &  verts_count_out,
int *&  faces_out,
int &  faces_count_out,
double  inflate 
)
static

Definition at line 2773 of file cd_hull.cpp.

◆ overhullv()

static int ConvexDecomposition::overhullv ( double3 verts,
int  verts_count,
int  maxplanes,
double3 *&  verts_out,
int &  verts_count_out,
int *&  faces_out,
int &  faces_count_out,
double  inflate,
double  bevangle,
int  vlimit 
)
static

Definition at line 2864 of file cd_hull.cpp.

◆ overlapAABB()

bool ConvexDecomposition::overlapAABB ( const double *  bmin1,
const double *  bmax1,
const double *  bmin2,
const double *  bmax2 
)

Definition at line 469 of file bestfit.cpp.

◆ performConvexDecomposition()

unsigned int ConvexDecomposition::performConvexDecomposition ( const DecompDesc desc)

Definition at line 1049 of file ConvexDecomposition.cpp.

◆ Pitch() [1/2]

double ConvexDecomposition::Pitch ( const double3 v)

Definition at line 1255 of file cd_hull.cpp.

◆ Pitch() [2/2]

double ConvexDecomposition::Pitch ( const Quaternion q)

Definition at line 1236 of file cd_hull.cpp.

◆ PlaneFlip()

Plane ConvexDecomposition::PlaneFlip ( const Plane plane)
inline

Definition at line 563 of file cd_hull.cpp.

◆ PlaneLineIntersection()

double3 ConvexDecomposition::PlaneLineIntersection ( const Plane plane,
const double3 p0,
const double3 p1 
)

Definition at line 1336 of file cd_hull.cpp.

◆ PlaneProject()

double3 ConvexDecomposition::PlaneProject ( const Plane plane,
const double3 point 
)

Definition at line 1346 of file cd_hull.cpp.

◆ PlaneTest()

int ConvexDecomposition::PlaneTest ( const Plane p,
const REAL3 v 
)

Definition at line 1700 of file cd_hull.cpp.

◆ planeTriIntersection()

PlaneTriResult ConvexDecomposition::planeTriIntersection ( const double *  _plane,
const double *  triangle,
unsigned int  tstride,
double  epsilon,
double *  front,
unsigned int &  fcount,
double *  back,
unsigned int &  bcount 
)

Definition at line 244 of file planetri.cpp.

◆ PolyHit()

int ConvexDecomposition::PolyHit ( const double3 vert,
const int  n,
const double3 v0,
const double3 v1,
double3 impact = NULL,
double3 normal = NULL 
)

Definition at line 1557 of file cd_hull.cpp.

◆ Process()

bool ConvexDecomposition::Process ( const Vec2dVector contour,
Vec2dVector result 
)
static

Definition at line 154 of file triangulate.cpp.

◆ rayIntersectsTriangle()

bool ConvexDecomposition::rayIntersectsTriangle ( const double *  p,
const double *  d,
const double *  v0,
const double *  v1,
const double *  v2,
double &  t 
)

Definition at line 87 of file raytri.cpp.

◆ relativeDiff()

static RDIFF ConvexDecomposition::relativeDiff ( const double *  a,
const double *  b,
double  magnitude 
)
static

Definition at line 268 of file vlookup.cpp.

◆ ReleaseHull()

void ConvexDecomposition::ReleaseHull ( PHullResult result)

Definition at line 2932 of file cd_hull.cpp.

◆ removeb2b()

void ConvexDecomposition::removeb2b ( Tri s,
Tri t 
)

Definition at line 2451 of file cd_hull.cpp.

◆ Roll()

double ConvexDecomposition::Roll ( Quaternion  q)

Definition at line 1243 of file cd_hull.cpp.

◆ roll3()

int3 ConvexDecomposition::roll3 ( int3  a)

Definition at line 2345 of file cd_hull.cpp.

◆ RotationArc()

Quaternion ConvexDecomposition::RotationArc ( double3  v0,
double3  v1 
)

Definition at line 1286 of file cd_hull.cpp.

◆ Round() [1/2]

double3 ConvexDecomposition::Round ( const double3 a,
double  precision 
)

Definition at line 754 of file cd_hull.cpp.

◆ Round() [2/2]

double ConvexDecomposition::Round ( double  a,
double  precision 
)

Definition at line 595 of file cd_hull.cpp.

◆ safenormalize()

double3 ConvexDecomposition::safenormalize ( const double3 v)

Definition at line 745 of file cd_hull.cpp.

◆ Set() [1/2]

static void ConvexDecomposition::Set ( double *  n,
double  x,
double  y,
double  z 
)
inlinestatic

Definition at line 85 of file fitsphere.cpp.

◆ Set() [2/2]

static void ConvexDecomposition::Set ( float *  n,
float  x,
float  y,
float  z 
)
inlinestatic

Definition at line 228 of file fitsphere.cpp.

◆ shareedge()

int ConvexDecomposition::shareedge ( const int3 a,
const int3 b 
)

Definition at line 2379 of file cd_hull.cpp.

◆ slerp()

Quaternion ConvexDecomposition::slerp ( Quaternion  a,
const Quaternion b,
double  interp 
)

Definition at line 1197 of file cd_hull.cpp.

◆ Snip()

bool ConvexDecomposition::Snip ( const Vec2dVector contour,
int  u,
int  v,
int  w,
int  n,
int *  V 
)
static

Definition at line 135 of file triangulate.cpp.

◆ Split_Polygon()

void ConvexDecomposition::Split_Polygon ( polygon poly,
plane part,
polygon front,
polygon back 
)

Definition at line 202 of file planetri.cpp.

◆ splitRect()

void ConvexDecomposition::splitRect ( unsigned int  axis,
const Rect3d source,
Rect3d b1,
Rect3d b2,
const double *  midpoint 
)

Definition at line 169 of file splitplane.cpp.

◆ SplitTest()

int ConvexDecomposition::SplitTest ( ConvexH convex,
const Plane plane 
)

Definition at line 1706 of file cd_hull.cpp.

◆ sqr()

double ConvexDecomposition::sqr ( double  a)

Definition at line 591 of file cd_hull.cpp.

◆ Swap()

template<class T >
void ConvexDecomposition::Swap ( T &  a,
T &  b 
)

Definition at line 329 of file cd_hull.cpp.

◆ test_btbq()

ConvexH* ConvexDecomposition::test_btbq ( )

Definition at line 1787 of file cd_hull.cpp.

◆ test_cube()

ConvexH* ConvexDecomposition::test_cube ( )

Definition at line 1815 of file cd_hull.cpp.

◆ tetVolume() [1/2]

double ConvexDecomposition::tetVolume ( const double *  p0,
const double *  p1,
const double *  p2,
const double *  p3 
)
inline

Definition at line 101 of file meshvolume.cpp.

◆ tetVolume() [2/2]

float ConvexDecomposition::tetVolume ( const float *  p0,
const float *  p1,
const float *  p2,
const float *  p3 
)
inline

Definition at line 196 of file meshvolume.cpp.

◆ ThreePlaneIntersection()

double3 ConvexDecomposition::ThreePlaneIntersection ( const Plane p0,
const Plane p1,
const Plane p2 
)

Definition at line 878 of file cd_hull.cpp.

◆ Transpose()

double3x3 ConvexDecomposition::Transpose ( const double3x3 m)

Definition at line 814 of file cd_hull.cpp.

◆ triangulate2d()

unsigned int ConvexDecomposition::triangulate2d ( unsigned int  pcount,
const double *  vertices,
double *  triangles,
unsigned int  maxTri 
)

Definition at line 368 of file triangulate.cpp.

◆ triangulate3d() [1/2]

unsigned int ConvexDecomposition::triangulate3d ( unsigned int  pcount,
const double *  vertices,
double *  triangles,
unsigned int  maxTri,
const double *  plane 
)

Definition at line 203 of file triangulate.cpp.

◆ triangulate3d() [2/2]

unsigned int ConvexDecomposition::triangulate3d ( unsigned int  pcount,
const unsigned int *  indices,
const double *  vertices,
double *  triangles,
unsigned int  maxTri,
const double *  plane 
)

Definition at line 336 of file triangulate.cpp.

◆ TriNormal()

double3 ConvexDecomposition::TriNormal ( const double3 v0,
const double3 v1,
const double3 v2 
)

Definition at line 1370 of file cd_hull.cpp.

◆ vabs()

double3 ConvexDecomposition::vabs ( const double3 v)

Definition at line 718 of file cd_hull.cpp.

◆ VectorMax()

double3 ConvexDecomposition::VectorMax ( const double3 a,
const double3 b 
)

Definition at line 769 of file cd_hull.cpp.

◆ VectorMin()

double3 ConvexDecomposition::VectorMin ( const double3 a,
const double3 b 
)

Definition at line 765 of file cd_hull.cpp.

◆ VirtualTrackBall()

Quaternion ConvexDecomposition::VirtualTrackBall ( const double3 cop,
const double3 cor,
const double3 dir0,
const double3 dir1 
)

Definition at line 1511 of file cd_hull.cpp.

◆ Vl_createVertexLookup()

VertexLookup ConvexDecomposition::Vl_createVertexLookup ( void  )

Definition at line 308 of file vlookup.cpp.

◆ Vl_getIndex()

unsigned int ConvexDecomposition::Vl_getIndex ( VertexLookup  vlook,
const double *  pos 
)

Definition at line 320 of file vlookup.cpp.

◆ Vl_getVcount()

unsigned int ConvexDecomposition::Vl_getVcount ( VertexLookup  vlook)

Definition at line 334 of file vlookup.cpp.

◆ Vl_getVertices()

const double * ConvexDecomposition::Vl_getVertices ( VertexLookup  vlook)

Definition at line 327 of file vlookup.cpp.

◆ Vl_releaseVertexLookup()

void ConvexDecomposition::Vl_releaseVertexLookup ( VertexLookup  vlook)

Definition at line 314 of file vlookup.cpp.

◆ Yaw() [1/2]

double ConvexDecomposition::Yaw ( const double3 v)

Definition at line 1250 of file cd_hull.cpp.

◆ Yaw() [2/2]

double ConvexDecomposition::Yaw ( const Quaternion q)

Definition at line 1229 of file cd_hull.cpp.

◆ YawPitchRoll()

Quaternion ConvexDecomposition::YawPitchRoll ( double  yaw,
double  pitch,
double  roll 
)

Definition at line 1221 of file cd_hull.cpp.

Variable Documentation

◆ countpolyhit

int ConvexDecomposition::countpolyhit =0

Definition at line 1556 of file cd_hull.cpp.

◆ DEG_TO_RAD

const double ConvexDecomposition::DEG_TO_RAD = ((2.0f * 3.14152654f) / 360.0f)

Definition at line 79 of file cd_vector.h.

◆ EPSILON

const double ConvexDecomposition::EPSILON =0.0000000001f
static

Definition at line 106 of file triangulate.cpp.

◆ FM_DEG_TO_RAD

const double ConvexDecomposition::FM_DEG_TO_RAD = ((2.0f * FM_PI) / 360.0f)

Definition at line 83 of file float_math.h.

◆ FM_PI

const double ConvexDecomposition::FM_PI = 3.141592654f

Copyright (c) 2007 by John W. Ratcliff jratc.nosp@m.liff.nosp@m.@infi.nosp@m.nipl.nosp@m.ex.ne.nosp@m.t

Portions of this source has been released with the PhysXViewer application, as well as Rocket, CreateDynamics, ODF, and as a number of sample code snippets.

If you find this code useful or you are feeling particularily generous I would ask that you please go to http://www.amillionpixels.us and make a donation to Troy DeMolay.

DeMolay is a youth group for young men between the ages of 12 and 21.
It teaches strong moral principles, as well as leadership skills and public speaking. The donations page uses the 'pay for pixels' paradigm where, in this case, a pixel is only a single penny. Donations can be made for as small as $4 or as high as a $100 block. Each person who donates will get a link to their own site as well as acknowledgement on the donations blog located here http://www.amillionpixels.blogspot.com/

If you wish to contact me you can use the following methods:

Skype Phone: 636-486-4040 (let it ring a long time while it goes through switches) Skype ID: jratcliff63367 Yahoo: jratcliff63367 AOL: jratcliff1961 email: jratc.nosp@m.liff.nosp@m.@infi.nosp@m.nipl.nosp@m.ex.ne.nosp@m.t Personal website: http://jratcliffscarab.blogspot.com Coding Website: http://codesuppository.blogspot.com FundRaising Blog: http://amillionpixels.blogspot.com Fundraising site: http://www.amillionpixels.us New Temple Site: http://newtemple.blogspot.com

The MIT license:

Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions:

The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software.

THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.

Definition at line 82 of file float_math.h.

◆ FM_RAD_TO_DEG

const double ConvexDecomposition::FM_RAD_TO_DEG = (360.0f / (2.0f * FM_PI))

Definition at line 84 of file float_math.h.

◆ minadjangle

double ConvexDecomposition::minadjangle = 3.0f

Definition at line 2202 of file cd_hull.cpp.

◆ planetestepsilon

double ConvexDecomposition::planetestepsilon = PAPERWIDTH

Definition at line 1649 of file cd_hull.cpp.

◆ RAD_TO_DEG

const double ConvexDecomposition::RAD_TO_DEG = (360.0f / (2.0f * 3.141592654f))

Definition at line 80 of file cd_vector.h.

◆ tmpp

double ConvexDecomposition::tmpp[3] = {0,0,0}

Definition at line 257 of file vlookup.cpp.

◆ tris

Array<Tri*> ConvexDecomposition::tris
static

Definition at line 2390 of file cd_hull.cpp.



convex_decomposition
Author(s): John W. Ratcliff
autogenerated on Wed Mar 2 2022 00:05:00