#include <PQPCollision.h>
Public Member Functions | |
virtual void | activateBody (const Body *body, bool active) |
Activates / deactivates a body inside the collision detection system. | |
virtual void | activatePair (const Body *body1, const Body *body2, bool active) |
Toggles collision between a particular pair of bodies. | |
virtual bool | addBody (Body *body, bool ExpectEmpty=false) |
Add a new body to the collision detection system. | |
virtual int | allCollisions (DetectionType type, CollisionReport *report, const std::vector< Body * > *interestList) |
virtual int | allContacts (CollisionReport *report, double threshold, const std::vector< Body * > *interestList) |
virtual void | bodyRegion (const Body *body, position point, vec3 normal, double radius, Neighborhood *neighborhood) |
virtual double | bodyToBodyDistance (const Body *body1, const Body *body2, position &p1, position &p2) |
virtual void | cloneBody (Body *clone, const Body *original) |
virtual int | contact (ContactReport *report, double threshold, const Body *body1, const Body *body2) |
virtual void | getBoundingVolumes (const Body *body, int depth, std::vector< BoundingBox > *bvs) |
Returns the bounding box hierarchy at a certin depth for a body. | |
virtual bool | isActive (const Body *body1, const Body *body2=NULL) |
Tells us if collisions for a body in general, or a particular pair of bodies, are active. | |
virtual void | newThread () |
Also checks if threading is enabled inside VCollide. | |
virtual double | pointToBodyDistance (const Body *body1, position point, position &closestPoint, vec3 &closestNormal) |
PQPCollision () | |
virtual void | removeBody (Body *body) |
Remove a body from the collision detection system. | |
virtual void | setBodyTransform (Body *body, const transf &t) |
Set the position of a body in the collision detection system. | |
~PQPCollision () | |
Private Member Functions | |
void | convertContactReport (PQP_ContactResult *pqpReport, ContactReport *report) |
Body * | getBody (int id) |
int | getId (const Body *body) |
bool | getIdsFromList (const std::vector< Body * > *interestList, int **iList, int *iSize) |
Private Attributes | |
std::map< int, Body * > | mBodies |
std::map< const Body *, int > | mIds |
VCollide * | mVc |
Static Private Attributes | |
static const int | MAXCOLLISIONS = 256 |
Implementation of the graspit collison interface using modified versions of the PQP and VCollisde systems from UNC. See CollisionInterface class for interface reference. The original versions of PQP and VCollide are copyright 1997 The University of North Carolina at Chapel Hill.
Definition at line 43 of file PQPCollision.h.
PQPCollision::PQPCollision | ( | ) |
Definition at line 35 of file PQPCollision.cpp.
PQPCollision::~PQPCollision | ( | ) |
Definition at line 40 of file PQPCollision.cpp.
void PQPCollision::activateBody | ( | const Body * | body, | |
bool | active | |||
) | [virtual] |
Activates / deactivates a body inside the collision detection system.
If a body is deactivated, it is not removed from the system, but it stops producing either collisions or contacts. Can be re-activated any time desired, it is very cheap.
Implements CollisionInterface.
Definition at line 157 of file PQPCollision.cpp.
Toggles collision between a particular pair of bodies.
Implements CollisionInterface.
Definition at line 172 of file PQPCollision.cpp.
bool PQPCollision::addBody | ( | Body * | body, | |
bool | ExpectEmpty = false | |||
) | [virtual] |
Add a new body to the collision detection system.
Implements CollisionInterface.
Definition at line 46 of file PQPCollision.cpp.
int PQPCollision::allCollisions | ( | DetectionType | type, | |
CollisionReport * | report, | |||
const std::vector< Body * > * | interestList | |||
) | [virtual] |
Goes through all the bodies in the world and returns collisions. If type is FAST_COLLISION, returns 1 as soon as any collision is found. If type is ALL_COLLISIONS, returns the total number of collisions in the world.
The list of all colliding bodies is placed in the report.
If an is passed, then it only queries for collisions involving at least one body in the list.
Implements CollisionInterface.
Definition at line 227 of file PQPCollision.cpp.
int PQPCollision::allContacts | ( | CollisionReport * | report, | |
double | threshold, | |||
const std::vector< Body * > * | interestList | |||
) | [virtual] |
Finds all the contacts in the world. interestList is used the same way as in allCollisions().
Implements CollisionInterface.
Definition at line 290 of file PQPCollision.cpp.
void PQPCollision::bodyRegion | ( | const Body * | body, | |
position | point, | |||
vec3 | normal, | |||
double | radius, | |||
Neighborhood * | neighborhood | |||
) | [virtual] |
Finds the neighborhood of a given point on the surface of a body. Given the point point, it will find all the vertices of the body that are with radius of this point, as long as they belong to triangles that do not have normals pointing in the opposite direction. This is done in order not to return vertices that are on the other side of a thin body.
Assumes both point and normal are in the coordinate frame of body
Implements CollisionInterface.
Definition at line 377 of file PQPCollision.cpp.
double PQPCollision::bodyToBodyDistance | ( | const Body * | body1, | |
const Body * | body2, | |||
position & | p1, | |||
position & | p2 | |||
) | [virtual] |
Distance between two bodies, or -1 if the bodies interpenetrate. On exit, p1 and p2 are the two points on the bodies that are closest to each other, each in its own body coordinate frame
Implements CollisionInterface.
Definition at line 359 of file PQPCollision.cpp.
Creates a clone of a body that shares the collision geometry hierarchy but has its own transform and can be moved and queried for collision independently. WARNING: there are still problems with the cloning mechanism. If the original is deleted, ot if its collision structures are changed, the lingering clone is almost certain to cause a crash.
Implements CollisionInterface.
Definition at line 116 of file PQPCollision.cpp.
int PQPCollision::contact | ( | ContactReport * | report, | |
double | threshold, | |||
const Body * | body1, | |||
const Body * | body2 | |||
) | [virtual] |
Finds the contacts between two specified bodies
Implements CollisionInterface.
Definition at line 320 of file PQPCollision.cpp.
void PQPCollision::convertContactReport | ( | PQP_ContactResult * | pqpReport, | |
ContactReport * | report | |||
) | [private] |
Definition at line 274 of file PQPCollision.cpp.
Body * PQPCollision::getBody | ( | int | id | ) | [inline, private] |
Definition at line 108 of file PQPCollision.h.
void PQPCollision::getBoundingVolumes | ( | const Body * | , | |
int | , | |||
std::vector< BoundingBox > * | ||||
) | [virtual] |
Returns the bounding box hierarchy at a certin depth for a body.
Reimplemented from CollisionInterface.
Definition at line 397 of file PQPCollision.cpp.
int PQPCollision::getId | ( | const Body * | body | ) | [inline, private] |
Definition at line 101 of file PQPCollision.h.
bool PQPCollision::getIdsFromList | ( | const std::vector< Body * > * | interestList, | |
int ** | iList, | |||
int * | iSize | |||
) | [private] |
Definition at line 206 of file PQPCollision.cpp.
Tells us if collisions for a body in general, or a particular pair of bodies, are active.
If body2 is NULL, it returns whether body1 is active in the collision detection system. Otherwise, it returns whether collisions between this particular pair of bodies are active.
Implements CollisionInterface.
Definition at line 187 of file PQPCollision.cpp.
void PQPCollision::newThread | ( | ) | [virtual] |
Also checks if threading is enabled inside VCollide.
Reimplemented from CollisionInterface.
Definition at line 423 of file PQPCollision.cpp.
double PQPCollision::pointToBodyDistance | ( | const Body * | body1, | |
position | point, | |||
position & | closestPoint, | |||
vec3 & | closestNormal | |||
) | [virtual] |
Distance from a point point specified in world coordinates to a body. On exit, closestPoint is the point on the body that is closest to the given point, and closestNormal is the body normal at that point. Both closestPoint and closestNormal are in world coordinates
Implements CollisionInterface.
Definition at line 337 of file PQPCollision.cpp.
void PQPCollision::removeBody | ( | Body * | body | ) | [virtual] |
Remove a body from the collision detection system.
Implements CollisionInterface.
Definition at line 100 of file PQPCollision.cpp.
Set the position of a body in the collision detection system.
Implements CollisionInterface.
Definition at line 144 of file PQPCollision.cpp.
const int PQPCollision::MAXCOLLISIONS = 256 [static, private] |
Definition at line 46 of file PQPCollision.h.
std::map<int, Body*> PQPCollision::mBodies [private] |
Definition at line 50 of file PQPCollision.h.
std::map<const Body*, int> PQPCollision::mIds [private] |
Definition at line 49 of file PQPCollision.h.
VCollide* PQPCollision::mVc [private] |
Definition at line 48 of file PQPCollision.h.