#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 | |
void | clear () |
clear collision information | |
std::vector< collision_data > & | collisions () |
get collision information | |
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 | |
void | set (ColdetModelSharedDataSet *model0, ColdetModelSharedDataSet *model1) |
virtual | ~CollisionPairInserterBase () |
Public Attributes | |
Matrix33 | CD_Rot1 |
rotation of the first mesh | |
Matrix33 | CD_Rot2 |
rotation of the second mesh | |
double | CD_s1 |
scale of the first mesh | |
double | CD_s2 |
scale of the second mesh | |
Vector3 | CD_Trans1 |
translation of the first mesh | |
Vector3 | CD_Trans2 |
translation of the second mesh | |
std::vector< collision_data > | cdContact |
collision information | |
ColdetModelSharedDataSet * | models [2] |
Definition at line 27 of file CollisionPairInserterBase.h.
virtual hrp::CollisionPairInserterBase::~CollisionPairInserterBase | ( | ) | [inline, virtual] |
Definition at line 30 of file CollisionPairInserterBase.h.
virtual int hrp::CollisionPairInserterBase::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 | ||
) | [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.
void hrp::CollisionPairInserterBase::clear | ( | void | ) | [inline] |
clear collision information
Definition at line 34 of file CollisionPairInserterBase.h.
std::vector<collision_data>& hrp::CollisionPairInserterBase::collisions | ( | ) | [inline] |
get collision information
Definition at line 94 of file CollisionPairInserterBase.h.
virtual int hrp::CollisionPairInserterBase::detectTriTriOverlap | ( | const Vector3 & | P1, |
const Vector3 & | P2, | ||
const Vector3 & | P3, | ||
const Vector3 & | Q1, | ||
const Vector3 & | Q2, | ||
const Vector3 & | Q3, | ||
collision_data * | col_p | ||
) | [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.
void hrp::CollisionPairInserterBase::set | ( | ColdetModelSharedDataSet * | model0, |
ColdetModelSharedDataSet * | model1 | ||
) | [inline] |
Definition at line 98 of file CollisionPairInserterBase.h.
rotation of the first mesh
Definition at line 104 of file CollisionPairInserterBase.h.
rotation of the second mesh
Definition at line 108 of file CollisionPairInserterBase.h.
scale of the first mesh
Definition at line 106 of file CollisionPairInserterBase.h.
scale of the second mesh
Definition at line 110 of file CollisionPairInserterBase.h.
translation of the first mesh
Definition at line 105 of file CollisionPairInserterBase.h.
translation of the second mesh
Definition at line 109 of file CollisionPairInserterBase.h.
std::vector<collision_data> hrp::CollisionPairInserterBase::cdContact |
collision information
Definition at line 112 of file CollisionPairInserterBase.h.
Definition at line 114 of file CollisionPairInserterBase.h.