#include <graspitCollision.h>
Public Member Functions | |
virtual void | activateBody (const Body *, bool) |
Activates / deactivates a body inside the collision detection system. | |
virtual void | activatePair (const Body *, const Body *, bool) |
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 *, const Body *) |
virtual int | contact (ContactReport *report, double threshold, const Body *body1, const Body *body2) |
virtual void | getBoundingVolumes (const Body *, int, std::vector< BoundingBox > *) |
Returns the bounding box hierarchy at a certin depth for a body. | |
virtual int | getThread () |
GraspitCollision () | |
virtual bool | isActive (const Body *, const Body *) |
Tells us if collisions for a body in general, or a particular pair of bodies, are active. | |
virtual void | newThread () |
virtual double | pointToBodyDistance (const Body *body1, position point, position &closestPoint, vec3 &closestNormal) |
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. | |
virtual | ~GraspitCollision () |
Private Types | |
typedef std::pair< const CollisionModel *, const CollisionModel * > | CollisionPair |
typedef std::multimap< const CollisionModel *, const CollisionModel * >::iterator | DisabledIterator |
Private Member Functions | |
void | convertInterestList (const std::vector< Body * > *inList, std::set< CollisionModel * > *outSet) |
void | getActivePairs (std::list< CollisionPair > *activePairs, const std::set< CollisionModel * > *interestList) |
Returns all the pairs of bodies that collision should be cheked for. | |
Body * | getBody (const CollisionModel *model) |
CollisionModel * | getModel (const Body *body) |
Private Attributes | |
std::map< const CollisionModel *, Body * > | mBodyMap |
Maps internal collision model pointers to GraspIt Body pointers. | |
std::multimap< const CollisionModel *, const CollisionModel * > | mDisabledMap |
Stores all the disabled pairs of bodies. | |
std::map< const Body *, CollisionModel * > | mModelMap |
Maps GraspIt Body pointers to internal collision model pointers. | |
std::vector< CollisionModel * > | mModels |
Stores the pointers to collision models sorted in ascending order of pointer comparisons. |
Definition at line 46 of file graspitCollision.h.
typedef std::pair<const CollisionModel*, const CollisionModel*> GraspitCollision::CollisionPair [private] |
Definition at line 70 of file graspitCollision.h.
typedef std::multimap<const CollisionModel*, const CollisionModel*>::iterator GraspitCollision::DisabledIterator [private] |
Definition at line 62 of file graspitCollision.h.
GraspitCollision::GraspitCollision | ( | ) | [inline] |
Definition at line 78 of file graspitCollision.h.
virtual GraspitCollision::~GraspitCollision | ( | ) | [inline, virtual] |
Definition at line 79 of file graspitCollision.h.
void GraspitCollision::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 103 of file graspitCollision.cpp.
void GraspitCollision::activatePair | ( | const Body * | body1, | |
const Body * | body2, | |||
bool | active | |||
) | [virtual] |
Toggles collision between a particular pair of bodies.
Implements CollisionInterface.
Definition at line 114 of file graspitCollision.cpp.
bool GraspitCollision::addBody | ( | Body * | body, | |
bool | ExpectEmpty = false | |||
) | [virtual] |
Add a new body to the collision detection system.
Implements CollisionInterface.
Definition at line 183 of file graspitCollision.cpp.
int GraspitCollision::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 291 of file graspitCollision.cpp.
int GraspitCollision::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 324 of file graspitCollision.cpp.
void GraspitCollision::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 438 of file graspitCollision.cpp.
double GraspitCollision::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 417 of file graspitCollision.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 241 of file graspitCollision.cpp.
int GraspitCollision::contact | ( | ContactReport * | report, | |
double | threshold, | |||
const Body * | body1, | |||
const Body * | body2 | |||
) | [virtual] |
Finds the contacts between two specified bodies
Implements CollisionInterface.
Definition at line 366 of file graspitCollision.cpp.
void GraspitCollision::convertInterestList | ( | const std::vector< Body * > * | inList, | |
std::set< CollisionModel * > * | outSet | |||
) | [private] |
Definition at line 277 of file graspitCollision.cpp.
void GraspitCollision::getActivePairs | ( | std::list< CollisionPair > * | activePairs, | |
const std::set< CollisionModel * > * | interestList | |||
) | [private] |
Returns all the pairs of bodies that collision should be cheked for.
A pair of bodies is active iff:
Definition at line 56 of file graspitCollision.cpp.
Body * GraspitCollision::getBody | ( | const CollisionModel * | model | ) | [inline, private] |
Definition at line 121 of file graspitCollision.h.
void GraspitCollision::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 458 of file graspitCollision.cpp.
CollisionModel * GraspitCollision::getModel | ( | const Body * | body | ) | [inline, private] |
Definition at line 129 of file graspitCollision.h.
virtual int GraspitCollision::getThread | ( | ) | [inline, virtual] |
Definition at line 117 of file graspitCollision.h.
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 141 of file graspitCollision.cpp.
virtual void GraspitCollision::newThread | ( | ) | [inline, virtual] |
Informs the collision detection system that this is now a new thread. All bodies or clones added from now on are specific to this thread. Bodies from a given thread can collide ONLY with bodies from the same thread, or with bodies from the master thread, which has ID 0.
Reimplemented from CollisionInterface.
Definition at line 116 of file graspitCollision.h.
double GraspitCollision::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 394 of file graspitCollision.cpp.
void GraspitCollision::removeBody | ( | Body * | body | ) | [virtual] |
Remove a body from the collision detection system.
Implements CollisionInterface.
Definition at line 217 of file graspitCollision.cpp.
Set the position of a body in the collision detection system.
Implements CollisionInterface.
Definition at line 266 of file graspitCollision.cpp.
std::map<const CollisionModel*, Body*> GraspitCollision::mBodyMap [private] |
Maps internal collision model pointers to GraspIt Body pointers.
Definition at line 56 of file graspitCollision.h.
std::multimap<const CollisionModel*, const CollisionModel*> GraspitCollision::mDisabledMap [private] |
Stores all the disabled pairs of bodies.
When inserting a new pair in here, always make sure that the *key* pointer and the value pointer compare such that key < value. This allows us to know, for any two pointers, which is supposed to be the key for indexing here. It also allows for more efficient traversal of the complete list of bodies
Definition at line 68 of file graspitCollision.h.
std::map<const Body*, CollisionModel*> GraspitCollision::mModelMap [private] |
Maps GraspIt Body pointers to internal collision model pointers.
Definition at line 54 of file graspitCollision.h.
std::vector<CollisionModel*> GraspitCollision::mModels [private] |
Stores the pointers to collision models sorted in ascending order of pointer comparisons.
Definition at line 51 of file graspitCollision.h.