Classes | Public Member Functions | Private Member Functions | Static Private Member Functions | List of all members
hrp::CollisionPairInserter Class Reference

#include <CollisionPairInserter.h>

Inheritance diagram for hrp::CollisionPairInserter:
Inheritance graph
[legend]

Classes

class  col_tri
 
class  tri
 

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)
 refine collision information using neighboring triangls More...
 
 CollisionPairInserter ()
 
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)
 detect collsiion between triangles More...
 
virtual ~CollisionPairInserter ()
 
- Public Member Functions inherited from hrp::CollisionPairInserterBase
void clear ()
 clear collision information More...
 
 CollisionPairInserterBase ()
 
std::vector< collision_data > & collisions ()
 get collision information More...
 
void set (ColdetModelSharedDataSet *model0, ColdetModelSharedDataSet *model1)
 
virtual ~CollisionPairInserterBase ()
 

Private Member Functions

void check_separability (int id1, int id2, int ctype)
 
void examine_normal_vector (int id1, int id2, int ctype)
 
void find_signed_distance (Vector3 &signed_distance, col_tri *trp, int nth, int ctype, int obj)
 
void find_signed_distance (Vector3 &signed_distance, const Vector3 &vert, int nth, int ctype, int obj)
 
void find_signed_distance (Vector3 &signed_distance1, ColdetModelSharedDataSet *model0, int id1, int contactIndex, int ctype, int obj)
 
int get_triangles_in_convex_neighbor (ColdetModelSharedDataSet *model, int id, col_tri *tri_convex_neighbor, int max_num)
 
void get_triangles_in_convex_neighbor (ColdetModelSharedDataSet *model, int id, col_tri *tri_convex_neighbor, std::vector< int > &map, int &count)
 
int new_point_test (int k)
 
void triangleIndexToPoint (ColdetModelSharedDataSet *model, int id, col_tri &tri)
 

Static Private Member Functions

static void calc_normal_vector (col_tri *t)
 
static void copy_tri (col_tri *t1, tri *t2)
 
static void copy_tri (col_tri *t1, col_tri *t2)
 
static int is_convex_neighbor (col_tri *t1, col_tri *t2)
 

Additional Inherited Members

- Public Attributes inherited from hrp::CollisionPairInserterBase
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_datacdContact
 collision information More...
 
ColdetModelSharedDataSetmodels [2]
 
bool normalVectorCorrection
 flag to enable/disable normal vector correction More...
 

Detailed Description

Definition at line 18 of file CollisionPairInserter.h.

Constructor & Destructor Documentation

CollisionPairInserter::CollisionPairInserter ( )

Definition at line 51 of file CollisionPairInserter.cpp.

CollisionPairInserter::~CollisionPairInserter ( )
virtual

Definition at line 57 of file CollisionPairInserter.cpp.

Member Function Documentation

int CollisionPairInserter::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 
)
virtual

refine collision information using neighboring triangls

Parameters
b1node of the first colliding triangle
b2node of the second colliding triangle
id1id of the first colliding triangle
id2id of the second colliding triangle
num_of_i_pointsthe number of intersecting points
i_pointsintersecting points
n_vectornormal vector of collision
depthpenetration depth
n1normal vector of the first triangle
m1normal vector of the second triangle
ctypecollision type
mesh1mesh which includes the first triangle
mesh2mesh which includes the second triangle
Returns
CD_OK if refined successfully
Note
collision information is expressed in the second mesh coordinates

Implements hrp::CollisionPairInserterBase.

Definition at line 390 of file CollisionPairInserter.cpp.

void CollisionPairInserter::calc_normal_vector ( col_tri t)
staticprivate

Definition at line 83 of file CollisionPairInserter.cpp.

void CollisionPairInserter::check_separability ( int  id1,
int  id2,
int  ctype 
)
private

Definition at line 196 of file CollisionPairInserter.cpp.

void CollisionPairInserter::copy_tri ( col_tri t1,
tri t2 
)
staticprivate

Definition at line 63 of file CollisionPairInserter.cpp.

void CollisionPairInserter::copy_tri ( col_tri t1,
col_tri t2 
)
staticprivate

Definition at line 71 of file CollisionPairInserter.cpp.

int CollisionPairInserter::detectTriTriOverlap ( const Vector3 P1,
const Vector3 P2,
const Vector3 P3,
const Vector3 Q1,
const Vector3 Q2,
const Vector3 Q3,
collision_data col_p 
)
virtual

detect collsiion between triangles

Parameters
P1the first vertex of the first triangle
P2the second vertex of the first triangle
P3the third vertex of the first triangle
Q1the first vertex of the second triangle
Q2the second vertex of the second triangle
Q3the third vertex of the second triangle
col_pcollision information
Returns
1 if collision is detected, 0 otherwise
Note
all vertices must be represented in the same coordinates

Implements hrp::CollisionPairInserterBase.

Definition at line 446 of file CollisionPairInserter.cpp.

void CollisionPairInserter::examine_normal_vector ( int  id1,
int  id2,
int  ctype 
)
private

Definition at line 191 of file CollisionPairInserter.cpp.

void CollisionPairInserter::find_signed_distance ( Vector3 signed_distance,
col_tri trp,
int  nth,
int  ctype,
int  obj 
)
private

Definition at line 271 of file CollisionPairInserter.cpp.

void CollisionPairInserter::find_signed_distance ( Vector3 signed_distance,
const Vector3 vert,
int  nth,
int  ctype,
int  obj 
)
private

Definition at line 279 of file CollisionPairInserter.cpp.

void CollisionPairInserter::find_signed_distance ( Vector3 signed_distance1,
ColdetModelSharedDataSet model0,
int  id1,
int  contactIndex,
int  ctype,
int  obj 
)
private

Definition at line 351 of file CollisionPairInserter.cpp.

int CollisionPairInserter::get_triangles_in_convex_neighbor ( ColdetModelSharedDataSet model,
int  id,
col_tri tri_convex_neighbor,
int  max_num 
)
private

Definition at line 167 of file CollisionPairInserter.cpp.

void CollisionPairInserter::get_triangles_in_convex_neighbor ( ColdetModelSharedDataSet model,
int  id,
col_tri tri_convex_neighbor,
std::vector< int > &  map,
int count 
)
private

Definition at line 126 of file CollisionPairInserter.cpp.

int CollisionPairInserter::is_convex_neighbor ( col_tri t1,
col_tri t2 
)
staticprivate

Definition at line 94 of file CollisionPairInserter.cpp.

int CollisionPairInserter::new_point_test ( int  k)
private

Definition at line 370 of file CollisionPairInserter.cpp.

void CollisionPairInserter::triangleIndexToPoint ( ColdetModelSharedDataSet model,
int  id,
col_tri tri 
)
private

Definition at line 116 of file CollisionPairInserter.cpp.


The documentation for this class was generated from the following files:


openhrp3
Author(s): AIST, General Robotix Inc., Nakamura Lab of Dept. of Mechano Informatics at University of Tokyo
autogenerated on Sat May 8 2021 02:42:45