$search
Main namespace. More...
Classes | |
class | AABB |
A class describing the AABB collision structure, which is a box in 3D space determined by two diagonal points. More... | |
class | BVFitter |
A class for fitting a bounding volume to a set of points. More... | |
class | BVFitter< OBB > |
Specification of BVFitter for OBB bounding volume. More... | |
class | BVFitter< RSS > |
Specification of BVFitter for RSS bounding volume. More... | |
struct | BVH_CAResult |
struct | BVH_CollideResult |
A class describing the collision result. More... | |
struct | BVH_DistanceResult |
struct | BVHCollisionPair |
The indices of in-collision primitives of objects. More... | |
struct | BVHFrontNode |
A class describing the node for BVH front. More... | |
class | BVHModel |
A class describing the bounding hierarchy of a mesh model. More... | |
struct | BVNode |
A class describing a bounding volume node. More... | |
class | BVSplitRule |
A class describing the split rule that splits each BV node. More... | |
class | BVSplitRule< OBB > |
BVHSplitRule specialization for OBB. More... | |
struct | BVT |
Bounding volume test structure. More... | |
struct | BVT_Comparer |
Comparer between two BVT. More... | |
struct | CollisionGeom |
struct | CollisionMesh |
struct | CollisionMesh< OBB > |
Specialization for OBB. More... | |
struct | Edge2f |
Simple edge with two indices for its endpoints. More... | |
class | InterpMotion |
Linear interpolation motion Each Motion is assumed to have constant linear velocity and angular velocity. More... | |
class | Intersect |
CCD intersect kernel among primitives. More... | |
class | KDOP |
KDOP class describes the KDOP collision structures. K is set as the template parameter, which should be 16, 18, or 24 The KDOP structure is defined by some pairs of parallel planes defined by some axes. For K = 18, the planes are 6 AABB planes and 12 diagonal planes that cut off some space of the edges: (-1,0,0) and (1,0,0) -> indices 0 and 9 (0,-1,0) and (0,1,0) -> indices 1 and 10 (0,0,-1) and (0,0,1) -> indices 2 and 11 (-1,-1,0) and (1,1,0) -> indices 3 and 12 (-1,0,-1) and (1,0,1) -> indices 4 and 13 (0,-1,-1) and (0,1,1) -> indices 5 and 14 (-1,1,0) and (1,-1,0) -> indices 6 and 15 (-1,0,1) and (1,0,-1) -> indices 7 and 16 (0,-1,1) and (0,1,-1) -> indices 8 and 17. More... | |
class | OBB |
OBB class. More... | |
class | PolySolver |
A class solves polynomial degree (1,2,3) equations. More... | |
class | RSS |
struct | Triangle3e |
Simple triangle with 3 indices for points. More... | |
struct | Triangle3f |
Simple triangle with three indices for 3 neighboring triangles. More... | |
class | TriangleDistance |
class | Vec3f |
A class describing a three-dimensional vector. More... | |
Typedefs | |
typedef double | BVH_REAL |
typedef std::list< BVHFrontNode > | BVHFrontList |
A class describing the BVH front list. | |
typedef std::priority_queue < BVT, std::vector< BVT > , BVT_Comparer > | BVTQ |
typedef Triangle3e | Triangle |
Enumerations | |
enum | BVHBuildState { BVH_BUILD_STATE_EMPTY, BVH_BUILD_STATE_BEGUN, BVH_BUILD_STATE_PROCESSED, BVH_BUILD_STATE_UPDATE_BEGUN, BVH_BUILD_STATE_UPDATED, BVH_BUILD_STATE_REPLACE_BEGUN } |
States for BVH construction empty->begun->processed ->replace_begun->processed -> ...... | |-> update_begun -> updated -> ..... More... | |
enum | BVHModelType { BVH_MODEL_UNKNOWN, BVH_MODEL_TRIANGLES, BVH_MODEL_POINTCLOUD } |
BVH model type. More... | |
enum | BVHReturnCode { BVH_OK = 0, BVH_ERR_MODEL_OUT_OF_MEMORY = -1, BVH_ERR_OUT_OF_MEMORY = -2, BVH_ERR_UNPROCESSED_MODEL = -3, BVH_ERR_BUILD_OUT_OF_SEQUENCE = -4, BVH_ERR_BUILD_EMPTY_MODEL = -5, BVH_ERR_BUILD_EMPTY_PREVIOUS_FRAME = -6, BVH_ERR_UNSUPPORTED_FUNCTION = -7, BVH_ERR_UNUPDATED_MODEL = -8, BVH_ERR_INCORRECT_DATA = -9, BVH_ERR_UNKNOWN = -10 } |
Error code for BVH. More... | |
enum | SplitMethodType { SPLIT_METHOD_MEAN, SPLIT_METHOD_MEDIAN, SPLIT_METHOD_BV_CENTER } |
Functions | |
Vec3f | abs (const Vec3f &v) |
int | collide (const BVHModel< RSS > &model1, const Vec3f R1[3], const Vec3f &T1, const BVHModel< RSS > &model2, const Vec3f R2[3], const Vec3f &T2, BVH_CollideResult *res, BVHFrontList *front_list=NULL) |
Collision between two RSS models, only support mesh-mesh For RSS, we provide a specification that need not update the mesh vertices. | |
int | collide (const BVHModel< OBB > &model1, const Vec3f R1[3], const Vec3f &T1, const BVHModel< OBB > &model2, const Vec3f R2[3], const Vec3f &T2, BVH_CollideResult *res, BVHFrontList *front_list=NULL) |
Collision between two OBB models, only support mesh-mesh For OBB, we provide a specification that need not update the mesh vertices. | |
template<typename BV > | |
int | collide (const BVHModel< BV > &model1, const BVHModel< BV > &model2, BVH_CollideResult *res, BVHFrontList *front_list=NULL) |
Collision between two BVH models, only support mesh-mesh. | |
void | collideRecurse (BVNode< RSS > *tree1, BVNode< RSS > *tree2, const Vec3f R[3], const Vec3f &T, int b1, int b2, Vec3f *vertices1, Vec3f *vertices2, Triangle *tri_indices1, Triangle *tri_indices2, BVH_CollideResult *res, BVHFrontList *front_list=NULL) |
Recursive collision kernel between two RSS trees: for rigid motion. | |
void | collideRecurse (BVNode< OBB > *tree1, BVNode< OBB > *tree2, const Vec3f R[3], const Vec3f &T, int b1, int b2, Vec3f *vertices1, Vec3f *vertices2, Triangle *tri_indices1, Triangle *tri_indices2, BVH_CollideResult *res, BVHFrontList *front_list=NULL) |
Recursive collision kernel between two OBB trees: for rigid motion. | |
template<typename BV > | |
void | collideRecurse (BVNode< BV > *tree1, BVNode< BV > *tree2, int b1, int b2, Vec3f *vertices1, Vec3f *vertices2, Triangle *tri_indices1, Triangle *tri_indices2, BVH_CollideResult *res, BVHFrontList *front_list=NULL) |
Recursive collision kernel between between two BV trees. | |
void | conservativeAdvancementRecurse (BVNode< RSS > *tree1, BVNode< RSS > *tree2, const Vec3f R[3], const Vec3f &T, int b1, int b2, Vec3f *vertices1, Vec3f *vertices2, Triangle *tri_indices1, Triangle *tri_indices2, BVH_CAResult *res, BVHFrontList *front_list=NULL) |
Recursive conservative advancement kernel between two RSS trees. | |
template<typename BV > | |
int | continuousCollide (BVHModel< BV > &model1, BVHModel< BV > &model2, BVH_CollideResult *res, BVHFrontList *front_list=NULL) |
Continuous collision between two BVH models, support mesh-mesh or mesh-point clouds. | |
void | continuousCollide_CA (const BVHModel< RSS > &model1, const Vec3f R1_1[3], const Vec3f &T1_1, const Vec3f R1_2[3], const Vec3f &T1_2, const BVHModel< RSS > &model2, const Vec3f R2_1[3], const Vec3f &T2_1, const Vec3f R2_2[3], const Vec3f &T2_2, BVH_CAResult *res, BVHFrontList *front_list=NULL) |
Continuous collision detection query between two RSS models based on conservative advancement. | |
template<typename BV > | |
void | continuousCollideRecurse (BVNode< BV > *tree1, BVNode< BV > *tree2, int b1, int b2, Vec3f *vertices1, Vec3f *vertices2, Vec3f *prev_vertices1, Vec3f *prev_vertices2, Triangle *tri_indices1, Triangle *tri_indices2, BVH_CollideResult *res, BVHFrontList *front_list=NULL) |
Recursive continuous collision kernel between between two BV trees. | |
template<typename BV > | |
void | continuousPropagateBVHFrontList (BVNode< BV > *tree1, BVNode< BV > *tree2, Vec3f *vertices1, Vec3f *vertices2, Vec3f *prev_vertices1, Vec3f *prev_vertices2, Triangle *tri_indices1, Triangle *tri_indices2, BVH_CollideResult *res, BVHFrontList *front_list) |
BVH front list propagation for continuous collision. | |
template<typename BV > | |
int | continuousSelfCollide (BVHModel< BV > &model, BVH_CollideResult *res, BVHFrontList *front_list=NULL) |
Continuous self collision for one BVH model, only support mesh. | |
template<typename BV > | |
void | continuousSelfCollideRecurse (BVNode< BV > *tree, int b, Vec3f *vertices, Vec3f *prev_vertices, Triangle *tri_indices, BVH_CollideResult *res, BVHFrontList *front_list=NULL) |
Recursive continuous self collision kernel between between two BV trees. | |
BVH_REAL | distance (const Vec3f R0[3], const Vec3f &T0, const RSS &b1, const RSS &b2, Vec3f *P=NULL, Vec3f *Q=NULL) |
distance between two RSS bounding volumes P and Q (optional return values) are the closest points in the rectangles, not the RSS. But the direction P - Q is the correct direction for cloest points Notice that P and Q are both in the local frame of the first RSS (not global frame and not even the local frame of object 1) | |
int | distance (const BVHModel< RSS > &model1, const Vec3f R1[3], const Vec3f &T1, const BVHModel< RSS > &model2, const Vec3f R2[3], const Vec3f &T2, BVH_DistanceResult *res, BVHFrontList *front_list=NULL) |
Proximity query between two RSS models, only support mesh-mesh For RSS, we provide a specification that need not update the mesh vertices. | |
template<typename BV > | |
int | distance (const BVHModel< BV > &model1, const BVHModel< BV > &model2, BVH_DistanceResult *res, BVHFrontList *front_list=NULL) |
Proximity query between two BVH models, only support mesh-mesh now. | |
void | distanceQueueRecurse (BVNode< RSS > *tree1, BVNode< RSS > *tree2, const Vec3f R[3], const Vec3f &T, int b1, int b2, Vec3f *vertices1, Vec3f *vertices2, Triangle *tri_indices1, Triangle *tri_indices2, BVH_DistanceResult *res, BVHFrontList *front_list=NULL) |
Recursive proximity kernel between two RSS trees, using BVT queue acceleration. | |
void | distanceRecurse (BVNode< RSS > *tree1, BVNode< RSS > *tree2, const Vec3f R[3], const Vec3f &T, int b1, int b2, Vec3f *vertices1, Vec3f *vertices2, Triangle *tri_indices1, Triangle *tri_indices2, BVH_DistanceResult *res, BVHFrontList *front_list=NULL) |
Recursive proximity kernel between two RSS trees. | |
template<typename BV > | |
void | distanceRecurse (BVNode< BV > *tree1, BVNode< BV > *tree2, int b1, int b2, Vec3f *vertices1, Vec3f *vertices2, Triangle *tri_indices1, Triangle *tri_indices2, BVH_DistanceResult *res, BVHFrontList *front_list=NULL) |
Recursive proximity kernel between two BV trees. | |
void | getCovariance (Vec3f *ps, Vec3f *ps2, Triangle *ts, unsigned int *indices, int n, Vec3f M[3]) |
Compute the covariance matrix for a set or subset of triangles. | |
void | getCovariance (Vec3f *ps, Vec3f *ps2, unsigned int *indices, int n, Vec3f M[3]) |
Compute the covariance matrix for a set or subset of points. | |
template<size_t N> | |
void | getDistances (const Vec3f &p, BVH_REAL d[]) |
Compute the distances to planes with normals from KDOP vectors except those of AABB face planes. | |
template<> | |
void | getDistances< 5 > (const Vec3f &p, BVH_REAL d[]) |
Specification of getDistances. | |
template<> | |
void | getDistances< 6 > (const Vec3f &p, BVH_REAL d[]) |
template<> | |
void | getDistances< 9 > (const Vec3f &p, BVH_REAL d[]) |
void | getExtentAndCenter (Vec3f *ps, Vec3f *ps2, Triangle *ts, unsigned int *indices, int n, Vec3f axis[3], Vec3f ¢er, Vec3f &extent) |
Compute the bounding volume extent and center for a set or subset of points. The bounding volume axes are known. | |
void | getExtentAndCenter (Vec3f *ps, Vec3f *ps2, unsigned int *indices, int n, Vec3f axis[3], Vec3f ¢er, Vec3f &extent) |
Compute the bounding volume extent and center for a set or subset of points. The bounding volume axes are known. | |
void | getRadiusAndOriginAndRectangleSize (Vec3f *ps, Vec3f *ps2, Triangle *ts, unsigned int *indices, int n, Vec3f axis[3], Vec3f &origin, BVH_REAL l[2], BVH_REAL &r) |
Compute the RSS bounding volume parameters: radius, rectangle size and the origin. The bounding volume axes are known. | |
void | getRadiusAndOriginAndRectangleSize (Vec3f *ps, Vec3f *ps2, unsigned int *indices, int n, Vec3f axis[3], Vec3f &origin, BVH_REAL l[2], BVH_REAL &r) |
Compute the RSS bounding volume parameters: radius, rectangle size and the origin. The bounding volume axes are known. | |
template<typename FPT > | |
bool | isSmall (FPT v, FPT tolerance) |
Check whether one float value is close to zero. | |
template<typename BV > | |
CollisionMesh< BV > * | makeBox (double a, double b, double c) |
template<typename BV > | |
CollisionMesh< BV > * | makeCylinder (double r, double h, unsigned int tot=16) |
template<typename BV > | |
CollisionMesh< BV > * | makeMesh (const std::vector< Vec3f > &points, const std::vector< Triangle > &tri_indices) |
template<typename BV > | |
CollisionMesh< BV > * | makeSphere (double r, unsigned int seg=16, unsigned int ring=16) |
Vec3f | max (const Vec3f &a, const Vec3f &b) |
the maximum of two vectors | |
void | Meigen (Vec3f a[3], BVH_REAL dout[3], Vec3f vout[3]) |
Compute the eigen value and vector for a given matrix a. | |
Vec3f | min (const Vec3f &a, const Vec3f &b) |
The minimum of two vectors. | |
void | minmax (BVH_REAL p, BVH_REAL &minv, BVH_REAL &maxv) |
Merge the interval [minv, maxv] and value p. | |
void | minmax (BVH_REAL a, BVH_REAL b, BVH_REAL &minv, BVH_REAL &maxv) |
Find the smaller and larger one of two values. | |
Vec3f | MTxV (const Vec3f M[3], const Vec3f &v) |
Vec3f | MxV (const Vec3f M[3], const Vec3f &v) |
bool | overlap (const Vec3f R0[3], const Vec3f &T0, const RSS &b1, const RSS &b2) |
bool | overlap (const Vec3f R0[3], const Vec3f &T0, const OBB &b1, const OBB &b2) |
void | propagateBVHFrontList (BVNode< RSS > *tree1, BVNode< RSS > *tree2, Vec3f R[3], const Vec3f &T, Vec3f *vertices1, Vec3f *vertices2, Triangle *tri_indices1, Triangle *tri_indices2, BVH_CollideResult *res, BVHFrontList *front_list) |
RSS front list propagation for collision of RSS trees. | |
void | propagateBVHFrontList (BVNode< OBB > *tree1, BVNode< OBB > *tree2, Vec3f R[3], const Vec3f &T, Vec3f *vertices1, Vec3f *vertices2, Triangle *tri_indices1, Triangle *tri_indices2, BVH_CollideResult *res, BVHFrontList *front_list) |
BVH front list propagation for collision of OBB trees. | |
template<typename BV > | |
void | propagateBVHFrontList (BVNode< BV > *tree1, BVNode< BV > *tree2, Vec3f *vertices1, Vec3f *vertices2, Triangle *tri_indices1, Triangle *tri_indices2, BVH_CollideResult *res, BVHFrontList *front_list) |
BVH front list propagation for collision. | |
template<typename FPT > | |
bool | roughlyEqual (FPT left, FPT right, FPT tolerance) |
Compare whether two float values are close enough. | |
void | saveOBjFile (const std::string &name, const std::vector< Vec3f > &points, const std::vector< Triangle > &tri_indices) |
template<typename BV > | |
int | selfCollide (const BVHModel< BV > &model, BVH_CollideResult *res, BVHFrontList *front_list=NULL) |
Self collision for one BVH model, only support mesh. | |
template<typename BV > | |
void | selfCollideRecurse (BVNode< BV > *tree, int b, Vec3f *vertices, Triangle *tri_indices, BVH_CollideResult *res, BVHFrontList *front_list=NULL) |
Recursive self collision kernel on one BV tree. |
Main namespace.
typedef double collision_checking::BVH_REAL |
Definition at line 43 of file BVH_defs.h.
typedef std::list<BVHFrontNode> collision_checking::BVHFrontList |
A class describing the BVH front list.
Definition at line 63 of file BVH_front.h.
typedef std::priority_queue<BVT, std::vector<BVT>, BVT_Comparer> collision_checking::BVTQ |
Definition at line 66 of file distance_primitive.cpp.
Definition at line 75 of file primitive.h.
States for BVH construction empty->begun->processed ->replace_begun->processed -> ...... | |-> update_begun -> updated -> .....
BVH_BUILD_STATE_EMPTY | |
BVH_BUILD_STATE_BEGUN | |
BVH_BUILD_STATE_PROCESSED | |
BVH_BUILD_STATE_UPDATE_BEGUN | |
BVH_BUILD_STATE_UPDATED | |
BVH_BUILD_STATE_REPLACE_BEGUN |
Definition at line 50 of file BVH_defs.h.
BVH model type.
Definition at line 77 of file BVH_defs.h.
Error code for BVH.
Definition at line 61 of file BVH_defs.h.
Definition at line 52 of file BVH_split_rule.h.
int collision_checking::collide | ( | const BVHModel< RSS > & | model1, | |
const Vec3f | R1[3], | |||
const Vec3f & | T1, | |||
const BVHModel< RSS > & | model2, | |||
const Vec3f | R2[3], | |||
const Vec3f & | T2, | |||
BVH_CollideResult * | res, | |||
BVHFrontList * | front_list = NULL | |||
) |
Collision between two RSS models, only support mesh-mesh For RSS, we provide a specification that need not update the mesh vertices.
Definition at line 109 of file collision.cpp.
int collision_checking::collide | ( | const BVHModel< OBB > & | model1, | |
const Vec3f | R1[3], | |||
const Vec3f & | T1, | |||
const BVHModel< OBB > & | model2, | |||
const Vec3f | R2[3], | |||
const Vec3f & | T2, | |||
BVH_CollideResult * | res, | |||
BVHFrontList * | front_list = NULL | |||
) |
Collision between two OBB models, only support mesh-mesh For OBB, we provide a specification that need not update the mesh vertices.
Definition at line 43 of file collision.cpp.
int collision_checking::collide | ( | const BVHModel< BV > & | model1, | |
const BVHModel< BV > & | model2, | |||
BVH_CollideResult * | res, | |||
BVHFrontList * | front_list = NULL | |||
) | [inline] |
Collision between two BVH models, only support mesh-mesh.
Definition at line 51 of file collision.h.
void collision_checking::collideRecurse | ( | BVNode< RSS > * | tree1, | |
BVNode< RSS > * | tree2, | |||
const Vec3f | R[3], | |||
const Vec3f & | T, | |||
int | b1, | |||
int | b2, | |||
Vec3f * | vertices1, | |||
Vec3f * | vertices2, | |||
Triangle * | tri_indices1, | |||
Triangle * | tri_indices2, | |||
BVH_CollideResult * | res, | |||
BVHFrontList * | front_list = NULL | |||
) |
Recursive collision kernel between two RSS trees: for rigid motion.
Definition at line 206 of file collision_primitive.cpp.
void collision_checking::collideRecurse | ( | BVNode< OBB > * | tree1, | |
BVNode< OBB > * | tree2, | |||
const Vec3f | R[3], | |||
const Vec3f & | T, | |||
int | b1, | |||
int | b2, | |||
Vec3f * | vertices1, | |||
Vec3f * | vertices2, | |||
Triangle * | tri_indices1, | |||
Triangle * | tri_indices2, | |||
BVH_CollideResult * | res, | |||
BVHFrontList * | front_list = NULL | |||
) |
Recursive collision kernel between two OBB trees: for rigid motion.
Definition at line 103 of file collision_primitive.cpp.
void collision_checking::collideRecurse | ( | BVNode< BV > * | tree1, | |
BVNode< BV > * | tree2, | |||
int | b1, | |||
int | b2, | |||
Vec3f * | vertices1, | |||
Vec3f * | vertices2, | |||
Triangle * | tri_indices1, | |||
Triangle * | tri_indices2, | |||
BVH_CollideResult * | res, | |||
BVHFrontList * | front_list = NULL | |||
) | [inline] |
Recursive collision kernel between between two BV trees.
Definition at line 153 of file collision_primitive.h.
void collision_checking::conservativeAdvancementRecurse | ( | BVNode< RSS > * | tree1, | |
BVNode< RSS > * | tree2, | |||
const Vec3f | R[3], | |||
const Vec3f & | T, | |||
int | b1, | |||
int | b2, | |||
Vec3f * | vertices1, | |||
Vec3f * | vertices2, | |||
Triangle * | tri_indices1, | |||
Triangle * | tri_indices2, | |||
BVH_CAResult * | res, | |||
BVHFrontList * | front_list = NULL | |||
) |
Recursive conservative advancement kernel between two RSS trees.
n is the local frame of object 1
turn n into the global frame
n is in local frame of RSS c1
turn n into the global frame
n is in the local frame of RSS a1
turn n into the global frame
n is in the local frame of RSS a1
turn n into the global frame
n is the local frame of RSS c1
turn n into the global frame
n is the local frame of object 1
turn n into the global frame
n is in local frame of RSS c1
turn n into the global frame
n is in the local frame of RSS a1
turn n into the global frame
n is in the local frame of RSS a1
turn n into the global frame
n is the local frame of RSS c1
turn n into the global frame
Definition at line 236 of file conservative_advancement.cpp.
int collision_checking::continuousCollide | ( | BVHModel< BV > & | model1, | |
BVHModel< BV > & | model2, | |||
BVH_CollideResult * | res, | |||
BVHFrontList * | front_list = NULL | |||
) | [inline] |
Continuous collision between two BVH models, support mesh-mesh or mesh-point clouds.
Definition at line 51 of file continuous_collision.h.
void collision_checking::continuousCollide_CA | ( | const BVHModel< RSS > & | model1, | |
const Vec3f | R1_1[3], | |||
const Vec3f & | T1_1, | |||
const Vec3f | R1_2[3], | |||
const Vec3f & | T1_2, | |||
const BVHModel< RSS > & | model2, | |||
const Vec3f | R2_1[3], | |||
const Vec3f & | T2_1, | |||
const Vec3f | R2_2[3], | |||
const Vec3f & | T2_2, | |||
BVH_CAResult * | res, | |||
BVHFrontList * | front_list = NULL | |||
) |
Continuous collision detection query between two RSS models based on conservative advancement.
Definition at line 424 of file conservative_advancement.cpp.
void collision_checking::continuousCollideRecurse | ( | BVNode< BV > * | tree1, | |
BVNode< BV > * | tree2, | |||
int | b1, | |||
int | b2, | |||
Vec3f * | vertices1, | |||
Vec3f * | vertices2, | |||
Vec3f * | prev_vertices1, | |||
Vec3f * | prev_vertices2, | |||
Triangle * | tri_indices1, | |||
Triangle * | tri_indices2, | |||
BVH_CollideResult * | res, | |||
BVHFrontList * | front_list = NULL | |||
) | [inline] |
Recursive continuous collision kernel between between two BV trees.
Definition at line 287 of file collision_primitive.h.
void collision_checking::continuousPropagateBVHFrontList | ( | BVNode< BV > * | tree1, | |
BVNode< BV > * | tree2, | |||
Vec3f * | vertices1, | |||
Vec3f * | vertices2, | |||
Vec3f * | prev_vertices1, | |||
Vec3f * | prev_vertices2, | |||
Triangle * | tri_indices1, | |||
Triangle * | tri_indices2, | |||
BVH_CollideResult * | res, | |||
BVHFrontList * | front_list | |||
) | [inline] |
BVH front list propagation for continuous collision.
Definition at line 609 of file collision_primitive.h.
int collision_checking::continuousSelfCollide | ( | BVHModel< BV > & | model, | |
BVH_CollideResult * | res, | |||
BVHFrontList * | front_list = NULL | |||
) | [inline] |
Continuous self collision for one BVH model, only support mesh.
Definition at line 107 of file continuous_collision.h.
void collision_checking::continuousSelfCollideRecurse | ( | BVNode< BV > * | tree, | |
int | b, | |||
Vec3f * | vertices, | |||
Vec3f * | prev_vertices, | |||
Triangle * | tri_indices, | |||
BVH_CollideResult * | res, | |||
BVHFrontList * | front_list = NULL | |||
) | [inline] |
Recursive continuous self collision kernel between between two BV trees.
Definition at line 498 of file collision_primitive.h.
BVH_REAL collision_checking::distance | ( | const Vec3f | R0[3], | |
const Vec3f & | T0, | |||
const RSS & | b1, | |||
const RSS & | b2, | |||
Vec3f * | P = NULL , |
|||
Vec3f * | Q = NULL | |||
) |
distance between two RSS bounding volumes P and Q (optional return values) are the closest points in the rectangles, not the RSS. But the direction P - Q is the correct direction for cloest points Notice that P and Q are both in the local frame of the first RSS (not global frame and not even the local frame of object 1)
int collision_checking::distance | ( | const BVHModel< RSS > & | model1, | |
const Vec3f | R1[3], | |||
const Vec3f & | T1, | |||
const BVHModel< RSS > & | model2, | |||
const Vec3f | R2[3], | |||
const Vec3f & | T2, | |||
BVH_DistanceResult * | res, | |||
BVHFrontList * | front_list = NULL | |||
) |
Proximity query between two RSS models, only support mesh-mesh For RSS, we provide a specification that need not update the mesh vertices.
Definition at line 44 of file proximity.cpp.
int collision_checking::distance | ( | const BVHModel< BV > & | model1, | |
const BVHModel< BV > & | model2, | |||
BVH_DistanceResult * | res, | |||
BVHFrontList * | front_list = NULL | |||
) | [inline] |
Proximity query between two BVH models, only support mesh-mesh now.
Definition at line 49 of file proximity.h.
void collision_checking::distanceQueueRecurse | ( | BVNode< RSS > * | tree1, | |
BVNode< RSS > * | tree2, | |||
const Vec3f | R[3], | |||
const Vec3f & | T, | |||
int | b1, | |||
int | b2, | |||
Vec3f * | vertices1, | |||
Vec3f * | vertices2, | |||
Triangle * | tri_indices1, | |||
Triangle * | tri_indices2, | |||
BVH_DistanceResult * | res, | |||
BVHFrontList * | front_list = NULL | |||
) |
Recursive proximity kernel between two RSS trees, using BVT queue acceleration.
Compute the distance between two RSS modes.
Definition at line 97 of file distance_primitive.cpp.
void collision_checking::distanceRecurse | ( | BVNode< RSS > * | tree1, | |
BVNode< RSS > * | tree2, | |||
const Vec3f | R[3], | |||
const Vec3f & | T, | |||
int | b1, | |||
int | b2, | |||
Vec3f * | vertices1, | |||
Vec3f * | vertices2, | |||
Triangle * | tri_indices1, | |||
Triangle * | tri_indices2, | |||
BVH_DistanceResult * | res, | |||
BVHFrontList * | front_list = NULL | |||
) |
Recursive proximity kernel between two RSS trees.
Definition at line 222 of file distance_primitive.cpp.
void collision_checking::distanceRecurse | ( | BVNode< BV > * | tree1, | |
BVNode< BV > * | tree2, | |||
int | b1, | |||
int | b2, | |||
Vec3f * | vertices1, | |||
Vec3f * | vertices2, | |||
Triangle * | tri_indices1, | |||
Triangle * | tri_indices2, | |||
BVH_DistanceResult * | res, | |||
BVHFrontList * | front_list = NULL | |||
) | [inline] |
Recursive proximity kernel between two BV trees.
Definition at line 96 of file distance_primitive.h.
void collision_checking::getCovariance | ( | Vec3f * | ps, | |
Vec3f * | ps2, | |||
Triangle * | ts, | |||
unsigned int * | indices, | |||
int | n, | |||
Vec3f | M[3] | |||
) |
Compute the covariance matrix for a set or subset of triangles.
Definition at line 90 of file BV_fitter.cpp.
void collision_checking::getCovariance | ( | Vec3f * | ps, | |
Vec3f * | ps2, | |||
unsigned int * | indices, | |||
int | n, | |||
Vec3f | M[3] | |||
) |
Compute the covariance matrix for a set or subset of points.
Definition at line 44 of file BV_fitter.cpp.
void collision_checking::getDistances | ( | const Vec3f & | p, | |
BVH_REAL | d[] | |||
) | [inline] |
void collision_checking::getDistances< 5 > | ( | const Vec3f & | p, | |
BVH_REAL | d[] | |||
) | [inline] |
Specification of getDistances.
void collision_checking::getDistances< 6 > | ( | const Vec3f & | p, | |
BVH_REAL | d[] | |||
) | [inline] |
void collision_checking::getDistances< 9 > | ( | const Vec3f & | p, | |
BVH_REAL | d[] | |||
) | [inline] |
void collision_checking::getExtentAndCenter | ( | Vec3f * | ps, | |
Vec3f * | ps2, | |||
Triangle * | ts, | |||
unsigned int * | indices, | |||
int | n, | |||
Vec3f | axis[3], | |||
Vec3f & | center, | |||
Vec3f & | extent | |||
) |
Compute the bounding volume extent and center for a set or subset of points. The bounding volume axes are known.
Definition at line 816 of file BV_fitter.cpp.
void collision_checking::getExtentAndCenter | ( | Vec3f * | ps, | |
Vec3f * | ps2, | |||
unsigned int * | indices, | |||
int | n, | |||
Vec3f | axis[3], | |||
Vec3f & | center, | |||
Vec3f & | extent | |||
) |
Compute the bounding volume extent and center for a set or subset of points. The bounding volume axes are known.
Definition at line 758 of file BV_fitter.cpp.
void collision_checking::getRadiusAndOriginAndRectangleSize | ( | Vec3f * | ps, | |
Vec3f * | ps2, | |||
Triangle * | ts, | |||
unsigned int * | indices, | |||
int | n, | |||
Vec3f | axis[3], | |||
Vec3f & | origin, | |||
BVH_REAL | l[2], | |||
BVH_REAL & | r | |||
) |
Compute the RSS bounding volume parameters: radius, rectangle size and the origin. The bounding volume axes are known.
Definition at line 508 of file BV_fitter.cpp.
void collision_checking::getRadiusAndOriginAndRectangleSize | ( | Vec3f * | ps, | |
Vec3f * | ps2, | |||
unsigned int * | indices, | |||
int | n, | |||
Vec3f | axis[3], | |||
Vec3f & | origin, | |||
BVH_REAL | l[2], | |||
BVH_REAL & | r | |||
) |
Compute the RSS bounding volume parameters: radius, rectangle size and the origin. The bounding volume axes are known.
Definition at line 266 of file BV_fitter.cpp.
bool collision_checking::isSmall | ( | FPT | v, | |
FPT | tolerance | |||
) | [inline] |
Check whether one float value is close to zero.
Definition at line 55 of file roughly_comp.h.
CollisionMesh< BV > * collision_checking::makeBox | ( | double | a, | |
double | b, | |||
double | c | |||
) | [inline] |
Definition at line 418 of file collision_geom.h.
CollisionMesh< BV > * collision_checking::makeCylinder | ( | double | r, | |
double | h, | |||
unsigned int | tot = 16 | |||
) | [inline] |
Definition at line 455 of file collision_geom.h.
CollisionMesh< BV > * collision_checking::makeMesh | ( | const std::vector< Vec3f > & | points, | |
const std::vector< Triangle > & | tri_indices | |||
) | [inline] |
Definition at line 406 of file collision_geom.h.
CollisionMesh< BV > * collision_checking::makeSphere | ( | double | r, | |
unsigned int | seg = 16 , |
|||
unsigned int | ring = 16 | |||
) | [inline] |
Definition at line 525 of file collision_geom.h.
Vec3f collision_checking::max | ( | const Vec3f & | a, | |
const Vec3f & | b | |||
) | [inline] |
void collision_checking::Meigen | ( | Vec3f | a[3], | |
BVH_REAL | dout[3], | |||
Vec3f | vout[3] | |||
) |
Compute the eigen value and vector for a given matrix a.
Definition at line 175 of file BV_fitter.cpp.
Vec3f collision_checking::min | ( | const Vec3f & | a, | |
const Vec3f & | b | |||
) | [inline] |
void collision_checking::minmax | ( | BVH_REAL | p, | |
BVH_REAL & | minv, | |||
BVH_REAL & | maxv | |||
) | [inline] |
void collision_checking::minmax | ( | BVH_REAL | a, | |
BVH_REAL | b, | |||
BVH_REAL & | minv, | |||
BVH_REAL & | maxv | |||
) | [inline] |
Vec3f collision_checking::MTxV | ( | const Vec3f | M[3], | |
const Vec3f & | v | |||
) |
Definition at line 52 of file vec_3f.cpp.
Vec3f collision_checking::MxV | ( | const Vec3f | M[3], | |
const Vec3f & | v | |||
) |
Definition at line 47 of file vec_3f.cpp.
bool collision_checking::overlap | ( | const Vec3f | R0[3], | |
const Vec3f & | T0, | |||
const RSS & | b1, | |||
const RSS & | b2 | |||
) |
bool collision_checking::overlap | ( | const Vec3f | R0[3], | |
const Vec3f & | T0, | |||
const OBB & | b1, | |||
const OBB & | b2 | |||
) |
void collision_checking::propagateBVHFrontList | ( | BVNode< RSS > * | tree1, | |
BVNode< RSS > * | tree2, | |||
Vec3f | R[3], | |||
const Vec3f & | T, | |||
Vec3f * | vertices1, | |||
Vec3f * | vertices2, | |||
Triangle * | tri_indices1, | |||
Triangle * | tri_indices2, | |||
BVH_CollideResult * | res, | |||
BVHFrontList * | front_list | |||
) |
RSS front list propagation for collision of RSS trees.
Definition at line 382 of file collision_primitive.cpp.
void collision_checking::propagateBVHFrontList | ( | BVNode< OBB > * | tree1, | |
BVNode< OBB > * | tree2, | |||
Vec3f | R[3], | |||
const Vec3f & | T, | |||
Vec3f * | vertices1, | |||
Vec3f * | vertices2, | |||
Triangle * | tri_indices1, | |||
Triangle * | tri_indices2, | |||
BVH_CollideResult * | res, | |||
BVHFrontList * | front_list | |||
) |
BVH front list propagation for collision of OBB trees.
Definition at line 308 of file collision_primitive.cpp.
void collision_checking::propagateBVHFrontList | ( | BVNode< BV > * | tree1, | |
BVNode< BV > * | tree2, | |||
Vec3f * | vertices1, | |||
Vec3f * | vertices2, | |||
Triangle * | tri_indices1, | |||
Triangle * | tri_indices2, | |||
BVH_CollideResult * | res, | |||
BVHFrontList * | front_list | |||
) | [inline] |
BVH front list propagation for collision.
Definition at line 519 of file collision_primitive.h.
bool collision_checking::roughlyEqual | ( | FPT | left, | |
FPT | right, | |||
FPT | tolerance | |||
) | [inline] |
Compare whether two float values are close enough.
Definition at line 47 of file roughly_comp.h.
void collision_checking::saveOBjFile | ( | const std::string & | name, | |
const std::vector< Vec3f > & | points, | |||
const std::vector< Triangle > & | tri_indices | |||
) | [inline] |
Definition at line 49 of file collision_geom.h.
int collision_checking::selfCollide | ( | const BVHModel< BV > & | model, | |
BVH_CollideResult * | res, | |||
BVHFrontList * | front_list = NULL | |||
) | [inline] |
Self collision for one BVH model, only support mesh.
Definition at line 86 of file collision.h.
void collision_checking::selfCollideRecurse | ( | BVNode< BV > * | tree, | |
int | b, | |||
Vec3f * | vertices, | |||
Triangle * | tri_indices, | |||
BVH_CollideResult * | res, | |||
BVHFrontList * | front_list = NULL | |||
) | [inline] |
Recursive self collision kernel on one BV tree.
Definition at line 268 of file collision_primitive.h.