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
00030 #include <math.h>
00031 #include <string.h>
00032
00033 #include "gws.h"
00034 #include "grasp.h"
00035 #include "mytools.h"
00036 #include "body.h"
00037
00038
00039 #include "debug.h"
00040
00041 extern "C" {
00042 #include "qhull_a.h"
00043 }
00044 #include "qhull_mutex.h"
00045
00047 QMutex qhull_mutex;
00048
00049
00050
00051 #ifdef USE_DMALLOC
00052 #include "dmalloc.h"
00053 #endif
00054
00055 #define IVTOL 1e-5
00056
00057 const char *GWS::TYPE_LIST[] = {"L1 Norm","LInfinity Norm",NULL};
00058 const char *L1GWS::type = "L1 Norm";
00059 const char *LInfGWS::type = "LInfinity Norm";
00060
00061 typedef double *doublePtr;
00062
00064 const std::vector<int> GWS::ALL_DIMENSIONS = std::vector<int>(6, 1);
00065
00069 GWS::~GWS()
00070 {
00071 DBGA("deleting GWS");
00072 clearGWS();
00073 }
00074
00075 void
00076 GWS::clearGWS()
00077 {
00078 if (hyperPlanes) {
00079 for (int i=0;i<numHyperPlanes;i++)
00080 delete [] hyperPlanes[i];
00081 delete [] hyperPlanes;
00082 hyperPlanes=NULL;
00083 }
00084 numHyperPlanes = 0;
00085 hullArea = hullVolume = 0.0;
00086 forceClosure = false;
00087 }
00088
00092 GWS *
00093 GWS::createInstance(const char *desiredType,Grasp *g)
00094 {
00095 if (!strcmp(desiredType,L1GWS::getClassType()))
00096 return new L1GWS(g);
00097
00098 if (!strcmp(desiredType,LInfGWS::getClassType()))
00099 return new LInfGWS(g);
00100
00101 return NULL;
00102 }
00103
00104
00113 int
00114 GWS::projectTo3D(double *projCoords, std::set<int> fixedCoordSet,
00115 std::vector<position> &hullCoords, std::vector<int> &hullIndices)
00116 {
00117 int i,j,k,validPlanes,numCoords,numInLoop;
00118 double **planes;
00119 int freeCoord[3],fixedCoord[3];
00120
00121
00122 boolT ismalloc;
00123 int curlong,totlong,exitcode;
00124 char options[200];
00125 facetT *facet;
00126
00127 if (numHyperPlanes == 0) {
00128 DBGP("No hyperplanes");
00129 return SUCCESS;
00130 }
00131
00132 planes = (double **) malloc(numHyperPlanes * sizeof(double *));
00133 if (!planes) {
00134 #ifdef GRASPITDBG
00135 pr_error("GWS::ProjectTo3D,Out of memory allocating planes array");
00136 printf("NumHyperplanes: %d\n",numHyperPlanes);
00137 #endif
00138 return FAILURE;
00139 }
00140
00141 validPlanes = 0;
00142
00143
00144
00145 for (i=0,j=0,k=0;i<6;i++) {
00146 if (fixedCoordSet.find(i) == fixedCoordSet.end()) {
00147 freeCoord[k++] = i;
00148 } else {
00149 fixedCoord[j++] = i;
00150 }
00151 }
00152
00153
00154 for (i=0;i<numHyperPlanes;i++) {
00155 double len = sqrt(hyperPlanes[i][freeCoord[0]]*hyperPlanes[i][freeCoord[0]] +
00156 hyperPlanes[i][freeCoord[1]]*hyperPlanes[i][freeCoord[1]] +
00157 hyperPlanes[i][freeCoord[2]]*hyperPlanes[i][freeCoord[2]]);
00158
00159 if (len>1e-11) {
00160 planes[validPlanes] = (double *) malloc(4 * sizeof(double));
00161 if (!planes[validPlanes]) {
00162 pr_error("Out of memory allocating planes array");
00163 DBGP("Out of memory allocating planes array");
00164 return FAILURE;
00165 }
00166 planes[validPlanes][0] = hyperPlanes[i][freeCoord[0]]/len;
00167 planes[validPlanes][1] = hyperPlanes[i][freeCoord[1]]/len;
00168 planes[validPlanes][2] = hyperPlanes[i][freeCoord[2]]/len;
00169 planes[validPlanes][3] = (hyperPlanes[i][6] +
00170 hyperPlanes[i][fixedCoord[0]]*projCoords[fixedCoord[0]] +
00171 hyperPlanes[i][fixedCoord[1]]*projCoords[fixedCoord[1]] +
00172 hyperPlanes[i][fixedCoord[2]]*projCoords[fixedCoord[2]])/len;
00173
00174 validPlanes++;
00175 }
00176 }
00177
00178 if (validPlanes<numHyperPlanes) {
00179 DBGP("Ignored " << numHyperPlanes-validPlanes <<
00180 " hyperplanes which did not intersect this 3-space");
00181 }
00182 if (!validPlanes) {
00183 DBGA("No valid planes in 3D projection!");
00184 return FAILURE;
00185 }
00186
00187
00188
00189
00190
00191 coordT *array = new coordT[validPlanes*3];
00192 coordT *p = &array[0];
00193
00194 boolT zerodiv;
00195 coordT *point, *normp, *coordp, **pointp, *feasiblep;
00196 vertexT *vertex, **vertexp;
00197
00198 #ifdef GRASPITDBG
00199 printf("Calling qhull to perform a 3D halfspace intersection of %d planes...\n",validPlanes);
00200 #endif
00201
00202 ismalloc = False;
00203
00204
00205
00206 FILE *qhfp = fopen("logfile","w");
00207
00208 if (!qhfp) {
00209 fprintf(stderr,"Could not open qhull logfile!\n");
00210 qh_init_A(NULL, stdout, stderr, 0, NULL);
00211 }
00212 else
00213 qh_init_A(NULL, qhfp, qhfp, 0, NULL);
00214
00215 if ((exitcode = setjmp(qh errexit))) {
00216 delete [] array;
00217 qh NOerrexit= True;
00218 qh_freeqhull(!qh_ALL);
00219 qh_memfreeshort (&curlong, &totlong);
00220 if (curlong || totlong)
00221 fprintf (stderr, "qhull internal warning (main): did not free %d bytes of long memory (%d pieces)\n",
00222 totlong, curlong);
00223 for (i=0;i<validPlanes;i++)
00224 free(planes[i]);
00225 free(planes);
00226 if (qhfp) fclose(qhfp);
00227 DBGP("Qhull forces the exit; probably no valid intersection");
00228 return FAILURE;
00229 }
00230 sprintf(options, "qhull -H0,0,0 Pp");
00231 qh_initflags(options);
00232 qh_setfeasible(3);
00233 if (!(qh feasible_point)) printf("why is qh_qh NULL?\n");
00234 for(i=0;i<validPlanes;i++) {
00235 qh_sethalfspace (3, p, &p, planes[i],&(planes[i][3]), qh feasible_point);
00236 }
00237
00238 qh_init_B(&array[0], validPlanes, 3, ismalloc);
00239 qh_qhull();
00240 qh_check_output();
00241 if (qhfp) fclose(qhfp);
00242
00243
00244
00245
00246 hullCoords.clear();
00247 numCoords = qh num_facets;
00248 hullCoords.reserve(numCoords);
00249 int *indices = new int[numCoords];
00250
00251 double scale = grasp->getMaxRadius();
00252
00253 point= (pointT*)qh_memalloc (qh normal_size);
00254
00255 FORALLfacets {
00256 coordp = point;
00257 if (facet->offset > 0)
00258 goto LABELprintinfinite;
00259
00260 normp= facet->normal;
00261 feasiblep= qh feasible_point;
00262 if (facet->offset < -qh MINdenom) {
00263 for (k= qh hull_dim; k--; )
00264 *(coordp++)= (*(normp++) / - facet->offset) + *(feasiblep++);
00265 }else {
00266 for (k= qh hull_dim; k--; ) {
00267 *(coordp++)= qh_divzero (*(normp++), facet->offset, qh MINdenom_1,&zerodiv) + *(feasiblep++);
00268 if (zerodiv) {
00269 goto LABELprintinfinite;
00270 }
00271 }
00272 }
00273 hullCoords.push_back(position(point[0]*scale,point[1]*scale,
00274 point[2]*scale));
00275 continue;
00276 LABELprintinfinite:
00277 hullCoords.push_back(position(qh_INFINITE,qh_INFINITE,qh_INFINITE));
00278 fprintf(stderr,"intersection at infinity!\n");
00279 }
00280 qh_memfree (point, qh normal_size);
00281
00282
00283
00284
00285
00286 double dot;
00287 vec3 testNormal, refNormal;
00288
00289 int numfacets, numsimplicial, numridges, totneighbors, numneighbors, numcoplanars;
00290 setT *vertices, *vertex_points, *coplanar_points;
00291 int numpoints= qh num_points + qh_setsize (qh other_points);
00292 int vertex_i, vertex_n;
00293 facetT *neighbor, **neighborp;
00294 int unused_numnumtricoplanarsp;
00295
00296 qh_countfacets (qh facet_list, NULL, !qh_ALL, &numfacets, &numsimplicial,
00297 &totneighbors, &numridges, &numcoplanars, &unused_numnumtricoplanarsp);
00298
00299 qh_vertexneighbors();
00300 vertices= qh_facetvertices (qh facet_list, NULL, !qh_ALL);
00301 vertex_points= qh_settemp (numpoints);
00302 coplanar_points= qh_settemp (numpoints);
00303 qh_setzero (vertex_points, 0, numpoints);
00304 qh_setzero (coplanar_points, 0, numpoints);
00305 FOREACHvertex_(vertices)
00306 qh_point_add (vertex_points, vertex->point, vertex);
00307 FORALLfacet_(qh facet_list) {
00308 FOREACHpoint_(facet->coplanarset)
00309 qh_point_add (coplanar_points, point, facet);
00310 }
00311
00312 FOREACHvertex_i_(vertex_points) {
00313 if (vertex) {
00314 numneighbors= qh_setsize (vertex->neighbors);
00315
00316 numInLoop = numneighbors;
00317 qh_order_vertexneighbors (vertex);
00318 j=0;
00319 FOREACHneighbor_(vertex) {
00320 if (!neighbor->visitid) {
00321 fprintf(stderr,"Uh oh! neighbor->visitId==0, -neighbor->id: %d\n",-int(neighbor->id));
00322 numInLoop--;
00323 }
00324 else
00325 indices[j] = neighbor->visitid - 1;
00326
00327 if (j>0 && ((hullCoords[indices[j]]-hullCoords[indices[j-1]]).len() < IVTOL ||
00328 (hullCoords[indices[j]]-hullCoords[indices[0]]).len() < IVTOL))
00329 {
00330 numInLoop--;
00331 }
00332 else j++;
00333 }
00334 } else if ((facet= SETelemt_(coplanar_points, vertex_i, facetT))) {
00335 numInLoop=1;
00336 } else {
00337 numInLoop=0;
00338 continue;
00339 }
00340
00341 if (numInLoop<3) {
00342 DBGP("too few vertices to make a face. Ignoring ...");
00343 continue;
00344 }
00345
00346
00347 testNormal = (hullCoords[indices[1]] - hullCoords[indices[0]]) * (hullCoords[indices[j-1]] - hullCoords[indices[0]]);
00348 refNormal = vec3(planes[vertex_i][0],planes[vertex_i][1],planes[vertex_i][2]);
00349
00350 if ((dot = testNormal % refNormal) > 0.0) {
00351 for (j=0;j<numInLoop;j++)
00352 hullIndices.push_back(indices[j]);
00353 hullIndices.push_back(-1);
00354 } else {
00355
00356 for (j=numInLoop-1;j>=0;j--)
00357 hullIndices.push_back(indices[j]);
00358 hullIndices.push_back(-1);
00359 }
00360 }
00361
00362 qh_settempfree (&coplanar_points);
00363 qh_settempfree (&vertex_points);
00364 qh_settempfree (&vertices);
00365
00366 qh NOerrexit= True;
00367 qh_freeqhull(!qh_ALL);
00368 qh_memfreeshort (&curlong, &totlong);
00369 if (curlong || totlong)
00370 fprintf (stderr, "qhull internal warning (main): did not free %d bytes of long memory (%d pieces)\n",
00371 totlong, curlong);
00372
00373 for (i=0;i<validPlanes;i++)
00374 free(planes[i]);
00375 free(planes);
00376
00377 delete [] indices;
00378 delete [] array;
00379 DBGP("Succesfull completion of intersection task");
00380 return SUCCESS;
00381 }
00382
00383
00384 void
00385 GWS::setGravity(bool use, vec3 gd)
00386 {
00387 useGravity = use;
00388 if (!use) gravDirection = vec3(0,0,0);
00389 else gravDirection = gd;
00390 }
00391
00401 void
00402 GWS::computeHyperplaneMetrics()
00403 {
00404 if (!numHyperPlanes) {
00405 forceClosure = false;
00406 return;
00407 }
00408
00409 int posOffsets = 0;
00410 int minIndex = 0;
00411 double minOffset = -1.0;
00412
00413 for (int i=0; i<numHyperPlanes; i++) {
00414 if (hyperPlanes[i][6] > 0) posOffsets++;
00415 if (minOffset == -1.0 || -hyperPlanes[i][6]<minOffset) {
00416 minOffset = -hyperPlanes[i][6];
00417 minIndex = i;
00418 }
00419 }
00420
00421 grasp->setMinWrench(hyperPlanes[minIndex]);
00422
00423 if (posOffsets>0) {
00424 DBGP("QUALITY: NON FORCE CLOSURE GRASP, late exit");
00425 forceClosure = false;
00426 }
00427 else {
00428 DBGP("FORCE CLOSURE GRASP");
00429 forceClosure = true;
00430 }
00431 }
00432
00445 int
00446 GWS::buildHyperplanesFromWrenches(void *wr, int numWrenches,
00447 std::vector<int> useDimensions)
00448 {
00449 DBGP("Qhull init on " << numWrenches << " wrenches");
00450
00451 int dimensions = 0;
00452 for (int d=0; d<6; d++) {
00453 if (useDimensions[d]) dimensions++;
00454 }
00455
00456
00457 coordT *wrenches = (coordT*)wr;
00458 boolT ismalloc;
00459 int curlong, totlong, exitcode;
00460 char options[200];
00461 facetT *facet;
00462 int i;
00463
00464 ismalloc = False;
00465 FILE *qhfp = fopen("logfile-qhull","w");
00466 if (!qhfp) {
00467 fprintf(stderr,"Could not open qhull logfile!\n");
00468 qh_init_A(NULL, stdout, stderr, 0, NULL);
00469 }
00470 else
00471 qh_init_A(NULL, qhfp, qhfp, 0, NULL);
00472
00473
00474 if ((exitcode = setjmp(qh errexit))) {
00475 DBGP("QUALITY: 0 volume in " << dimensions <<"D, quick exit");
00476 qh NOerrexit= True;
00477 qh_freeqhull(!qh_ALL);
00478 qh_memfreeshort (&curlong, &totlong);
00479 if (curlong || totlong)
00480 fprintf (stderr, "qhull internal warning (main): did not free %d bytes of long memory (%d pieces)\n",
00481 totlong, curlong);
00482 if (qhfp) fclose(qhfp);
00483 return FAILURE;
00484 }
00485
00486 sprintf(options, "qhull Pp n Qx C-0.0001");
00487 qh_initflags(options);
00488 qh_init_B(&wrenches[0], numWrenches, dimensions, ismalloc);
00489 qh_qhull();
00490 qh_check_output();
00491 qh_getarea(qh facet_list);
00492 if (qhfp) fclose(qhfp);
00493
00494 hullArea = qh totarea;
00495 hullVolume = qh totvol;
00496 numHyperPlanes = qh num_facets;
00497
00498 hyperPlanes = new doublePtr[numHyperPlanes];
00499 if (!hyperPlanes) {
00500 DBGA("Out of memory allocating hyperPlanes array");
00501 return FAILURE;
00502 }
00503
00504 for (i=0;i<numHyperPlanes;i++) {
00505 hyperPlanes[i] = new double[7];
00506 if (!hyperPlanes[i]) {
00507 DBGA("Out of memory allocating hyperPlanes array");
00508 return FAILURE;
00509 }
00510 }
00511
00512 i=0;
00513
00514 mUsedDimensions = useDimensions;
00515 FORALLfacets {
00516 int hd = 0;
00517 for (int d=0; d<6; d++) {
00518 if (useDimensions[d]) {
00519 hyperPlanes[i][d] = facet->normal[hd];
00520 hd++;
00521 } else {
00522 hyperPlanes[i][d] = 0;
00523 }
00524 }
00525 hyperPlanes[i][6] = facet->offset;
00526 i++;
00527 }
00528
00529 qh NOerrexit= True;
00530 qh_freeqhull(!qh_ALL);
00531 qh_memfreeshort (&curlong, &totlong);
00532 if (curlong || totlong) {
00533 fprintf (stderr, "qhull internal warning (main): did not free %d bytes of long memory (%d pieces)\n",
00534 totlong, curlong);
00535 }
00536 DBGP("Qhull SUCCESS");
00537 return SUCCESS;
00538 }
00539
00562 int
00563 L1GWS::build(std::vector<int> useDimensions)
00564 {
00565 DBGP("in L1 gws build");
00566 if (useGravity) {
00567 DBGP("Gravity: " << gravDirection.x() << " " << gravDirection.y()
00568 << " " << gravDirection.z());
00569 } else {
00570 DBGP("No gravity");
00571 }
00572
00573 clearGWS();
00574
00575 if (!grasp->getNumContacts()) {
00576 forceClosure = false;
00577 DBGP(" No contacts, returning");
00578 return SUCCESS;
00579 }
00580
00581 int wrenchCount = 0;
00582 for (int i=0;i<grasp->getNumContacts();i++) {
00583 wrenchCount += grasp->getContact(i)->getMate()->numFrictionEdges;
00584 }
00585
00586
00587 int numDimensions = 0;
00588 for (int d=0; d<6; d++) {
00589 if (useDimensions[d]) {
00590 numDimensions++;
00591 }
00592 }
00593 DBGP("Building a " << numDimensions << "D L1 GWS");
00594
00595 if (numDimensions < 2) {
00596 DBGA("At least 2 used dimensions needed");
00597 return FAILURE;
00598 }
00599
00600 coordT *array = new coordT[wrenchCount*numDimensions];
00601 if (!array) {
00602 DBGA("Failed to allocate memory for wrenchCount" << wrenchCount);
00603 return FAILURE;
00604 }
00605
00606 coordT *p = &array[0];
00607 for (int i=0; i<grasp->getNumContacts(); i++) {
00608 for (int w=0; w<grasp->getContact(i)->getMate()->numFrictionEdges; w++) {
00609
00610 DBGP(" x: " << grasp->getContact(i)->getMate()->wrench[w].force.x() <<
00611 " y: " << grasp->getContact(i)->getMate()->wrench[w].force.y() <<
00612 " z: " << grasp->getContact(i)->getMate()->wrench[w].force.z() );
00613 DBGP("tx: " << grasp->getContact(i)->getMate()->wrench[w].torque.x() <<
00614 " ty: " << grasp->getContact(i)->getMate()->wrench[w].torque.y() <<
00615 " tz: " << grasp->getContact(i)->getMate()->wrench[w].torque.z() );
00616
00617 if (useDimensions[0]) *p++ = grasp->getContact(i)->getMate()->wrench[w].force.x();
00618 if (useGravity) *(p-1) = *(p-1) + gravDirection.x();
00619 if (useDimensions[1]) *p++ = grasp->getContact(i)->getMate()->wrench[w].force.y();
00620 if (useGravity) *(p-1) = *(p-1) + gravDirection.y();
00621 if (useDimensions[2]) *p++ = grasp->getContact(i)->getMate()->wrench[w].force.z();
00622 if (useGravity) *(p-1) = *(p-1) + gravDirection.z();
00623
00624 if (useDimensions[3]) *p++ = grasp->getContact(i)->getMate()->wrench[w].torque.x();
00625 if (useDimensions[4]) *p++ = grasp->getContact(i)->getMate()->wrench[w].torque.y();
00626 if (useDimensions[5]) *p++ = grasp->getContact(i)->getMate()->wrench[w].torque.z();
00627
00628 }
00629 }
00630
00631
00632 qhull_mutex.lock();
00633
00634 int result;
00635 try {
00636 result = buildHyperplanesFromWrenches(array, wrenchCount, useDimensions);
00637 } catch(...) {
00638 DBGA("Build QHull failed!!!");
00639 result = FAILURE;
00640 }
00641
00642
00643 qhull_mutex.unlock();
00644
00645 if (result == SUCCESS) {
00646 computeHyperplaneMetrics();
00647 } else{
00648 clearGWS();
00649 }
00650
00651 DBGP("HULL AREA: " << hullArea);
00652 DBGP("HULL VOLUME: " << hullVolume);
00653
00654 delete [] array;
00655 return result;
00656 }
00657
00663 void
00664 minkowskiSum(Grasp *g, int c, int &wrenchNum, coordT *wrenchArray, Wrench prevSum,
00665 std::vector<int> useDimensions)
00666 {
00667 static Wrench sum;
00668
00669 int nd = 0;
00670 for (int d=0; d<6; d++) {
00671 if (useDimensions[d]) nd++;
00672 }
00673 if (c == g->getNumContacts()) {
00674 if (useDimensions[0]) wrenchArray[ wrenchNum*nd + 0 ] = prevSum.force.x();
00675 if (useDimensions[1]) wrenchArray[ wrenchNum*nd + 1 ] = prevSum.force.y();
00676 if (useDimensions[2]) wrenchArray[ wrenchNum*nd + 2 ] = prevSum.force.z();
00677 if (useDimensions[3]) wrenchArray[ wrenchNum*nd + 3 ] = prevSum.torque.x();
00678 if (useDimensions[4]) wrenchArray[ wrenchNum*nd + 4 ] = prevSum.torque.y();
00679 if (useDimensions[5]) wrenchArray[ wrenchNum*nd + 5 ] = prevSum.torque.z();
00680 wrenchNum++;
00681 return;
00682 }
00683
00684
00685 minkowskiSum(g, c+1, wrenchNum, wrenchArray, prevSum, useDimensions);
00686
00687
00688 for (int w=0; w < g->getContact(c)->numFrictionEdges; w++) {
00689
00690 sum.force = prevSum.force + g->getContact(c)->getMate()->wrench[w].force;
00691 sum.torque = prevSum.torque + g->getContact(c)->getMate()->wrench[w].torque;
00692
00693 minkowskiSum(g, c+1, wrenchNum, wrenchArray, sum, useDimensions);
00694 }
00695 }
00696
00719 int
00720 LInfGWS::build(std::vector<int> useDimensions)
00721 {
00722 clearGWS();
00723 if (!grasp->getNumContacts()) {
00724 forceClosure = false;
00725 return SUCCESS;
00726 }
00727
00728
00729 int numDimensions = 0;
00730 for (int d=0; d<6; d++) {
00731 if (useDimensions[d]) {
00732 numDimensions++;
00733 }
00734 }
00735
00736 int wrenchCount = 1;
00737 for (int i=0; i<grasp->getNumContacts(); i++) {
00738 wrenchCount *= grasp->getContact(i)->getMate()->numFCWrenches + 1;
00739 if (wrenchCount > INT_MAX/6.0) {
00740 DBGA("Too many contacts to compute the Minkowski sum!");
00741 return FAILURE;
00742 }
00743 }
00744
00745 coordT *array = new coordT[wrenchCount*6];
00746 if (!array) {
00747 DBGA("Could not allocate wrench array in ComputeLInfHull. wrenchCount: " << wrenchCount);
00748 return FAILURE;
00749 }
00750
00751 Wrench initSum;
00752 initSum.force = vec3::ZERO;
00753 initSum.torque = vec3::ZERO;
00754
00755 int wrenchNum = 0;
00756 minkowskiSum(grasp, 0, wrenchNum, array, initSum, useDimensions);
00757
00758
00759 qhull_mutex.lock();
00760
00761 int result;
00762 try {
00763 result = buildHyperplanesFromWrenches(array, wrenchCount, useDimensions);
00764 } catch(...) {
00765 DBGA("Build QHull 3D failed!!!");
00766 result = FAILURE;
00767 }
00768
00769
00770 qhull_mutex.unlock();
00771
00772 if (result == SUCCESS) {
00773 computeHyperplaneMetrics();
00774 } else{
00775 clearGWS();
00776 }
00777
00778 DBGP("HULL VOLUME: " << hullVolume);
00779
00780 delete [] array;
00781 return result;
00782 }