#include <CollisionPairInserterBase.h>
Public Member Functions | |
virtual int | apply (const Opcode::AABBCollisionNode *b1, const Opcode::AABBCollisionNode *b2, int id1, int id2, int num_of_i_points, Vector3 i_points[4], Vector3 &n_vector, double depth, Vector3 &n1, Vector3 &m1, int ctype, Opcode::MeshInterface *mesh1, Opcode::MeshInterface *mesh2)=0 |
refine collision information using neighboring triangls More... | |
void | clear () |
clear collision information More... | |
CollisionPairInserterBase () | |
std::vector< collision_data > & | collisions () |
get collision information More... | |
virtual int | detectTriTriOverlap (const Vector3 &P1, const Vector3 &P2, const Vector3 &P3, const Vector3 &Q1, const Vector3 &Q2, const Vector3 &Q3, collision_data *col_p)=0 |
detect collsiion between triangles More... | |
void | set (ColdetModelSharedDataSet *model0, ColdetModelSharedDataSet *model1) |
virtual | ~CollisionPairInserterBase () |
Public Attributes | |
Matrix33 | CD_Rot1 |
rotation of the first mesh More... | |
Matrix33 | CD_Rot2 |
rotation of the second mesh More... | |
double | CD_s1 |
scale of the first mesh More... | |
double | CD_s2 |
scale of the second mesh More... | |
Vector3 | CD_Trans1 |
translation of the first mesh More... | |
Vector3 | CD_Trans2 |
translation of the second mesh More... | |
std::vector< collision_data > | cdContact |
collision information More... | |
ColdetModelSharedDataSet * | models [2] |
bool | normalVectorCorrection |
flag to enable/disable normal vector correction More... | |
Definition at line 27 of file CollisionPairInserterBase.h.
|
inline |
Definition at line 30 of file CollisionPairInserterBase.h.
|
inlinevirtual |
Definition at line 31 of file CollisionPairInserterBase.h.
|
pure virtual |
refine collision information using neighboring triangls
b1 | node of the first colliding triangle |
b2 | node of the second colliding triangle |
id1 | id of the first colliding triangle |
id2 | id of the second colliding triangle |
num_of_i_points | the number of intersecting points |
i_points | intersecting points |
n_vector | normal vector of collision |
depth | penetration depth |
n1 | normal vector of the first triangle |
m1 | normal vector of the second triangle |
ctype | collision type |
mesh1 | mesh which includes the first triangle |
mesh2 | mesh which includes the second triangle |
Implemented in hrp::CollisionPairInserter.
clear collision information
Definition at line 35 of file CollisionPairInserterBase.h.
|
inline |
get collision information
Definition at line 95 of file CollisionPairInserterBase.h.
|
pure virtual |
detect collsiion between triangles
P1 | the first vertex of the first triangle |
P2 | the second vertex of the first triangle |
P3 | the third vertex of the first triangle |
Q1 | the first vertex of the second triangle |
Q2 | the second vertex of the second triangle |
Q3 | the third vertex of the second triangle |
col_p | collision information |
Implemented in hrp::CollisionPairInserter.
|
inline |
Definition at line 99 of file CollisionPairInserterBase.h.
Matrix33 hrp::CollisionPairInserterBase::CD_Rot1 |
rotation of the first mesh
Definition at line 105 of file CollisionPairInserterBase.h.
Matrix33 hrp::CollisionPairInserterBase::CD_Rot2 |
rotation of the second mesh
Definition at line 109 of file CollisionPairInserterBase.h.
double hrp::CollisionPairInserterBase::CD_s1 |
scale of the first mesh
Definition at line 107 of file CollisionPairInserterBase.h.
double hrp::CollisionPairInserterBase::CD_s2 |
scale of the second mesh
Definition at line 111 of file CollisionPairInserterBase.h.
Vector3 hrp::CollisionPairInserterBase::CD_Trans1 |
translation of the first mesh
Definition at line 106 of file CollisionPairInserterBase.h.
Vector3 hrp::CollisionPairInserterBase::CD_Trans2 |
translation of the second mesh
Definition at line 110 of file CollisionPairInserterBase.h.
std::vector<collision_data> hrp::CollisionPairInserterBase::cdContact |
collision information
Definition at line 113 of file CollisionPairInserterBase.h.
ColdetModelSharedDataSet* hrp::CollisionPairInserterBase::models[2] |
Definition at line 115 of file CollisionPairInserterBase.h.
bool hrp::CollisionPairInserterBase::normalVectorCorrection |
flag to enable/disable normal vector correction
Definition at line 118 of file CollisionPairInserterBase.h.