collada_parser.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2010, University of Tokyo
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redstributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 /* Author: Rosen Diankov, used OpenRAVE files for reference  */
00036 #include <vector>
00037 #include <list>
00038 #include <map>
00039 #include <stdint.h>
00040 #include <cstdlib>
00041 #include <cmath>
00042 #include <string>
00043 #include <sstream>
00044 
00045 #include <dae.h>
00046 #include <dae/daeErrorHandler.h>
00047 #include <dom/domCOLLADA.h>
00048 #include <dae/domAny.h>
00049 #include <dom/domConstants.h>
00050 #include <dom/domTriangles.h>
00051 #include <dae/daeStandardURIResolver.h>
00052 
00053 #include <boost/assert.hpp>
00054 #include <boost/format.hpp>
00055 #include <boost/shared_ptr.hpp>
00056 
00057 #include <ros/ros.h>
00058 #include <collada_parser/collada_parser.h>
00059 #include <urdf_model/model.h>
00060 
00061 #ifndef HAVE_MKSTEMPS
00062 #include <fstream>
00063 #include <fcntl.h>
00064 #endif
00065 #ifndef HAVE_MKSTEMPS
00066 #include <fstream>
00067 #include <fcntl.h>
00068 #endif
00069 
00070 #define FOREACH(it, v) for(typeof((v).begin())it = (v).begin(); it != (v).end(); (it)++)
00071 #define FOREACHC FOREACH
00072 
00073 namespace ColladaDOM150 { }
00074 
00075 namespace urdf {
00076 
00077 using namespace ColladaDOM150;
00078 
00079 class UnlinkFilename
00080 {
00081 public:
00082     UnlinkFilename(const std::string& filename) : _filename(filename) {
00083     }
00084     virtual ~UnlinkFilename() {
00085         unlink(_filename.c_str());
00086     }
00087     std::string _filename;
00088 };
00089 static std::list<boost::shared_ptr<UnlinkFilename> > _listTempFilenames;
00090 
00091 class ColladaModelReader : public daeErrorHandler
00092 {
00093 
00094     class JointAxisBinding
00095     {
00096 public:
00097         JointAxisBinding(daeElementRef pvisualtrans, domAxis_constraintRef pkinematicaxis, domCommon_float_or_paramRef jointvalue, domKinematics_axis_infoRef kinematics_axis_info, domMotion_axis_infoRef motion_axis_info) : pvisualtrans(pvisualtrans), pkinematicaxis(pkinematicaxis), jointvalue(jointvalue), kinematics_axis_info(kinematics_axis_info), motion_axis_info(motion_axis_info) {
00098             BOOST_ASSERT( !!pkinematicaxis );
00099             daeElement* pae = pvisualtrans->getParentElement();
00100             while (!!pae) {
00101                 visualnode = daeSafeCast<domNode> (pae);
00102                 if (!!visualnode) {
00103                     break;
00104                 }
00105                 pae = pae->getParentElement();
00106             }
00107 
00108             if (!visualnode) {
00109                 ROS_WARN_STREAM(str(boost::format("couldn't find parent node of element id %s, sid %s\n")%pkinematicaxis->getID()%pkinematicaxis->getSid()));
00110             }
00111         }
00112 
00113         daeElementRef pvisualtrans;
00114         domAxis_constraintRef pkinematicaxis;
00115         domCommon_float_or_paramRef jointvalue;
00116         domNodeRef visualnode;
00117         domKinematics_axis_infoRef kinematics_axis_info;
00118         domMotion_axis_infoRef motion_axis_info;
00119     };
00120 
00122     class LinkBinding
00123     {
00124 public:
00125         domNodeRef node;
00126         domLinkRef domlink;
00127         domInstance_rigid_bodyRef irigidbody;
00128         domRigid_bodyRef rigidbody;
00129         domNodeRef nodephysicsoffset;
00130     };
00131 
00133     class KinematicsSceneBindings
00134     {
00135 public:
00136         std::list< std::pair<domNodeRef,domInstance_kinematics_modelRef> > listKinematicsVisualBindings;
00137         std::list<JointAxisBinding> listAxisBindings;
00138         std::list<LinkBinding> listLinkBindings;
00139 
00140         bool AddAxisInfo(const domInstance_kinematics_model_Array& arr, domKinematics_axis_infoRef kinematics_axis_info, domMotion_axis_infoRef motion_axis_info)
00141         {
00142             if( !kinematics_axis_info ) {
00143                 return false;
00144             }
00145             for(size_t ik = 0; ik < arr.getCount(); ++ik) {
00146                 daeElement* pelt = daeSidRef(kinematics_axis_info->getAxis(), arr[ik]->getUrl().getElement()).resolve().elt;
00147                 if( !!pelt ) {
00148                     // look for the correct placement
00149                     bool bfound = false;
00150                     FOREACH(itbinding,listAxisBindings) {
00151                         if( itbinding->pkinematicaxis.cast() == pelt ) {
00152                             itbinding->kinematics_axis_info = kinematics_axis_info;
00153                             if( !!motion_axis_info ) {
00154                                 itbinding->motion_axis_info = motion_axis_info;
00155                             }
00156                             bfound = true;
00157                             break;
00158                         }
00159                     }
00160                     if( !bfound ) {
00161                         ROS_WARN_STREAM(str(boost::format("could not find binding for axis: %s, %s\n")%kinematics_axis_info->getAxis()%pelt->getAttribute("sid")));
00162                         return false;
00163                     }
00164                     return true;
00165                 }
00166             }
00167             ROS_WARN_STREAM(str(boost::format("could not find kinematics axis target: %s\n")%kinematics_axis_info->getAxis()));
00168             return false;
00169         }
00170     };
00171 
00172     struct USERDATA
00173     {
00174         USERDATA() {
00175         }
00176         USERDATA(double scale) : scale(scale) {
00177         }
00178         double scale;
00179 #if URDFDOM_HEADERS_MAJOR_VERSION < 1
00180         boost::shared_ptr<void> p; 
00181 #else
00182         std::shared_ptr<void> p; 
00183 #endif
00184     };
00185 
00186     enum GeomType {
00187         GeomNone = 0,
00188         GeomBox = 1,
00189         GeomSphere = 2,
00190         GeomCylinder = 3,
00191         GeomTrimesh = 4,
00192     };
00193 
00194     struct GEOMPROPERTIES
00195     {
00196         Pose _t;                
00197         Vector3 vGeomData; 
00198 
00199 
00200 
00201         Color diffuseColor, ambientColor; 
00202         std::vector<Vector3> vertices;
00203         std::vector<int> indices;
00204 
00206         GeomType type;         
00207 
00208 
00209         // generate a sphere triangulation starting with an icosahedron
00210         // all triangles are oriented counter clockwise
00211         static void GenerateSphereTriangulation(std::vector<Vector3> realvertices, std::vector<int> realindices, int levels)
00212         {
00213             const double GTS_M_ICOSAHEDRON_X = 0.850650808352039932181540497063011072240401406;
00214             const double GTS_M_ICOSAHEDRON_Y = 0.525731112119133606025669084847876607285497935;
00215             const double GTS_M_ICOSAHEDRON_Z  = 0;
00216             std::vector<Vector3> tempvertices[2];
00217             std::vector<int> tempindices[2];
00218 
00219             tempvertices[0].push_back(Vector3(+GTS_M_ICOSAHEDRON_Z, +GTS_M_ICOSAHEDRON_X, -GTS_M_ICOSAHEDRON_Y));
00220             tempvertices[0].push_back(Vector3(+GTS_M_ICOSAHEDRON_X, +GTS_M_ICOSAHEDRON_Y, +GTS_M_ICOSAHEDRON_Z));
00221             tempvertices[0].push_back(Vector3(+GTS_M_ICOSAHEDRON_Y, +GTS_M_ICOSAHEDRON_Z, -GTS_M_ICOSAHEDRON_X));
00222             tempvertices[0].push_back(Vector3(+GTS_M_ICOSAHEDRON_Y, +GTS_M_ICOSAHEDRON_Z, +GTS_M_ICOSAHEDRON_X));
00223             tempvertices[0].push_back(Vector3(+GTS_M_ICOSAHEDRON_X, -GTS_M_ICOSAHEDRON_Y, +GTS_M_ICOSAHEDRON_Z));
00224             tempvertices[0].push_back(Vector3(+GTS_M_ICOSAHEDRON_Z, +GTS_M_ICOSAHEDRON_X, +GTS_M_ICOSAHEDRON_Y));
00225             tempvertices[0].push_back(Vector3(-GTS_M_ICOSAHEDRON_Y, +GTS_M_ICOSAHEDRON_Z, +GTS_M_ICOSAHEDRON_X));
00226             tempvertices[0].push_back(Vector3(+GTS_M_ICOSAHEDRON_Z, -GTS_M_ICOSAHEDRON_X, -GTS_M_ICOSAHEDRON_Y));
00227             tempvertices[0].push_back(Vector3(-GTS_M_ICOSAHEDRON_X, +GTS_M_ICOSAHEDRON_Y, +GTS_M_ICOSAHEDRON_Z));
00228             tempvertices[0].push_back(Vector3(-GTS_M_ICOSAHEDRON_Y, +GTS_M_ICOSAHEDRON_Z, -GTS_M_ICOSAHEDRON_X));
00229             tempvertices[0].push_back(Vector3(-GTS_M_ICOSAHEDRON_X, -GTS_M_ICOSAHEDRON_Y, +GTS_M_ICOSAHEDRON_Z));
00230             tempvertices[0].push_back(Vector3(+GTS_M_ICOSAHEDRON_Z, -GTS_M_ICOSAHEDRON_X, +GTS_M_ICOSAHEDRON_Y));
00231 
00232             const int nindices=60;
00233             int indices[nindices] = {
00234                 0, 1, 2,
00235                 1, 3, 4,
00236                 3, 5, 6,
00237                 2, 4, 7,
00238                 5, 6, 8,
00239                 2, 7, 9,
00240                 0, 5, 8,
00241                 7, 9, 10,
00242                 0, 1, 5,
00243                 7, 10, 11,
00244                 1, 3, 5,
00245                 6, 10, 11,
00246                 3, 6, 11,
00247                 9, 10, 8,
00248                 3, 4, 11,
00249                 6, 8, 10,
00250                 4, 7, 11,
00251                 1, 2, 4,
00252                 0, 8, 9,
00253                 0, 2, 9
00254             };
00255 
00256             Vector3 v[3];
00257             // make sure oriented CCW
00258             for(int i = 0; i < nindices; i += 3 ) {
00259                 v[0] = tempvertices[0][indices[i]];
00260                 v[1] = tempvertices[0][indices[i+1]];
00261                 v[2] = tempvertices[0][indices[i+2]];
00262                 if( _dot3(v[0], _cross3(_sub3(v[1],v[0]),_sub3(v[2],v[0]))) < 0 ) {
00263                     std::swap(indices[i], indices[i+1]);
00264                 }
00265             }
00266 
00267             tempindices[0].resize(nindices);
00268             std::copy(&indices[0],&indices[nindices],tempindices[0].begin());
00269             std::vector<Vector3>* curvertices = &tempvertices[0], *newvertices = &tempvertices[1];
00270             std::vector<int> *curindices = &tempindices[0], *newindices = &tempindices[1];
00271             while(levels-- > 0) {
00272 
00273                 newvertices->resize(0);
00274                 newvertices->reserve(2*curvertices->size());
00275                 newvertices->insert(newvertices->end(), curvertices->begin(), curvertices->end());
00276                 newindices->resize(0);
00277                 newindices->reserve(4*curindices->size());
00278 
00279                 std::map< uint64_t, int > mapnewinds;
00280                 std::map< uint64_t, int >::iterator it;
00281 
00282                 for(size_t i = 0; i < curindices->size(); i += 3) {
00283                     // for ever tri, create 3 new vertices and 4 new triangles.
00284                     v[0] = curvertices->at(curindices->at(i));
00285                     v[1] = curvertices->at(curindices->at(i+1));
00286                     v[2] = curvertices->at(curindices->at(i+2));
00287 
00288                     int inds[3];
00289                     for(int j = 0; j < 3; ++j) {
00290                         uint64_t key = ((uint64_t)curindices->at(i+j)<<32)|(uint64_t)curindices->at(i + ((j+1)%3));
00291                         it = mapnewinds.find(key);
00292 
00293                         if( it == mapnewinds.end() ) {
00294                             inds[j] = mapnewinds[key] = mapnewinds[(key<<32)|(key>>32)] = (int)newvertices->size();
00295                             newvertices->push_back(_normalize3(_add3(v[j],v[(j+1)%3 ])));
00296                         }
00297                         else {
00298                             inds[j] = it->second;
00299                         }
00300                     }
00301 
00302                     newindices->push_back(curindices->at(i));    newindices->push_back(inds[0]);    newindices->push_back(inds[2]);
00303                     newindices->push_back(inds[0]);    newindices->push_back(curindices->at(i+1));    newindices->push_back(inds[1]);
00304                     newindices->push_back(inds[2]);    newindices->push_back(inds[0]);    newindices->push_back(inds[1]);
00305                     newindices->push_back(inds[2]);    newindices->push_back(inds[1]);    newindices->push_back(curindices->at(i+2));
00306                 }
00307 
00308                 std::swap(newvertices,curvertices);
00309                 std::swap(newindices,curindices);
00310             }
00311 
00312             realvertices = *curvertices;
00313             realindices = *curindices;
00314         }
00315 
00316         bool InitCollisionMesh(double fTessellation=1.0)
00317         {
00318             if( type == GeomTrimesh ) {
00319                 return true;
00320             }
00321             indices.clear();
00322             vertices.clear();
00323 
00324             if( fTessellation < 0.01f ) {
00325                 fTessellation = 0.01f;
00326             }
00327             // start tesselating
00328             switch(type) {
00329             case GeomSphere: {
00330                 // log_2 (1+ tess)
00331                 GenerateSphereTriangulation(vertices,indices, 3 + (int)(logf(fTessellation) / logf(2.0f)) );
00332                 double fRadius = vGeomData.x;
00333                 FOREACH(it, vertices) {
00334                     it->x *= fRadius;
00335                     it->y *= fRadius;
00336                     it->z *= fRadius;
00337                 }
00338                 break;
00339             }
00340             case GeomBox: {
00341                 // trivial
00342                 Vector3 ex = vGeomData;
00343                 Vector3 v[8] = { Vector3(ex.x, ex.y, ex.z),
00344                                  Vector3(ex.x, ex.y, -ex.z),
00345                                  Vector3(ex.x, -ex.y, ex.z),
00346                                  Vector3(ex.x, -ex.y, -ex.z),
00347                                  Vector3(-ex.x, ex.y, ex.z),
00348                                  Vector3(-ex.x, ex.y, -ex.z),
00349                                  Vector3(-ex.x, -ex.y, ex.z),
00350                                  Vector3(-ex.x, -ex.y, -ex.z) };
00351                 const int nindices = 36;
00352                 int startindices[] = {
00353                     0, 1, 2,
00354                     1, 2, 3,
00355                     4, 5, 6,
00356                     5, 6, 7,
00357                     0, 1, 4,
00358                     1, 4, 5,
00359                     2, 3, 6,
00360                     3, 6, 7,
00361                     0, 2, 4,
00362                     2, 4, 6,
00363                     1, 3, 5,
00364                     3, 5, 7
00365                 };
00366 
00367                 for(int i = 0; i < nindices; i += 3 ) {
00368                     Vector3 v1 = v[startindices[i]];
00369                     Vector3 v2 = v[startindices[i+1]];
00370                     Vector3 v3 = v[startindices[i+2]];
00371                     if( _dot3(v1, _sub3(v2,_cross3(v1, _sub3(v3,v1)))) < 0 ) {
00372                         std::swap(indices[i], indices[i+1]);
00373                     }
00374                 }
00375 
00376                 vertices.resize(8);
00377                 std::copy(&v[0],&v[8],vertices.begin());
00378                 indices.resize(nindices);
00379                 std::copy(&startindices[0],&startindices[nindices],indices.begin());
00380                 break;
00381             }
00382             case GeomCylinder: {
00383                 // cylinder is on y axis
00384                 double rad = vGeomData.x, len = vGeomData.y*0.5f;
00385 
00386                 int numverts = (int)(fTessellation*24.0f) + 3;
00387                 double dtheta = 2 * M_PI / (double)numverts;
00388                 vertices.push_back(Vector3(0,0,len));
00389                 vertices.push_back(Vector3(0,0,-len));
00390                 vertices.push_back(Vector3(rad,0,len));
00391                 vertices.push_back(Vector3(rad,0,-len));
00392 
00393                 for(int i = 0; i < numverts+1; ++i) {
00394                     double s = rad * std::sin(dtheta * (double)i);
00395                     double c = rad * std::cos(dtheta * (double)i);
00396 
00397                     int off = (int)vertices.size();
00398                     vertices.push_back(Vector3(c, s, len));
00399                     vertices.push_back(Vector3(c, s, -len));
00400 
00401                     indices.push_back(0);       indices.push_back(off);       indices.push_back(off-2);
00402                     indices.push_back(1);       indices.push_back(off-1);       indices.push_back(off+1);
00403                     indices.push_back(off-2);   indices.push_back(off);         indices.push_back(off-1);
00404                     indices.push_back(off);   indices.push_back(off-1);         indices.push_back(off+1);
00405                 }
00406                 break;
00407             }
00408             default:
00409                 BOOST_ASSERT(0);
00410             }
00411             return true;
00412         }
00413     };
00414 
00415 public:
00416     ColladaModelReader(urdf::ModelInterfaceSharedPtr model) : _dom(NULL), _nGlobalSensorId(0), _nGlobalManipulatorId(0), _model(model) {
00417         daeErrorHandler::setErrorHandler(this);
00418         _resourcedir = ".";
00419     }
00420     virtual ~ColladaModelReader() {
00421         _vuserdata.clear();
00422         _collada.reset();
00423         DAE::cleanup();
00424     }
00425 
00426     bool InitFromFile(const std::string& filename) {
00427         ROS_DEBUG_STREAM(str(boost::format("init COLLADA reader version: %s, namespace: %s, filename: %s\n")%COLLADA_VERSION%COLLADA_NAMESPACE%filename));
00428         _collada.reset(new DAE);
00429         _dom = (domCOLLADA*)_collada->open(filename);
00430         if (!_dom) {
00431             return false;
00432         }
00433         _filename=filename;
00434 
00435         size_t maxchildren = _countChildren(_dom);
00436         _vuserdata.resize(0);
00437         _vuserdata.reserve(maxchildren);
00438 
00439         double dScale = 1.0;
00440         _processUserData(_dom, dScale);
00441         ROS_DEBUG_STREAM(str(boost::format("processed children: %d/%d\n")%_vuserdata.size()%maxchildren));
00442         return _Extract();
00443     }
00444 
00445     bool InitFromData(const std::string& pdata) {
00446         ROS_DEBUG_STREAM(str(boost::format("init COLLADA reader version: %s, namespace: %s\n")%COLLADA_VERSION%COLLADA_NAMESPACE));
00447         _collada.reset(new DAE);
00448         _dom = (domCOLLADA*)_collada->openFromMemory(".",pdata.c_str());
00449         if (!_dom) {
00450             return false;
00451         }
00452 
00453         size_t maxchildren = _countChildren(_dom);
00454         _vuserdata.resize(0);
00455         _vuserdata.reserve(maxchildren);
00456 
00457         double dScale = 1.0;
00458         _processUserData(_dom, dScale);
00459         ROS_DEBUG_STREAM(str(boost::format("processed children: %d/%d\n")%_vuserdata.size()%maxchildren));
00460         return _Extract();
00461     }
00462 
00463 protected:
00464 
00466     bool _Extract()
00467     {
00468         _model->clear();
00469         std::list< std::pair<domInstance_kinematics_modelRef, boost::shared_ptr<KinematicsSceneBindings> > > listPossibleBodies;
00470         domCOLLADA::domSceneRef allscene = _dom->getScene();
00471         if( !allscene ) {
00472             return false;
00473         }
00474 
00475         //  parse each instance kinematics scene, prioritize real robots
00476         for (size_t iscene = 0; iscene < allscene->getInstance_kinematics_scene_array().getCount(); iscene++) {
00477             domInstance_kinematics_sceneRef kiscene = allscene->getInstance_kinematics_scene_array()[iscene];
00478             domKinematics_sceneRef kscene = daeSafeCast<domKinematics_scene> (kiscene->getUrl().getElement().cast());
00479             if (!kscene) {
00480                 continue;
00481             }
00482             boost::shared_ptr<KinematicsSceneBindings> bindings(new KinematicsSceneBindings());
00483             _ExtractKinematicsVisualBindings(allscene->getInstance_visual_scene(),kiscene,*bindings);
00484             _ExtractPhysicsBindings(allscene,*bindings);
00485             for(size_t ias = 0; ias < kscene->getInstance_articulated_system_array().getCount(); ++ias) {
00486                 if( _ExtractArticulatedSystem(kscene->getInstance_articulated_system_array()[ias], *bindings) ) {
00487                     _PostProcess();
00488                     return true;
00489                 }
00490             }
00491             for(size_t ikmodel = 0; ikmodel < kscene->getInstance_kinematics_model_array().getCount(); ++ikmodel) {
00492                 listPossibleBodies.push_back(std::make_pair(kscene->getInstance_kinematics_model_array()[ikmodel], bindings));
00493             }
00494         }
00495 
00496         FOREACH(it, listPossibleBodies) {
00497             if( _ExtractKinematicsModel(it->first, *it->second) ) {
00498                 _PostProcess();
00499                 return true;
00500             }
00501         }
00502 
00503         return false;
00504     }
00505 
00506     void _PostProcess()
00507     {
00508         std::map<std::string, std::string> parent_link_tree;
00509         // building tree: name mapping
00510         try
00511         {
00512             _model->initTree(parent_link_tree);
00513         }
00514         catch(ParseError &e)
00515         {
00516             ROS_ERROR("Failed to build tree: %s", e.what());
00517         }
00518 
00519         // find the root link
00520         try
00521         {
00522             _model->initRoot(parent_link_tree);
00523         }
00524         catch(ParseError &e)
00525         {
00526             ROS_ERROR("Failed to find root link: %s", e.what());
00527         }
00528     }
00529 
00531     bool _ExtractArticulatedSystem(domInstance_articulated_systemRef ias, KinematicsSceneBindings& bindings)
00532     {
00533         if( !ias ) {
00534             return false;
00535         }
00536         ROS_DEBUG_STREAM(str(boost::format("instance articulated system sid %s\n")%ias->getSid()));
00537         domArticulated_systemRef articulated_system = daeSafeCast<domArticulated_system> (ias->getUrl().getElement().cast());
00538         if( !articulated_system ) {
00539             return false;
00540         }
00541 
00542         boost::shared_ptr<std::string> pinterface_type = _ExtractInterfaceType(ias->getExtra_array());
00543         if( !pinterface_type ) {
00544             pinterface_type = _ExtractInterfaceType(articulated_system->getExtra_array());
00545         }
00546         if( !!pinterface_type ) {
00547             ROS_DEBUG_STREAM(str(boost::format("robot type: %s")%(*pinterface_type)));
00548         }
00549 
00550         // set the name
00551         if( _model->name_.size() == 0 && !!ias->getName() ) {
00552             _model->name_ = ias->getName();
00553         }
00554         if( _model->name_.size() == 0 && !!ias->getSid()) {
00555             _model->name_ = ias->getSid();
00556         }
00557         if( _model->name_.size() == 0 && !!articulated_system->getName() ) {
00558             _model->name_ = articulated_system->getName();
00559         }
00560         if( _model->name_.size() == 0 && !!articulated_system->getId()) {
00561             _model->name_ = articulated_system->getId();
00562         }
00563 
00564         if( !!articulated_system->getMotion() ) {
00565             domInstance_articulated_systemRef ias_new = articulated_system->getMotion()->getInstance_articulated_system();
00566             if( !!articulated_system->getMotion()->getTechnique_common() ) {
00567                 for(size_t i = 0; i < articulated_system->getMotion()->getTechnique_common()->getAxis_info_array().getCount(); ++i) {
00568                     domMotion_axis_infoRef motion_axis_info = articulated_system->getMotion()->getTechnique_common()->getAxis_info_array()[i];
00569                     // this should point to a kinematics axis_info
00570                     domKinematics_axis_infoRef kinematics_axis_info = daeSafeCast<domKinematics_axis_info>(daeSidRef(motion_axis_info->getAxis(), ias_new->getUrl().getElement()).resolve().elt);
00571                     if( !!kinematics_axis_info ) {
00572                         // find the parent kinematics and go through all its instance kinematics models
00573                         daeElement* pparent = kinematics_axis_info->getParent();
00574                         while(!!pparent && pparent->typeID() != domKinematics::ID()) {
00575                             pparent = pparent->getParent();
00576                         }
00577                         BOOST_ASSERT(!!pparent);
00578                         bindings.AddAxisInfo(daeSafeCast<domKinematics>(pparent)->getInstance_kinematics_model_array(), kinematics_axis_info, motion_axis_info);
00579                     }
00580                     else {
00581                         ROS_WARN_STREAM(str(boost::format("failed to find kinematics axis %s\n")%motion_axis_info->getAxis()));
00582                     }
00583                 }
00584             }
00585             if( !_ExtractArticulatedSystem(ias_new,bindings) ) {
00586                 return false;
00587             }
00588         }
00589         else {
00590             if( !articulated_system->getKinematics() ) {
00591                 ROS_WARN_STREAM(str(boost::format("collada <kinematics> tag empty? instance_articulated_system=%s\n")%ias->getID()));
00592                 return true;
00593             }
00594 
00595             if( !!articulated_system->getKinematics()->getTechnique_common() ) {
00596                 for(size_t i = 0; i < articulated_system->getKinematics()->getTechnique_common()->getAxis_info_array().getCount(); ++i) {
00597                     bindings.AddAxisInfo(articulated_system->getKinematics()->getInstance_kinematics_model_array(), articulated_system->getKinematics()->getTechnique_common()->getAxis_info_array()[i], NULL);
00598                 }
00599             }
00600 
00601             for(size_t ik = 0; ik < articulated_system->getKinematics()->getInstance_kinematics_model_array().getCount(); ++ik) {
00602                 _ExtractKinematicsModel(articulated_system->getKinematics()->getInstance_kinematics_model_array()[ik],bindings);
00603             }
00604         }
00605 
00606         _ExtractRobotAttachedActuators(articulated_system);
00607         _ExtractRobotManipulators(articulated_system);
00608         _ExtractRobotAttachedSensors(articulated_system);
00609         return true;
00610     }
00611 
00612     bool _ExtractKinematicsModel(domInstance_kinematics_modelRef ikm, KinematicsSceneBindings& bindings)
00613     {
00614         if( !ikm ) {
00615             return false;
00616         }
00617         ROS_DEBUG_STREAM(str(boost::format("instance kinematics model sid %s\n")%ikm->getSid()));
00618         domKinematics_modelRef kmodel = daeSafeCast<domKinematics_model> (ikm->getUrl().getElement().cast());
00619         if (!kmodel) {
00620             ROS_WARN_STREAM(str(boost::format("%s does not reference valid kinematics\n")%ikm->getSid()));
00621             return false;
00622         }
00623         domPhysics_modelRef pmodel;
00624         boost::shared_ptr<std::string> pinterface_type = _ExtractInterfaceType(ikm->getExtra_array());
00625         if( !pinterface_type ) {
00626             pinterface_type = _ExtractInterfaceType(kmodel->getExtra_array());
00627         }
00628         if( !!pinterface_type ) {
00629             ROS_DEBUG_STREAM(str(boost::format("kinbody interface type: %s")%(*pinterface_type)));
00630         }
00631 
00632         // find matching visual node
00633         domNodeRef pvisualnode;
00634         FOREACH(it, bindings.listKinematicsVisualBindings) {
00635             if( it->second == ikm ) {
00636                 pvisualnode = it->first;
00637                 break;
00638             }
00639         }
00640         if( !pvisualnode ) {
00641             ROS_WARN_STREAM(str(boost::format("failed to find visual node for instance kinematics model %s\n")%ikm->getSid()));
00642             return false;
00643         }
00644 
00645         if( _model->name_.size() == 0 && !!ikm->getName() ) {
00646             _model->name_ = ikm->getName();
00647         }
00648         if( _model->name_.size() == 0 && !!ikm->getID() ) {
00649             _model->name_ = ikm->getID();
00650         }
00651 
00652         if (!_ExtractKinematicsModel(kmodel, pvisualnode, pmodel, bindings)) {
00653             ROS_WARN_STREAM(str(boost::format("failed to load kinbody from kinematics model %s\n")%kmodel->getID()));
00654             return false;
00655         }
00656         return true;
00657     }
00658 
00660     bool _ExtractKinematicsModel(domKinematics_modelRef kmodel, domNodeRef pnode, domPhysics_modelRef pmodel, const KinematicsSceneBindings& bindings)
00661     {
00662         std::vector<domJointRef> vdomjoints;
00663         ROS_DEBUG_STREAM(str(boost::format("kinematics model: %s\n")%_model->name_));
00664         if( !!pnode ) {
00665             ROS_DEBUG_STREAM(str(boost::format("node name: %s\n")%pnode->getId()));
00666         }
00667 
00668         //  Process joint of the kinbody
00669         domKinematics_model_techniqueRef ktec = kmodel->getTechnique_common();
00670 
00671         //  Store joints
00672         for (size_t ijoint = 0; ijoint < ktec->getJoint_array().getCount(); ++ijoint) {
00673             vdomjoints.push_back(ktec->getJoint_array()[ijoint]);
00674         }
00675 
00676         //  Store instances of joints
00677         for (size_t ijoint = 0; ijoint < ktec->getInstance_joint_array().getCount(); ++ijoint) {
00678             domJointRef pelt = daeSafeCast<domJoint> (ktec->getInstance_joint_array()[ijoint]->getUrl().getElement());
00679             if (!pelt) {
00680                 ROS_WARN_STREAM("failed to get joint from instance\n");
00681             }
00682             else {
00683                 vdomjoints.push_back(pelt);
00684             }
00685         }
00686 
00687         ROS_DEBUG_STREAM(str(boost::format("Number of root links in the kmodel %d\n")%ktec->getLink_array().getCount()));
00688         for (size_t ilink = 0; ilink < ktec->getLink_array().getCount(); ++ilink) {
00689             domLinkRef pdomlink = ktec->getLink_array()[ilink];
00690             _RootOrigin  = _poseFromMatrix(_ExtractFullTransform(pdomlink));
00691             ROS_DEBUG("RootOrigin: %s %lf %lf %lf %lf %lf %lf %lf",
00692                       pdomlink->getName(),
00693                       _RootOrigin.position.x, _RootOrigin.position.y, _RootOrigin.position.z,
00694                       _RootOrigin.rotation.x, _RootOrigin.rotation.y, _RootOrigin.rotation.z, _RootOrigin.rotation.w);
00695 
00696             domNodeRef pvisualnode;
00697             FOREACH(it, bindings.listKinematicsVisualBindings) {
00698               if(strcmp(it->first->getName() ,pdomlink->getName()) == 0) {
00699                 pvisualnode = it->first;
00700                 break;
00701               }
00702             }
00703             if (!!pvisualnode) {
00704               _VisualRootOrigin  = _poseFromMatrix(_getNodeParentTransform(pvisualnode));
00705               ROS_DEBUG("VisualRootOrigin: %s %lf %lf %lf %lf %lf %lf %lf",
00706                         pdomlink->getName(),
00707                         _VisualRootOrigin.position.x, _VisualRootOrigin.position.y, _VisualRootOrigin.position.z,
00708                         _VisualRootOrigin.rotation.x, _VisualRootOrigin.rotation.y, _VisualRootOrigin.rotation.z, _VisualRootOrigin.rotation.w);
00709             }
00710             _ExtractLink(pdomlink, ilink == 0 ? pnode : domNodeRef(), Pose(), Pose(), vdomjoints, bindings);
00711         }
00712 
00713         //  TODO: implement mathml
00714         for (size_t iform = 0; iform < ktec->getFormula_array().getCount(); ++iform) {
00715             domFormulaRef pf = ktec->getFormula_array()[iform];
00716             if (!pf->getTarget()) {
00717                 ROS_WARN_STREAM("formula target not valid\n");
00718                 continue;
00719             }
00720 
00721             // find the target joint
00722             urdf::JointSharedPtr pjoint = _getJointFromRef(pf->getTarget()->getParam()->getValue(),pf);
00723             if (!pjoint) {
00724                 continue;
00725             }
00726 
00727             if (!!pf->getTechnique_common()) {
00728                 daeElementRef peltmath;
00729                 daeTArray<daeElementRef> children;
00730                 pf->getTechnique_common()->getChildren(children);
00731                 for (size_t ichild = 0; ichild < children.getCount(); ++ichild) {
00732                     daeElementRef pelt = children[ichild];
00733                     if (_checkMathML(pelt,std::string("math")) ) {
00734                         peltmath = pelt;
00735                     }
00736                     else {
00737                         ROS_WARN_STREAM(str(boost::format("unsupported formula element: %s\n")%pelt->getElementName()));
00738                     }
00739                 }
00740                 if (!!peltmath) {
00741                     // full math xml spec not supported, only looking for ax+b pattern:
00742                     // <apply> <plus/> <apply> <times/> <ci>a</ci> x </apply> <ci>b</ci> </apply>
00743                     double a = 1, b = 0;
00744                     daeElementRef psymboljoint;
00745                     BOOST_ASSERT(peltmath->getChildren().getCount()>0);
00746                     daeElementRef papplyelt = peltmath->getChildren()[0];
00747                     BOOST_ASSERT(_checkMathML(papplyelt,"apply"));
00748                     BOOST_ASSERT(papplyelt->getChildren().getCount()>0);
00749                     if( _checkMathML(papplyelt->getChildren()[0],"plus") ) {
00750                         BOOST_ASSERT(papplyelt->getChildren().getCount()==3);
00751                         daeElementRef pa = papplyelt->getChildren()[1];
00752                         daeElementRef pb = papplyelt->getChildren()[2];
00753                         if( !_checkMathML(papplyelt->getChildren()[1],"apply") ) {
00754                             std::swap(pa,pb);
00755                         }
00756                         if( !_checkMathML(pa,"csymbol") ) {
00757                             BOOST_ASSERT(_checkMathML(pa,"apply"));
00758                             BOOST_ASSERT(_checkMathML(pa->getChildren()[0],"times"));
00759                             if( _checkMathML(pa->getChildren()[1],"csymbol") ) {
00760                                 psymboljoint = pa->getChildren()[1];
00761                                 BOOST_ASSERT(_checkMathML(pa->getChildren()[2],"cn"));
00762                                 std::stringstream ss(pa->getChildren()[2]->getCharData());
00763                                 ss >> a;
00764                             }
00765                             else {
00766                                 psymboljoint = pa->getChildren()[2];
00767                                 BOOST_ASSERT(_checkMathML(pa->getChildren()[1],"cn"));
00768                                 std::stringstream ss(pa->getChildren()[1]->getCharData());
00769                                 ss >> a;
00770                             }
00771                         }
00772                         else {
00773                             psymboljoint = pa;
00774                         }
00775                         BOOST_ASSERT(_checkMathML(pb,"cn"));
00776                         {
00777                             std::stringstream ss(pb->getCharData());
00778                             ss >> b;
00779                         }
00780                     }
00781                     else if( _checkMathML(papplyelt->getChildren()[0],"minus") ) {
00782                         BOOST_ASSERT(_checkMathML(papplyelt->getChildren()[1],"csymbol"));
00783                         a = -1;
00784                         psymboljoint = papplyelt->getChildren()[1];
00785                     }
00786                     else {
00787                         BOOST_ASSERT(_checkMathML(papplyelt->getChildren()[0],"csymbol"));
00788                         psymboljoint = papplyelt->getChildren()[0];
00789                     }
00790                     BOOST_ASSERT(psymboljoint->hasAttribute("encoding"));
00791                     BOOST_ASSERT(psymboljoint->getAttribute("encoding")==std::string("COLLADA"));
00792                     urdf::JointSharedPtr pbasejoint = _getJointFromRef(psymboljoint->getCharData().c_str(),pf);
00793                     if( !!pbasejoint ) {
00794                         // set the mimic properties
00795                         pjoint->mimic.reset(new JointMimic());
00796                         pjoint->mimic->joint_name = pbasejoint->name;
00797                         pjoint->mimic->multiplier = a;
00798                         pjoint->mimic->offset = b;
00799                         ROS_DEBUG_STREAM(str(boost::format("assigning joint %s to mimic %s %f %f\n")%pjoint->name%pbasejoint->name%a%b));
00800                     }
00801                 }
00802             }
00803         }
00804         return true;
00805     }
00806 
00808     urdf::LinkSharedPtr _ExtractLink(const domLinkRef pdomlink,const domNodeRef pdomnode, const Pose& tParentWorldLink, const Pose& tParentLink, const std::vector<domJointRef>& vdomjoints, const KinematicsSceneBindings& bindings) {
00809         const std::list<JointAxisBinding>& listAxisBindings = bindings.listAxisBindings;
00810         //  Set link name with the name of the COLLADA's Link
00811         std::string linkname = _ExtractLinkName(pdomlink);
00812         if( linkname.size() == 0 ) {
00813             ROS_WARN_STREAM("<link> has no name or id, falling back to <node>!\n");
00814             if( !!pdomnode ) {
00815                 if (!!pdomnode->getName()) {
00816                     linkname = pdomnode->getName();
00817                 }
00818                 if( linkname.size() == 0 && !!pdomnode->getID()) {
00819                     linkname = pdomnode->getID();
00820                 }
00821             }
00822         }
00823 
00824         urdf::LinkSharedPtr plink;
00825         _model->getLink(linkname,plink);
00826         if( !plink ) {
00827             plink.reset(new Link());
00828             plink->name = linkname;
00829             plink->visual.reset(new Visual());
00830             plink->visual->material_name = "";
00831             plink->visual->material.reset(new Material());
00832             plink->visual->material->name = "Red";
00833             plink->visual->material->color.r = 0.0;
00834             plink->visual->material->color.g = 1.0;
00835             plink->visual->material->color.b = 0.0;
00836             plink->visual->material->color.a = 1.0;
00837             plink->inertial.reset();
00838             _model->links_.insert(std::make_pair(linkname,plink));
00839         }
00840 
00841         _getUserData(pdomlink)->p = plink;
00842         if( !!pdomnode ) {
00843             ROS_DEBUG_STREAM(str(boost::format("Node Id %s and Name %s\n")%pdomnode->getId()%pdomnode->getName()));
00844         }
00845 
00846         // physics
00847         domInstance_rigid_bodyRef irigidbody;
00848         domRigid_bodyRef rigidbody;
00849         bool bFoundBinding = false;
00850         FOREACH(itlinkbinding, bindings.listLinkBindings) {
00851             if( !!pdomnode->getID() && !!itlinkbinding->node->getID() && strcmp(pdomnode->getID(),itlinkbinding->node->getID()) == 0 ) {
00852                 bFoundBinding = true;
00853                 irigidbody = itlinkbinding->irigidbody;
00854                 rigidbody = itlinkbinding->rigidbody;
00855             }
00856         }
00857 
00858         if( !!rigidbody && !!rigidbody->getTechnique_common() ) {
00859             domRigid_body::domTechnique_commonRef rigiddata = rigidbody->getTechnique_common();
00860             if( !!rigiddata->getMass() ) {
00861                 if ( !plink->inertial ) {
00862                     plink->inertial.reset(new Inertial());
00863                 }
00864                 plink->inertial->mass = rigiddata->getMass()->getValue();
00865             }
00866             if( !!rigiddata->getInertia() ) {
00867                 if ( !plink->inertial ) {
00868                     plink->inertial.reset(new Inertial());
00869                 }
00870                 plink->inertial->ixx = rigiddata->getInertia()->getValue()[0];
00871                 plink->inertial->iyy = rigiddata->getInertia()->getValue()[1];
00872                 plink->inertial->izz = rigiddata->getInertia()->getValue()[2];
00873             }
00874             if( !!rigiddata->getMass_frame() ) {
00875                 if ( !plink->inertial ) {
00876                     plink->inertial.reset(new Inertial());
00877                 }
00878                 //plink->inertial->origin = _poseMult(_poseInverse(tParentWorldLink), _poseFromMatrix(_ExtractFullTransform(rigiddata->getMass_frame())));
00879                 Pose tlink = _poseFromMatrix(_ExtractFullTransform(pdomlink));
00880                 plink->inertial->origin = _poseMult(_poseInverse(_poseMult(_poseInverse(_RootOrigin),
00881                                                                            _poseMult(tParentWorldLink, tlink))),
00882                                                     _poseFromMatrix(_ExtractFullTransform(rigiddata->getMass_frame())));
00883             }
00884         }
00885 
00886         std::list<GEOMPROPERTIES> listGeomProperties;
00887         if (!pdomlink) {
00888             ROS_WARN_STREAM("Extract object NOT kinematics !!!\n");
00889             _ExtractGeometry(pdomnode,listGeomProperties,listAxisBindings,Pose());
00890         }
00891         else {
00892             ROS_DEBUG_STREAM(str(boost::format("Attachment link elements: %d\n")%pdomlink->getAttachment_full_array().getCount()));
00893             Pose tlink = _poseFromMatrix(_ExtractFullTransform(pdomlink));
00894             ROS_DEBUG("tlink: %s: %lf %lf %lf %lf %lf %lf %lf",
00895                       linkname.c_str(),
00896                       tlink.position.x,  tlink.position.y, tlink.position.z,
00897                       tlink.rotation.x, tlink.rotation.y, tlink.rotation.z, tlink.rotation.w);
00898             plink->visual->origin = _poseMult(tParentLink, tlink); // use the kinematics coordinate system for each link
00899             //            ROS_INFO("link %s rot: %f %f %f %f",linkname.c_str(),plink->visual->origin.rotation.w, plink->visual->origin.rotation.x,plink->visual->origin.rotation.y,plink->visual->origin.rotation.z);
00900             //            ROS_INFO("link %s trans: %f %f %f",linkname.c_str(),plink->visual->origin.position.x,plink->visual->origin.position.y,plink->visual->origin.position.z);
00901 
00902             // Get the geometry
00903             _ExtractGeometry(pdomnode, listGeomProperties, listAxisBindings,
00904                              _poseMult(_poseMult(tParentWorldLink,tlink), plink->visual->origin));
00905 
00906             ROS_DEBUG_STREAM(str(boost::format("After ExtractGeometry Attachment link elements: %d\n")%pdomlink->getAttachment_full_array().getCount()));
00907 
00908             //  Process all atached links
00909             for (size_t iatt = 0; iatt < pdomlink->getAttachment_full_array().getCount(); ++iatt) {
00910                 domLink::domAttachment_fullRef pattfull = pdomlink->getAttachment_full_array()[iatt];
00911 
00912                 // get link kinematics transformation
00913                 Pose tatt = _poseFromMatrix(_ExtractFullTransform(pattfull));
00914 
00915                 // process attached links
00916                 daeElement* peltjoint = daeSidRef(pattfull->getJoint(), pattfull).resolve().elt;
00917                 domJointRef pdomjoint = daeSafeCast<domJoint> (peltjoint);
00918 
00919                 if (!pdomjoint) {
00920                     domInstance_jointRef pdomijoint = daeSafeCast<domInstance_joint> (peltjoint);
00921                     if (!!pdomijoint) {
00922                         pdomjoint = daeSafeCast<domJoint> (pdomijoint->getUrl().getElement().cast());
00923                     }
00924                 }
00925 
00926                 if (!pdomjoint || pdomjoint->typeID() != domJoint::ID()) {
00927                     ROS_WARN_STREAM(str(boost::format("could not find attached joint %s!\n")%pattfull->getJoint()));
00928                     return urdf::LinkSharedPtr();
00929                 }
00930 
00931                 // get direct child link
00932                 if (!pattfull->getLink()) {
00933                     ROS_WARN_STREAM(str(boost::format("joint %s needs to be attached to a valid link\n")%pdomjoint->getID()));
00934                     continue;
00935                 }
00936 
00937                 // find the correct joint in the bindings
00938                 daeTArray<domAxis_constraintRef> vdomaxes = pdomjoint->getChildrenByType<domAxis_constraint>();
00939                 domNodeRef pchildnode;
00940 
00941                 // see if joint has a binding to a visual node
00942                 FOREACHC(itaxisbinding,listAxisBindings) {
00943                     for (size_t ic = 0; ic < vdomaxes.getCount(); ++ic) {
00944                         //  If the binding for the joint axis is found, retrieve the info
00945                         if (vdomaxes[ic] == itaxisbinding->pkinematicaxis) {
00946                             pchildnode = itaxisbinding->visualnode;
00947                             break;
00948                         }
00949                     }
00950                     if( !!pchildnode ) {
00951                         break;
00952                     }
00953                 }
00954                 if (!pchildnode) {
00955                     ROS_DEBUG_STREAM(str(boost::format("joint %s has no visual binding\n")%pdomjoint->getID()));
00956                 }
00957 
00958                 // create the joints before creating the child links
00959                 std::vector<urdf::JointSharedPtr > vjoints(vdomaxes.getCount());
00960                 for (size_t ic = 0; ic < vdomaxes.getCount(); ++ic) {
00961                     bool joint_active = true; // if not active, put into the passive list
00962                     FOREACHC(itaxisbinding,listAxisBindings) {
00963                         if (vdomaxes[ic] == itaxisbinding->pkinematicaxis) {
00964                             if( !!itaxisbinding->kinematics_axis_info ) {
00965                                 if( !!itaxisbinding->kinematics_axis_info->getActive() ) {
00966                                     joint_active = resolveBool(itaxisbinding->kinematics_axis_info->getActive(),itaxisbinding->kinematics_axis_info);
00967                                 }
00968                             }
00969                             break;
00970                         }
00971                     }
00972 
00973                     urdf::JointSharedPtr pjoint(new Joint());
00974                     pjoint->limits.reset(new JointLimits());
00975                     pjoint->limits->velocity = 0.0;
00976                     pjoint->limits->effort = 0.0;
00977                     pjoint->parent_link_name = plink->name;
00978 
00979                     if( !!pdomjoint->getName() ) {
00980                         pjoint->name = pdomjoint->getName();
00981                     }
00982                     else {
00983                         pjoint->name = str(boost::format("dummy%d")%_model->joints_.size());
00984                     }
00985 
00986                     if( !joint_active ) {
00987                         ROS_INFO_STREAM(str(boost::format("joint %s is passive, but adding to hierarchy\n")%pjoint->name));
00988                     }
00989 
00990                     domAxis_constraintRef pdomaxis = vdomaxes[ic];
00991                     if( strcmp(pdomaxis->getElementName(), "revolute") == 0 ) {
00992                         pjoint->type = Joint::REVOLUTE;
00993                     }
00994                     else if( strcmp(pdomaxis->getElementName(), "prismatic") == 0 ) {
00995                         pjoint->type = Joint::PRISMATIC;
00996                     }
00997                     else {
00998                         ROS_WARN_STREAM(str(boost::format("unsupported joint type: %s\n")%pdomaxis->getElementName()));
00999                     }
01000 
01001                     _getUserData(pdomjoint)->p = pjoint;
01002 #if URDFDOM_HEADERS_MAJOR_VERSION < 1
01003                     _getUserData(pdomaxis)->p = boost::shared_ptr<int>(new int(_model->joints_.size()));
01004 #else
01005                     _getUserData(pdomaxis)->p = std::shared_ptr<int>(new int(_model->joints_.size()));
01006 #endif
01007                     _model->joints_[pjoint->name] = pjoint;
01008                     vjoints[ic] = pjoint;
01009                 }
01010 
01011                 urdf::LinkSharedPtr pchildlink = _ExtractLink(pattfull->getLink(), pchildnode, _poseMult(_poseMult(tParentWorldLink,tlink), tatt), tatt, vdomjoints, bindings);
01012 
01013                 if (!pchildlink) {
01014                     ROS_WARN_STREAM(str(boost::format("Link has no child: %s\n")%plink->name));
01015                     continue;
01016                 }
01017 
01018                 int numjoints = 0;
01019                 for (size_t ic = 0; ic < vdomaxes.getCount(); ++ic) {
01020                     domKinematics_axis_infoRef kinematics_axis_info;
01021                     domMotion_axis_infoRef motion_axis_info;
01022                     FOREACHC(itaxisbinding,listAxisBindings) {
01023                         bool bfound = false;
01024                         if (vdomaxes[ic] == itaxisbinding->pkinematicaxis) {
01025                             kinematics_axis_info = itaxisbinding->kinematics_axis_info;
01026                             motion_axis_info = itaxisbinding->motion_axis_info;
01027                             bfound = true;
01028                             break;
01029                         }
01030                     }
01031                     domAxis_constraintRef pdomaxis = vdomaxes[ic];
01032                     if (!pchildlink) {
01033                         // create dummy child link
01034                         // multiple axes can be easily done with "empty links"
01035                         ROS_WARN_STREAM(str(boost::format("creating dummy link %s, num joints %d\n")%plink->name%numjoints));
01036 
01037                         std::stringstream ss;
01038                         ss << plink->name;
01039                         ss <<"_dummy" << numjoints;
01040                         pchildlink.reset(new Link());
01041                         pchildlink->name = ss.str();
01042                         _model->links_.insert(std::make_pair(pchildlink->name,pchildlink));
01043                     }
01044 
01045                     ROS_DEBUG_STREAM(str(boost::format("Joint %s assigned %d \n")%vjoints[ic]->name%ic));
01046                     urdf::JointSharedPtr pjoint = vjoints[ic];
01047                     pjoint->child_link_name = pchildlink->name;
01048 
01049 #define PRINT_POSE(pname, apose) ROS_DEBUG(pname" pos: %f %f %f, rot: %f %f %f %f", \
01050                                            apose.position.x, apose.position.y, apose.position.z, \
01051                                            apose.rotation.x, apose.rotation.y, apose.rotation.z, apose.rotation.w);
01052                     {
01053                       PRINT_POSE("tatt", tatt);
01054                       PRINT_POSE("trans_joint_to_child", tatt);
01055                       Pose trans_joint_to_child = _poseFromMatrix(_ExtractFullTransform(pattfull->getLink()));
01056 
01057                       pjoint->parent_to_joint_origin_transform = _poseMult(tatt, trans_joint_to_child);
01058                       //  Axes and Anchor assignment.
01059                       Vector3 ax(pdomaxis->getAxis()->getValue()[0],
01060                                  pdomaxis->getAxis()->getValue()[1],
01061                                  pdomaxis->getAxis()->getValue()[2]);
01062                       Pose pinv = _poseInverse(trans_joint_to_child);
01063                       // rotate axis
01064                       ax = pinv.rotation * ax;
01065 
01066                       pjoint->axis.x = ax.x;
01067                       pjoint->axis.y = ax.y;
01068                       pjoint->axis.z = ax.z;
01069 
01070                       ROS_DEBUG("joint %s axis: %f %f %f -> %f %f %f\n", pjoint->name.c_str(),
01071                                 pdomaxis->getAxis()->getValue()[0],
01072                                 pdomaxis->getAxis()->getValue()[1],
01073                                 pdomaxis->getAxis()->getValue()[2],
01074                                 pjoint->axis.x, pjoint->axis.y, pjoint->axis.z);
01075                     }
01076 
01077                     if (!motion_axis_info) {
01078                         ROS_WARN_STREAM(str(boost::format("No motion axis info for joint %s\n")%pjoint->name));
01079                     }
01080 
01081                     //  Sets the Speed and the Acceleration of the joint
01082                     if (!!motion_axis_info) {
01083                         if (!!motion_axis_info->getSpeed()) {
01084                             pjoint->limits->velocity = resolveFloat(motion_axis_info->getSpeed(),motion_axis_info);
01085                             ROS_DEBUG("... Joint Speed: %f...\n",pjoint->limits->velocity);
01086                         }
01087                         if (!!motion_axis_info->getAcceleration()) {
01088                             pjoint->limits->effort = resolveFloat(motion_axis_info->getAcceleration(),motion_axis_info);
01089                             ROS_DEBUG("... Joint effort: %f...\n",pjoint->limits->effort);
01090                         }
01091                     }
01092 
01093                     bool joint_locked = false; // if locked, joint angle is static
01094                     bool kinematics_limits = false;
01095 
01096                     if (!!kinematics_axis_info) {
01097                         if (!!kinematics_axis_info->getLocked()) {
01098                             joint_locked = resolveBool(kinematics_axis_info->getLocked(),kinematics_axis_info);
01099                         }
01100 
01101                         if (joint_locked) { // If joint is locked set limits to the static value.
01102                             if( pjoint->type == Joint::REVOLUTE || pjoint->type ==Joint::PRISMATIC) {
01103                                 ROS_WARN_STREAM("lock joint!!\n");
01104                                 pjoint->limits->lower = 0;
01105                                 pjoint->limits->upper = 0;
01106                             }
01107                         }
01108                         else if (kinematics_axis_info->getLimits()) { // If there are articulated system kinematics limits
01109                             kinematics_limits   = true;
01110                             double fscale = (pjoint->type == Joint::REVOLUTE) ? (M_PI/180.0f) : _GetUnitScale(kinematics_axis_info);
01111                             if( pjoint->type == Joint::REVOLUTE || pjoint->type ==Joint::PRISMATIC) {
01112                                 pjoint->limits->lower = fscale*(double)(resolveFloat(kinematics_axis_info->getLimits()->getMin(),kinematics_axis_info));
01113                                 pjoint->limits->upper = fscale*(double)(resolveFloat(kinematics_axis_info->getLimits()->getMax(),kinematics_axis_info));
01114                                 if ( pjoint->limits->lower == 0 && pjoint->limits->upper == 0 ) {
01115                                     pjoint->type = Joint::FIXED;
01116                                 }
01117                             }
01118                         }
01119                     }
01120 
01121                     //  Search limits in the joints section
01122                     if (!kinematics_axis_info || (!joint_locked && !kinematics_limits)) {
01123                         //  If there are NO LIMITS
01124                         if( !pdomaxis->getLimits() ) {
01125                             ROS_DEBUG_STREAM(str(boost::format("There are NO LIMITS in joint %s:%d ...\n")%pjoint->name%kinematics_limits));
01126                             if( pjoint->type == Joint::REVOLUTE ) {
01127                                 pjoint->type = Joint::CONTINUOUS; // continuous means revolute?
01128                                 pjoint->limits->lower = -M_PI;
01129                                 pjoint->limits->upper = M_PI;
01130                             }
01131                             else {
01132                                 pjoint->limits->lower = -100000;
01133                                 pjoint->limits->upper = 100000;
01134                             }
01135                         }
01136                         else {
01137                             ROS_DEBUG_STREAM(str(boost::format("There are LIMITS in joint %s ...\n")%pjoint->name));
01138                             double fscale = (pjoint->type == Joint::REVOLUTE) ? (M_PI/180.0f) : _GetUnitScale(pdomaxis);
01139                             pjoint->limits->lower = (double)pdomaxis->getLimits()->getMin()->getValue()*fscale;
01140                             pjoint->limits->upper = (double)pdomaxis->getLimits()->getMax()->getValue()*fscale;
01141                             if ( pjoint->limits->lower == 0 && pjoint->limits->upper == 0 ) {
01142                                 pjoint->type = Joint::FIXED;
01143                             }
01144                         }
01145                     }
01146 
01147                     if (pjoint->limits->velocity == 0.0) {
01148                       pjoint->limits->velocity = pjoint->type == Joint::PRISMATIC ? 0.01 : 0.5f;
01149                     }
01150                     pchildlink.reset();
01151                     ++numjoints;
01152                 }
01153             }
01154         }
01155 
01156         if( pdomlink->getAttachment_start_array().getCount() > 0 ) {
01157             ROS_WARN("urdf collada reader does not support attachment_start\n");
01158         }
01159         if( pdomlink->getAttachment_end_array().getCount() > 0 ) {
01160             ROS_WARN("urdf collada reader does not support attachment_end\n");
01161         }
01162 
01163         plink->visual->geometry = _CreateGeometry(plink->name, listGeomProperties);
01164         // visual_groups deprecated
01165         //boost::shared_ptr<std::vector<urdf::VisualSharedPtr > > viss;
01166         //viss.reset(new std::vector<urdf::VisualSharedPtr >);
01167         //viss->push_back(plink->visual);
01168         //plink->visual_groups.insert(std::make_pair("default", viss));
01169 
01170         if( !plink->visual->geometry ) {
01171           plink->visual.reset();
01172           plink->collision.reset();
01173         } else {
01174           // collision
01175           plink->collision.reset(new Collision());
01176           plink->collision->geometry = plink->visual->geometry;
01177           plink->collision->origin   = plink->visual->origin;
01178         }
01179 
01180         // collision_groups deprecated
01181         //boost::shared_ptr<std::vector<urdf::CollisionSharedPtr > > cols;
01182         //cols.reset(new std::vector<urdf::CollisionSharedPtr >);
01183         //cols->push_back(plink->collision);
01184         //plink->collision_groups.insert(std::make_pair("default", cols));
01185 
01186         return plink;
01187     }
01188 
01189     urdf::GeometrySharedPtr _CreateGeometry(const std::string& name, const std::list<GEOMPROPERTIES>& listGeomProperties)
01190     {
01191         std::vector<std::vector<Vector3> > vertices;
01192         std::vector<std::vector<int> > indices;
01193         std::vector<Color> ambients;
01194         std::vector<Color> diffuses;
01195         unsigned int index, vert_counter;
01196         vertices.resize(listGeomProperties.size());
01197         indices.resize(listGeomProperties.size());
01198         ambients.resize(listGeomProperties.size());
01199         diffuses.resize(listGeomProperties.size());
01200         index = 0;
01201         vert_counter = 0;
01202         FOREACHC(it, listGeomProperties) {
01203             vertices[index].resize(it->vertices.size());
01204             for(size_t i = 0; i < it->vertices.size(); ++i) {
01205                 vertices[index][i] = _poseMult(it->_t, it->vertices[i]);
01206                 vert_counter++;
01207             }
01208             indices[index].resize(it->indices.size());
01209             for(size_t i = 0; i < it->indices.size(); ++i) {
01210                 indices[index][i] = it->indices[i];
01211             }
01212             ambients[index] = it->ambientColor;
01213             diffuses[index] = it->diffuseColor;
01214 // workaround for mesh_loader.cpp:421
01215 // Most of are DAE files don't have ambient color defined
01216             ambients[index].r *= 0.5; ambients[index].g *= 0.5; ambients[index].b *= 0.5;
01217             if ( ambients[index].r == 0.0 ) {
01218                 ambients[index].r = 0.0001;
01219             }
01220             if ( ambients[index].g == 0.0 ) {
01221                 ambients[index].g = 0.0001;
01222             }
01223             if ( ambients[index].b == 0.0 ) {
01224                 ambients[index].b = 0.0001;
01225             }
01226             index++;
01227         }
01228 
01229         if (vert_counter == 0) {
01230           urdf::MeshSharedPtr ret;
01231           ret.reset();
01232           return ret;
01233         }
01234 
01235         urdf::MeshSharedPtr geometry(new Mesh());
01236         geometry->type = Geometry::MESH;
01237         geometry->scale.x = 1;
01238         geometry->scale.y = 1;
01239         geometry->scale.z = 1;
01240 
01241         // have to save the geometry into individual collada 1.4 files since URDF does not allow triangle meshes to be specified
01242         std::stringstream daedata;
01243         daedata << str(boost::format("<?xml version=\"1.0\" encoding=\"utf-8\"?>\n\
01244 <COLLADA xmlns=\"http://www.collada.org/2005/11/COLLADASchema\" version=\"1.4.1\">\n\
01245   <asset>\n\
01246     <contributor>\n\
01247       <author>Rosen Diankov</author>\n\
01248       <comments>\n\
01249         robot_model/urdf temporary collada geometry\n\
01250       </comments>\n\
01251     </contributor>\n\
01252     <unit name=\"meter\" meter=\"1.0\"/>\n\
01253     <up_axis>Y_UP</up_axis>\n\
01254   </asset>\n\
01255   <library_materials>\n"));
01256         for(unsigned int i=0; i < index; i++) {
01257             daedata << str(boost::format("\
01258     <material id=\"blinn2%d\" name=\"blinn2%d\">\n\
01259       <instance_effect url=\"#blinn2-fx%d\"/>\n\
01260     </material>\n")%i%i%i);
01261         }
01262         daedata << "\
01263   </library_materials>\n\
01264   <library_effects>\n";
01265         for(unsigned int i=0; i < index; i++) {
01266             daedata << str(boost::format("\
01267     <effect id=\"blinn2-fx%d\">\n\
01268           <profile_COMMON>\n\
01269                 <technique sid=\"common\">\n\
01270                   <phong>\n\
01271                         <ambient>\n\
01272                           <color>%f %f %f %f</color>\n\
01273                         </ambient>\n\
01274                         <diffuse>\n\
01275                           <color>%f %f %f %f</color>\n\
01276                         </diffuse>\n\
01277                         <specular>\n\
01278                           <color>0 0 0 1</color>\n\
01279                         </specular>\n\
01280                   </phong>\n\
01281                 </technique>\n\
01282       </profile_COMMON>\n\
01283     </effect>\n")%i%ambients[i].r%ambients[i].g%ambients[i].b%ambients[i].a%diffuses[i].r%diffuses[i].g%diffuses[i].b%diffuses[i].a);
01284         }
01285         daedata << str(boost::format("\
01286   </library_effects>\n\
01287   <library_geometries>\n"));
01288         // fill with vertices
01289         for(unsigned int i=0; i < index; i++) {
01290             daedata << str(boost::format("\
01291     <geometry id=\"base2_M1KShape%d\" name=\"base2_M1KShape%d\">\n\
01292           <mesh>\n\
01293                 <source id=\"geo0.positions\">\n\
01294                   <float_array id=\"geo0.positions-array\" count=\"%d\">")%i%i%(vertices[i].size()*3));
01295             FOREACH(it,vertices[i]) {
01296                 daedata << it->x << " " << it->y << " " << it->z << " ";
01297             }
01298             daedata << str(boost::format("\n\
01299           </float_array>\n\
01300                   <technique_common>\n\
01301                         <accessor count=\"%d\" source=\"#geo0.positions-array\" stride=\"3\">\n\
01302                           <param name=\"X\" type=\"float\"/>\n\
01303                           <param name=\"Y\" type=\"float\"/>\n\
01304                           <param name=\"Z\" type=\"float\"/>\n\
01305                         </accessor>\n\
01306                   </technique_common>\n\
01307                 </source>\n\
01308                 <vertices id=\"geo0.vertices\">\n\
01309                   <input semantic=\"POSITION\" source=\"#geo0.positions\"/>\n\
01310                 </vertices>\n\
01311                 <triangles count=\"%d\" material=\"lambert2SG\">\n\
01312                   <input offset=\"0\" semantic=\"VERTEX\" source=\"#geo0.vertices\"/>\n\
01313           <p>")%vertices[i].size()%(indices[i].size()/3));
01314             // fill with indices
01315             FOREACH(it,indices[i]) {
01316                 daedata << *it << " ";
01317             }
01318             daedata << str(boost::format("</p>\n\
01319                 </triangles>\n\
01320           </mesh>\n\
01321     </geometry>\n"));
01322         }
01323         daedata << str(boost::format("\
01324   </library_geometries>\n\
01325   <library_visual_scenes>\n\
01326     <visual_scene id=\"VisualSceneNode\" name=\"base1d_med\">\n\
01327       <node id=\"%s\" name=\"%s\" type=\"NODE\">\n")%name%name);
01328         for(unsigned int i=0; i < index; i++) {
01329             daedata << str(boost::format("\
01330         <instance_geometry url=\"#base2_M1KShape%i\">\n\
01331           <bind_material>\n\
01332             <technique_common>\n\
01333               <instance_material symbol=\"lambert2SG\" target=\"#blinn2%i\"/>\n\
01334             </technique_common>\n\
01335           </bind_material>\n\
01336         </instance_geometry>\n")%i%i);
01337         }
01338         daedata << str(boost::format("\
01339       </node>\n\
01340     </visual_scene>\n\
01341   </library_visual_scenes>\n\
01342   <scene>\n\
01343     <instance_visual_scene url=\"#VisualSceneNode\"/>\n\
01344   </scene>\n\
01345 </COLLADA>"));
01346 
01347 #ifdef HAVE_MKSTEMPS
01348         geometry->filename = str(boost::format("/tmp/collada_model_reader_%s_XXXXXX.dae")%name);
01349         int fd = mkstemps(&geometry->filename[0],4);
01350 #else
01351         int fd = -1;
01352         for(int iter = 0; iter < 1000; ++iter) {
01353             geometry->filename = str(boost::format("/tmp/collada_model_reader_%s_%d.dae")%name%rand());
01354             if( !!std::ifstream(geometry->filename.c_str())) {
01355                 fd = open(geometry->filename.c_str(),O_WRONLY|O_CREAT|O_EXCL);
01356                 if( fd != -1 ) {
01357                     break;
01358                 }
01359             }
01360         }
01361         if( fd == -1 ) {
01362             ROS_ERROR("failed to open geometry dae file %s",geometry->filename.c_str());
01363             return geometry;
01364         }
01365 #endif
01366         //ROS_INFO("temp file: %s",geometry->filename.c_str());
01367         std::string daedatastr = daedata.str();
01368         if( (size_t)write(fd,daedatastr.c_str(),daedatastr.size()) != daedatastr.size() ) {
01369             ROS_ERROR("failed to write to geometry dae file %s",geometry->filename.c_str());
01370         }
01371         close(fd);
01372         _listTempFilenames.push_back(boost::shared_ptr<UnlinkFilename>(new UnlinkFilename(geometry->filename)));
01373         geometry->filename = std::string("file://") + geometry->filename;
01374         return geometry;
01375     }
01376 
01380     void _ExtractGeometry(const domNodeRef pdomnode,std::list<GEOMPROPERTIES>& listGeomProperties, const std::list<JointAxisBinding>& listAxisBindings, const Pose& tlink)
01381     {
01382         if( !pdomnode ) {
01383             return;
01384         }
01385 
01386         ROS_DEBUG_STREAM(str(boost::format("ExtractGeometry(node,link) of %s\n")%pdomnode->getName()));
01387 
01388         // For all child nodes of pdomnode
01389         for (size_t i = 0; i < pdomnode->getNode_array().getCount(); i++) {
01390             // check if contains a joint
01391             bool contains=false;
01392             FOREACHC(it,listAxisBindings) {
01393                 // don't check ID's check if the reference is the same!
01394                 if ( (pdomnode->getNode_array()[i])  == (it->visualnode)) {
01395                     contains=true;
01396                     break;
01397                 }
01398             }
01399             if (contains) {
01400                 continue;
01401             }
01402 
01403             _ExtractGeometry(pdomnode->getNode_array()[i],listGeomProperties, listAxisBindings,tlink);
01404             // Plink stayes the same for all children
01405             // replace pdomnode by child = pdomnode->getNode_array()[i]
01406             // hope for the best!
01407             // put everything in a subroutine in order to process pdomnode too!
01408         }
01409 
01410         unsigned int nGeomBefore =  listGeomProperties.size(); // #of Meshes already associated to this link
01411 
01412         // get the geometry
01413         for (size_t igeom = 0; igeom < pdomnode->getInstance_geometry_array().getCount(); ++igeom) {
01414             domInstance_geometryRef domigeom = pdomnode->getInstance_geometry_array()[igeom];
01415             domGeometryRef domgeom = daeSafeCast<domGeometry> (domigeom->getUrl().getElement());
01416             if (!domgeom) {
01417                 continue;
01418             }
01419 
01420             //  Gets materials
01421             std::map<std::string, domMaterialRef> mapmaterials;
01422             if (!!domigeom->getBind_material() && !!domigeom->getBind_material()->getTechnique_common()) {
01423                 const domInstance_material_Array& matarray = domigeom->getBind_material()->getTechnique_common()->getInstance_material_array();
01424                 for (size_t imat = 0; imat < matarray.getCount(); ++imat) {
01425                     domMaterialRef pmat = daeSafeCast<domMaterial>(matarray[imat]->getTarget().getElement());
01426                     if (!!pmat) {
01427                         mapmaterials[matarray[imat]->getSymbol()] = pmat;
01428                     }
01429                 }
01430             }
01431 
01432             //  Gets the geometry
01433             _ExtractGeometry(domgeom, mapmaterials, listGeomProperties);
01434         }
01435 
01436         std::list<GEOMPROPERTIES>::iterator itgeom= listGeomProperties.begin();
01437         for (unsigned int i=0; i< nGeomBefore; i++) {
01438             itgeom++; // change only the transformations of the newly found geometries.
01439         }
01440 
01441         boost::array<double,12> tmnodegeom = _poseMult(_matrixFromPose(_poseInverse(tlink)),
01442                                                        _poseMult(_poseMult(_matrixFromPose(_poseInverse(_VisualRootOrigin)),
01443                                                                            _getNodeParentTransform(pdomnode)),
01444                                                                  _ExtractFullTransform(pdomnode)));
01445         Pose tnodegeom;
01446         Vector3 vscale(1,1,1);
01447         _decompose(tmnodegeom, tnodegeom, vscale);
01448 
01449         ROS_DEBUG_STREAM("tnodegeom: " << pdomnode->getName()
01450                          << tnodegeom.position.x << " " << tnodegeom.position.y << " " << tnodegeom.position.z << " / "
01451                          << tnodegeom.rotation.x << " " << tnodegeom.rotation.y << " " << tnodegeom.rotation.z << " "
01452                          << tnodegeom.rotation.w);
01453 
01454         //        std::stringstream ss; ss << "geom: ";
01455         //        for(int i = 0; i < 4; ++i) {
01456         //            ss << tmnodegeom[4*0+i] << " " << tmnodegeom[4*1+i] << " " << tmnodegeom[4*2+i] << " ";
01457         //        }
01458         //        ROS_INFO(ss.str().c_str());
01459 
01460         //  Switch between different type of geometry PRIMITIVES
01461         for (; itgeom != listGeomProperties.end(); itgeom++) {
01462             itgeom->_t = tnodegeom;
01463             switch (itgeom->type) {
01464             case GeomBox:
01465                 itgeom->vGeomData.x *= vscale.x;
01466                 itgeom->vGeomData.y *= vscale.y;
01467                 itgeom->vGeomData.z *= vscale.z;
01468                 break;
01469             case GeomSphere: {
01470                 itgeom->vGeomData.x *= std::max(vscale.z, std::max(vscale.x, vscale.y));
01471                 break;
01472             }
01473             case GeomCylinder:
01474                 itgeom->vGeomData.x *= std::max(vscale.x, vscale.y);
01475                 itgeom->vGeomData.y *= vscale.z;
01476                 break;
01477             case GeomTrimesh:
01478                 for(size_t i = 0; i < itgeom->vertices.size(); ++i ) {
01479                     itgeom->vertices[i] = _poseMult(tmnodegeom,itgeom->vertices[i]);
01480                 }
01481                 itgeom->_t = Pose(); // reset back to identity
01482                 break;
01483             default:
01484                 ROS_WARN_STREAM(str(boost::format("unknown geometry type: %d\n")%itgeom->type));
01485             }
01486         }
01487     }
01488 
01492     void _FillGeometryColor(const domMaterialRef pmat, GEOMPROPERTIES& geom)
01493     {
01494         if( !!pmat && !!pmat->getInstance_effect() ) {
01495             domEffectRef peffect = daeSafeCast<domEffect>(pmat->getInstance_effect()->getUrl().getElement().cast());
01496             if( !!peffect ) {
01497                 domProfile_common::domTechnique::domPhongRef pphong = daeSafeCast<domProfile_common::domTechnique::domPhong>(peffect->getDescendant(daeElement::matchType(domProfile_common::domTechnique::domPhong::ID())));
01498                 if( !!pphong ) {
01499                     if( !!pphong->getAmbient() && !!pphong->getAmbient()->getColor() ) {
01500                         domFx_color c = pphong->getAmbient()->getColor()->getValue();
01501                         geom.ambientColor.r = c[0];
01502                         geom.ambientColor.g = c[1];
01503                         geom.ambientColor.b = c[2];
01504                         geom.ambientColor.a = c[3];
01505                     }
01506                     if( !!pphong->getDiffuse() && !!pphong->getDiffuse()->getColor() ) {
01507                         domFx_color c = pphong->getDiffuse()->getColor()->getValue();
01508                         geom.diffuseColor.r = c[0];
01509                         geom.diffuseColor.g = c[1];
01510                         geom.diffuseColor.b = c[2];
01511                         geom.diffuseColor.a = c[3];
01512                     }
01513                 }
01514             }
01515         }
01516     }
01517 
01523     bool _ExtractGeometry(const domTrianglesRef triRef, const domVerticesRef vertsRef, const std::map<std::string,domMaterialRef>& mapmaterials, std::list<GEOMPROPERTIES>& listGeomProperties)
01524     {
01525         if( !triRef ) {
01526             return false;
01527         }
01528         listGeomProperties.push_back(GEOMPROPERTIES());
01529         GEOMPROPERTIES& geom = listGeomProperties.back();
01530         geom.type = GeomTrimesh;
01531 
01532         // resolve the material and assign correct colors to the geometry
01533         if( !!triRef->getMaterial() ) {
01534             std::map<std::string,domMaterialRef>::const_iterator itmat = mapmaterials.find(triRef->getMaterial());
01535             if( itmat != mapmaterials.end() ) {
01536                 _FillGeometryColor(itmat->second,geom);
01537             }
01538         }
01539 
01540         size_t triangleIndexStride = 0, vertexoffset = -1;
01541         domInput_local_offsetRef indexOffsetRef;
01542 
01543         for (unsigned int w=0; w<triRef->getInput_array().getCount(); w++) {
01544             size_t offset = triRef->getInput_array()[w]->getOffset();
01545             daeString str = triRef->getInput_array()[w]->getSemantic();
01546             if (!strcmp(str,"VERTEX")) {
01547                 indexOffsetRef = triRef->getInput_array()[w];
01548                 vertexoffset = offset;
01549             }
01550             if (offset> triangleIndexStride) {
01551                 triangleIndexStride = offset;
01552             }
01553         }
01554         triangleIndexStride++;
01555 
01556         const domList_of_uints& indexArray =triRef->getP()->getValue();
01557         geom.indices.reserve(triRef->getCount()*3);
01558         geom.vertices.reserve(triRef->getCount()*3);
01559         for (size_t i=0; i<vertsRef->getInput_array().getCount(); ++i) {
01560             domInput_localRef localRef = vertsRef->getInput_array()[i];
01561             daeString str = localRef->getSemantic();
01562             if ( strcmp(str,"POSITION") == 0 ) {
01563                 const domSourceRef node = daeSafeCast<domSource>(localRef->getSource().getElement());
01564                 if( !node ) {
01565                     continue;
01566                 }
01567                 double fUnitScale = _GetUnitScale(node);
01568                 const domFloat_arrayRef flArray = node->getFloat_array();
01569                 if (!!flArray) {
01570                     const domList_of_floats& listFloats = flArray->getValue();
01571                     int k=vertexoffset;
01572                     int vertexStride = 3; //instead of hardcoded stride, should use the 'accessor'
01573                     for(size_t itri = 0; itri < triRef->getCount(); ++itri) {
01574                         if(k+2*triangleIndexStride < indexArray.getCount() ) {
01575                             for (int j=0; j<3; j++) {
01576                                 int index0 = indexArray.get(k)*vertexStride;
01577                                 domFloat fl0 = listFloats.get(index0);
01578                                 domFloat fl1 = listFloats.get(index0+1);
01579                                 domFloat fl2 = listFloats.get(index0+2);
01580                                 k+=triangleIndexStride;
01581                                 geom.indices.push_back(geom.vertices.size());
01582                                 geom.vertices.push_back(Vector3(fl0*fUnitScale,fl1*fUnitScale,fl2*fUnitScale));
01583                             }
01584                         }
01585                     }
01586                 }
01587                 else {
01588                     ROS_WARN_STREAM("float array not defined!\n");
01589                 }
01590                 break;
01591             }
01592         }
01593         if( geom.indices.size() != 3*triRef->getCount() ) {
01594             ROS_WARN_STREAM("triangles declares wrong count!\n");
01595         }
01596         geom.InitCollisionMesh();
01597         return true;
01598     }
01599 
01604     bool _ExtractGeometry(const domTrifansRef triRef, const domVerticesRef vertsRef, const std::map<std::string,domMaterialRef>& mapmaterials, std::list<GEOMPROPERTIES>& listGeomProperties)
01605     {
01606         if( !triRef ) {
01607             return false;
01608         }
01609         listGeomProperties.push_back(GEOMPROPERTIES());
01610         GEOMPROPERTIES& geom = listGeomProperties.back();
01611         geom.type = GeomTrimesh;
01612 
01613         // resolve the material and assign correct colors to the geometry
01614         if( !!triRef->getMaterial() ) {
01615             std::map<std::string,domMaterialRef>::const_iterator itmat = mapmaterials.find(triRef->getMaterial());
01616             if( itmat != mapmaterials.end() ) {
01617                 _FillGeometryColor(itmat->second,geom);
01618             }
01619         }
01620 
01621         size_t triangleIndexStride = 0, vertexoffset = -1;
01622         domInput_local_offsetRef indexOffsetRef;
01623 
01624         for (unsigned int w=0; w<triRef->getInput_array().getCount(); w++) {
01625             size_t offset = triRef->getInput_array()[w]->getOffset();
01626             daeString str = triRef->getInput_array()[w]->getSemantic();
01627             if (!strcmp(str,"VERTEX")) {
01628                 indexOffsetRef = triRef->getInput_array()[w];
01629                 vertexoffset = offset;
01630             }
01631             if (offset> triangleIndexStride) {
01632                 triangleIndexStride = offset;
01633             }
01634         }
01635         triangleIndexStride++;
01636         size_t primitivecount = triRef->getCount();
01637         if( primitivecount > triRef->getP_array().getCount() ) {
01638             ROS_WARN_STREAM("trifans has incorrect count\n");
01639             primitivecount = triRef->getP_array().getCount();
01640         }
01641         for(size_t ip = 0; ip < primitivecount; ++ip) {
01642             domList_of_uints indexArray =triRef->getP_array()[ip]->getValue();
01643             for (size_t i=0; i<vertsRef->getInput_array().getCount(); ++i) {
01644                 domInput_localRef localRef = vertsRef->getInput_array()[i];
01645                 daeString str = localRef->getSemantic();
01646                 if ( strcmp(str,"POSITION") == 0 ) {
01647                     const domSourceRef node = daeSafeCast<domSource>(localRef->getSource().getElement());
01648                     if( !node ) {
01649                         continue;
01650                     }
01651                     double fUnitScale = _GetUnitScale(node);
01652                     const domFloat_arrayRef flArray = node->getFloat_array();
01653                     if (!!flArray) {
01654                         const domList_of_floats& listFloats = flArray->getValue();
01655                         int k=vertexoffset;
01656                         int vertexStride = 3; //instead of hardcoded stride, should use the 'accessor'
01657                         size_t usedindices = 3*(indexArray.getCount()-2);
01658                         if( geom.indices.capacity() < geom.indices.size()+usedindices ) {
01659                             geom.indices.reserve(geom.indices.size()+usedindices);
01660                         }
01661                         if( geom.vertices.capacity() < geom.vertices.size()+indexArray.getCount() ) {
01662                             geom.vertices.reserve(geom.vertices.size()+indexArray.getCount());
01663                         }
01664                         size_t startoffset = (int)geom.vertices.size();
01665                         while(k < (int)indexArray.getCount() ) {
01666                             int index0 = indexArray.get(k)*vertexStride;
01667                             domFloat fl0 = listFloats.get(index0);
01668                             domFloat fl1 = listFloats.get(index0+1);
01669                             domFloat fl2 = listFloats.get(index0+2);
01670                             k+=triangleIndexStride;
01671                             geom.vertices.push_back(Vector3(fl0*fUnitScale,fl1*fUnitScale,fl2*fUnitScale));
01672                         }
01673                         for(size_t ivert = startoffset+2; ivert < geom.vertices.size(); ++ivert) {
01674                             geom.indices.push_back(startoffset);
01675                             geom.indices.push_back(ivert-1);
01676                             geom.indices.push_back(ivert);
01677                         }
01678                     }
01679                     else {
01680                         ROS_WARN_STREAM("float array not defined!\n");
01681                     }
01682                     break;
01683                 }
01684             }
01685         }
01686 
01687         geom.InitCollisionMesh();
01688         return false;
01689     }
01690 
01695     bool _ExtractGeometry(const domTristripsRef triRef, const domVerticesRef vertsRef, const std::map<std::string,domMaterialRef>& mapmaterials, std::list<GEOMPROPERTIES>& listGeomProperties)
01696     {
01697         if( !triRef ) {
01698             return false;
01699         }
01700         listGeomProperties.push_back(GEOMPROPERTIES());
01701         GEOMPROPERTIES& geom = listGeomProperties.back();
01702         geom.type = GeomTrimesh;
01703 
01704         // resolve the material and assign correct colors to the geometry
01705         if( !!triRef->getMaterial() ) {
01706             std::map<std::string,domMaterialRef>::const_iterator itmat = mapmaterials.find(triRef->getMaterial());
01707             if( itmat != mapmaterials.end() ) {
01708                 _FillGeometryColor(itmat->second,geom);
01709             }
01710         }
01711         size_t triangleIndexStride = 0, vertexoffset = -1;
01712         domInput_local_offsetRef indexOffsetRef;
01713 
01714         for (unsigned int w=0; w<triRef->getInput_array().getCount(); w++) {
01715             size_t offset = triRef->getInput_array()[w]->getOffset();
01716             daeString str = triRef->getInput_array()[w]->getSemantic();
01717             if (!strcmp(str,"VERTEX")) {
01718                 indexOffsetRef = triRef->getInput_array()[w];
01719                 vertexoffset = offset;
01720             }
01721             if (offset> triangleIndexStride) {
01722                 triangleIndexStride = offset;
01723             }
01724         }
01725         triangleIndexStride++;
01726         size_t primitivecount = triRef->getCount();
01727         if( primitivecount > triRef->getP_array().getCount() ) {
01728             ROS_WARN_STREAM("tristrips has incorrect count\n");
01729             primitivecount = triRef->getP_array().getCount();
01730         }
01731         for(size_t ip = 0; ip < primitivecount; ++ip) {
01732             domList_of_uints indexArray = triRef->getP_array()[ip]->getValue();
01733             for (size_t i=0; i<vertsRef->getInput_array().getCount(); ++i) {
01734                 domInput_localRef localRef = vertsRef->getInput_array()[i];
01735                 daeString str = localRef->getSemantic();
01736                 if ( strcmp(str,"POSITION") == 0 ) {
01737                     const domSourceRef node = daeSafeCast<domSource>(localRef->getSource().getElement());
01738                     if( !node ) {
01739                         continue;
01740                     }
01741                     double fUnitScale = _GetUnitScale(node);
01742                     const domFloat_arrayRef flArray = node->getFloat_array();
01743                     if (!!flArray) {
01744                         const domList_of_floats& listFloats = flArray->getValue();
01745                         int k=vertexoffset;
01746                         int vertexStride = 3; //instead of hardcoded stride, should use the 'accessor'
01747                         size_t usedindices = indexArray.getCount()-2;
01748                         if( geom.indices.capacity() < geom.indices.size()+usedindices ) {
01749                             geom.indices.reserve(geom.indices.size()+usedindices);
01750                         }
01751                         if( geom.vertices.capacity() < geom.vertices.size()+indexArray.getCount() ) {
01752                             geom.vertices.reserve(geom.vertices.size()+indexArray.getCount());
01753                         }
01754 
01755                         size_t startoffset = (int)geom.vertices.size();
01756                         while(k < (int)indexArray.getCount() ) {
01757                             int index0 = indexArray.get(k)*vertexStride;
01758                             domFloat fl0 = listFloats.get(index0);
01759                             domFloat fl1 = listFloats.get(index0+1);
01760                             domFloat fl2 = listFloats.get(index0+2);
01761                             k+=triangleIndexStride;
01762                             geom.vertices.push_back(Vector3(fl0*fUnitScale,fl1*fUnitScale,fl2*fUnitScale));
01763                         }
01764 
01765                         bool bFlip = false;
01766                         for(size_t ivert = startoffset+2; ivert < geom.vertices.size(); ++ivert) {
01767                             geom.indices.push_back(ivert-2);
01768                             geom.indices.push_back(bFlip ? ivert : ivert-1);
01769                             geom.indices.push_back(bFlip ? ivert-1 : ivert);
01770                             bFlip = !bFlip;
01771                         }
01772                     }
01773                     else {
01774                         ROS_WARN_STREAM("float array not defined!\n");
01775                     }
01776                     break;
01777                 }
01778             }
01779         }
01780 
01781         geom.InitCollisionMesh();
01782         return false;
01783     }
01784 
01789     bool _ExtractGeometry(const domPolylistRef triRef, const domVerticesRef vertsRef, const std::map<std::string,domMaterialRef>& mapmaterials, std::list<GEOMPROPERTIES>& listGeomProperties)
01790     {
01791         if( !triRef ) {
01792             return false;
01793         }
01794         listGeomProperties.push_back(GEOMPROPERTIES());
01795         GEOMPROPERTIES& geom = listGeomProperties.back();
01796         geom.type = GeomTrimesh;
01797 
01798         // resolve the material and assign correct colors to the geometry
01799         if( !!triRef->getMaterial() ) {
01800             std::map<std::string,domMaterialRef>::const_iterator itmat = mapmaterials.find(triRef->getMaterial());
01801             if( itmat != mapmaterials.end() ) {
01802                 _FillGeometryColor(itmat->second,geom);
01803             }
01804         }
01805 
01806         size_t triangleIndexStride = 0,vertexoffset = -1;
01807         domInput_local_offsetRef indexOffsetRef;
01808         for (unsigned int w=0; w<triRef->getInput_array().getCount(); w++) {
01809             size_t offset = triRef->getInput_array()[w]->getOffset();
01810             daeString str = triRef->getInput_array()[w]->getSemantic();
01811             if (!strcmp(str,"VERTEX")) {
01812                 indexOffsetRef = triRef->getInput_array()[w];
01813                 vertexoffset = offset;
01814             }
01815             if (offset> triangleIndexStride) {
01816                 triangleIndexStride = offset;
01817             }
01818         }
01819         triangleIndexStride++;
01820         const domList_of_uints& indexArray =triRef->getP()->getValue();
01821         for (size_t i=0; i<vertsRef->getInput_array().getCount(); ++i) {
01822             domInput_localRef localRef = vertsRef->getInput_array()[i];
01823             daeString str = localRef->getSemantic();
01824             if ( strcmp(str,"POSITION") == 0 ) {
01825                 const domSourceRef node = daeSafeCast<domSource>(localRef->getSource().getElement());
01826                 if( !node ) {
01827                     continue;
01828                 }
01829                 double fUnitScale = _GetUnitScale(node);
01830                 const domFloat_arrayRef flArray = node->getFloat_array();
01831                 if (!!flArray) {
01832                     const domList_of_floats& listFloats = flArray->getValue();
01833                     size_t k=vertexoffset;
01834                     int vertexStride = 3; //instead of hardcoded stride, should use the 'accessor'
01835                     for(size_t ipoly = 0; ipoly < triRef->getVcount()->getValue().getCount(); ++ipoly) {
01836                         size_t numverts = triRef->getVcount()->getValue()[ipoly];
01837                         if(numverts > 0 && k+(numverts-1)*triangleIndexStride < indexArray.getCount() ) {
01838                             size_t startoffset = geom.vertices.size();
01839                             for (size_t j=0; j<numverts; j++) {
01840                                 int index0 = indexArray.get(k)*vertexStride;
01841                                 domFloat fl0 = listFloats.get(index0);
01842                                 domFloat fl1 = listFloats.get(index0+1);
01843                                 domFloat fl2 = listFloats.get(index0+2);
01844                                 k+=triangleIndexStride;
01845                                 geom.vertices.push_back(Vector3(fl0*fUnitScale,fl1*fUnitScale,fl2*fUnitScale));
01846                             }
01847                             for(size_t ivert = startoffset+2; ivert < geom.vertices.size(); ++ivert) {
01848                                 geom.indices.push_back(startoffset);
01849                                 geom.indices.push_back(ivert-1);
01850                                 geom.indices.push_back(ivert);
01851                             }
01852                         }
01853                     }
01854                 }
01855                 else {
01856                     ROS_WARN_STREAM("float array not defined!\n");
01857                 }
01858                 break;
01859             }
01860         }
01861         geom.InitCollisionMesh();
01862         return false;
01863     }
01864 
01868     bool _ExtractGeometry(const domGeometryRef geom, const std::map<std::string,domMaterialRef>& mapmaterials, std::list<GEOMPROPERTIES>& listGeomProperties)
01869     {
01870         if( !geom ) {
01871             return false;
01872         }
01873         std::vector<Vector3> vconvexhull;
01874         if (geom->getMesh()) {
01875             const domMeshRef meshRef = geom->getMesh();
01876             for (size_t tg = 0; tg<meshRef->getTriangles_array().getCount(); tg++) {
01877                 _ExtractGeometry(meshRef->getTriangles_array()[tg], meshRef->getVertices(), mapmaterials, listGeomProperties);
01878             }
01879             for (size_t tg = 0; tg<meshRef->getTrifans_array().getCount(); tg++) {
01880                 _ExtractGeometry(meshRef->getTrifans_array()[tg], meshRef->getVertices(), mapmaterials, listGeomProperties);
01881             }
01882             for (size_t tg = 0; tg<meshRef->getTristrips_array().getCount(); tg++) {
01883                 _ExtractGeometry(meshRef->getTristrips_array()[tg], meshRef->getVertices(), mapmaterials, listGeomProperties);
01884             }
01885             for (size_t tg = 0; tg<meshRef->getPolylist_array().getCount(); tg++) {
01886                 _ExtractGeometry(meshRef->getPolylist_array()[tg], meshRef->getVertices(), mapmaterials, listGeomProperties);
01887             }
01888             if( meshRef->getPolygons_array().getCount()> 0 ) {
01889                 ROS_WARN_STREAM("openrave does not support collada polygons\n");
01890             }
01891 
01892             //            if( alltrimesh.vertices.size() == 0 ) {
01893             //                const domVerticesRef vertsRef = meshRef->getVertices();
01894             //                for (size_t i=0;i<vertsRef->getInput_array().getCount();i++) {
01895             //                    domInput_localRef localRef = vertsRef->getInput_array()[i];
01896             //                    daeString str = localRef->getSemantic();
01897             //                    if ( strcmp(str,"POSITION") == 0 ) {
01898             //                        const domSourceRef node = daeSafeCast<domSource>(localRef->getSource().getElement());
01899             //                        if( !node )
01900             //                            continue;
01901             //                        double fUnitScale = _GetUnitScale(node);
01902             //                        const domFloat_arrayRef flArray = node->getFloat_array();
01903             //                        if (!!flArray) {
01904             //                            const domList_of_floats& listFloats = flArray->getValue();
01905             //                            int vertexStride = 3;//instead of hardcoded stride, should use the 'accessor'
01906             //                            vconvexhull.reserve(vconvexhull.size()+listFloats.getCount());
01907             //                            for (size_t vertIndex = 0;vertIndex < listFloats.getCount();vertIndex+=vertexStride) {
01908             //                                //btVector3 verts[3];
01909             //                                domFloat fl0 = listFloats.get(vertIndex);
01910             //                                domFloat fl1 = listFloats.get(vertIndex+1);
01911             //                                domFloat fl2 = listFloats.get(vertIndex+2);
01912             //                                vconvexhull.push_back(Vector3(fl0*fUnitScale,fl1*fUnitScale,fl2*fUnitScale));
01913             //                            }
01914             //                        }
01915             //                    }
01916             //                }
01917             //
01918             //                _computeConvexHull(vconvexhull,alltrimesh);
01919             //            }
01920 
01921             return true;
01922         }
01923         else if (geom->getConvex_mesh()) {
01924             {
01925                 const domConvex_meshRef convexRef = geom->getConvex_mesh();
01926                 daeElementRef otherElemRef = convexRef->getConvex_hull_of().getElement();
01927                 if ( !!otherElemRef ) {
01928                     domGeometryRef linkedGeom = *(domGeometryRef*)&otherElemRef;
01929                     ROS_WARN_STREAM( "otherLinked\n");
01930                 }
01931                 else {
01932                     ROS_WARN("convexMesh polyCount = %d\n",(int)convexRef->getPolygons_array().getCount());
01933                     ROS_WARN("convexMesh triCount = %d\n",(int)convexRef->getTriangles_array().getCount());
01934                 }
01935             }
01936 
01937             const domConvex_meshRef convexRef = geom->getConvex_mesh();
01938             //daeString urlref = convexRef->getConvex_hull_of().getURI();
01939             daeString urlref2 = convexRef->getConvex_hull_of().getOriginalURI();
01940             if (urlref2) {
01941                 daeElementRef otherElemRef = convexRef->getConvex_hull_of().getElement();
01942 
01943                 // Load all the geometry libraries
01944                 for ( size_t i = 0; i < _dom->getLibrary_geometries_array().getCount(); i++) {
01945                     domLibrary_geometriesRef libgeom = _dom->getLibrary_geometries_array()[i];
01946                     for (size_t i = 0; i < libgeom->getGeometry_array().getCount(); i++) {
01947                         domGeometryRef lib = libgeom->getGeometry_array()[i];
01948                         if (!strcmp(lib->getId(),urlref2+1)) { // skip the # at the front of urlref2
01949                             //found convex_hull geometry
01950                             domMesh *meshElement = lib->getMesh(); //linkedGeom->getMesh();
01951                             if (meshElement) {
01952                                 const domVerticesRef vertsRef = meshElement->getVertices();
01953                                 for (size_t i=0; i<vertsRef->getInput_array().getCount(); i++) {
01954                                     domInput_localRef localRef = vertsRef->getInput_array()[i];
01955                                     daeString str = localRef->getSemantic();
01956                                     if ( strcmp(str,"POSITION") == 0) {
01957                                         const domSourceRef node = daeSafeCast<domSource>(localRef->getSource().getElement());
01958                                         if( !node ) {
01959                                             continue;
01960                                         }
01961                                         double fUnitScale = _GetUnitScale(node);
01962                                         const domFloat_arrayRef flArray = node->getFloat_array();
01963                                         if (!!flArray) {
01964                                             vconvexhull.reserve(vconvexhull.size()+flArray->getCount());
01965                                             const domList_of_floats& listFloats = flArray->getValue();
01966                                             for (size_t k=0; k+2<flArray->getCount(); k+=3) {
01967                                                 domFloat fl0 = listFloats.get(k);
01968                                                 domFloat fl1 = listFloats.get(k+1);
01969                                                 domFloat fl2 = listFloats.get(k+2);
01970                                                 vconvexhull.push_back(Vector3(fl0*fUnitScale,fl1*fUnitScale,fl2*fUnitScale));
01971                                             }
01972                                         }
01973                                     }
01974                                 }
01975                             }
01976                         }
01977                     }
01978                 }
01979             }
01980             else {
01981                 //no getConvex_hull_of but direct vertices
01982                 const domVerticesRef vertsRef = convexRef->getVertices();
01983                 for (size_t i=0; i<vertsRef->getInput_array().getCount(); i++) {
01984                     domInput_localRef localRef = vertsRef->getInput_array()[i];
01985                     daeString str = localRef->getSemantic();
01986                     if ( strcmp(str,"POSITION") == 0 ) {
01987                         const domSourceRef node = daeSafeCast<domSource>(localRef->getSource().getElement());
01988                         if( !node ) {
01989                             continue;
01990                         }
01991                         double fUnitScale = _GetUnitScale(node);
01992                         const domFloat_arrayRef flArray = node->getFloat_array();
01993                         if (!!flArray) {
01994                             const domList_of_floats& listFloats = flArray->getValue();
01995                             vconvexhull.reserve(vconvexhull.size()+flArray->getCount());
01996                             for (size_t k=0; k+2<flArray->getCount(); k+=3) {
01997                                 domFloat fl0 = listFloats.get(k);
01998                                 domFloat fl1 = listFloats.get(k+1);
01999                                 domFloat fl2 = listFloats.get(k+2);
02000                                 vconvexhull.push_back(Vector3(fl0*fUnitScale,fl1*fUnitScale,fl2*fUnitScale));
02001                             }
02002                         }
02003                     }
02004                 }
02005             }
02006 
02007             if( vconvexhull.size()> 0 ) {
02008                 listGeomProperties.push_back(GEOMPROPERTIES());
02009                 GEOMPROPERTIES& geom = listGeomProperties.back();
02010                 geom.type = GeomTrimesh;
02011 
02012                 //_computeConvexHull(vconvexhull,trimesh);
02013                 geom.InitCollisionMesh();
02014             }
02015             return true;
02016         }
02017 
02018         return false;
02019     }
02020 
02022     void _ExtractRobotAttachedActuators(const domArticulated_systemRef as)
02023     {
02024         // over write joint parameters by elements in instance_actuator
02025         for(size_t ie = 0; ie < as->getExtra_array().getCount(); ++ie) {
02026             domExtraRef pextra = as->getExtra_array()[ie];
02027             if( strcmp(pextra->getType(), "attach_actuator") == 0 ) {
02028                 //std::string aname = pextra->getAttribute("name");
02029                 domTechniqueRef tec = _ExtractOpenRAVEProfile(pextra->getTechnique_array());
02030                 if( !!tec ) {
02031                     urdf::JointSharedPtr pjoint;
02032                     daeElementRef domactuator;
02033                     {
02034                         daeElementRef bact = tec->getChild("bind_actuator");
02035                         pjoint = _getJointFromRef(bact->getAttribute("joint").c_str(), as);
02036                         if (!pjoint) continue;
02037                     }
02038                     {
02039                         daeElementRef iact = tec->getChild("instance_actuator");
02040                         if(!iact) continue;
02041                         std::string instance_url = iact->getAttribute("url");
02042                         domactuator = daeURI(*iact, instance_url).getElement();
02043                         if(!domactuator) continue;
02044                     }
02045                     daeElement *nom_torque = domactuator->getChild("nominal_torque");
02046                     if ( !! nom_torque ) {
02047                         if( !! pjoint->limits ) {
02048                             pjoint->limits->effort = boost::lexical_cast<double>(nom_torque->getCharData());
02049                             ROS_DEBUG("effort limit at joint (%s) is over written by %f",
02050                                       pjoint->name.c_str(), pjoint->limits->effort);
02051                         }
02052                     }
02053                 }
02054             }
02055         }
02056     }
02057 
02059     void _ExtractRobotManipulators(const domArticulated_systemRef as)
02060     {
02061         ROS_DEBUG("collada manipulators not supported yet");
02062     }
02063 
02065     void _ExtractRobotAttachedSensors(const domArticulated_systemRef as)
02066     {
02067         ROS_DEBUG("collada sensors not supported yet");
02068     }
02069 
02070     inline daeElementRef _getElementFromUrl(const daeURI &uri)
02071     {
02072         return daeStandardURIResolver(*_collada).resolveElement(uri);
02073     }
02074 
02075     static daeElement* searchBinding(domCommon_sidref_or_paramRef paddr, daeElementRef parent)
02076     {
02077         if( !!paddr->getSIDREF() ) {
02078             return daeSidRef(paddr->getSIDREF()->getValue(),parent).resolve().elt;
02079         }
02080         if (!!paddr->getParam()) {
02081             return searchBinding(paddr->getParam()->getValue(),parent);
02082         }
02083         return NULL;
02084     }
02085 
02089     static daeElement* searchBinding(daeString ref, daeElementRef parent)
02090     {
02091         if( !parent ) {
02092             return NULL;
02093         }
02094         daeElement* pelt = NULL;
02095         domKinematics_sceneRef kscene = daeSafeCast<domKinematics_scene>(parent.cast());
02096         if( !!kscene ) {
02097             pelt = searchBindingArray(ref,kscene->getInstance_articulated_system_array());
02098             if( !!pelt ) {
02099                 return pelt;
02100             }
02101             return searchBindingArray(ref,kscene->getInstance_kinematics_model_array());
02102         }
02103         domArticulated_systemRef articulated_system = daeSafeCast<domArticulated_system>(parent.cast());
02104         if( !!articulated_system ) {
02105             if( !!articulated_system->getKinematics() ) {
02106                 pelt = searchBindingArray(ref,articulated_system->getKinematics()->getInstance_kinematics_model_array());
02107                 if( !!pelt ) {
02108                     return pelt;
02109                 }
02110             }
02111             if( !!articulated_system->getMotion() ) {
02112                 return searchBinding(ref,articulated_system->getMotion()->getInstance_articulated_system());
02113             }
02114             return NULL;
02115         }
02116         // try to get a bind array
02117         daeElementRef pbindelt;
02118         const domKinematics_bind_Array* pbindarray = NULL;
02119         const domKinematics_newparam_Array* pnewparamarray = NULL;
02120         domInstance_articulated_systemRef ias = daeSafeCast<domInstance_articulated_system>(parent.cast());
02121         if( !!ias ) {
02122             pbindarray = &ias->getBind_array();
02123             pbindelt = ias->getUrl().getElement();
02124             pnewparamarray = &ias->getNewparam_array();
02125         }
02126         if( !pbindarray || !pbindelt ) {
02127             domInstance_kinematics_modelRef ikm = daeSafeCast<domInstance_kinematics_model>(parent.cast());
02128             if( !!ikm ) {
02129                 pbindarray = &ikm->getBind_array();
02130                 pbindelt = ikm->getUrl().getElement();
02131                 pnewparamarray = &ikm->getNewparam_array();
02132             }
02133         }
02134         if( !!pbindarray && !!pbindelt ) {
02135             for (size_t ibind = 0; ibind < pbindarray->getCount(); ++ibind) {
02136                 domKinematics_bindRef pbind = (*pbindarray)[ibind];
02137                 if( !!pbind->getSymbol() && strcmp(pbind->getSymbol(), ref) == 0 ) {
02138                     // found a match
02139                     if( !!pbind->getParam() ) {
02140                         return daeSidRef(pbind->getParam()->getRef(), pbindelt).resolve().elt;
02141                     }
02142                     else if( !!pbind->getSIDREF() ) {
02143                         return daeSidRef(pbind->getSIDREF()->getValue(), pbindelt).resolve().elt;
02144                     }
02145                 }
02146             }
02147             for(size_t inewparam = 0; inewparam < pnewparamarray->getCount(); ++inewparam) {
02148                 domKinematics_newparamRef newparam = (*pnewparamarray)[inewparam];
02149                 if( !!newparam->getSid() && strcmp(newparam->getSid(), ref) == 0 ) {
02150                     if( !!newparam->getSIDREF() ) { // can only bind with SIDREF
02151                         return daeSidRef(newparam->getSIDREF()->getValue(),pbindelt).resolve().elt;
02152                     }
02153                     ROS_WARN_STREAM(str(boost::format("newparam sid=%s does not have SIDREF\n")%newparam->getSid()));
02154                 }
02155             }
02156         }
02157         ROS_WARN_STREAM(str(boost::format("failed to get binding '%s' for element: %s\n")%ref%parent->getElementName()));
02158         return NULL;
02159     }
02160 
02161     static daeElement* searchBindingArray(daeString ref, const domInstance_articulated_system_Array& paramArray)
02162     {
02163         for(size_t iikm = 0; iikm < paramArray.getCount(); ++iikm) {
02164             daeElement* pelt = searchBinding(ref,paramArray[iikm].cast());
02165             if( !!pelt ) {
02166                 return pelt;
02167             }
02168         }
02169         return NULL;
02170     }
02171 
02172     static daeElement* searchBindingArray(daeString ref, const domInstance_kinematics_model_Array& paramArray)
02173     {
02174         for(size_t iikm = 0; iikm < paramArray.getCount(); ++iikm) {
02175             daeElement* pelt = searchBinding(ref,paramArray[iikm].cast());
02176             if( !!pelt ) {
02177                 return pelt;
02178             }
02179         }
02180         return NULL;
02181     }
02182 
02183     template <typename U> static xsBoolean resolveBool(domCommon_bool_or_paramRef paddr, const U& parent) {
02184         if( !!paddr->getBool() ) {
02185             return paddr->getBool()->getValue();
02186         }
02187         if( !paddr->getParam() ) {
02188             ROS_WARN_STREAM("param not specified, setting to 0\n");
02189             return false;
02190         }
02191         for(size_t iparam = 0; iparam < parent->getNewparam_array().getCount(); ++iparam) {
02192             domKinematics_newparamRef pnewparam = parent->getNewparam_array()[iparam];
02193             if( !!pnewparam->getSid() && strcmp(pnewparam->getSid(), paddr->getParam()->getValue()) == 0 ) {
02194                 if( !!pnewparam->getBool() ) {
02195                     return pnewparam->getBool()->getValue();
02196                 }
02197                 else if( !!pnewparam->getSIDREF() ) {
02198                     domKinematics_newparam::domBoolRef ptarget = daeSafeCast<domKinematics_newparam::domBool>(daeSidRef(pnewparam->getSIDREF()->getValue(), pnewparam).resolve().elt);
02199                     if( !ptarget ) {
02200                         ROS_WARN("failed to resolve %s from %s\n", pnewparam->getSIDREF()->getValue(), paddr->getID());
02201                         continue;
02202                     }
02203                     return ptarget->getValue();
02204                 }
02205             }
02206         }
02207         ROS_WARN_STREAM(str(boost::format("failed to resolve %s\n")%paddr->getParam()->getValue()));
02208         return false;
02209     }
02210     template <typename U> static domFloat resolveFloat(domCommon_float_or_paramRef paddr, const U& parent) {
02211         if( !!paddr->getFloat() ) {
02212             return paddr->getFloat()->getValue();
02213         }
02214         if( !paddr->getParam() ) {
02215             ROS_WARN_STREAM("param not specified, setting to 0\n");
02216             return 0;
02217         }
02218         for(size_t iparam = 0; iparam < parent->getNewparam_array().getCount(); ++iparam) {
02219             domKinematics_newparamRef pnewparam = parent->getNewparam_array()[iparam];
02220             if( !!pnewparam->getSid() && strcmp(pnewparam->getSid(), paddr->getParam()->getValue()) == 0 ) {
02221                 if( !!pnewparam->getFloat() ) {
02222                     return pnewparam->getFloat()->getValue();
02223                 }
02224                 else if( !!pnewparam->getSIDREF() ) {
02225                     domKinematics_newparam::domFloatRef ptarget = daeSafeCast<domKinematics_newparam::domFloat>(daeSidRef(pnewparam->getSIDREF()->getValue(), pnewparam).resolve().elt);
02226                     if( !ptarget ) {
02227                         ROS_WARN("failed to resolve %s from %s\n", pnewparam->getSIDREF()->getValue(), paddr->getID());
02228                         continue;
02229                     }
02230                     return ptarget->getValue();
02231                 }
02232             }
02233         }
02234         ROS_WARN_STREAM(str(boost::format("failed to resolve %s\n")%paddr->getParam()->getValue()));
02235         return 0;
02236     }
02237 
02238     static bool resolveCommon_float_or_param(daeElementRef pcommon, daeElementRef parent, float& f)
02239     {
02240         daeElement* pfloat = pcommon->getChild("float");
02241         if( !!pfloat ) {
02242             std::stringstream sfloat(pfloat->getCharData());
02243             sfloat >> f;
02244             return !!sfloat;
02245         }
02246         daeElement* pparam = pcommon->getChild("param");
02247         if( !!pparam ) {
02248             if( pparam->hasAttribute("ref") ) {
02249                 ROS_WARN_STREAM("cannot process param ref\n");
02250             }
02251             else {
02252                 daeElement* pelt = daeSidRef(pparam->getCharData(),parent).resolve().elt;
02253                 if( !!pelt ) {
02254                     ROS_WARN_STREAM(str(boost::format("found param ref: %s from %s\n")%pelt->getCharData()%pparam->getCharData()));
02255                 }
02256             }
02257         }
02258         return false;
02259     }
02260 
02261     static boost::array<double,12> _matrixIdentity()
02262     {
02263         boost::array<double,12> m = {{1,0,0,0,0,1,0,0,0,0,1,0}};
02264         return m;
02265     };
02266 
02268     static boost::array<double,12> _getTransform(daeElementRef pelt)
02269     {
02270         boost::array<double,12> m = _matrixIdentity();
02271         domRotateRef protate = daeSafeCast<domRotate>(pelt);
02272         if( !!protate ) {
02273             m = _matrixFromAxisAngle(Vector3(protate->getValue()[0],protate->getValue()[1],protate->getValue()[2]), (double)(protate->getValue()[3]*(M_PI/180.0)));
02274             return m;
02275         }
02276 
02277         domTranslateRef ptrans = daeSafeCast<domTranslate>(pelt);
02278         if( !!ptrans ) {
02279             double scale = _GetUnitScale(pelt);
02280             m[3] = ptrans->getValue()[0]*scale;
02281             m[7] = ptrans->getValue()[1]*scale;
02282             m[11] = ptrans->getValue()[2]*scale;
02283             return m;
02284         }
02285 
02286         domMatrixRef pmat = daeSafeCast<domMatrix>(pelt);
02287         if( !!pmat ) {
02288             double scale = _GetUnitScale(pelt);
02289             for(int i = 0; i < 3; ++i) {
02290                 m[4*i+0] = pmat->getValue()[4*i+0];
02291                 m[4*i+1] = pmat->getValue()[4*i+1];
02292                 m[4*i+2] = pmat->getValue()[4*i+2];
02293                 m[4*i+3] = pmat->getValue()[4*i+3]*scale;
02294             }
02295             return m;
02296         }
02297 
02298         domScaleRef pscale = daeSafeCast<domScale>(pelt);
02299         if( !!pscale ) {
02300             m[0] = pscale->getValue()[0];
02301             m[4*1+1] = pscale->getValue()[1];
02302             m[4*2+2] = pscale->getValue()[2];
02303             return m;
02304         }
02305 
02306         domLookatRef pcamera = daeSafeCast<domLookat>(pelt);
02307         if( pelt->typeID() == domLookat::ID() ) {
02308             ROS_ERROR_STREAM("look at transform not implemented\n");
02309             return m;
02310         }
02311 
02312         domSkewRef pskew = daeSafeCast<domSkew>(pelt);
02313         if( !!pskew ) {
02314             ROS_ERROR_STREAM("skew transform not implemented\n");
02315         }
02316 
02317         return m;
02318     }
02319 
02322     template <typename T> static boost::array<double,12> _getNodeParentTransform(const T pelt) {
02323         domNodeRef pnode = daeSafeCast<domNode>(pelt->getParent());
02324         if( !pnode ) {
02325             return _matrixIdentity();
02326         }
02327         return _poseMult(_getNodeParentTransform(pnode), _ExtractFullTransform(pnode));
02328     }
02329 
02331     template <typename T> static boost::array<double,12> _ExtractFullTransform(const T pelt) {
02332         boost::array<double,12> t = _matrixIdentity();
02333         for(size_t i = 0; i < pelt->getContents().getCount(); ++i) {
02334             t = _poseMult(t, _getTransform(pelt->getContents()[i]));
02335         }
02336         return t;
02337     }
02338 
02340     template <typename T> static boost::array<double,12> _ExtractFullTransformFromChildren(const T pelt) {
02341         boost::array<double,12> t = _matrixIdentity();
02342         daeTArray<daeElementRef> children; pelt->getChildren(children);
02343         for(size_t i = 0; i < children.getCount(); ++i) {
02344             t = _poseMult(t, _getTransform(children[i]));
02345         }
02346         return t;
02347     }
02348 
02349     // decompose a matrix into a scale and rigid transform (necessary for model scales)
02350     void _decompose(const boost::array<double,12>& tm, Pose& tout, Vector3& vscale)
02351     {
02352         vscale.x = 1; vscale.y = 1; vscale.z = 1;
02353         tout = _poseFromMatrix(tm);
02354     }
02355 
02356     virtual void handleError( daeString msg )
02357     {
02358         ROS_ERROR("COLLADA error: %s\n", msg);
02359     }
02360 
02361     virtual void handleWarning( daeString msg )
02362     {
02363         ROS_WARN("COLLADA warning: %s\n", msg);
02364     }
02365 
02366     inline static double _GetUnitScale(daeElement* pelt)
02367     {
02368         return ((USERDATA*)pelt->getUserData())->scale;
02369     }
02370 
02371     domTechniqueRef _ExtractOpenRAVEProfile(const domTechnique_Array& arr)
02372     {
02373         for(size_t i = 0; i < arr.getCount(); ++i) {
02374             if( strcmp(arr[i]->getProfile(), "OpenRAVE") == 0 ) {
02375                 return arr[i];
02376             }
02377         }
02378         return domTechniqueRef();
02379     }
02380 
02382     boost::shared_ptr<std::string> _ExtractInterfaceType(const domExtra_Array& arr) {
02383         for(size_t i = 0; i < arr.getCount(); ++i) {
02384             if( strcmp(arr[i]->getType(),"interface_type") == 0 ) {
02385                 domTechniqueRef tec = _ExtractOpenRAVEProfile(arr[i]->getTechnique_array());
02386                 if( !!tec ) {
02387                     daeElement* ptype = tec->getChild("interface");
02388                     if( !!ptype ) {
02389                         return boost::shared_ptr<std::string>(new std::string(ptype->getCharData()));
02390                     }
02391                 }
02392             }
02393         }
02394         return boost::shared_ptr<std::string>();
02395     }
02396 
02397     std::string _ExtractLinkName(domLinkRef pdomlink) {
02398         std::string linkname;
02399         if( !!pdomlink ) {
02400             if( !!pdomlink->getName() ) {
02401                 linkname = pdomlink->getName();
02402             }
02403             if( linkname.size() == 0 && !!pdomlink->getID() ) {
02404                 linkname = pdomlink->getID();
02405             }
02406         }
02407         return linkname;
02408     }
02409 
02410     bool _checkMathML(daeElementRef pelt,const std::string& type)
02411     {
02412         if( pelt->getElementName()==type ) {
02413             return true;
02414         }
02415         // check the substring after ':'
02416         std::string name = pelt->getElementName();
02417         std::size_t pos = name.find_last_of(':');
02418         if( pos == std::string::npos ) {
02419             return false;
02420         }
02421         return name.substr(pos+1)==type;
02422     }
02423 
02424         urdf::JointSharedPtr _getJointFromRef(xsToken targetref, daeElementRef peltref) {
02425         daeElement* peltjoint = daeSidRef(targetref, peltref).resolve().elt;
02426         domJointRef pdomjoint = daeSafeCast<domJoint> (peltjoint);
02427 
02428         if (!pdomjoint) {
02429             domInstance_jointRef pdomijoint = daeSafeCast<domInstance_joint> (peltjoint);
02430             if (!!pdomijoint) {
02431                 pdomjoint = daeSafeCast<domJoint> (pdomijoint->getUrl().getElement().cast());
02432             }
02433         }
02434 
02435         if (!pdomjoint || pdomjoint->typeID() != domJoint::ID() || !pdomjoint->getName()) {
02436             ROS_WARN_STREAM(str(boost::format("could not find collada joint %s!\n")%targetref));
02437             return urdf::JointSharedPtr();
02438         }
02439 
02440         urdf::JointSharedPtr pjoint;
02441         std::string name(pdomjoint->getName());
02442         if (_model->joints_.find(name) == _model->joints_.end()) {
02443             pjoint.reset();
02444         } else {
02445             pjoint = _model->joints_.find(name)->second;
02446         }
02447         if(!pjoint) {
02448             ROS_WARN_STREAM(str(boost::format("could not find openrave joint %s!\n")%pdomjoint->getName()));
02449         }
02450         return pjoint;
02451     }
02452 
02456     static void _ExtractKinematicsVisualBindings(domInstance_with_extraRef viscene, domInstance_kinematics_sceneRef kiscene, KinematicsSceneBindings& bindings)
02457     {
02458         domKinematics_sceneRef kscene = daeSafeCast<domKinematics_scene> (kiscene->getUrl().getElement().cast());
02459         if (!kscene) {
02460             return;
02461         }
02462         for (size_t imodel = 0; imodel < kiscene->getBind_kinematics_model_array().getCount(); imodel++) {
02463             domArticulated_systemRef articulated_system; // if filled, contains robot-specific information, so create a robot
02464             domBind_kinematics_modelRef kbindmodel = kiscene->getBind_kinematics_model_array()[imodel];
02465             if (!kbindmodel->getNode()) {
02466                 ROS_WARN_STREAM("do not support kinematics models without references to nodes\n");
02467                 continue;
02468             }
02469 
02470             // visual information
02471             domNodeRef node = daeSafeCast<domNode>(daeSidRef(kbindmodel->getNode(), viscene->getUrl().getElement()).resolve().elt);
02472             if (!node) {
02473                 ROS_WARN_STREAM(str(boost::format("bind_kinematics_model does not reference valid node %s\n")%kbindmodel->getNode()));
02474                 continue;
02475             }
02476 
02477             //  kinematics information
02478             daeElement* pelt = searchBinding(kbindmodel,kscene);
02479             domInstance_kinematics_modelRef kimodel = daeSafeCast<domInstance_kinematics_model>(pelt);
02480             if (!kimodel) {
02481                 if( !pelt ) {
02482                     ROS_WARN_STREAM("bind_kinematics_model does not reference element\n");
02483                 }
02484                 else {
02485                     ROS_WARN_STREAM(str(boost::format("bind_kinematics_model cannot find reference to %s:\n")%pelt->getElementName()));
02486                 }
02487                 continue;
02488             }
02489             bindings.listKinematicsVisualBindings.push_back(std::make_pair(node,kimodel));
02490         }
02491         // axis info
02492         for (size_t ijoint = 0; ijoint < kiscene->getBind_joint_axis_array().getCount(); ++ijoint) {
02493             domBind_joint_axisRef bindjoint = kiscene->getBind_joint_axis_array()[ijoint];
02494             daeElementRef pjtarget = daeSidRef(bindjoint->getTarget(), viscene->getUrl().getElement()).resolve().elt;
02495             if (!pjtarget) {
02496                 ROS_ERROR_STREAM(str(boost::format("Target Node %s NOT found!!!\n")%bindjoint->getTarget()));
02497                 continue;
02498             }
02499             daeElement* pelt = searchBinding(bindjoint->getAxis(),kscene);
02500             domAxis_constraintRef pjointaxis = daeSafeCast<domAxis_constraint>(pelt);
02501             if (!pjointaxis) {
02502                 continue;
02503             }
02504             bindings.listAxisBindings.push_back(JointAxisBinding(pjtarget, pjointaxis, bindjoint->getValue(), NULL, NULL));
02505         }
02506     }
02507 
02508     static void _ExtractPhysicsBindings(domCOLLADA::domSceneRef allscene, KinematicsSceneBindings& bindings)
02509     {
02510         for(size_t iphysics = 0; iphysics < allscene->getInstance_physics_scene_array().getCount(); ++iphysics) {
02511             domPhysics_sceneRef pscene = daeSafeCast<domPhysics_scene>(allscene->getInstance_physics_scene_array()[iphysics]->getUrl().getElement().cast());
02512             for(size_t imodel = 0; imodel < pscene->getInstance_physics_model_array().getCount(); ++imodel) {
02513                 domInstance_physics_modelRef ipmodel = pscene->getInstance_physics_model_array()[imodel];
02514                 domPhysics_modelRef pmodel = daeSafeCast<domPhysics_model> (ipmodel->getUrl().getElement().cast());
02515                 domNodeRef nodephysicsoffset = daeSafeCast<domNode>(ipmodel->getParent().getElement().cast());
02516                 for(size_t ibody = 0; ibody < ipmodel->getInstance_rigid_body_array().getCount(); ++ibody) {
02517                     LinkBinding lb;
02518                     lb.irigidbody = ipmodel->getInstance_rigid_body_array()[ibody];
02519                     lb.node = daeSafeCast<domNode>(lb.irigidbody->getTarget().getElement().cast());
02520                     lb.rigidbody = daeSafeCast<domRigid_body>(daeSidRef(lb.irigidbody->getBody(),pmodel).resolve().elt);
02521                     lb.nodephysicsoffset = nodephysicsoffset;
02522                     if( !!lb.rigidbody && !!lb.node ) {
02523                         bindings.listLinkBindings.push_back(lb);
02524                     }
02525                 }
02526             }
02527         }
02528     }
02529 
02530 
02531     size_t _countChildren(daeElement* pelt) {
02532         size_t c = 1;
02533         daeTArray<daeElementRef> children;
02534         pelt->getChildren(children);
02535         for (size_t i = 0; i < children.getCount(); ++i) {
02536             c += _countChildren(children[i]);
02537         }
02538         return c;
02539     }
02540 
02541     void _processUserData(daeElement* pelt, double scale)
02542     {
02543         // getChild could be optimized since asset tag is supposed to appear as the first element
02544         domAssetRef passet = daeSafeCast<domAsset> (pelt->getChild("asset"));
02545         if (!!passet && !!passet->getUnit()) {
02546             scale = passet->getUnit()->getMeter();
02547         }
02548 
02549         _vuserdata.push_back(USERDATA(scale));
02550         pelt->setUserData(&_vuserdata.back());
02551         daeTArray<daeElementRef> children;
02552         pelt->getChildren(children);
02553         for (size_t i = 0; i < children.getCount(); ++i) {
02554             if (children[i] != passet) {
02555                 _processUserData(children[i], scale);
02556             }
02557         }
02558     }
02559 
02560     USERDATA* _getUserData(daeElement* pelt)
02561     {
02562         BOOST_ASSERT(!!pelt);
02563         void* p = pelt->getUserData();
02564         BOOST_ASSERT(!!p);
02565         return (USERDATA*)p;
02566     }
02567 
02568     //
02569     // openrave math functions (from geometry.h)
02570     //
02571 
02572     static Vector3 _poseMult(const Pose& p, const Vector3& v)
02573     {
02574         double ww = 2 * p.rotation.x * p.rotation.x;
02575         double wx = 2 * p.rotation.x * p.rotation.y;
02576         double wy = 2 * p.rotation.x * p.rotation.z;
02577         double wz = 2 * p.rotation.x * p.rotation.w;
02578         double xx = 2 * p.rotation.y * p.rotation.y;
02579         double xy = 2 * p.rotation.y * p.rotation.z;
02580         double xz = 2 * p.rotation.y * p.rotation.w;
02581         double yy = 2 * p.rotation.z * p.rotation.z;
02582         double yz = 2 * p.rotation.z * p.rotation.w;
02583         Vector3 vnew;
02584         vnew.x = (1-xx-yy) * v.x + (wx-yz) * v.y + (wy+xz)*v.z + p.position.x;
02585         vnew.y = (wx+yz) * v.x + (1-ww-yy) * v.y + (xy-wz)*v.z + p.position.y;
02586         vnew.z = (wy-xz) * v.x + (xy+wz) * v.y + (1-ww-xx)*v.z + p.position.z;
02587         return vnew;
02588     }
02589 
02590     static Vector3 _poseMult(const boost::array<double,12>& m, const Vector3& v)
02591     {
02592         Vector3 vnew;
02593         vnew.x = m[4*0+0] * v.x + m[4*0+1] * v.y + m[4*0+2] * v.z + m[4*0+3];
02594         vnew.y = m[4*1+0] * v.x + m[4*1+1] * v.y + m[4*1+2] * v.z + m[4*1+3];
02595         vnew.z = m[4*2+0] * v.x + m[4*2+1] * v.y + m[4*2+2] * v.z + m[4*2+3];
02596         return vnew;
02597     }
02598 
02599     static boost::array<double,12> _poseMult(const boost::array<double,12>& m0, const boost::array<double,12>& m1)
02600     {
02601         boost::array<double,12> mres;
02602         mres[0*4+0] = m0[0*4+0]*m1[0*4+0]+m0[0*4+1]*m1[1*4+0]+m0[0*4+2]*m1[2*4+0];
02603         mres[0*4+1] = m0[0*4+0]*m1[0*4+1]+m0[0*4+1]*m1[1*4+1]+m0[0*4+2]*m1[2*4+1];
02604         mres[0*4+2] = m0[0*4+0]*m1[0*4+2]+m0[0*4+1]*m1[1*4+2]+m0[0*4+2]*m1[2*4+2];
02605         mres[1*4+0] = m0[1*4+0]*m1[0*4+0]+m0[1*4+1]*m1[1*4+0]+m0[1*4+2]*m1[2*4+0];
02606         mres[1*4+1] = m0[1*4+0]*m1[0*4+1]+m0[1*4+1]*m1[1*4+1]+m0[1*4+2]*m1[2*4+1];
02607         mres[1*4+2] = m0[1*4+0]*m1[0*4+2]+m0[1*4+1]*m1[1*4+2]+m0[1*4+2]*m1[2*4+2];
02608         mres[2*4+0] = m0[2*4+0]*m1[0*4+0]+m0[2*4+1]*m1[1*4+0]+m0[2*4+2]*m1[2*4+0];
02609         mres[2*4+1] = m0[2*4+0]*m1[0*4+1]+m0[2*4+1]*m1[1*4+1]+m0[2*4+2]*m1[2*4+1];
02610         mres[2*4+2] = m0[2*4+0]*m1[0*4+2]+m0[2*4+1]*m1[1*4+2]+m0[2*4+2]*m1[2*4+2];
02611         mres[3] = m1[3] * m0[0] + m1[7] * m0[1] + m1[11] * m0[2] + m0[3];
02612         mres[7] = m1[3] * m0[4] + m1[7] * m0[5] + m1[11] * m0[6] + m0[7];
02613         mres[11] = m1[3] * m0[8] + m1[7] * m0[9] + m1[11] * m0[10] + m0[11];
02614         return mres;
02615     }
02616 
02617     static Pose _poseMult(const Pose& p0, const Pose& p1)
02618     {
02619         Pose p;
02620         p.position = _poseMult(p0,p1.position);
02621         p.rotation = _quatMult(p0.rotation,p1.rotation);
02622         return p;
02623     }
02624 
02625     static Pose _poseInverse(const Pose& p)
02626     {
02627         Pose pinv;
02628         pinv.rotation.x = -p.rotation.x;
02629         pinv.rotation.y = -p.rotation.y;
02630         pinv.rotation.z = -p.rotation.z;
02631         pinv.rotation.w = p.rotation.w;
02632         Vector3 t = _poseMult(pinv,p.position);
02633         pinv.position.x = -t.x;
02634         pinv.position.y = -t.y;
02635         pinv.position.z = -t.z;
02636         return pinv;
02637     }
02638 
02639     static Rotation _quatMult(const Rotation& quat0, const Rotation& quat1)
02640     {
02641         Rotation q;
02642         q.x = quat0.w*quat1.x + quat0.x*quat1.w + quat0.y*quat1.z - quat0.z*quat1.y;
02643         q.y = quat0.w*quat1.y + quat0.y*quat1.w + quat0.z*quat1.x - quat0.x*quat1.z;
02644         q.z = quat0.w*quat1.z + quat0.z*quat1.w + quat0.x*quat1.y - quat0.y*quat1.x;
02645         q.w = quat0.w*quat1.w - quat0.x*quat1.x - quat0.y*quat1.y - quat0.z*quat1.z;
02646         double fnorm = std::sqrt(q.x*q.x+q.y*q.y+q.z*q.z+q.w*q.w);
02647         // don't touch the divides
02648         q.x /= fnorm;
02649         q.y /= fnorm;
02650         q.z /= fnorm;
02651         q.w /= fnorm;
02652         return q;
02653     }
02654 
02655     static boost::array<double,12> _matrixFromAxisAngle(const Vector3& axis, double angle)
02656     {
02657         return _matrixFromQuat(_quatFromAxisAngle(axis.x,axis.y,axis.z,angle));
02658     }
02659 
02660     static boost::array<double,12> _matrixFromQuat(const Rotation& quat)
02661     {
02662         boost::array<double,12> m;
02663         double qq1 = 2*quat.x*quat.x;
02664         double qq2 = 2*quat.y*quat.y;
02665         double qq3 = 2*quat.z*quat.z;
02666         m[4*0+0] = 1 - qq2 - qq3;
02667         m[4*0+1] = 2*(quat.x*quat.y - quat.w*quat.z);
02668         m[4*0+2] = 2*(quat.x*quat.z + quat.w*quat.y);
02669         m[4*0+3] = 0;
02670         m[4*1+0] = 2*(quat.x*quat.y + quat.w*quat.z);
02671         m[4*1+1] = 1 - qq1 - qq3;
02672         m[4*1+2] = 2*(quat.y*quat.z - quat.w*quat.x);
02673         m[4*1+3] = 0;
02674         m[4*2+0] = 2*(quat.x*quat.z - quat.w*quat.y);
02675         m[4*2+1] = 2*(quat.y*quat.z + quat.w*quat.x);
02676         m[4*2+2] = 1 - qq1 - qq2;
02677         m[4*2+3] = 0;
02678         return m;
02679     }
02680 
02681     static Pose _poseFromMatrix(const boost::array<double,12>& m)
02682     {
02683         Pose t;
02684         t.rotation = _quatFromMatrix(m);
02685         t.position.x = m[3];
02686         t.position.y = m[7];
02687         t.position.z = m[11];
02688         return t;
02689     }
02690 
02691     static boost::array<double,12> _matrixFromPose(const Pose& t)
02692     {
02693         boost::array<double,12> m = _matrixFromQuat(t.rotation);
02694         m[3] = t.position.x;
02695         m[7] = t.position.y;
02696         m[11] = t.position.z;
02697         return m;
02698     }
02699 
02700     static Rotation _quatFromAxisAngle(double x, double y, double z, double angle)
02701     {
02702         Rotation q;
02703         double axislen = std::sqrt(x*x+y*y+z*z);
02704         if( axislen == 0 ) {
02705             return q;
02706         }
02707         angle *= 0.5;
02708         double sang = std::sin(angle)/axislen;
02709         q.w = std::cos(angle);
02710         q.x = x*sang;
02711         q.y = y*sang;
02712         q.z = z*sang;
02713         return q;
02714     }
02715 
02716     static Rotation _quatFromMatrix(const boost::array<double,12>& mat)
02717     {
02718         Rotation rot;
02719         double tr = mat[4*0+0] + mat[4*1+1] + mat[4*2+2];
02720         if (tr >= 0) {
02721             rot.w = tr + 1;
02722             rot.x = (mat[4*2+1] - mat[4*1+2]);
02723             rot.y = (mat[4*0+2] - mat[4*2+0]);
02724             rot.z = (mat[4*1+0] - mat[4*0+1]);
02725         }
02726         else {
02727             // find the largest diagonal element and jump to the appropriate case
02728             if (mat[4*1+1] > mat[4*0+0]) {
02729                 if (mat[4*2+2] > mat[4*1+1]) {
02730                     rot.z = (mat[4*2+2] - (mat[4*0+0] + mat[4*1+1])) + 1;
02731                     rot.x = (mat[4*2+0] + mat[4*0+2]);
02732                     rot.y = (mat[4*1+2] + mat[4*2+1]);
02733                     rot.w = (mat[4*1+0] - mat[4*0+1]);
02734                 }
02735                 else {
02736                     rot.y = (mat[4*1+1] - (mat[4*2+2] + mat[4*0+0])) + 1;
02737                     rot.z = (mat[4*1+2] + mat[4*2+1]);
02738                     rot.x = (mat[4*0+1] + mat[4*1+0]);
02739                     rot.w = (mat[4*0+2] - mat[4*2+0]);
02740                 }
02741             }
02742             else if (mat[4*2+2] > mat[4*0+0]) {
02743                 rot.z = (mat[4*2+2] - (mat[4*0+0] + mat[4*1+1])) + 1;
02744                 rot.x = (mat[4*2+0] + mat[4*0+2]);
02745                 rot.y = (mat[4*1+2] + mat[4*2+1]);
02746                 rot.w = (mat[4*1+0] - mat[4*0+1]);
02747             }
02748             else {
02749                 rot.x = (mat[4*0+0] - (mat[4*1+1] + mat[4*2+2])) + 1;
02750                 rot.y = (mat[4*0+1] + mat[4*1+0]);
02751                 rot.z = (mat[4*2+0] + mat[4*0+2]);
02752                 rot.w = (mat[4*2+1] - mat[4*1+2]);
02753             }
02754         }
02755         double fnorm = std::sqrt(rot.x*rot.x+rot.y*rot.y+rot.z*rot.z+rot.w*rot.w);
02756         // don't touch the divides
02757         rot.x /= fnorm;
02758         rot.y /= fnorm;
02759         rot.z /= fnorm;
02760         rot.w /= fnorm;
02761         return rot;
02762     }
02763 
02764     static double _dot3(const Vector3& v0, const Vector3& v1)
02765     {
02766         return v0.x*v1.x + v0.y*v1.y + v0.z*v1.z;
02767     }
02768     static Vector3 _cross3(const Vector3& v0, const Vector3& v1)
02769     {
02770         Vector3 v;
02771         v.x = v0.y * v1.z - v0.z * v1.y;
02772         v.y = v0.z * v1.x - v0.x * v1.z;
02773         v.z = v0.x * v1.y - v0.y * v1.x;
02774         return v;
02775     }
02776     static Vector3 _sub3(const Vector3& v0, const Vector3& v1)
02777     {
02778         Vector3 v;
02779         v.x = v0.x-v1.x;
02780         v.y = v0.y-v1.y;
02781         v.z = v0.z-v1.z;
02782         return v;
02783     }
02784     static Vector3 _add3(const Vector3& v0, const Vector3& v1)
02785     {
02786         Vector3 v;
02787         v.x = v0.x+v1.x;
02788         v.y = v0.y+v1.y;
02789         v.z = v0.z+v1.z;
02790         return v;
02791     }
02792     static Vector3 _normalize3(const Vector3& v0)
02793     {
02794         Vector3 v;
02795         double norm = std::sqrt(v0.x*v0.x+v0.y*v0.y+v0.z*v0.z);
02796         v.x = v0.x/norm;
02797         v.y = v0.y/norm;
02798         v.z = v0.z/norm;
02799         return v;
02800     }
02801 
02802     boost::shared_ptr<DAE> _collada;
02803     domCOLLADA* _dom;
02804     std::vector<USERDATA> _vuserdata; // all userdata
02805     int _nGlobalSensorId, _nGlobalManipulatorId;
02806     std::string _filename;
02807     std::string _resourcedir;
02808     urdf::ModelInterfaceSharedPtr _model;
02809     Pose _RootOrigin;
02810     Pose _VisualRootOrigin;
02811 };
02812 
02813 
02814 
02815 
02816 urdf::ModelInterfaceSharedPtr parseCollada(const std::string &xml_str)
02817 {
02818     urdf::ModelInterfaceSharedPtr model(new ModelInterface);
02819 
02820     ColladaModelReader reader(model);
02821     if (!reader.InitFromData(xml_str))
02822         model.reset();
02823     return model;
02824 }
02825 }


collada_parser
Author(s): Rosen Diankov, Kei Okada, Ioan Sucan , Jackie Kay
autogenerated on Sat Jun 8 2019 20:34:11