00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026 #include "graspitCollision.h"
00027
00028 #include <algorithm>
00029
00030
00031 #include "debug.h"
00032
00033 #include "body.h"
00034 #include "collisionModel.h"
00035 #include "collisionAlgorithms.h"
00036
00037
00038 #include "profiling.h"
00039
00040 using namespace Collision;
00041
00055 void
00056 GraspitCollision::getActivePairs(std::list<CollisionPair> *activePairs,
00057 const std::set<CollisionModel*> *interestList)
00058 {
00059 int myThread = getThreadId();
00060
00061 std::vector<CollisionModel*>::iterator it1, it2;
00062 for (it1=mModels.begin(); it1!=mModels.end(); it1++) {
00063
00064 if ( !(*it1)->isActive() ) continue;
00065
00066 if ( (*it1)->getThreadId() != myThread && (*it1)->getThreadId() != 0) continue;
00067
00068
00069 std::pair<DisabledIterator, DisabledIterator> range;
00070 range = mDisabledMap.equal_range(*it1);
00071
00072 bool interest1 = true;
00073 if (interestList) {
00074 if (interestList->find(*it1) == interestList->end()) interest1 = false;
00075 }
00076
00077
00078 for (it2 = it1+1; it2!=mModels.end(); it2++) {
00079
00080 if ( !(*it2)->isActive() ) continue;
00081
00082 if ( (*it2)->getThreadId() != myThread && (*it2)->getThreadId() != 0) continue;
00083 if ( myThread != 0 && (*it1)->getThreadId() == 0 && (*it2)->getThreadId() == 0) continue;
00084
00085 DisabledIterator rangeIt;
00086 bool disabled = false;
00087 for (rangeIt = range.first; rangeIt != range.second && !disabled; rangeIt++) {
00088 if (rangeIt->second == *it2) disabled = true;
00089 }
00090
00091 if (disabled) continue;
00092
00093 if (!interest1) {
00094 if (interestList->find(*it2) == interestList->end()) continue;
00095 }
00096
00097 activePairs->push_back( CollisionPair(*it1, *it2) );
00098 }
00099 }
00100 }
00101
00102 void
00103 GraspitCollision::activateBody(const Body* body, bool active)
00104 {
00105 CollisionModel *model = getModel(body);
00106 if (!model) {
00107 DBGA("GCOL: model not found");
00108 return;
00109 }
00110 model->setActive(active);
00111 }
00112
00113 void
00114 GraspitCollision::activatePair(const Body* body1, const Body* body2, bool active)
00115 {
00116 CollisionModel *model1 = getModel(body1);
00117 CollisionModel *model2 = getModel(body2);
00118 if (!model1 || !model2) {
00119 DBGA("GCOL: model not found");
00120 return;
00121 }
00122 if (model2 == model1) {
00123
00124 DBGA("GCOL Warning: insertion collision pair is actually one body");
00125 model1->setActive(active);
00126 return;
00127 }
00128 else if (model2 < model1) {
00129
00130 std::swap(model1, model2);
00131 }
00132 if (!active) {
00133 DBGP("Disable pair: " << model1 << " -- " << model2);
00134 mDisabledMap.insert( std::pair<const CollisionModel*, const CollisionModel*>(model1, model2) );
00135 } else {
00136
00137 }
00138 }
00139
00140 bool
00141 GraspitCollision::isActive(const Body* body1, const Body* body2)
00142 {
00143 CollisionModel *model1 = getModel(body1);
00144 if (!model1) {
00145 DBGA("GCOL: model not found");
00146 return false;
00147 }
00148 if (!body2) return model1->isActive();
00149
00150 CollisionModel *model2 = getModel(body2);
00151 if (!model2) {
00152 DBGA("GCOL: model not found");
00153 return false;
00154 }
00155 if (!model1->isActive() || !model2->isActive()) {
00156 return false;
00157 }
00158 if (model2==model1) {
00159
00160 DBGA("GCOL Warning: collision pair is actually one body");
00161 return model1->isActive();
00162 }
00163 else if (model2 < model1) {
00164
00165 std::swap(model1, model2);
00166 }
00167
00168
00169
00170 std::pair<DisabledIterator, DisabledIterator> range;
00171 range = mDisabledMap.equal_range(model1);
00172
00173 DisabledIterator rangeIt;
00174 bool disabled = false;
00175 for (rangeIt = range.first; rangeIt != range.second && !disabled; rangeIt++) {
00176 if (rangeIt->second == model2) disabled = true;
00177 }
00178 if (disabled) return false;
00179 return true;
00180 }
00181
00182 bool
00183 GraspitCollision::addBody(Body *body, bool)
00184 {
00185 if (getModel(body)) {
00186 DBGA("GCOL: body already present");
00187 return false;
00188 }
00189
00190 CollisionModel *model = new CollisionModel(getThreadId());
00191
00192
00193 std::vector<Triangle> triangles;
00194 body->getGeometryTriangles(&triangles);
00195
00196
00197 for (int i=0; i<(int)triangles.size(); i++) {
00198 model->addTriangle(triangles[i]);
00199 }
00200
00201
00202 model->build();
00203
00204
00205 mModelMap[body] = model;
00206 mBodyMap[model] = body;
00207 mModels.push_back(model);
00208
00209
00210
00211 std::sort( mModels.begin(), mModels.end() );
00212
00213 return true;
00214 }
00215
00216 bool GraspitCollision::updateBodyGeometry(Body* body, bool)
00217 {
00218 CollisionModel *model = getModel(body);
00219 if (!model)
00220 {
00221 DBGA("GCOL: body not found for geometry update");
00222 return false;
00223 }
00224 model->reset();
00225
00226
00227 std::vector<Triangle> triangles;
00228 body->getGeometryTriangles(&triangles);
00229
00230
00231 for (int i=0; i<(int)triangles.size(); i++) {
00232 model->addTriangle(triangles[i]);
00233 }
00234
00235
00236 model->build();
00237 return true;
00238 }
00239
00240 void
00241 GraspitCollision::removeBody(Body *body)
00242 {
00243 CollisionModel *model = getModel(body);
00244 if (!model) {
00245 DBGA("GCOL: model not found");
00246 return;
00247 }
00248
00249 std::vector<CollisionModel*>::iterator it;
00250 for (it=mModels.begin(); it!=mModels.end(); it++){
00251 if ( *it == model ) break;
00252 }
00253 if (it==mModels.end()) {
00254 DBGA("GCOL error: model for deletion not present");
00255 } else {
00256 mModels.erase(it);
00257 }
00258
00259 mModelMap.erase( mModelMap.find(body) );
00260 mBodyMap.erase( mBodyMap.find(model) );
00261 delete model;
00262 }
00263
00264 void
00265 GraspitCollision::cloneBody(Body* clone, const Body* original)
00266 {
00267 CollisionModel *originalModel = getModel(original);
00268 if (!originalModel) {
00269 DBGA("GCOL: model not found");
00270 return;
00271 }
00272 if (getModel(clone) ) {
00273 DBGA("GCOL: clone already in collision detection system");
00274 return;
00275 }
00276 CollisionModel *cloneModel = new CollisionModel(getThreadId());
00277 cloneModel->cloneModel(originalModel);
00278
00279
00280 mModelMap[clone] = cloneModel;
00281 mBodyMap[cloneModel] = clone;
00282 mModels.push_back(cloneModel);
00283
00284
00285
00286 std::sort( mModels.begin(), mModels.end() );
00287 }
00288
00289 void
00290 GraspitCollision::setBodyTransform(Body *body, const transf &t)
00291 {
00292 CollisionModel *model = getModel(body);
00293 if (!model) {
00294 DBGA("GCOL: model not found");
00295 return;
00296 }
00297 model->setTran(t);
00298 }
00299
00300 void
00301 GraspitCollision::convertInterestList(const std::vector<Body*> *inList,
00302 std::set<CollisionModel*> *outSet)
00303 {
00304 for (int i=0; i<(int)inList->size(); i++) {
00305 CollisionModel *model = getModel((*inList)[i]);
00306 if (!model) {
00307 DBGA("GCOL: interest list model not found");
00308 } else {
00309 outSet->insert(model);
00310 }
00311 }
00312 }
00313
00314 int
00315 GraspitCollision::allCollisions(DetectionType type, CollisionReport *report,
00316 const std::vector<Body*> *interestList)
00317 {
00318 int collisions = 0;
00319
00320 std::set<CollisionModel*> *intModelList = NULL;
00321 if (interestList) {
00322 intModelList = new std::set<CollisionModel*>;
00323 convertInterestList(interestList, intModelList);
00324 }
00325
00326 std::list<CollisionPair> activeList;
00327 getActivePairs(&activeList, intModelList);
00328 std::list<CollisionPair>::iterator it;
00329 for (it = activeList.begin(); it!=activeList.end(); it++) {
00330 CollisionCallback cc(it->first, it->second);
00331
00332 startRecursion(it->first, it->second, &cc);
00333 DBGST( cc.printStatistics() );
00334 if ( cc.isCollision() ) {
00335 collisions++;
00336 if (type == FAST_COLLISION) break;
00337 Body *b1 = getBody(it->first);
00338 Body *b2 = getBody(it->second);
00339 assert(b1 && b2);
00340 report->push_back( CollisionData(b1,b2) );
00341 }
00342 }
00343 if (intModelList) delete intModelList;
00344 return collisions;
00345 }
00346
00347 int
00348 GraspitCollision::allContacts(CollisionReport *report, double threshold,
00349 const std::vector<Body*> *interestList)
00350 {
00351 int contacts = 0;
00352
00353 std::set<CollisionModel*> *intModelList = NULL;
00354 if (interestList) {
00355 intModelList = new std::set<CollisionModel*>;
00356 convertInterestList(interestList, intModelList);
00357 }
00358
00359 std::list<CollisionPair> activeList;
00360 getActivePairs(&activeList, intModelList);
00361 std::list<CollisionPair>::iterator it;
00362 for (it = activeList.begin(); it!=activeList.end(); it++) {
00363 ContactCallback cc(threshold, it->first, it->second);
00364
00365 startRecursion(it->first, it->second, &cc);
00366 DBGST( cc.printStatistics() );
00367 if (!cc.getReport().empty()) {
00368 contacts ++;
00369 Body *b1 = getBody(it->first);
00370 Body *b2 = getBody(it->second);
00371 assert(b1 && b2);
00372 report->push_back( CollisionData(b1,b2) );
00373 report->back().contacts = cc.getReport();
00374
00375
00376 DBGP("Body: " << getBody(it->first)->getName().latin1());
00377 DBGP("Before duplicate removal: " << report->back().contacts.size() );
00378 removeContactDuplicates(&(report->back().contacts), CONTACT_DUPLICATE_THRESHOLD);
00379 DBGP("After duplicate removal: " << report->back().contacts.size() );
00380
00381 compactContactSet(&report->back().contacts);
00382 DBGP("After compact set: " << report->back().contacts.size() );
00383 }
00384 }
00385 if (intModelList) delete intModelList;
00386 return contacts;
00387 }
00388
00389 int
00390 GraspitCollision::contact(ContactReport *report, double threshold,
00391 const Body *body1, const Body *body2)
00392 {
00393 CollisionModel *model1 = getModel(body1);
00394 CollisionModel *model2 = getModel(body2);
00395 if (!model1 || !model2) {
00396 DBGA("GCOL: model not found");
00397 return 0;
00398 }
00399
00400 ContactCallback cc(threshold, model1, model2);
00401 startRecursion(model1, model2, &cc);
00402 DBGST( cc.printStatistics() );
00403 if (!cc.getReport().empty()) {
00404 *report = cc.getReport();
00405
00406
00407 DBGP("Before duplicate removal: " << report->size() );
00408 removeContactDuplicates(report, CONTACT_DUPLICATE_THRESHOLD);
00409 DBGP("After duplicate removal: " << report->size() );
00410
00411 compactContactSet(report);
00412 DBGP("After compact set: " << report->size() );
00413 }
00414 return report->size();
00415 }
00416
00417 double
00418 GraspitCollision::pointToBodyDistance(const Body *body1, position point,
00419 position &closestPoint, vec3 &closestNormal)
00420 {
00421 CollisionModel *model = getModel(body1);
00422 if (!model) {
00423 DBGA("GCOL: model not found");
00424 return 0;
00425 }
00426
00427 ClosestPtCallback pc(model, point * body1->getTran().inverse());
00428 startRecursion(model, NULL, &pc);
00429 DBGST( pc.printStatistics() );
00430
00431 closestPoint = pc.getClosestPt() * body1->getTran();
00432
00433
00434
00435
00436 closestNormal = normalise(closestPoint - point);
00437 return pc.getMin();
00438 }
00439
00440 double
00441 GraspitCollision::bodyToBodyDistance(const Body *body1, const Body *body2,
00442 position &p1, position &p2)
00443 {
00444 CollisionModel *model1 = getModel(body1);
00445 CollisionModel *model2 = getModel(body2);
00446 if (!model1 || !model2) {
00447 DBGA("GCOL: model not found");
00448 return 0;
00449 }
00450 DistanceCallback dc(model1, model2);
00451
00452 startRecursion(model1, model2, &dc);
00453 DBGST( dc.printStatistics() );
00454 dc.getClosestPoints(p1, p2);
00455
00456 p1 = p1 * body1->getTran().inverse();
00457 p2 = p2 * body2->getTran().inverse();
00458 return dc.getMin();
00459 }
00460
00461 void
00462 GraspitCollision::bodyRegion(const Body *body, position point, vec3 normal,
00463 double radius, Neighborhood *neighborhood)
00464 {
00465 CollisionModel *model = getModel(body);
00466 if (!model) {
00467 DBGA("GCOL: model not found");
00468 return;
00469 }
00470
00471 RegionCallback rc(model, point, normal, radius);
00472
00473 startRecursion(model, NULL, &rc);
00474 DBGST( rc.printStatistics() );
00475 *neighborhood = rc.getRegion();
00476
00477 neighborhood->push_back(point);
00478 }
00479
00480
00481 void
00482 GraspitCollision::getBoundingVolumes(const Body* body, int depth, std::vector<BoundingBox>* bvs)
00483 {
00484 CollisionModel *model = getModel(body);
00485 if (!model) {
00486 DBGA("GCOL: model not found");
00487 return;
00488 }
00489 model->getBoundingVolumes(depth, bvs);
00490
00491 }