Public Member Functions | Protected Member Functions | Private Member Functions | List of all members
SSVTreeCollider Class Reference

collision detector based on SSV(Sphere Swept Volume) More...

#include <SSVTreeCollider.h>

Inheritance diagram for SSVTreeCollider:
Inheritance graph
[legend]

Public Member Functions

bool Collide (BVTCache &cache, double tolerance, const Matrix4x4 *world0=null, const Matrix4x4 *world1=null)
 detect collision between links. More...
 
bool Distance (BVTCache &cache, float &minD, Point &point0, Point &point1, const Matrix4x4 *world0=null, const Matrix4x4 *world1=null)
 compute the minimum distance and the closest points More...
 
 SSVTreeCollider ()
 constructor More...
 
 ~SSVTreeCollider ()
 destructor More...
 
- Public Member Functions inherited from Opcode::AABBTreeCollider
 AABBTreeCollider ()
 
bool Collide (BVTCache &cache, const Matrix4x4 *world0=null, const Matrix4x4 *world1=null)
 
bool Collide (const AABBCollisionTree *tree0, const AABBCollisionTree *tree1, const Matrix4x4 *world0=null, const Matrix4x4 *world1=null, Pair *cache=null)
 
bool Collide (const AABBNoLeafTree *tree0, const AABBNoLeafTree *tree1, const Matrix4x4 *world0=null, const Matrix4x4 *world1=null, Pair *cache=null)
 
bool Collide (const AABBQuantizedTree *tree0, const AABBQuantizedTree *tree1, const Matrix4x4 *world0=null, const Matrix4x4 *world1=null, Pair *cache=null)
 
bool Collide (const AABBQuantizedNoLeafTree *tree0, const AABBQuantizedNoLeafTree *tree1, const Matrix4x4 *world0=null, const Matrix4x4 *world1=null, Pair *cache=null)
 
inline_ udword GetNbBVBVTests () const
 
inline_ udword GetNbBVPrimTests () const
 
inline_ udword GetNbPairs () const
 
inline_ udword GetNbPrimPrimTests () const
 
inline_ const PairGetPairs () const
 
 override (Collider) HRP_COLLISION_EXPORT const char *ValidateSettings()
 
void setCollisionPairInserter (hrp::CollisionPairInserterBase *collisionPairInserter)
 
inline_ void SetFullBoxBoxTest (bool flag)
 
inline_ void SetFullPrimBoxTest (bool flag)
 
virtual ~AABBTreeCollider ()
 
- Public Member Functions inherited from Opcode::Collider
 Collider ()
 
inline_ BOOL ContactFound () const
 
inline_ BOOL FirstContactEnabled () const
 
inline_ BOOL GetContactStatus () const
 
inline_ void SetFirstContact (bool flag)
 
inline_ void SetPrimitiveTests (bool flag)
 
inline_ void SetTemporalCoherence (bool flag)
 
inline_ BOOL SkipPrimitiveTests () const
 
inline_ BOOL TemporalCoherenceEnabled () const
 
inline_ BOOL TemporalHit () const
 
virtual const char * ValidateSettings ()=0
 
virtual ~Collider ()
 

Protected Member Functions

float PrimDist (udword id0, udword id1, Point &point0, Point &point1)
 compute distance between primitives(triangles) More...
 
float SsvSsvDist (const AABBCollisionNode *b0, const AABBCollisionNode *b1)
 compute distance between SSV(Swept Sphere Volume)s More...
 
- Protected Member Functions inherited from Opcode::AABBTreeCollider
void _Collide (const AABBCollisionNode *b0, const AABBCollisionNode *b1)
 
void _Collide (const AABBQuantizedNode *b0, const AABBQuantizedNode *b1, const Point &a, const Point &Pa, const Point &b, const Point &Pb)
 
void _Collide (const AABBNoLeafNode *a, const AABBNoLeafNode *b)
 
void _Collide (const AABBQuantizedNoLeafNode *a, const AABBQuantizedNoLeafNode *b)
 
void _CollideBoxTri (const AABBNoLeafNode *b)
 
void _CollideBoxTri (const AABBQuantizedNoLeafNode *b)
 
void _CollideTriBox (const AABBNoLeafNode *b)
 
void _CollideTriBox (const AABBQuantizedNoLeafNode *b)
 
inline_ BOOL BoxBoxOverlap (const Point &ea, const Point &ca, const Point &eb, const Point &cb)
 
bool CheckTemporalCoherence (Pair *cache)
 
HRP_COLLISION_EXPORT void InitQuery (const Matrix4x4 *world0=null, const Matrix4x4 *world1=null)
 
void PrimTest (udword id0, udword id1)
 
inline_ void PrimTestIndexTri (udword id0)
 
inline_ void PrimTestTriIndex (udword id1)
 
inline_ BOOL Setup (const MeshInterface *mi0, const MeshInterface *mi1)
 
inline_ BOOL TriBoxOverlap (const Point &center, const Point &extents)
 
BOOL TriTriOverlap (const Point &V0, const Point &V1, const Point &V2, const Point &U0, const Point &U1, const Point &U2)
 
- Protected Member Functions inherited from Opcode::Collider
virtual inline_ void InitQuery ()
 
inline_ BOOL Setup (const BaseModel *model)
 

Private Member Functions

bool _Collide (const AABBCollisionNode *b0, const AABBCollisionNode *b1, double tolerance)
 
void _Distance (const AABBCollisionNode *b0, const AABBCollisionNode *b1, float &minD, Point &point0, Point &point1)
 
bool Collide (const AABBCollisionTree *tree0, const AABBCollisionTree *tree1, const Matrix4x4 *world0, const Matrix4x4 *world1, Pair *cache, double tolerance)
 
void Distance (const AABBCollisionTree *tree0, const AABBCollisionTree *tree1, const Matrix4x4 *world0, const Matrix4x4 *world1, Pair *cache, float &minD, Point &point0, Point &point1)
 
float LssLssDist (float r0, const Point &point0, const Point &point1, float r1, const Point &point2, const Point &point3)
 compute distance between LSS(Line Swept Sphere)s More...
 
float LssPssDist (float r0, const Point &point0, const Point &point1, float r1, const Point &center0)
 compute distance between PSS(Point Swept Sphere) and LSS(Line Swept Sphere) More...
 
float PssLssDist (float r0, const Point &center0, float r1, const Point &point0, const Point &point1)
 compute distance between PSS(Point Swept Sphere) and LSS(Line Swept Sphere) More...
 
float PssPssDist (float r0, const Point &center0, float r1, const Point &center1)
 compute distance between PSS(Point Swept Sphere) More...
 

Additional Inherited Members

- Protected Attributes inherited from Opcode::AABBTreeCollider
hrp::CollisionPairInserterBasecollisionPairInserter
 
Matrix3x3 mAR
 Absolute rotation matrix. More...
 
Point mCenterCoeff0
 
Point mCenterCoeff1
 
Point mExtentsCoeff0
 
Point mExtentsCoeff1
 
bool mFullBoxBoxTest
 Perform full BV-BV tests (true) or SAT-lite tests (false) More...
 
bool mFullPrimBoxTest
 Perform full Primitive-BV tests (true) or SAT-lite tests (false) More...
 
udword mId0
 
udword mId1
 
const MeshInterfacemIMesh0
 User-defined mesh interface for object0. More...
 
const MeshInterfacemIMesh1
 User-defined mesh interface for object1. More...
 
udword mLeafIndex
 Triangle index. More...
 
Point mLeafVerts [3]
 Triangle vertices. More...
 
udword mNbBVBVTests
 Number of BV-BV tests. More...
 
udword mNbBVPrimTests
 Number of BV-Primitive tests. More...
 
udword mNbPrimPrimTests
 Number of Primitive-Primitive tests. More...
 
const AABBCollisionNodemNowNode0
 
const AABBCollisionNodemNowNode1
 
Container mPairs
 Pairs of colliding primitives. More...
 
Matrix3x3 mR0to1
 Rotation from object0 to object1. More...
 
Matrix3x3 mR1to0
 Rotation from object1 to object0. More...
 
Point mT0to1
 Translation from object0 to object1. More...
 
Point mT1to0
 Translation from object1 to object0. More...
 
- Protected Attributes inherited from Opcode::Collider
const BaseModelmCurrentModel
 Current model for collision query (owner of touched faces) More...
 
udword mFlags
 Bit flags. More...
 
const MeshInterfacemIMesh
 User-defined mesh interface. More...
 

Detailed Description

collision detector based on SSV(Sphere Swept Volume)

Definition at line 12 of file SSVTreeCollider.h.

Constructor & Destructor Documentation

SSVTreeCollider::SSVTreeCollider ( )

constructor

Definition at line 7 of file SSVTreeCollider.cpp.

SSVTreeCollider::~SSVTreeCollider ( )
inline

destructor

Definition at line 22 of file SSVTreeCollider.h.

Member Function Documentation

bool SSVTreeCollider::_Collide ( const AABBCollisionNode b0,
const AABBCollisionNode b1,
double  tolerance 
)
private

Definition at line 205 of file SSVTreeCollider.cpp.

void SSVTreeCollider::_Distance ( const AABBCollisionNode b0,
const AABBCollisionNode b1,
float &  minD,
Point point0,
Point point1 
)
private

Definition at line 166 of file SSVTreeCollider.cpp.

bool SSVTreeCollider::Collide ( BVTCache cache,
double  tolerance,
const Matrix4x4 world0 = null,
const Matrix4x4 world1 = null 
)

detect collision between links.

Parameters
cache
toleranceIf distance between links is smaller than this value, it is regarded as collision
world0transformation of the first link
world1transformation of the second link
Returns
true if collision is detected, false otherwise

Definition at line 72 of file SSVTreeCollider.cpp.

bool SSVTreeCollider::Collide ( const AABBCollisionTree tree0,
const AABBCollisionTree tree1,
const Matrix4x4 world0,
const Matrix4x4 world1,
Pair cache,
double  tolerance 
)
private

Definition at line 89 of file SSVTreeCollider.cpp.

bool SSVTreeCollider::Distance ( BVTCache cache,
float &  minD,
Point point0,
Point point1,
const Matrix4x4 world0 = null,
const Matrix4x4 world1 = null 
)

compute the minimum distance and the closest points

Parameters
cache
minDthe minimum distance
point0the closest point on the first link
point1the closest point on the second link
world0transformation of the first link
world1transformation of the second link
Returns
true if computed successfully, false otherwise

Definition at line 11 of file SSVTreeCollider.cpp.

void SSVTreeCollider::Distance ( const AABBCollisionTree tree0,
const AABBCollisionTree tree1,
const Matrix4x4 world0,
const Matrix4x4 world1,
Pair cache,
float &  minD,
Point point0,
Point point1 
)
private

Definition at line 30 of file SSVTreeCollider.cpp.

float SSVTreeCollider::LssLssDist ( float  r0,
const Point point0,
const Point point1,
float  r1,
const Point point2,
const Point point3 
)
private

compute distance between LSS(Line Swept Sphere)s

Parameters
r0radius of the first LSS
point0one of end points of the first line segment
point1the other end points of the first line segment
r1radius of the second LSS
point2one of end points of the second line segment
point3the other end points of the second line segment
Returns
distance

Definition at line 157 of file SSVTreeCollider.cpp.

float SSVTreeCollider::LssPssDist ( float  r0,
const Point point0,
const Point point1,
float  r1,
const Point center0 
)
private

compute distance between PSS(Point Swept Sphere) and LSS(Line Swept Sphere)

Parameters
r0radius of the PSS
point0one of end points of the line segment
point1the other end points of the line segment
r1radius of the LSS
center0center of the PSS
Returns
distance

Definition at line 148 of file SSVTreeCollider.cpp.

float SSVTreeCollider::PrimDist ( udword  id0,
udword  id1,
Point point0,
Point point1 
)
protected

compute distance between primitives(triangles)

Parameters
id0index of the first primitive
id1index of the second primitive
point0the closest point on the first primitive
point1the closest point on the second primitive
Returns
the minimum distance

Definition at line 242 of file SSVTreeCollider.cpp.

float SSVTreeCollider::PssLssDist ( float  r0,
const Point center0,
float  r1,
const Point point0,
const Point point1 
)
private

compute distance between PSS(Point Swept Sphere) and LSS(Line Swept Sphere)

Parameters
r0radius of the PSS
center0center of the PSS
r1radius of the LSS
point0one of end points of the line segment
point1the other end points of the line segment
Returns
distance

Definition at line 140 of file SSVTreeCollider.cpp.

float SSVTreeCollider::PssPssDist ( float  r0,
const Point center0,
float  r1,
const Point center1 
)
private

compute distance between PSS(Point Swept Sphere)

Parameters
r0radius of the first sphere
center0center of the first sphere
r1radius of the first sphere
center1center of the first sphere
Returns
distance

Definition at line 133 of file SSVTreeCollider.cpp.

float SSVTreeCollider::SsvSsvDist ( const AABBCollisionNode b0,
const AABBCollisionNode b1 
)
protected

compute distance between SSV(Swept Sphere Volume)s

Parameters
b0collision node from the left tree
b1collision node from the right tree
returndistance

Definition at line 110 of file SSVTreeCollider.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:43