SetupCollisionPair.cpp
Go to the documentation of this file.
00001 // -*- C++ -*-
00010 #include <iomanip>
00011 #include <hrpModel/Link.h>
00012 #include <hrpModel/ModelLoaderUtil.h>
00013 #include <hrpModel/JointPath.h>
00014 #include <hrpUtil/Eigen3d.h>
00015 #include <hrpUtil/Eigen4d.h>
00016 #include <hrpCollision/ColdetModel.h>
00017 #include "CollisionDetector.h"
00018 extern "C" {
00019 #if (defined __APPLE__)
00020 #include <pcl/surface/qhull.h>
00021 #else
00022 #include <qhull/qhull_a.h>
00023 #endif
00024 }
00025 
00026 #define deg2rad(x)      ((x)*M_PI/180)
00027 #define rad2deg(x)      ((x)*180/M_PI)
00028 
00029 std::vector<hrp::ColdetLinkPairPtr> m_pair;
00030 std::vector<std::string> blacklist;
00031 hrp::BodyPtr m_robot;
00032 
00033 RTC::ReturnCode_t setupCollisionModel(hrp::BodyPtr m_robot, const char *url, OpenHRP::BodyInfo_var binfo) {
00034     // do qhull
00035     OpenHRP::ShapeInfoSequence_var sis = binfo->shapes();
00036     OpenHRP::LinkInfoSequence_var lis = binfo->links();
00037     for(unsigned int i = 0; i < m_robot->numLinks(); i++ ) {
00038         const OpenHRP::LinkInfo& i_li = lis[i];
00039         const OpenHRP::TransformedShapeIndexSequence& tsis = i_li.shapeIndices;
00040         // setup
00041         int numTriangles = 0;
00042         for (unsigned int l=0; l<tsis.length(); l++) {
00043             OpenHRP::ShapeInfo& si = sis[tsis[l].shapeIndex];
00044             const OpenHRP::LongSequence& triangles = si.triangles;
00045             numTriangles += triangles.length();
00046         }
00047         double points[numTriangles*3];
00048         int points_i = 0;
00049         hrp::Matrix44 Rs44; // inv
00050         hrp::Matrix33 Rs33 = m_robot->link(i)->Rs;
00051 
00052         Rs44 << Rs33(0,0),Rs33(0,1), Rs33(0,2), 0,
00053             Rs33(1,0),Rs33(1,1), Rs33(1,2), 0,
00054             Rs33(2,0),Rs33(2,1), Rs33(2,2), 0,
00055             0.0,      0.0,       0.0,    1.0;
00056         for (unsigned int l=0; l<tsis.length(); l++) {
00057             const OpenHRP::DblArray12& M = tsis[l].transformMatrix;
00058             hrp::Matrix44 T0;
00059             T0 << M[0], M[1], M[2],  M[3],
00060                 M[4], M[5], M[6],  M[7],
00061                 M[8], M[9], M[10], M[11],
00062                 0.0,  0.0,  0.0,   1.0;
00063             hrp::Matrix44 T(Rs44 * T0);
00064             const OpenHRP::ShapeInfo& si = sis[tsis[l].shapeIndex];
00065             const OpenHRP::LongSequence& triangles = si.triangles;
00066             const float *vertices = si.vertices.get_buffer();
00067 
00068             for(unsigned int j=0; j < triangles.length() / 3; ++j){
00069                 for(int k=0; k < 3; ++k){
00070                     long orgVertexIndex = si.triangles[j * 3 + k];
00071                     int p = orgVertexIndex * 3;
00072 
00073                     hrp::Vector4 v(T * hrp::Vector4(vertices[p+0], vertices[p+1], vertices[p+2], 1.0));
00074                     points[points_i++] =  v[0];
00075                     points[points_i++] =  v[1];
00076                     points[points_i++] =  v[2];
00077                 }
00078             }
00079         }
00080 
00081         hrp::ColdetModelPtr coldetModel(new hrp::ColdetModel());
00082         coldetModel->setName(std::string(i_li.name));
00083         // qhull
00084         int vertexIndex = 0;
00085         int triangleIndex = 0;
00086         int num = 0;
00087         char flags[250];
00088         boolT ismalloc = False;
00089         sprintf(flags,"qhull Qt Tc");
00090         if (! qh_new_qhull (3,numTriangles,points,ismalloc,flags,NULL,stderr) ) {
00091 
00092             qh_triangulate();
00093             qh_vertexneighbors();
00094 
00095             vertexT *vertex,**vertexp;
00096             coldetModel->setNumVertices(qh num_vertices);
00097             coldetModel->setNumTriangles(qh num_facets);
00098             int index[qh num_vertices];
00099             FORALLvertices {
00100                 int p = qh_pointid(vertex->point);
00101                 index[p] = vertexIndex;
00102                 coldetModel->setVertex(vertexIndex++, points[p*3+0], points[p*3+1], points[p*3+2]);
00103             }
00104             facetT *facet;
00105             num = qh num_facets;;
00106             {
00107                 FORALLfacets {
00108                     int j = 0, p[3];
00109                     setT *vertices = qh_facet3vertex (facet);
00110                     FOREACHvertexreverse12_ (vertices) {
00111                         if (j<3) {
00112                             p[j] = index[qh_pointid(vertex->point)];
00113                         } else {
00114                             fprintf(stderr, "extra vertex %d\n",j);
00115                         }
00116                         j++;
00117                     }
00118                     coldetModel->setTriangle(triangleIndex++, p[0], p[1], p[2]);
00119                 }
00120             }
00121         } // qh_new_qhull
00122 
00123         coldetModel->build();
00124         m_robot->link(i)->coldetModel =  coldetModel;
00125 
00126         qh_freeqhull(!qh_ALL);
00127         int curlong, totlong;
00128         qh_memfreeshort (&curlong, &totlong);
00129         if (curlong || totlong) {
00130             fprintf(stderr, "convhulln: did not free %d bytes of long memory (%d pieces)\n", totlong, curlong);
00131         }
00132         //
00133         std::cerr << std::setw(16) << i_li.name << " reduce triangles from " << std::setw(5) << numTriangles << " to " << std::setw(4) << num << std::endl;
00134     }
00135 
00136     return RTC::RTC_OK;
00137 }
00138 
00139 bool checkCollisionForAllJointRange(int i, hrp::JointPathPtr jointPath, std::vector<hrp::ColdetLinkPairPtr> &collisionPairs)
00140 {
00141     if ( i >= (int)jointPath->numJoints() ) return false;
00142     if ( collisionPairs.size() == 0 ) return true;
00143     hrp::Link *l = jointPath->joint(i);
00144 
00145     if ( l->jointType == hrp::Link::FIXED_JOINT ) {
00146         checkCollisionForAllJointRange(i+1, jointPath, collisionPairs);
00147     } else {
00148         double step = (l->ulimit - l->llimit)/2;
00149         for(float angle = l->llimit; angle <= l->ulimit; angle += step)
00150         {
00151             l->q = angle;
00152             m_robot->calcForwardKinematics(false,false);
00153             m_robot->updateLinkColdetModelPositions();
00154 
00155             //std::cerr << "    " << collisionPair->link(0)->name << ":" << collisionPair->link(1)->name << " ";
00156             //for(int j = 0; j < jointPath->numJoints(); j++) std::cerr << rad2deg(jointPath->joint(j)->q) << " ";
00157             // std::cerr << "id = " << i << "/" << jointPath->numJoints() << ", " << l->name << " " << rad2deg(angle) << " (" << rad2deg(l->llimit) << "," << rad2deg(l->ulimit) << ") " << collisionPair->detectIntersection() << " " << collisionPair->link(0)->name << ":" << collisionPair->link(1)->name << std::endl;
00158             for(std::vector<hrp::ColdetLinkPairPtr>::iterator it = collisionPairs.begin(); it != collisionPairs.end(); ) {
00159                 if ( (*it)->detectIntersection() ) {
00160                     std::cerr << "Find collision for " << (*it)->link(0)->name << " " << (*it)->link(1)->name << std::endl;
00161                     it = collisionPairs.erase(it);
00162                     continue;
00163                 }
00164                 it++;
00165             }
00166             checkCollisionForAllJointRange(i+1, jointPath, collisionPairs);
00167         }
00168     }
00169     return false;
00170 }
00171 
00172 bool checkBlackListJoint(hrp::Link *l) {
00173     for(std::vector<std::string>::iterator it = blacklist.begin(); it != blacklist.end(); it++ ) {
00174             if (l->name == (*it)) return true;
00175     }
00176     return false;
00177 }
00178 
00179 bool checkBlackListJointPair(hrp::Link *l1, hrp::Link *l2) {
00180     for(std::vector<std::string>::iterator it = blacklist.begin(); it != blacklist.end(); it++ ) {
00181             if ((l1->name + ":" + l2->name) == (*it) ||
00182                 (l2->name + ":" + l1->name) == (*it)) return true;
00183     }
00184     return false;
00185 }
00186 
00187 bool compare_joint_path_length(const hrp::ColdetLinkPairPtr& p1, const hrp::ColdetLinkPairPtr& p2) {
00188     return (m_robot->getJointPath(p1->link(0),p1->link(1))->numJoints()) > (m_robot->getJointPath(p2->link(0),p2->link(1))->numJoints());
00189 }
00190 
00191 void setupCollisionLinkPair()
00192 {
00193     std::vector<hrp::ColdetLinkPairPtr> tmp_pair;
00194 
00195     std::cerr << "Setup Initial collision pair without " << std::endl;
00196     for(std::vector<std::string>::iterator it = blacklist.begin(); it != blacklist.end(); it++ ) {
00197         std::cerr << *it << " ";
00198     }
00199     std::cerr << std::endl;
00200     // find link to be ignored as the link is included in the parent link
00201     // need AABBCollision?
00202     //
00203     // set all collisoin pair
00204     for (unsigned int i=0; i<m_robot->numLinks(); i++) {
00205         hrp::Link *l1 = m_robot->link(i);
00206         for (unsigned int j=i+1; j<m_robot->numLinks(); j++) {
00207             hrp::Link *l2 = m_robot->link(j);
00208             if ( l1->coldetModel && l2->coldetModel
00209                  &&  (!(checkBlackListJoint(l1) ||  checkBlackListJoint(l2) || checkBlackListJointPair(l1, l2)))
00210                 ) {
00211                 tmp_pair.push_back(new hrp::ColdetLinkPair(l1, l2));
00212             }
00213         }
00214     }
00215 
00216     std::cerr << "Initial collision pair size " << tmp_pair.size() << std::endl;
00217     std::vector<hrp::ColdetLinkPairPtr>::iterator it;
00218     // Remove collision pair if the pair always collides
00219     std::cerr << "step 0: Remove collision pair if they are adjacent pair" << std::endl;
00220     it = tmp_pair.begin();
00221     while ( it != tmp_pair.end() ) {
00222         hrp::JointPathPtr jointPath = m_robot->getJointPath((*it)->link(0),(*it)->link(1));
00223         if ( jointPath->numJoints() == 1 ) {
00224             hrp::Link *l = jointPath->joint(0);
00225             bool always_collide = true; // true if always collide
00226             bool never_collide = true;  // true if never collide ( crrect )
00227             l->llimit = -M_PI;l->ulimit = M_PI;
00228             std::cerr << l->name << " ulimit - " << l->llimit << " " << l->ulimit << std::endl;
00229             for(float angle = l->llimit; angle <= l->ulimit; angle += deg2rad(5)) {
00230                 l->q = angle;
00231                 m_robot->calcForwardKinematics(false,false);
00232                 m_robot->updateLinkColdetModelPositions();
00233                 if ( (*it)->detectIntersection() ) {
00234                     never_collide = false;
00235                 } else {
00236                     always_collide = false;
00237                 }
00238                 //std::cerr << l->name << " " << deg2rad(l->q) << " intersect:" << (*it)->detectIntersection() <<  " check:" << (*it)->checkCollision() << std::endl;
00239                 (*it)->clearCollisions();
00240             }
00241             std::cerr << "  pair (" << jointPath->numJoints() << ") " << (*it)->link(0)->name << "/" << (*it)->link(1)->name << (always_collide?" always collide":"") << (never_collide?" never collide":"") << std::endl;
00242             it = tmp_pair.erase(it);
00243             continue;
00244         }
00245         it++;
00246     }
00247     //
00248     std::cerr << "step 1: Remove complex (2 or 3 distance) collision pair if they never/always collide" << std::endl;
00249     it = tmp_pair.begin();
00250     while ( it != tmp_pair.end() ) {
00251         hrp::JointPathPtr jointPath = m_robot->getJointPath((*it)->link(0),(*it)->link(1));
00252         if ( jointPath->numJoints() == 2 || jointPath->numJoints() == 3 ) {
00253             hrp::Link *l = jointPath->joint(0);
00254             bool always_collide = true; // true if always collide
00255             bool never_collide = true;  // true if never collide ( crrect )
00256             for(float angle = l->llimit; angle <= l->ulimit; angle += deg2rad(5)) {
00257                 l->q = angle;
00258                 m_robot->calcForwardKinematics(false,false);
00259                 m_robot->updateLinkColdetModelPositions();
00260                 if ( (*it)->detectIntersection() ) {
00261                     never_collide = false;
00262                 } else {
00263                     always_collide = false;
00264                 }
00265                 //std::cerr << l->name << " " << deg2rad(l->q) << " intersect:" << (*it)->detectIntersection() <<  " check:" << (*it)->checkCollision() << std::endl;
00266                 (*it)->clearCollisions();
00267             }
00268             std::cerr << "  pair (" << jointPath->numJoints() << ") " << (*it)->link(0)->name << "/" << (*it)->link(1)->name << " always:" << always_collide << ", never:" << never_collide << " " << (( always_collide || never_collide )?"remove from list":"") << std::endl;
00269             if ( always_collide || never_collide ) {
00270                 it = tmp_pair.erase(it);
00271                 continue;
00272             } else {
00273                 m_pair.push_back(*it);
00274             }
00275         }
00276         it++;
00277     }
00278     std::cerr << "  Remove always/never collide pair for a length of 1,2,3 ... " << tmp_pair.size() << std::endl;
00279 
00280     // setup data structure for check collision pair
00281     // pair_tree[<pair:L1,L2,L3,L4>, [ <pair:L1,L2,L3,L4>, <pair:L1,L2,L3>, <pair:L1,L2> ]]
00282     // pair_tree[<pair:L2,L3,L4,L5>, [ <pair:L2,L3,L4,L5>, <pair:L2,L3,L4>, <pair:L2,L3> ]]
00283     std::map<hrp::ColdetLinkPairPtr, std::vector<hrp::ColdetLinkPairPtr> > pair_tree;
00284     std::sort(tmp_pair.begin(), tmp_pair.end(), compare_joint_path_length);
00285     int i = 0;
00286     it = tmp_pair.begin();
00287     while ( it != tmp_pair.end() ) {
00288         hrp::JointPathPtr jointPath1 = m_robot->getJointPath((*it)->link(0),(*it)->link(1));
00289         //std::cerr << "  " << i << "/" << tmp_pair.size() << "  pair (" << jointPath1->numJoints() << ") " << (*it)->link(0)->name << " " << (*it)->link(1)->name <<std::endl;
00290         // check if JointPath1 is included in some of the pair_tree (jointPath2)
00291         bool is_new_key = true;
00292         for (std::map<hrp::ColdetLinkPairPtr, std::vector<hrp::ColdetLinkPairPtr> >::iterator ii=pair_tree.begin(); ii != pair_tree.end(); ++ii) {
00293             hrp::JointPathPtr jointPath2 = m_robot->getJointPath(((*ii).first)->link(0),((*ii).first)->link(1));
00294             // check if JointPath1 is included in jointPath2
00295             bool find_key = true;
00296             for (unsigned int j = 0; j < jointPath1->numJoints() ; j++ ) {
00297                 if ( jointPath1->joint(j)->name != jointPath2->joint(j)->name ) {
00298                     find_key = false;
00299                     break;
00300                 }
00301             }
00302             if ( find_key ) {
00303                 (*ii).second.push_back(*it);
00304                 is_new_key = false;
00305             }
00306         }
00307         if (is_new_key) {
00308             pair_tree[*it] = std::vector<hrp::ColdetLinkPairPtr>(1,*it)
00309 ;
00310         }
00311         it++; i++;
00312     }
00313     // remove non-collisin pair from tmp_pair
00314     std::cerr << "step 2: Remove collision pair if they never collide" << std::endl;
00315     i = 0;
00316     for (std::map<hrp::ColdetLinkPairPtr, std::vector<hrp::ColdetLinkPairPtr> >::iterator ii=pair_tree.begin(); ii != pair_tree.end(); ++ii) {
00317         hrp::ColdetLinkPairPtr key_pair = (*ii).first;
00318         std::vector<hrp::ColdetLinkPairPtr> sub_pairs = (*ii).second;
00319         hrp::JointPathPtr jointPath = m_robot->getJointPath(key_pair->link(0),key_pair->link(1));
00320         std::sort(sub_pairs.begin(), sub_pairs.end(), compare_joint_path_length);
00321         //
00322         std::cerr << "  " << i << "/" << tmp_pair.size() << "  pair (" << jointPath->numJoints() << ") " << (*ii).first->link(0)->name << " " << (*ii).first->link(1)->name <<std::endl;
00323         i += (*ii).second.size();
00324         for(std::vector<hrp::ColdetLinkPairPtr>::iterator it = sub_pairs.begin(); it != sub_pairs.end(); it++ ) {
00325             hrp::JointPathPtr jointPath = m_robot->getJointPath((*it)->link(0),(*it)->link(1));
00326             for ( unsigned int j = 0; j < jointPath->numJoints(); j++ ) {
00327                 std::cerr << jointPath->joint(j)->name << " ";
00328             }
00329             std::cerr << std::endl;
00330         }
00331         // rmeove non-collision pair from sub_paris
00332         checkCollisionForAllJointRange(0, jointPath, sub_pairs);
00333         for(std::vector<hrp::ColdetLinkPairPtr>::iterator p = sub_pairs.begin(); p != sub_pairs.end(); p++ ) {
00334             for(std::vector<hrp::ColdetLinkPairPtr>::iterator it = tmp_pair.begin(); it != tmp_pair.end(); ) {
00335                 if ( (*p)->link(0) == (*it)->link(0) &&  (*p)->link(1) == (*it)->link(1) ) {
00336                     tmp_pair.erase(it);
00337                     continue;
00338                 }
00339                 it++;
00340             }
00341             //tmp_pair.erase(it); // does not work???
00342         }
00343     }
00344     it = tmp_pair.begin();
00345     while ( it != tmp_pair.end() ) {
00346         m_pair.push_back(*it);
00347         it++;
00348     }
00349     std::cerr << "Reduced collision pair size " << m_pair.size() << std::endl;
00350 }
00351 
00352 int main (int argc, char** argv)
00353 {
00354     std::string url;
00355 
00356     for (int i = 1; i < argc; ++ i) {
00357         std::string arg(argv[i]);
00358         coil::normalize(arg);
00359         if ( arg == "--model" ) {
00360             if (++i < argc) url = argv[i];
00361         } else if ( arg == "-o" ) {
00362             ++i;
00363         } else if ( arg[0] == '-' ||  arg[0] == '_'  ) {
00364             std::cerr << argv[0] << " : Unknwon arguments " << arg << std::endl;
00365         } else {
00366             blacklist.push_back(argv[i]);
00367         }
00368     }
00369     if (argc < 2) {
00370         std::cerr << "usage: " << argv[0] << " --model <model file> <blacklist : R_HAND_J0 L_HAND_J0 EYEBROW_P EYELID_P EYE_Y EYE_P MOUTH_P UPPERLIP_P LOWERLIP_P CHEEK_P>" << std::endl;
00371         exit(1);
00372     }
00373 
00374     m_robot = hrp::BodyPtr(new hrp::Body());
00375     OpenHRP::BodyInfo_var binfo = hrp::loadBodyInfo(url.c_str(), argc, argv);
00376     if (CORBA::is_nil(binfo)){
00377         std::cerr << "failed to load model[" << url << "]" << std::endl;
00378         return 1;
00379     }
00380     if (!loadBodyFromBodyInfo(m_robot, binfo)) {
00381         std::cerr << "failed to load model[" << url << "]" << std::endl;
00382         return 1;
00383     }
00384     setupCollisionModel(m_robot, url.c_str(), binfo);
00385     setupCollisionLinkPair();
00386 
00387     std::string fname = "/tmp/"+m_robot->name()+"collision_pair.conf";
00388     std::ofstream ofs(fname.c_str());
00389     ofs << "collision_pair:";
00390     for (std::vector<hrp::ColdetLinkPairPtr>::iterator it = m_pair.begin(); it != m_pair.end(); it++) {
00391         ofs << " " << (*it)->link(0)->name << ":" << (*it)->link(1)->name;
00392         std::cerr << (*it)->link(0)->name << ":" << (*it)->link(1)->name << std::endl;
00393     }
00394     ofs << std::endl;
00395     ofs.close();
00396     std::cerr << "Write collision pair conf file to " << fname << std::endl;
00397 
00398     return 0;
00399 }


hrpsys
Author(s): AIST, Fumio Kanehiro
autogenerated on Wed May 15 2019 05:02:19